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

Different cmd_vel msgs to multiple robots on Gazebo

asked 2011-10-11 11:27:28 -0500

130s gravatar image

updated 2011-10-18 07:45:34 -0500

I'm trying to control multiple robots on Gazebo. Right now I'm using turtlebot for that purpose, and have succeeded in spawning multiple robots and making those robots move with the same/single /turtlebot_node/cmd_vel message so that all of them move in the same way.

However, I want to give different cmd_vel to each robot so that each one moves differently. Any idea would be appreciated. I know the topic in use is specified in turtlebot_gazebo_plugins/src/gazebo_ros_create.cpp, but still I haven't figured out how to apply to my purpose.

Turtlebot is preferred but other robots are fine too as long as they meet my request and teleop source code is available, since for now I'm only interested in controlling feature of robots. Also, though I prefer permanent solution, ad-hoc way is fine this time. Thanks.

How I am advertising a msg:

nodeHandleInstance_.advertise<geometry_msgs::Twist>("/turtlebot_node/cmd_vel", 1);

Environment: Ubuntu 11.04, ROS electric


Update 10/12/2011) Although I tried @karthikdesingh 's suggestion, I still can't control multiple robots separately, or I even can't control any robot with it unfortunately. Robot nodes successfully publish the separate messages with the namespace at the beginning of the topic name, but gazebo is not subscribing to any of them, which I suppose necessary (I'm not sure about this though), and instead it still subscribes to the normal /turtlebot_node/cmd_vel. Here's gazebo's subscription copied from rxgraph's side window (crowd{ 1, 2 } are the namespaces I assigned):

/gazebo
Subscriptions: 
 * /crowd1/set_update_rate [unknown type]
 * /gazebo/set_model_state [unknown type]
 * /gazebo/set_link_state [unknown type]
 * /crowd2/set_hfov [unknown type]
 * /crowd1/set_hfov [unknown type]
 * /clock [rosgraph_msgs/Clock]
 * /turtlebot_node/cmd_vel [unknown type]
 * /crowd2/set_update_rate [unknown type]

Now I'm wondering it might depend on the behavior of the node? Here's the code of the node: http://pastebin.com/7mNprFqu

Two .launch files in use (that are called from parent .launch file): http://pastebin.com/WKD2mBi6 and http://pastebin.com/GKDA4uMh


Update 10/18/2011) As in the comment area in the selected answer, I assume the root cause is that in the launch file I didn't surround the subscriber node by group tag.

edit retag flag offensive close merge delete

5 Answers

Sort by ยป oldest newest most voted
6

answered 2011-10-11 14:53:36 -0500

karthik gravatar image

updated 2011-10-12 19:05:14 -0500

As you are spawning the robots successfully, i think you can define namespace of each bot in the launch file separately. Having done this you should publish the cmd_vel to each bot with separate topics which get created according to their namespace in launch file. Below is example of launch file i used.

<launch>    
    <group ns="Robot">
        <node pkg="velocity_obstacle" name="rosaria" type="robot_node" output="screen">
        <param name="port" value="10.2.36.7"/>
        </node>
    </group>
    <group ns="Obstacle1">
        <node pkg="velocity_obstacle" name="rosaria" type="robot_node" output="screen">
        <param name="port" value="10.2.36.6"/>
        </node>
    </group>
</launch>

And publishers as below

robot_vel_pub = n.advertise<geometry_msgs::Twist>("Robot/rosaria/cmd_vel", 1000);
obs1_vel_pub = n.advertise<<geometry_msgs::Twist>("Obstacle1/rosaria/cmd_vel", 1000);

