yujinrobot / kobuki

Software for iClebo Kobuki
kobuki.yujinrobot.com
221 stars 176 forks source link

To simulate multiple Kobuki robots #409

Closed vyi closed 4 years ago

vyi commented 4 years ago

I am able to simulate and perform trajectory tracking oepration with single kobuki robot. Now I need to simulate 3 (or more) kobuki robots.

Here is my urdf file:


<?xml version="1.0"?>
<robot name="kobo" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find kobuki_description)/urdf/kobuki.urdf.xacro"/> 
<kobuki/>
</robot>

Here is the working (and relevant) launch file content

<param name="robot_description" command="$(find xacro)/xacro.py '$(find kobo)/description/urdf/kobo_robot.urdf.xacro'"/>

  <node name="bot_0" pkg="gazebo_ros" type="spawn_model"
        args="-x -5 -y 0 -z 0 -Y -0.0 -urdf -param robot_description -model mobile_base"/>

<!-- Velocity muxer -->
  <node pkg="nodelet" type="nodelet" name="mobile_base_nodelet_manager" args="manager"/>
  <node pkg="nodelet" type="nodelet" name="cmd_vel_mux"
        args="load yocs_cmd_vel_mux/CmdVelMuxNodelet mobile_base_nodelet_manager">
    <param name="yaml_cfg_file" value="$(find kobo)/params/mux.yaml" />
    <remap from="cmd_vel_mux/output" to="mobile_base/commands/velocity"/>
  </node>

The above file uses 2 nodelets which I don't fully understand. The second nodelet is for remapping names of certain topics (sorry limited understanding).

I need to run 3 instances of Kobuki robot. I did the following (used namespace to separate the robot topics):

<node name="bot_1" pkg="gazebo_ros" type="spawn_model"    args="-urdf -param robot_description -model mobile_base1 -x -2.0 -y 3.46410161514 -z 0 -Y 5.23598775598  -ns bot_1" />
<node name="bot_2" pkg="gazebo_ros" type="spawn_model"    args="-urdf -param robot_description -model mobile_base2 -x -2.0 -y -3.46410161514 -z 0 -Y 7.33038285838  -ns bot_2" />
<node name="bot_3" pkg="gazebo_ros" type="spawn_model"    args="-urdf -param robot_description -model mobile_base3 -x 4.0 -y -9.79717439318e-16 -z 0 -Y 9.42477796077  -ns bot_3" />

I see 3 robots loading in my gazebo gui, but there is only 1 odometry topic and velocity topic The idea is to get separate odometry topic for each robot and separate velocity input topic for each robot. I expected to get /mobile_base1/odom, /mobile_base2/odom, /mobile_base3/odom

Here is the output of rostopic list


/mobile_base/commands/motor_power
/mobile_base/commands/reset_odometry
/mobile_base/commands/velocity
/mobile_base/events/bumper
/mobile_base/events/cliff
/mobile_base/sensors/imu_data
/odom
/rosout
/rosout_agg
/tf

When I issue a twist message to /mobile_base/commands/velocity topic, all three robots react to it. I need to have separate topics (velocity control and odom) so that I can control them separately. Kindly help!

drjsmith commented 4 years ago

Are you running instances of the nodelets for each robot? If not, you should. Also, each robot needs a separate namespace, and all nodes for a robot should be run in that namespace. I didn't want to have to manually do that for each robot, so I wrote some launch files (included below) to take care of it for me in the case of a Turtlebot robot. The first file is basically a wrapper around the second (the implementation), allowing a robot to be created either in the 'main' namespace or in its own namespace. A fair bit is going on here, but you should be able to adapt them fairly easily to your use case.

(Disclaimer: it has been a while since I have tested these, but they worked in the past)

<!-- gazebo_robot_spawner.launch-->
<!-- This launch file spawns a turtlebot into gazebo and starts up all necessary nodes -->

