From 071eae4a1be7fa7da4bc89028424384315db19cf Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Sun, 20 Nov 2016 11:58:13 +0100 Subject: [PATCH] -reenable range layer -navigation/exploration tuning --- config/costmap_common_params.yaml | 7 ++++++- config/costmap_exploration.yaml | 8 +++++++- config/local_costmap_params.yaml | 7 +------ launch/move_base.launch | 4 ++-- 4 files changed, 16 insertions(+), 10 deletions(-) diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml index 02ff12d..674c1cc 100644 --- a/config/costmap_common_params.yaml +++ b/config/costmap_common_params.yaml @@ -7,4 +7,9 @@ obstacle_layer: laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true} inflation_layer: - inflation_radius: 0.5 + inflation_radius: 0.25 + +range_layer: + topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"] + no_readings_timeout: 1.0 + clear_on_max_reading: true diff --git a/config/costmap_exploration.yaml b/config/costmap_exploration.yaml index 6414e9b..6368563 100644 --- a/config/costmap_exploration.yaml +++ b/config/costmap_exploration.yaml @@ -3,7 +3,7 @@ global_frame: map robot_base_frame: base_footprint update_frequency: 5.0 publish_frequency: 5.0 -resolution: 0.01 +resolution: 0.05 rolling_window: false track_unknown_space: true @@ -13,6 +13,7 @@ plugins: - {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"} # 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: @@ -21,6 +22,11 @@ static_layer: # 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: false frontier_travel_point: middle diff --git a/config/local_costmap_params.yaml b/config/local_costmap_params.yaml index 62b586d..29fc1bc 100644 --- a/config/local_costmap_params.yaml +++ b/config/local_costmap_params.yaml @@ -10,10 +10,5 @@ local_costmap: resolution: 0.05 plugins: - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'} - #- {name: range_layer, type: "range_sensor_layer::RangeSensorLayer"} + - {name: range_layer, type: "range_sensor_layer::RangeSensorLayer"} - {name: inflation_layer, type: 'costmap_2d::InflationLayer'} - - range_layer: - topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"] - no_readings_timeout: 1.0 - clear_on_max_reading: true diff --git a/launch/move_base.launch b/launch/move_base.launch index 30f7ff1..102f98d 100644 --- a/launch/move_base.launch +++ b/launch/move_base.launch @@ -8,13 +8,13 @@ - + - + -- 2.39.2