X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fcostmap_exploration.yaml;h=84c88efd4e137b9993a1b3f08568377e93588739;hp=26f38002682f8d61fe6b1917e7b57fd05dc66cbd;hb=c1769fc7f88e8ce879c7a8a9308338eb0df14bd7;hpb=0bf5df6648a8d2ad791e2c0f95b83524eaded03a diff --git a/config/costmap_exploration.yaml b/config/costmap_exploration.yaml index 26f3800..84c88ef 100644 --- a/config/costmap_exploration.yaml +++ b/config/costmap_exploration.yaml @@ -1,20 +1,29 @@ -#must match incoming static map +# must match incoming static map global_frame: map -robot_base_frame: base_link +robot_base_frame: base_footprint +update_frequency: 5.0 +publish_frequency: 5.0 resolution: 0.05 -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"} +# Can disable sensor layer if gmapping is fast enough to update scans +- {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'} +- {name: range_layer, type: "range_sensor_layer::RangeSensorLayer"} +- {name: inflation_layer, type: 'costmap_2d::InflationLayer'} + +static_layer: + # Can pull data from gmapping, map_server or a non-rolling costmap + map_topic: /map + # map_topic: move_base/global_costmap/costmap + subscribe_to_updates: true explore_boundary: resize_to_boundary: false frontier_travel_point: middle - #set to false for gmapping, true if re-exploring a known area + # set to false for gmapping, true if re-exploring a known area explore_clear_space: false