1. 配置launch文件
gazebo的加载相对容易,但rviz中加载,需要构建完整的tf树(world → map(或map_merged)→ odom → base_footprint → base_link → base_scan)才能正常显示,launch文件主要是在构建tf树。
<launch>
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="first_tb3" default="tb3_0"/>
<arg name="second_tb3" default="tb3_1"/>
<arg name="third_tb3" default="tb3_2"/>
<arg name="first_tb3_x_pos" default="-7.0"/>
<arg name="first_tb3_y_pos" default="-1.0"/>
<arg name="first_tb3_z_pos" default=" 0.0"/>
<arg name="first_tb3_yaw" default=" 1.57"/>
<arg name="second_tb3_x_pos" default=" 7.0"/>
<arg name="second_tb3_y_pos" default="-1.0"/>
<arg name="second_tb3_z_pos" default=" 0.0"/>
<arg name="second_tb3_yaw" default=" 1.57"/>
<arg name="third_tb3_x_pos" default=" 0.5"/>
<arg name="third_tb3_y_pos" default=" 3.0"/>
<arg name="third_tb3_z_pos" default=" 0.0"/>
<arg name="third_tb3_yaw" default=" 0.0"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find turtlebot3_gazebo)/worlds/turtlebot3_house.world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<group ns = "$(arg first_tb3)">
<arg name="robot_name" default="$(arg first_tb3)"/>
<arg name="tf_prefix" value="$(arg robot_name)"/>
<param name="robot_description" command="$(find xacro)/xacro $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro tf_prefix:=$(arg robot_name)" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" value="$(arg first_tb3)" />
</node>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf -model $(arg first_tb3) -x $(arg first_tb3_x_pos) -y $(arg first_tb3_y_pos) -z $(arg first_tb3_z_pos) -Y $(arg first_tb3_yaw) -param robot_description" />
<!-- TF 变换:从融合地图到机器人局部地图 -->
<node pkg="tf" type="static_transform_publisher" name="map_merged_to_robot1_map"
args="$0 0 0 0 0 0 map_merged $(arg tf_prefix)/map 100" />
<node pkg="tf" type="static_transform_publisher" name="robot1_map_to_robot1_odom"
args="$0 0 0 0 0 0 $(arg tf_prefix)/map $(arg tf_prefix)/odom 100" />
</group>
<group ns = "$(arg second_tb3)">
<arg name="robot_name" default="$(arg second_tb3)"/>
<arg name="tf_prefix" value="$(arg robot_name)"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro tf_prefix:=$(arg robot_name)" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" value="$(arg second_tb3)" />
</node>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf -model $(arg second_tb3) -x $(arg second_tb3_x_pos) -y $(arg second_tb3_y_pos) -z $(arg second_tb3_z_pos) -Y $(arg second_tb3_yaw) -param robot_description" />
<!-- TF 变换:从融合地图到机器人局部地图 -->
<node pkg="tf" type="static_transform_publisher" name="map_merged_to_robot2_map"
args="$0 0 0 0 0 0 map_merged $(arg tf_prefix)/map 100" />
<node pkg="tf" type="static_transform_publisher" name="robot2_map_to_robot2_odom"
args="$0 0 0 0 0 0 $(arg tf_prefix)/map $(arg tf_prefix)/odom 100" />
</group>
<group ns = "$(arg third_tb3)">
<arg name="robot_name" default="$(arg third_tb3)"/>
<arg name="tf_prefix" value="$(arg robot_name)"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro tf_prefix:=$(arg robot_name)" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" value="$(arg third_tb3)" />
</node>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf -model $(arg third_tb3) -x $(arg third_tb3_x_pos) -y $(arg third_tb3_y_pos) -z $(arg third_tb3_z_pos) -Y $(arg third_tb3_yaw) -param robot_description" />
<!-- TF 变换:从融合地图到机器人局部地图 -->
<node pkg="tf" type="static_transform_publisher" name="map_merged_to_robot3_map"
args="$0 0 0 0 0 0 map_merged $(arg tf_prefix)/map 100" />
<node pkg="tf" type="static_transform_publisher" name="robot3_map_to_robot3_odom"
args="$0 0 0 0 0 0 $(arg tf_prefix)/map $(arg tf_prefix)/odom 100" />
</group>
<node pkg="tf" type="static_transform_publisher" name="world_to_map_merged" args="0 0 0 0 0 0 world map_merged 100" />
<!-- 启动RViz -->
<node pkg="rviz" type="rviz" name="rviz" required="true" args="-d $(find multi_robot)/config/multi_robot.rviz"/>
</launch>
2. 修改urdf模型
nano ~/catkin_ws/src/turtlebot3/turtlebot3_description/urdf/turtlebot3_waffle_pi.gazebo.xacro
为各机器人增加tb3/odom->tb3/base_footprint的tf映射,防止odom->base_footprint全局tf映射。
<gazebo>
<plugin name="turtlebot3_waffle_pi_controller" filename="libgazebo_ros_diff_drive.so">
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>$(arg tf_prefix)/odom</odometryTopic>
<odometryFrame>$(arg tf_prefix)/odom</odometryFrame>
<odometrySource>world</odometrySource>
<publishOdomTF>true</publishOdomTF>
<robotBaseFrame>$(arg tf_prefix)/base_footprint</robotBaseFrame>
<publishWheelTF>false</publishWheelTF>
<publishTf>true</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<legacyMode>false</legacyMode>
<updateRate>30</updateRate>
<leftJoint>wheel_left_joint</leftJoint>
<rightJoint>wheel_right_joint</rightJoint>
<wheelSeparation>0.287</wheelSeparation>
<wheelDiameter>0.066</wheelDiameter>
<wheelAcceleration>1</wheelAcceleration>
<wheelTorque>10</wheelTorque>
<rosDebugLevel>na</rosDebugLevel>
</plugin>
</gazebo>
3. 执行
roslaunch turtlebot3_gazebo multi_turtlebot3_rviz.launch