59 lines
2.9 KiB
XML
59 lines
2.9 KiB
XML
<?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="robot_type" default="hool_150" doc="Can be 'hool_150' or 'imr' 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="robot" doc="Name of the Gazebo robot model (needs to be different for each robot)" />
|
|
|
|
|
|
<param name="rosconsole_config_file" value="$(find amr_startup)/rosconsole.config"/>
|
|
|
|
<!-- Load URDF -->
|
|
<include file="$(find robot_description)/launch/upload_urdf.launch">
|
|
<arg name="robot_type" value="$(arg robot_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)" output="screen" />
|
|
|
|
<!-- Load ros_control controller configurations -->
|
|
<rosparam file="$(find robot_description)/config/joint_state_controller.yaml" command="load" />
|
|
<rosparam file="$(find robot_description)/config/diffdrive_controller.yaml" command="load" subst_value="true" />
|
|
<rosparam file="$(find robot_description)/config/pid_gains.yaml" command="load" />
|
|
|
|
<!-- Start the controllers -->
|
|
<node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen"
|
|
args="joint_state_controller mobile_base_controller"/>
|
|
|
|
<!-- 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">[robot/joint_states]</rosparam>
|
|
<param name="rate" value="200.0" />
|
|
</node>
|
|
|
|
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" />
|
|
|
|
<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>
|
|
|
|
<!-- EKF -->
|
|
<include file="$(find amr_startup)/launch/includes/ekf.launch.xml">
|
|
<arg name="tf_prefix" value="$(arg prefix)" />
|
|
</include>
|
|
|
|
<!-- create combined scan topic (like on robot real) -->
|
|
<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"/>
|
|
|
|
</launch> |