]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
no duplicate options in global_costmap_params_odom.yaml
authorErik Andresen <erik@vontaene.de>
Sat, 10 Jun 2017 16:08:31 +0000 (18:08 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 10 Jun 2017 16:08:31 +0000 (18:08 +0200)
config/global_costmap_params_odom.yaml
config/wt_node.cfg
launch/move_base.launch

index 6f3b2e8d9a1f2e16c11ed738a0b50764003c446f..0cb31e5b23384b639c07bb713c531bd88fe9166e 100644 (file)
@@ -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'}
index 15fb37c42da3b5be261da2109c98fe87f5853ab8..725c56519a73e35f89b248f0e0fa1ce020594eb2 100755 (executable)
@@ -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)
index 9c6755d01a66ed35711e20b0aefe6af19e26d08c..c1320cb074dc75a9660c32d8d46420e08003fd2a 100644 (file)
@@ -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" />