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

Call gazebo/set_model_state without resetting position [closed]

asked 2014-06-30 15:28:11 -0500

K. Zeng gravatar image

Hi, everyone. I'm currently trying to use gazebo/set_model_state in a C++ program to set a robot's velocity. My preliminary code is below:

#include "ros/ros.h"
#include <gazebo_msgs/SetModelState.h>
#include <cstdlib>
//I'm going to implement user-specified twist values later.
int main (int argc, char **argv)
{
  ros::init(argc,argv,"robot_mover_mark_two");
  ros::NodeHandle n;
  ros::ServiceClient client = n.serviceClient<gazebo_msgs::SetModelState>("/gazebo/set_model_state");
  gazebo_msgs::SetModelState setmodelstate;
  gazebo_msgs::ModelState modelstate;
  modelstate.model_name = "my_robot";
  modelstate.reference_frame = "world";

  geometry_msgs::Twist model_twist;
  model_twist.linear.x = 1.0;
  model_twist.linear.y = 1.0;
  model_twist.linear.z = 0.0;
  model_twist.angular.x = 0.25;
  model_twist.angular.y = 0.0;
  model_twist.angular.z = 0.0;
  modelstate.twist = model_twist;

  setmodelstate.request.model_state = modelstate;

  if (client.call(setmodelstate))
  {
    ROS_INFO("BRILLIANT!!!");
    ROS_INFO("%f, %f",modelstate.pose.position.x,modelstate.pose.position.y);
  }  
  else
  {
    ROS_ERROR("Failed to call service ");
    return 1;
  }
  return 0;  
}

I noticed that every time I run the command, the robot's position is reset to the origin in the Gazebo simulation environment. Are the position parameters set to zero by default if I don't include them in the rosservice call? If so, are there any ways I can use this code and have the model stay in the current position?

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by K. Zeng
close date 2014-08-27 16:47:27.390757

1 Answer

Sort by ยป oldest newest most voted
1

answered 2014-07-16 10:55:45 -0500

jacobsolid gravatar image

Under fuerte, I ha the same problem, I diactivate the gravity from e GUI and used the follwing code:

ros::ServiceClient client = node_handle_.serviceClient<gazebo_msgs::SetModelState>("/gazebo/set_model_state"); 
 geometry_msgs::Pose start_pose;
start_pose.position.x = currPosel.x+0.01;
start_pose.position.y = currPosel.x+0.01;
start_pose.position.z = 1.0;
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 = 1.1;
start_twist.linear.y = 0;
start_twist.linear.z = 0;
start_twist.angular.x = 0.0;
start_twist.angular.y = 0.0;
start_twist.angular.z = 0.0;
//---------------------------------------------------------------------
gazebo_msgs::SetModelState setmodelstate;
gazebo_msgs::ModelState modelstate;
modelstate.model_name = "my_object"; 
modelstate.reference_frame = "world";
modelstate.twist = start_twist;
modelstate.pose = start_pose;
setmodelstate.request.model_state = modelstate;
if (client.call(setmodelstate))
{
  ROS_INFO("BRILLIANT!!!");
  ROS_INFO("%f, %f",modelstate.pose.position.x,modelstate.pose.position.y);
}
else
{
  ROS_ERROR("Failed to call service ");
  return 1;
}
return 0;
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-06-30 15:28:11 -0500

Seen: 2,654 times

Last updated: Jun 30 '14