]> defiant.homedns.org Git - ros_wild_thumper.git/blob - config/costmap_exploration.yaml
christmas: fix stop time
[ros_wild_thumper.git] / config / costmap_exploration.yaml
1 # must match incoming static map
2 global_frame: map
3 robot_base_frame: base_footprint
4 update_frequency: 5.0
5 publish_frequency: 5.0
6 resolution: 0.05
7
8 rolling_window: false
9 track_unknown_space: true
10
11 plugins: 
12 - {name: static_layer, type: 'costmap_2d::StaticLayer'}
13 - {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"}
14 # Can disable sensor layer if gmapping is fast enough to update scans
15 - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
16 - {name: range_layer,   type: "range_sensor_layer::RangeSensorLayer"}
17 - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
18
19 static_layer:
20   # Can pull data from gmapping, map_server or a non-rolling costmap
21   map_topic: /map
22   # map_topic: move_base/global_costmap/costmap
23   subscribe_to_updates: true
24
25 explore_boundary:
26   resize_to_boundary: false
27   frontier_travel_point: middle
28   # set to false for gmapping, true if re-exploring a known area
29   explore_clear_space: false