ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

calling service from c++ code. /gazebo/set_model_state

asked 2012-02-08 00:32:57 -0500

Maurizio88 gravatar image

updated 2014-01-28 17:11:18 -0500

ngrennan gravatar image

hi, i want to call the service /gazebo/set_model_state from gazebo package. I can do it by command-console:

rosservice call /gazebo/set_model_state '{model_state: { model_name: my_robot, pose: { position: { x: 0.0, y: 0.0 ,z: 0.1 }, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0 } }, twist: { linear: {x: 0.0 , y: 0 ,z: 0 } , angular: { x: 0.0 , y: 0 , z: 0.0 } } , reference_frame: world } }'

i tryed to do this in c++ code. someone can say me what is wrong? this is the code:

#include "gazebo/SetModelState.h"

...

        geometry_msgs::Pose start_pose;
        start_pose.position.x = 0.0;
        start_pose.position.y = 0.0;
        start_pose.position.z = 2;
        start_pose.orientation.x = 0.0;
        start_pose.orientation.y = 0.0;
        start_pose.orientation.z = 0.0;
        start_pose.orientation.w = 0.0;

        geometry_msgs::Twist start_twist;
        start_twist.linear.x = 0.0;
        start_twist.linear.y = 0.0;
        start_twist.linear.z = 0.0;
        start_twist.angular.x = 0.0;
        start_twist.angular.y = 0.0;
        start_twist.angular.z = 0.0;

        gazebo::ModelState modelstate;
        modelstate.model_name = (std::string) "robovolc";
        modelstate.reference_frame = (std::string) "world";
        modelstate.pose = start_pose;
        modelstate.twist = start_twist;

        ros::ServiceClient client = n.serviceClient<gazebo::SetModelState>("/gazebo/set_model_state");
        //ros::ServiceClient client = n.serviceClient<gazebo::SetModelState>("/gazebo/SetModelState");

        gazebo::SetModelState setmodelstate;
        setmodelstate.request.model_state = modelstate;
        client.call(setmodelstate);
edit retag flag offensive close merge delete

4 Answers

Sort by » oldest newest most voted
0

answered 2012-02-09 20:28:17 -0500

Maurizio88 gravatar image

i solved the problem! the line

ros::NodeHandle n;

wasn't visible for the call to node. i rewrote it close to the code.

edit flag offensive delete link more
1

answered 2012-02-08 09:15:49 -0500

hsu gravatar image
edit flag offensive delete link more
0

answered 2012-02-09 00:20:57 -0500

Maurizio88 gravatar image

I modified the code, it's not so different. i posted below the error message when i do rosmake.

#include <ros/ros.h>
#include "gazebo_msgs/SetModelState.h"

        geometry_msgs::Pose start_pose;
        start_pose.position.x = 0.0;
        start_pose.position.y = 0.0;
        start_pose.position.z = 2;
        start_pose.orientation.x = 0.0;
        start_pose.orientation.y = 0.0;
        start_pose.orientation.z = 0.0;
        start_pose.orientation.w = 0.0;

        geometry_msgs::Twist start_twist;
        start_twist.linear.x = 0.0;
        start_twist.linear.y = 0.0;
        start_twist.linear.z = 0.0;
        start_twist.angular.x = 0.0;
        start_twist.angular.y = 0.0;
        start_twist.angular.z = 0.0;

        gazebo_msgs::ModelState modelstate;
        modelstate.model_name = (std::string) "robovolc";
        modelstate.reference_frame = (std::string) "world";
        modelstate.pose = start_pose;
        modelstate.twist = start_twist;

        ros::ServiceClient client = n.serviceClient<gazebo_msgs::SetModelState>("/gazebo/set_model_state");
        gazebo_msgs::SetModelState setmodelstate;
        setmodelstate.request.model_state = modelstate;

        if (client.call(setmodelstate))
        {
            ROS_INFO("BRILLIANT!!!");
        }
        else
        {
            ROS_ERROR("Failed to call service ");
            return 1;
        }

