From 59f39a51a977ca93173e1074db0e7381a3d24e0d Mon Sep 17 00:00:00 2001
From: Erik Andresen <erik@vontaene.de>
Date: Sun, 16 Jul 2017 11:22:42 +0200
Subject: [PATCH] Use gps instead utm as gps frame

---
 ...stmap_params_utm.yaml => global_costmap_params_gps.yaml} | 2 +-
 launch/move_base.launch                                     | 6 +++---
 2 files changed, 4 insertions(+), 4 deletions(-)
 rename config/{global_costmap_params_utm.yaml => global_costmap_params_gps.yaml} (93%)

diff --git a/config/global_costmap_params_utm.yaml b/config/global_costmap_params_gps.yaml
similarity index 93%
rename from config/global_costmap_params_utm.yaml
rename to config/global_costmap_params_gps.yaml
index 8ecf0b5..fa54a35 100644
--- a/config/global_costmap_params_utm.yaml
+++ b/config/global_costmap_params_gps.yaml
@@ -1,6 +1,6 @@
 # only differences to config/global_costmap_params.yaml
 global_costmap:
-  global_frame: utm
+  global_frame: gps
   rolling_window: true
   width: 200.0
   height: 200.0
diff --git a/launch/move_base.launch b/launch/move_base.launch
index 69073a4..e64852e 100644
--- a/launch/move_base.launch
+++ b/launch/move_base.launch
@@ -2,7 +2,7 @@
 <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 -->
@@ -43,8 +43,8 @@
 		<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"/>
-- 
2.39.5