]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - config/costmap_common_params.yaml
range sensor layer: Use inflate_cone=0 to fix range sensor clearing
[ros_wild_thumper.git] / config / costmap_common_params.yaml
index 566291241a7ace3e40b29f20fbe6bc3088a9d6a0..5ff675a3ef8ddba8bd90fe07fb5c6450e9ef4633 100644 (file)
@@ -4,12 +4,14 @@ obstacle_layer:
   observation_sources: laser_scan_sensor
   obstacle_range: 2.5
   raytrace_range: 3.0
-  laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true}
+  laser_scan_sensor: {data_type: LaserScan, topic: scan, marking: true, clearing: true}
 
 inflation_layer:
   inflation_radius: 0.20
 
 range_layer:
-  topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"]
+  topics: ["/range_forward_left", "/range_backward", "/range_forward_right"]
   no_readings_timeout: 1.0
   clear_on_max_reading: true
+  mark_threshold: 0.7
+  inflate_cone: 0.0