calling service from c++ code. /gazebo/set_model_state
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);