]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/costmap_exploration.yaml
-reenable range layer
[ros_wild_thumper.git] / config / costmap_exploration.yaml
index 0f5bc4300aec73f1e88564d7b0bfe6dbf3a685d7..63685630a384cd62a8d03a2bfd64f966d3b0d831 100644 (file)
@@ -1,8 +1,9 @@
-#must match incoming static map
+# must match incoming static map
 global_frame: map
 robot_base_frame: base_footprint
 update_frequency: 5.0
-resolution: 0.01
+publish_frequency: 5.0
+resolution: 0.05
 
 rolling_window: false
 track_unknown_space: true
@@ -10,12 +11,24 @@ 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: 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
+
+range_layer:
+  topics: ["/range_forward", "/range_backward"]
+  no_readings_timeout: 1.0
+  clear_on_max_reading: 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