Browse Source

Navigation launch files comments tweak

pull/30/merge
Binit Shah 3 years ago
parent
commit
c9dd2e1619
2 changed files with 9 additions and 3 deletions
  1. +6
    -0
      stretch_navigation/launch/navigation.launch
  2. +3
    -3
      stretch_navigation/launch/navigation_gazebo.launch

+ 6
- 0
stretch_navigation/launch/navigation.launch View File

@ -3,16 +3,21 @@
<arg name="map_yaml" doc="filepath to previously captured map (required)" />
<arg name="rviz" default="true" doc="whether to show Rviz" />
<!-- STRETCH DRIVER -->
<param name="/stretch_driver/broadcast_odom_tf" type="bool" value="true"/>
<param name="/stretch_driver/mode" type="string" value="navigation" />
<include file="$(find stretch_core)/launch/stretch_driver.launch" pass_all_args="true"/>
<!-- LASER RANGE FINDER -->
<include file="$(find stretch_core)/launch/rplidar.launch" />
<!-- 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" />
@ -22,6 +27,7 @@
<remap from="/cmd_vel" to="/stretch/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>

+ 3
- 3
stretch_navigation/launch/navigation_gazebo.launch View File

@ -16,10 +16,10 @@
<!-- MAP SERVER -->
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_yaml)" />
<!-- AMCL -->
<!-- LOCALIZATION -->
<include file="$(find amcl)/examples/amcl_diff.launch" />
<!-- MOVE BASE -->
<!-- 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" />
@ -29,7 +29,7 @@
<remap from="/cmd_vel" to="/stretch_diff_drive_controller/cmd_vel" />
</node>
<!-- RVIZ -->
<!-- VISUALIZE -->
<node name="rviz" pkg="rviz" type="rviz" output="log" args="-d $(find stretch_navigation)/rviz/navigation.rviz" if="$(arg rviz)" />
</launch>

Loading…
Cancel
Save