From: Erik Andresen Date: Sun, 30 Apr 2017 07:46:52 +0000 (+0200) Subject: navigation tuning X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_roboint.git;a=commitdiff_plain;h=7acbe5c94bea992956f981598ca7d8679c6456ca navigation tuning --- diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml index b4f0f06..b079e1b 100644 --- a/config/costmap_common_params.yaml +++ b/config/costmap_common_params.yaml @@ -2,4 +2,4 @@ obstacle_range: 2.5 raytrace_range: 3.0 #footprint: [[x0, y0], [x1, y1], ... [xn, yn]] robot_radius: 0.105 -inflation_radius: 0.15 +inflation_radius: 0.02 diff --git a/config/local_costmap_params.yaml b/config/local_costmap_params.yaml index f3cfe7c..f7d9d66 100644 --- a/config/local_costmap_params.yaml +++ b/config/local_costmap_params.yaml @@ -5,9 +5,9 @@ local_costmap: publish_frequency: 2.0 static_map: false rolling_window: true - width: 4.0 - height: 4.0 - resolution: 0.01 + width: 2.0 + height: 2.0 + resolution: 0.05 plugins: - {name: sonar, type: "range_sensor_layer::RangeSensorLayer"} - {name: inflation_layer, type: 'costmap_2d::InflationLayer'} diff --git a/scripts/robo_explorer.py b/scripts/robo_explorer.py index 83cc48b..56e07d1 100755 --- a/scripts/robo_explorer.py +++ b/scripts/robo_explorer.py @@ -31,8 +31,8 @@ class RoboExplorer: scan.header.stamp = current_time scan.header.frame_id = "forward_sensor" scan.radiation_type = 0 - scan.field_of_view = 60*pi/180 - scan.min_range = 0.0 + scan.field_of_view = 30*pi/180 + scan.min_range = 0.04 scan.max_range = 4.0 scan.range = msg.d1/100.0 self.pub_sonar.publish(scan)