From dfa22bff12a5c6e0685b3e79e681ccc1d0bd1fa1 Mon Sep 17 00:00:00 2001
From: Erik Andresen <erik@vontaene.de>
Date: Sat, 10 Jun 2017 18:08:31 +0200
Subject: [PATCH] no duplicate options in global_costmap_params_odom.yaml

---
 config/global_costmap_params_odom.yaml | 5 ++---
 config/wt_node.cfg                     | 2 +-
 launch/move_base.launch                | 2 +-
 3 files changed, 4 insertions(+), 5 deletions(-)

diff --git a/config/global_costmap_params_odom.yaml b/config/global_costmap_params_odom.yaml
index 6f3b2e8..0cb31e5 100644
--- a/config/global_costmap_params_odom.yaml
+++ b/config/global_costmap_params_odom.yaml
@@ -1,12 +1,11 @@
+# only differences to config/global_costmap_params.yaml
 global_costmap:
   global_frame: odom
-  robot_base_frame: base_footprint
-  update_frequency: 5.0
-  static_map: true
   rolling_window: true
   width: 100.0
   height: 100.0
   resolution: 1.0
+  resolution: 0.05
   plugins:
   - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
diff --git a/config/wt_node.cfg b/config/wt_node.cfg
index 15fb37c..725c565 100755
--- a/config/wt_node.cfg
+++ b/config/wt_node.cfg
@@ -5,7 +5,7 @@ from dynamic_reconfigure.parameter_generator_catkin import *
 gen = ParameterGenerator()
 
 gen.add("range_sensor_clip",	bool_t,		0, "Clip range sensor values to max range", True)
-gen.add("range_sensor_max",	double_t,	0, "Range sensor max range", 0.5, 0.4, 4)
+gen.add("range_sensor_max",	double_t,	0, "Range sensor max range", 0.5, 0.04, 4)
 gen.add("odom_covar_xy",	double_t,	0, "Odometry covariance: translation", 1e-2, 1e-6, 1)
 gen.add("odom_covar_angle",	double_t,	0, "Odometry covariance: rotation", 1.00, 1e-6, 6.2832)
 gen.add("rollover_protect",	bool_t,		0, "Enable motor rollover protection on pitch", True)
diff --git a/launch/move_base.launch b/launch/move_base.launch
index 9c6755d..c1320cb 100644
--- a/launch/move_base.launch
+++ b/launch/move_base.launch
@@ -40,7 +40,7 @@
 		<param name="controller_frequency" value="10.0" />
 		<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" unless="$(arg nomap)" />
+		<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 nomap)" />
 		<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" />
-- 
2.39.5