]> defiant.homedns.org Git - ros_wild_thumper.git/blob - config/costmap_exploration.yaml
pid tuning with fixes
[ros_wild_thumper.git] / config / costmap_exploration.yaml
1 #must match incoming static map
2 global_frame: map
3 robot_base_frame: base_link
4 resolution: 0.05
5
6 track_unknown_space: true
7 rolling_window: false
8
9 plugins: 
10 - {name: static,           type: "costmap_2d::StaticLayer"}            
11 - {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"}
12 #Can disable sensor layer if gmapping is fast enough to update scans
13 - {name: sensor,           type: "costmap_2d::ObstacleLayer"}
14 - {name: inflation,        type: "costmap_2d::InflationLayer"}
15
16 explore_boundary:
17   resize_to_boundary: false
18   frontier_travel_point: middle
19   #set to false for gmapping, true if re-exploring a known area
20   explore_clear_space: false