For the updated question: I guess the mistake is in the launch file. You have the param section and node section written separately (I don't know their significance here and their effects) in the following way

<group ns="XXX">
      <param xxxxxxxxxxxxxxxxx /> #param closed here
      <node xxxxxxxxxxxxxxxxxx /> #node closed here
      <node xxxxxxxxxxxxxxxxxx /> #node closed here
</group> #group closed here

If you want a param specific to a node then you should have something like the below

<group ns="XXX>
      <node xxxxxxxxxxxxxxxxxx> #node not closed here
      <param xxxxxxxxxxxxxxxxx /> #param closed here but still in node which is not closed
      </node> #node closed here
</group> #group closed here

Hope this helps a bit in debugging your issue. Though i am not sure if this is your problem.

edit flag offensive delete link more

Comments

@karthikdesingh thank you! Although it really looks good, I still don't get what I want as I updated the original question body.
130s gravatar image 130s  ( 2011-10-12 13:09:34 -0500 )edit
You are welcome. I updated my answer. Hope it helps. But i am not sure if that is what is wrong in your approach.
karthik gravatar image karthik  ( 2011-10-12 19:06:53 -0500 )edit
@karthikdesingh thanks. Doesn't the way you do publish a msg with redundancy like "Robot/Robot/rosaria/cmd_vel" ? That's what happens to me
130s gravatar image 130s  ( 2011-10-13 07:47:43 -0500 )edit
My structure is like this. I have a robot node which is rosaria. I instantiate 2 bots of rosaria using this launch file. I have a controlling node where i give the velocities to the instantiated bots using the mentioned publishers. I dont get the redundancy.
karthik gravatar image karthik  ( 2011-10-13 08:12:53 -0500 )edit
@karthikdesingh thanks. Parameter location might not be relevant looking at the result I'm seeing. I've been trying every possible combination of all related configurations but not good at all..
130s gravatar image 130s  ( 2011-10-13 11:33:44 -0500 )edit
Could you specify your structure like i did in my previous comment?
karthik gravatar image karthik  ( 2011-10-13 15:28:27 -0500 )edit
Thx for keeping the interest! I spawn 2 robots with the .launch files of which I pasted the links above, then run a new node of which the link of the code is also pasted. I've just realized I don't have a "robot node" in the .launch files, instead the nodes in those files are for spawning & sensors
130s gravatar image 130s  ( 2011-10-13 17:02:44 -0500 )edit
I feel any issues caused should be related to the launch file. Try doing just for a single robot whose namespace is changed by you to "crowd1". If you are able to correct it for this then you will be able to do it for 2 robots.
karthik gravatar image karthik  ( 2011-10-13 17:06:54 -0500 )edit
1

answered 2012-04-04 10:08:32 -0500

hsu gravatar image

similar to the previous answers, here is probably a very round-about example for you. First off, in gazebo controller manager plugin implementation, each controller plugin starts a rosnode with a custom robot namespace, i.e.:

this->rosnode_ = new ros::NodeHandle(this->robotNamespace);

So each robot has its own plugin with a uniquely namespaced rosnode.

To assign namespaces, I left the option to assign robot namespace as a model XML parameter to be parsed by the plugin, or optionally insert the parameter at time of spawning the robot (e.g. spawn_model -namespace xxx .... This should be done along with starting all the non-simulation controller nodes in grouped namespace as mentioned in other answers. As an overall example, please see this launch file.

Any suggestions to make this process cleaner and more scalable are welcome. Thanks!

edit flag offensive delete link more
0

answered 2012-08-14 08:00:18 -0500

maurizio gravatar image

Hi,

I can not spawn two turtlebots. I have looked through this post and others ([http://answers.ros.org/question/33981/multiple-turtlebots-in-gazebo/?answer=41388#post-id-41388]) but I can not see neither /odom nor /cmd_vel in different name spaces. Here follows one configuration file for one robot.

Thank you for the attention,

    <launch>

  <param name="robot1/robot_description" command="$(find xacro)/xacro.py '$(find turtlebot_description)/urdf/turtlebot.urdf.xacro'"/>

  <node name="spawn_turtlebot_model" pkg="gazebo" type="spawn_model" args="$(optenv ROBOT_INITIAL_POSE) -unpause -urdf -param robot_description -x 9 -y 5 -z 0.05 -model turtlebot1 -robot_namespace robot1" respawn="false" output="screen" ns="robot1"/>

  <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" ns="robot1" >
    <rosparam command="load" file="$(find turtlebot_bringup)/config/diagnostics.yaml" />
  </node>

  <node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher" output="screen" ns="robot1">
    <param name="publish_frequency" type="double" value="20.0" />
  </node>


  <!-- The odometry estimator -->

  <node ns="robot1" pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf1" >
    <param name="freq" value="30.0"/>
    <param name="sensor_timeout" value="1.0"/>
    <param name="publish_tf" value="true"/>
    <param name="odom_used" value="true"/>
    <param name="imu_used" value="false"/>
    <param name="vo_used" value="false"/>
    <param name="output_frame" value="odom"/>
    <param name="output_frame" value="odom" />
  </node>


  <!-- throttling -->
  <node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_manager" respawn="true" ns="robot1">
    <param name="max_rate" value="20.0"/>
    <remap from="cloud_in" to="/camera/depth/points"/>
    <remap from="cloud_out" to="cloud_throttled"/>
  </node>

  <!-- Fake Laser -->
  <node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true" ns="robot1">
    <param name="output_frame_id" value="/camera_depth_frame"/>
    <!-- heights are in the (optical?) frame of the kinect -->
    <param name="min_height" value="-0.15"/>
    <param name="max_height" value="0.15"/>
    <remap from="cloud" to="/cloud_throttled"/>
  </node>

  <!-- Fake Laser (narrow one, for localization -->
  <node pkg="nodelet" type="nodelet" name="kinect_laser_narrow" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true" ns="robot1">
    <param name="output_frame_id" value="/camera_depth_frame"/>
    <!-- heights are in the (optical?) frame of the kinect -->
    <param name="min_height" value="-0.025"/>
    <param name="max_height" value="0.025"/>
    <remap from="cloud" to="/cloud_throttled"/>
    <remap from="scan" to="/narrow_scan"/>
  </node>


</launch>
edit flag offensive delete link more

Comments

@maurizio why not open a new question (and refer to this thread from there) to get responses?

130s gravatar image 130s  ( 2012-08-16 20:02:07 -0500 )edit
1

In case somebody else still has the problem, I think I got a workaround: http://answers.ros.org/question/33981... (I am commenting here since I found both threads with the same question, not sure which one to post on)

Ana gravatar image Ana  ( 2012-11-25 14:59:11 -0500 )edit
0

answered 2020-08-18 19:48:16 -0500

yuril gravatar image

I know this is an old question, but if you struggle with this, just I did, maybe you need to comment the topics "commandTopic" and "odometryTopic" on your gazebo file. This way the group namespace will be valid, at least, this was the way I solved this problem on kinetic

edit flag offensive delete link more

Comments

Thank you... this solved my issue.... :)

Navid A Mulla gravatar image Navid A Mulla  ( 2021-05-30 12:18:11 -0500 )edit
0

answered 2011-10-11 14:26:03 -0500

joq gravatar image

You probably should run each simulated robot in its own namespace.

edit flag offensive delete link more

Comments

@joq thank you. I assume what you're proposing is the same with @karthikdesingh 's.
130s gravatar image 130s  ( 2011-10-12 13:16:23 -0500 )edit
Yes. There are several ways to start a node in a namespace, @karthikdsingh shows how to do it with `roslaunch`.
joq gravatar image joq  ( 2011-10-12 13:59:18 -0500 )edit

IssacSaito, did you resolve the problem mentioned above ? If then, could you post right solution ? I am going to follow your procedure in order to simulate multiple robot in gazebo, quadrotor and ground vehicle.

maruchi gravatar image maruchi  ( 2012-04-04 07:58:05 -0500 )edit

@maruchi I didn't succeed in this before I gave up using gazebo. One thing I should have done in order to analyze the situation better is to look at rxgraph and make sure there were enough number of the robot nodes that are supposed to receive the topic, and they actually received them.

130s gravatar image 130s  ( 2012-04-04 08:22:03 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2011-10-11 11:27:28 -0500

Seen: 3,995 times

Last updated: Aug 18 '20