X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fcostmap_exploration.yaml;h=6414e9b6812d9f9c5d96caf2478cbdb1b212656e;hp=0f5bc4300aec73f1e88564d7b0bfe6dbf3a685d7;hb=e5d50b6babe986a2dcd4eff47a9600a6014e5d96;hpb=80b61518513631afbd8acdcab2b23a53266080ca diff --git a/config/costmap_exploration.yaml b/config/costmap_exploration.yaml index 0f5bc43..6414e9b 100644 --- a/config/costmap_exploration.yaml +++ b/config/costmap_exploration.yaml @@ -1,7 +1,8 @@ -#must match incoming static map +# must match incoming static map global_frame: map robot_base_frame: base_footprint update_frequency: 5.0 +publish_frequency: 5.0 resolution: 0.01 rolling_window: false @@ -10,12 +11,18 @@ track_unknown_space: true plugins: - {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 +# Can disable sensor layer if gmapping is fast enough to update scans - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'} - {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: true + 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: true