Files
mir_amr/mir_robot/mir_gazebo/launch/mir_gazebo_common.launch
2026-05-28 10:29:58 +07:00

72 lines
3.2 KiB
XML
Executable File

<?xml version="1.0" ?>
<launch>
<arg name="robot_x" default="0.0" />
<arg name="robot_y" default="0.0" />
<arg name="robot_yaw" default="0.0" />
<arg name="mir_type" default="mir_250" doc="The MiR variant. Can be 'mir_100' or 'mir_250' for now." />
<arg name="tf_prefix" default="" doc="tf_prefix to be used by gazebo plugins and in the robot's urdf etc." />
<arg name="prefix" value="$(arg tf_prefix)/" if="$(eval tf_prefix != '')" /> <!-- $(arg prefix) is used in all the config files! TODO: For multiple robots, create groups when loading the parameters to overwrite the arg? -->
<arg name="prefix" value="" unless="$(eval tf_prefix != '')" />
<arg name="model_name" default="mir" doc="Name of the Gazebo robot model (needs to be different for each robot)" />
<!-- Load URDF -->
<include file="$(find mir_description)/launch/upload_mir_urdf.launch">
<arg name="mir_type" value="$(arg mir_type)" />
<arg name="tf_prefix" value="$(arg tf_prefix)" />
</include>
<!-- Spawn the robot into Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model $(arg model_name)
-x $(arg robot_x) -y $(arg robot_y) -Y $(arg robot_yaw) " />
<!-- Load ros_control controller configurations -->
<rosparam file="$(find mir_description)/config/joint_state_controller.yaml" command="load" />
<rosparam file="$(find mir_description)/config/diffdrive_controller.yaml" command="load" subst_value="true" />
<!-- Start the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen"
args="joint_state_controller mobile_base_controller"/>
<!-- EKF -->
<include file="$(find mir_gazebo)/launch/includes/ekf.launch.xml">
<arg name="tf_prefix" value="$(arg prefix)" />
</include>
<!-- Add passive + mimic joints to joint_states topic -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<rosparam param="source_list">[mir/joint_states]</rosparam>
<param name="rate" value="200.0" />
</node>
<!-- Robot state publisher -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" />
<!-- Load teleop -->
<node name="rqt_robot_steering" pkg="rqt_robot_steering" type="rqt_robot_steering">
<param name="default_topic" value="cmd_vel"/>
<param name="default_vx_max" value="1.0" />
<param name="default_vx_min" value="-1.0" />
<param name="default_vw_max" value="1.5" />
<param name="default_vw_min" value="-1.5" />
</node>
<!-- create combined scan topic (like on real MiR) -->
<node pkg="topic_tools" type="relay" name="b_scan_relay" args="b_scan scan"/>
<node pkg="topic_tools" type="relay" name="f_scan_relay" args="f_scan scan"/>
<node name="b_rep117_laser_filter" pkg="mir_driver" type="rep117_filter.py" output="screen">
<remap from="scan" to="b_scan" />
<remap from="scan_filtered" to="b_scan_rep117" />
</node>
<node name="f_rep117_laser_filter" pkg="mir_driver" type="rep117_filter.py" output="screen">
<remap from="scan" to="f_scan" />
<remap from="scan_filtered" to="f_scan_rep117" />
</node>
</launch>