You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 

35 lines
2.0 KiB

<launch>
<arg name="map_yaml" doc="filepath to previously captured map (required)" />
<arg name="rviz" default="true" doc="whether to show Rviz" />
<arg name="gazebo_world" default="worlds/willowgarage.world" doc="the environment within which Stretch is loaded in Gazebo" />
<arg name="gazebo_gpu_lidar" default="false" doc="whether to compute lidar with hardware acceleration (requires GPU)" />
<arg name="gazebo_visualize_lidar" default="false" doc="whether to visualize planar lidar within Gazebo" />
<!-- GAZEBO SIMULATION -->
<include file="$(find stretch_gazebo)/launch/gazebo.launch">
<arg name="world" value="$(arg gazebo_world)" />
<arg name="visualize_lidar" value="$(arg gazebo_visualize_lidar)" />
<arg name="gpu_lidar" value="$(arg gazebo_gpu_lidar)" />
</include>
<!-- MAP SERVER -->
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_yaml)" />
<!-- LOCALIZATION -->
<include file="$(find amcl)/examples/amcl_diff.launch" />
<!-- NAVIGATION -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find stretch_navigation)/config/common_costmap_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find stretch_navigation)/config/common_costmap_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find stretch_navigation)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find stretch_navigation)/config/global_costmap_params_withmap.yaml" command="load" />
<rosparam file="$(find stretch_navigation)/config/base_local_planner_params.yaml" command="load" />
<remap from="/cmd_vel" to="/stretch_diff_drive_controller/cmd_vel" />
</node>
<!-- VISUALIZE -->
<node name="rviz" pkg="rviz" type="rviz" output="log" args="-d $(find stretch_navigation)/rviz/navigation.rviz" if="$(arg rviz)" />
</launch>