mirror of
https://github.com/ROBOTIS-GIT/turtlebot3_simulations.git
synced 2025-09-15 13:08:35 +08:00
65 lines
3.1 KiB
XML
65 lines
3.1 KiB
XML
<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)">
|
|
<param name="robot_description" command="$(find xacro)/xacro.py $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro" />
|
|
|
|
<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" />
|
|
</group>
|
|
|
|
<group ns = "$(arg second_tb3)">
|
|
<param name="robot_description" command="$(find xacro)/xacro.py $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro" />
|
|
|
|
<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" />
|
|
</group>
|
|
|
|
<group ns = "$(arg third_tb3)">
|
|
<param name="robot_description" command="$(find xacro)/xacro.py $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro" />
|
|
|
|
<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" />
|
|
</group>
|
|
|
|
</launch>
|