]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/global_costmap_params.yaml
Added full_coverage_path_planner launch file
[ros_wild_thumper.git] / config / global_costmap_params.yaml
index 5bb308db66f22f0b6c874f6d335bbc9f9d66f509..332d53341f77ae3becb2c199fe6e7add6897448f 100644 (file)
@@ -1,13 +1,16 @@
 global_costmap:
-  global_frame: /map
+  global_frame: map
   robot_base_frame: base_footprint
-  update_frequency: 5.0
-  static_map: true
+  publish_frequency: 1.0
   plugins:
   - {name: static_layer, type: 'costmap_2d::StaticLayer'}
+  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
   inflation_layer:
-    # low slope decay curve
-    inflation_radius: 1.75
-    cost_scaling_factor: 2.58
+    inflation_radius: 0.4 # plan distance around corners
+
+  obstacle_layer:
+    combination_method: 0 # overwrite
+    track_unknown_space: true
+    enabled: false