launching multiple robots in gazebo
Hi all,
I had a bit of problem launching two robots in gazebo; as the answers on the internet usually did not provide their final launch files to help other people, I am just posting the answer with my files here to help other people. ( So this is not a question :) ) The point for having multiple robots in Gazebo is in using namespaces properly. We also use tf_prefix to make the transforms work properly. This is my launch file that I could launch two same robots with it on Gazebo (I believe it should be okay for different robots as well, although I have not tried it).
<launch>
<!-- args-->
<arg name="rvizconfig" default="$(find mobile_manipulator_description)/rviz/urdf_final.rviz"/>
<arg name="model" default="$(find mobile_manipulator_description)/urdf/mm_mico_final.urdf.xacro"/>
<arg name="gui" default="true"/>
<arg name="paused" default="true"/>
<arg name="use_sim_time" default="true"/>
<arg name="debug" default="false"/>
<arg name="headless" default="false"/>
<arg name="manipulator" default="m1n6s300"/>
<arg name="manipulator_control_type" default="effort"/> <!-- position, velocity or effort-->
<arg name="world_file" default="$(find avatar_gazebo)/worlds/avatar.world"/>
<!-- Include files-->
<!-- gazebo-->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
<arg name="world_name" value="$(arg world_file)"/>
</include>
<!-- nodes for running the system-->
<node name="camera_tf" pkg="tf2_ros" type="static_transform_publisher" args="0.025 0 0.95 -1.5705 0 -1.905 odom camera_link"/>
<node name="mico_odom_tf" pkg="tf2_ros" type="static_transform_publisher" args="0 0 0 0 0 0 odom mico/odom"/>
<node name="mico2_odom_tf" pkg="tf2_ros" type="static_transform_publisher" args="0 0 0 0 0 0 odom mico2/odom"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true"/>
<!-- mobile manipulator groups -->
<group ns="mico">
<param name="robot_description" command="$(find xacro)/xacro $(arg model)"/>
<param name="tf_prefix" value="mico"/>
<rosparam command="load" file="$(find mobile_manipulator_description)/config/kinova_$(arg manipulator_control_type)_control_mico_final.yaml" />
<!-- nodes-->
<node name="$(arg manipulator)_joints_controller" pkg="controller_manager" type="spawner" respawn="false"
output="screen"
args="--namespace=/mico
joint_1_$(arg manipulator_control_type)_controller joint_2_$(arg manipulator_control_type)_controller joint_3_$(arg manipulator_control_type)_controller
joint_4_$(arg manipulator_control_type)_controller joint_5_$(arg manipulator_control_type)_controller joint_6_$(arg manipulator_control_type)_controller
finger_2_position_controller finger_1_position_controller finger_3_position_controller
finger_tip_1_position_controller finger_tip_2_position_controller finger_tip_3_position_controller
joint_state_controller_manipulator"/>
<node name="robot_state_publisher_mobilerobot" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/mico/joint_states"/>
</node>
<!-- Spawning the model-->
<node name="robot1_urdf_spawner" pkg="gazebo_ros" type="spawn_model" args="-z 0.5 -x 1 -y 1 -unpause -urdf -model robot1 -param robot_description" respawn="false" output="screen"/>
</group>
<group ns="mico2">
<param name="robot_description" command="$(find xacro)/xacro $(arg model)"/>
<param name="tf_prefix" value="mico2"/>
<rosparam command="load" file="$(find mobile_manipulator_description)/config/kinova_$(arg manipulator_control_type)_control_mico_final.yaml" />
<!-- nodes-->
<node name ...