range_sensor_layer marks max sonar range as obstacle?
I'm using Gazebo to simulate a 4-wheeled differential drive robot. The robot has a forward sonar sensor, so I added a simulated sonar sensor.
The sonar sensor appears to work; it detects obstacles and the Range messages look correct (e.g. max range value when no obstacles). The visualization in Gazebo also looks correct.
I use the range_sensor_layer package as a plugin for costmap_2d
.
My issue is that for some reason, when there is no obstacle and the sonar sensor is at max range, the cost map registers an obstacle.
Below is a screenshot of Gazebo (left), Rviz (top right), and the echo'd Range message (bottom right). I rotated the vehicle in a circle without any obstacles, yet the costmap shows that the robot is surrounded by obstacles.
Now there's a parameter in range_sensor_layer
called clear_on_max_reading
, which will remove obstacles when a reading is max. However I've found that this does more harm than good, because it will clear away actual obstacles by accident.
For example, when it's navigating it runs along the wall and starts creating a wall of obstacles. Eventually it decides to turn, and as the range value maxes out, it clears a whole chunk of actual obstacle. Now there's a hole in the wall, so it tries to navigate towards the hole, and relearns that it's indeed an obstacle. This repeats forever. It's both funny and infuriating.
Here are the YAML files I'm using for my costmap:
costmap_common_params.yaml
map_type: costmap
origin_z: 0.0
z_resolution: 1
z_voxels: 2
obstacle_range: 0.5
raytrace_range: 0.5
footprint: [[-0.21, -0.165], [-0.21, 0.165], [0.21, 0.165], [0.21, -0.165]]
footprint_padding: 0.1
plugins:
- {name: sonar_layer, type: "range_sensor_layer::RangeSensorLayer"}
- {name: inflater_layer, type: "costmap_2d::InflationLayer"}
sonar_layer:
ns: ""
topics: ["/sonar"]
no_readings_timeout: 1.0
clear_threshold: 0.2
mark_threshold: 0.80
clear_on_max_reading: false
inflater_layer:
inflation_radius: 0.3
local_costmap_params.yaml
local_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 20.0
publish_frequency: 5.0
width: 10.0
height: 10.0
resolution: 0.05
static_map: false
rolling_window: true
global_costmap_params.yaml
global_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 20
publish_frequency: 5
width: 40.0
height: 40.0
resolution: 0.05
origin_x: -20.0
origin_y: -20.0
static_map: true
rolling_window: false
In my robot URDF I include the sonar_sensor macro and instantiate my sonar sensor like so:
<xacro:sonar_sensor name="sonar" parent="front_mount" ros_topic="sonar" update_rate="10" min_range="0.15" max_range="1.5" field_of_view="${10*PI/180}" ray_count="3" visualize="true">
<origin xyz="0.0 0 0.05" rpy="0 0 0"/>
</xacro:sonar_sensor>
I'm not sure what's going on here. I'd appreciate any help.