[ 63%] Built target ROSBUILD_genmsg_cpp make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: uscita dalla directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" [ 73%] Built target ROSBUILD_genmsg_lisp make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: uscita dalla directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" [ 73%] Built target rospack_genmsg make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: uscita dalla directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" [ 73%] Built target rosbuild_precompile make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: uscita dalla directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" [ 78%] Built target add_two_ints_client make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: uscita dalla directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" [ 84%] Built target add_two_ints_server make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: uscita dalla directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" [ 94%] Built target ar_multi make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: uscita dalla directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" make[3]: ingresso nella directory "/home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/build" [100%] Building CXX object CMakeFiles/ar_single.dir/src/ar_single.o In file included from /home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/include/ar_pose/ar_single.h:45:0, from /home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/src/ar_single.cpp:28: /opt/ros/electric/stacks/vision_opencv/cv_bridge/include/cv_bridge/CvBridge.h: In static member function ‘static sensor_msgs::Image_<std::allocator<void> >::Ptr sensor_msgs::CvBridge::cvToImgMsg(const IplImage, std::string)’: /opt/ros/electric/stacks/vision_opencv/cv_bridge/include/cv_bridge/CvBridge.h:408:55: warning: ‘static bool sensor_msgs::CvBridge::fromIpltoRosImage(const IplImage, sensor_msgs::Image&, std::string)’ is deprecated (declared at /opt/ros/electric/stacks/vision_opencv/cv_bridge/include/cv_bridge/CvBridge.h:307) /home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/src/ar_single.cpp: In constructor ‘ar_pose::ARSinglePublisher::ARSinglePublisher(ros::NodeHandle&)’: /home/mauro/ros_workspace/ccny-ros-pkg/ccny_vision/ar_pose/src/ar_single.cpp:41:77: warning: ‘sensor_msgs::CvBridge::CvBridge()’ is deprecated (declared at /opt/ros/electric/stacks/vision_opencv/cv_bridge/include ... (more)

edit flag offensive delete link more

Comments

You cannot use `return 1` in that function. You must just use `retrurn`. If your function returns void, you can't return an integer.
DimitriProsser gravatar image DimitriProsser  ( 2012-02-09 00:32:39 -0500 )edit
thanks, but it doesn't still work!
Maurizio88 gravatar image Maurizio88  ( 2012-02-09 00:44:27 -0500 )edit
Is the error the same?
DimitriProsser gravatar image DimitriProsser  ( 2012-02-09 00:54:50 -0500 )edit
yes!! the same
Maurizio88 gravatar image Maurizio88  ( 2012-02-09 00:59:34 -0500 )edit
On line 371, you have a return statement with a value, but the function is supposed to return void.
DimitriProsser gravatar image DimitriProsser  ( 2012-02-09 01:00:19 -0500 )edit
thanks. but other problems are still there...
Maurizio88 gravatar image Maurizio88  ( 2012-02-09 01:08:01 -0500 )edit
0

answered 2012-02-08 00:41:23 -0500

DimitriProsser gravatar image

If you're using Electric, you should use the package gazebo_msgs instead of gazebo for your message and service descriptions.

Secondly, could you edit your question to include the error that you are receiving so that we can help you better?

edit flag offensive delete link more

Comments

so, should i write ros::ServiceClient client = n.serviceClient<gazebo_msgs::SetModelState>("/gazebo/set_model_state"); ? after that? i included #include "gazebo/SetModelState.h". when i do rosmake my_package i have error!
Maurizio88 gravatar image Maurizio88  ( 2012-02-08 01:09:56 -0500 )edit
Are you running diamondback or electric?
DimitriProsser gravatar image DimitriProsser  ( 2012-02-08 01:16:04 -0500 )edit
electric. actually, i have a lot of doubts about services. can i call the service /gazebo/set_model_state from my own package? is it the right way?
Maurizio88 gravatar image Maurizio88  ( 2012-02-08 01:21:42 -0500 )edit
You can call a service from anywhere. Did you include `<depend package="gazebo_msgs" />` in your manifest.xml?
DimitriProsser gravatar image DimitriProsser  ( 2012-02-08 01:30:50 -0500 )edit
yes, i dit it.
Maurizio88 gravatar image Maurizio88  ( 2012-02-08 01:36:36 -0500 )edit

Question Tools

Stats

Asked: 2012-02-08 00:32:57 -0500

Seen: 3,019 times

Last updated: Feb 09 '12