--- /dev/null
+# only differences to config/global_costmap_params.yaml
+global_costmap:
+ global_frame: gps
+ rolling_window: true
+ width: 200.0
+ height: 200.0
+ resolution: 0.10
+ plugins:
+ - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+ - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
+++ /dev/null
-# only differences to config/global_costmap_params.yaml
-global_costmap:
- global_frame: utm
- rolling_window: true
- width: 200.0
- height: 200.0
- resolution: 0.10
- plugins:
- - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
- - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
<launch>
<arg name="slam_gmapping" default="false" />
<arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
- <arg name="global_utm" default="false" />
+ <arg name="global_gps" default="false" />
<arg name="global_odom" default="false" />
<arg name="nomap" default="false" />
<arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
<rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
- <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg global_odm)" />
- <rosparam file="$(find wild_thumper)/config/global_costmap_params_utm.yaml" command="load" if="$(arg global_utm)" />
+ <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg global_odom)" />
+ <rosparam file="$(find wild_thumper)/config/global_costmap_params_gps.yaml" command="load" if="$(arg global_gps)" />
<rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />
<remap from="/cmd_vel" to="move_base/cmd_vel"/>