X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Flocal_costmap_params.yaml;h=62b586d16818b9e558c9e7dfb60aff2179495784;hp=e247bead4ef1ffbd03de2538567336057a559e1c;hb=0bf5df6648a8d2ad791e2c0f95b83524eaded03a;hpb=9706b0b09528077ec0553f429fe4c4d2f5aa9f57 diff --git a/config/local_costmap_params.yaml b/config/local_costmap_params.yaml index e247bea..62b586d 100644 --- a/config/local_costmap_params.yaml +++ b/config/local_costmap_params.yaml @@ -5,14 +5,15 @@ local_costmap: publish_frequency: 2.0 static_map: false rolling_window: true - width: 10.0 - height: 10.0 + width: 3.0 + height: 3.0 resolution: 0.05 plugins: - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'} - #- {name: sonar_layer, type: "range_sensor_layer::RangeSensorLayer"} + #- {name: range_layer, type: "range_sensor_layer::RangeSensorLayer"} - {name: inflation_layer, type: 'costmap_2d::InflationLayer'} - sonar_layer: - topics: ["range_forward", "range_backward", "range_left", "range_right"] + range_layer: + topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"] no_readings_timeout: 1.0 + clear_on_max_reading: true