]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/costmap_exploration.yaml
exploration tuning
[ros_wild_thumper.git] / config / costmap_exploration.yaml
index 26f38002682f8d61fe6b1917e7b57fd05dc66cbd..0f5bc4300aec73f1e88564d7b0bfe6dbf3a685d7 100644 (file)
@@ -1,20 +1,21 @@
 #must match incoming static map
 global_frame: map
-robot_base_frame: base_link
-resolution: 0.05
+robot_base_frame: base_footprint
+update_frequency: 5.0
+resolution: 0.01
 
-track_unknown_space: true
 rolling_window: false
+track_unknown_space: true
 
 plugins: 
-- {name: static,           type: "costmap_2d::StaticLayer"}            
+- {name: static_layer, type: 'costmap_2d::StaticLayer'}
 - {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"}
 #Can disable sensor layer if gmapping is fast enough to update scans
-- {name: sensor,           type: "costmap_2d::ObstacleLayer"}
-- {name: inflation,        type: "costmap_2d::InflationLayer"}
+- {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+- {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
 explore_boundary:
-  resize_to_boundary: false
+  resize_to_boundary: true
   frontier_travel_point: middle
   #set to false for gmapping, true if re-exploring a known area
-  explore_clear_space: false
+  explore_clear_space: true