<launch>
  <arg name="base"      default="$(optenv TURTLEBOT_BASE kobuki)"/> <!-- create, roomba -->
  <arg name="stacks"    default="$(optenv TURTLEBOT_STACKS hexagons)"/>  <!-- circles, hexagons --> 
  <arg name="3d_sensor" default="$(optenv TURTLEBOT_3D_SENSOR kinect)"/>  <!-- kinect, asus_xtion_pro --> 

  <arg name="index"     default="-1"/>
  <arg name="multi"     default="$(eval index > -1)"/>

  <arg name="robot_name" default="robot" unless="$(arg multi)"/>
  <arg name="robot_name" default="robot$(arg index)" if="$(arg multi)"/>

  <arg name="namespace" default="$(arg robot_name)"/>
  <arg name="tf_prefix" default="" unless="$(arg multi)"/>/>
  <arg name="tf_prefix" default="$(arg namespace)" if="$(arg multi)"/>/>

  <arg name="x" default="0"/>
  <arg name="y" default="0"/>
  <arg name="z" default="0"/>
  <arg name="roll" default="0"/>
  <arg name="pitch" default="0"/>
  <arg name="yaw" default="0"/>

  <group unless="$(arg multi)">
    <include file="$(find multi_robot_gazebo)/launch/includes/spawner_impl.launch">
        <arg name="base" value="$(arg base)"/>
        <arg name="stacks" value="$(arg stacks)"/>
        <arg name="3d_sensor" value="$(arg 3d_sensor)"/>

        <arg name="robot_name" value="$(arg robot_name)"/>
        <arg name="tf_prefix" value="$(arg tf_prefix)"/>

        <arg name="x" value="$(arg x)"/>
        <arg name="y" value="$(arg y)"/>
        <arg name="z" value="$(arg z)"/>
        <arg name="roll" value="$(arg roll)"/>
        <arg name="pitch" value="$(arg pitch)"/>
        <arg name="yaw" value="$(arg yaw)"/>
    </include>

  </group>

  <group ns="$(arg namespace)" if="$(arg multi)">
    <include file="$(find multi_robot_gazebo)/launch/includes/spawner_impl.launch">
        <arg name="base" value="$(arg base)"/>
        <arg name="stacks" value="$(arg stacks)"/>
        <arg name="3d_sensor" value="$(arg 3d_sensor)"/>

        <arg name="robot_name" value="$(arg robot_name)"/>
        <arg name="tf_prefix" value="$(arg tf_prefix)"/>

        <arg name="x" value="$(arg x)"/>
        <arg name="y" value="$(arg y)"/>
        <arg name="z" value="$(arg z)"/>
        <arg name="roll" value="$(arg roll)"/>
        <arg name="pitch" value="$(arg pitch)"/>
        <arg name="yaw" value="$(arg yaw)"/>
    </include>

  </group>

</launch>
<!-- multi_robot_gazebo/launch/includes/spawner_impl.launch-->
<launch>
  <arg name="base" /> <!-- create, roomba -->
  <arg name="stacks" />  <!-- circles, hexagons --> 
  <arg name="3d_sensor" />  <!-- kinect, asus_xtion_pro --> 

  <arg name="robot_name"/>
  <arg name="tf_prefix"/>

  <arg name="x" default="0"/>
  <arg name="y" default="0"/>
  <arg name="z" default="0"/>
  <arg name="roll" default="0"/>
  <arg name="pitch" default="0"/>
  <arg name="yaw" default="0"/>

  <param name="robot_name" value="$(arg robot_name)"/>

  <arg name="urdf_file" default="$(find xacro)/xacro.py '$(find turtlebot_description)/robots/$(arg base)_$(arg stacks)_$(arg 3d_sensor).urdf.xacro'" />
  <param name="robot_description" command="$(arg urdf_file)" />

  <!-- Gazebo model spawner -->
  <node name="spawn_turtlebot_model" pkg="gazebo_ros" type="spawn_model"
        args="-x $(arg x) -y $(arg y) -z $(arg z) -R $(arg roll) -P $(arg pitch) -Y $(arg yaw) -unpause -urdf -param robot_description -model $(arg robot_name)"/>

  <!-- Velocity muxer -->
  <node pkg="nodelet" type="nodelet" name="mobile_base_nodelet_manager" args="manager"/>
  <node pkg="nodelet" type="nodelet" name="cmd_vel_mux"
        args="load yocs_cmd_vel_mux/CmdVelMuxNodelet mobile_base_nodelet_manager">
    <param name="yaml_cfg_file" value="$(find turtlebot_bringup)/param/mux.yaml" />
    <remap from="cmd_vel_mux/output" to="mobile_base/commands/velocity"/>
  </node>

  <!-- Bumper/cliff to pointcloud (not working, as it needs sensors/core messages) -->
  <include file="$(find turtlebot_bringup)/launch/includes/kobuki/bumper2pc.launch.xml"/>

  <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
    <param name="tf_prefix" value="$(arg tf_prefix)" />
  </node>

  <!-- Fake laser -->
  <node pkg="nodelet" type="nodelet" name="laserscan_nodelet_manager" args="manager"/>
  <node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan"
        args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet laserscan_nodelet_manager">
    <param name="scan_height" value="10"/>
    <param name="output_frame_id" value="/camera_depth_frame"/>
    <param name="range_min" value="0.45"/>
    <remap from="image" to="/camera/depth/image_raw"/>
    <remap from="scan" to="/scan"/>
  </node>

</launch>
vyi commented 4 years ago

@drjsmith Thank you so much! I was able to make it work using the \<group> tag and namespace separation suggested by you.