Ask Your Question
0

range_sensor_layer marks max sonar range as obstacle?

asked 2016-06-28 16:15:03 -0600

triantatwo gravatar image

updated 2016-06-28 21:02:52 -0600

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.

image description

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.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-06-28 21:41:33 -0600

ahendrix gravatar image

You should check to see if your simulated sensors report a value greater than max range, or exactly max range when there is no obstacle within range, and compare that behavior to the code which handles maximum range: https://github.com/DLu/navigation_lay...

Ideally, if your sensor is reporting that there is no obstacle within range, there shouldn't be a costmap update for that sensor at all.

edit flag offensive delete link more

Comments

max_range=1.5 and range=1.5 .. judging by that code, it appears that there will be a call updateCostmap(1.5, false). Based off the behavior I'm seeing, it looks like that will update the costmap. I agree, perhaps processVariableRangeMsg should just return. I wonder why it doesn't?

triantatwo gravatar imagetriantatwo ( 2016-06-28 22:42:04 -0600 )edit

Might be a bug. You could look through the commit history and look at old pull requests against the package to see where that logic came from. You can also try modifying it to see if you can get the behavior you want, and submit your own pull request if it works.

ahendrix gravatar imageahendrix ( 2016-06-29 01:48:41 -0600 )edit

The solution was straight forward but the trick was knowing where to look. Thanks for your help, ahendrix. I've pushed a patch to my fork for the indigo branch: https://github.com/trianta2/navigatio...

triantatwo gravatar imagetriantatwo ( 2016-06-29 22:11:19 -0600 )edit

Hello, I need your help for something similar can you please check my question? http://answers.ros.org/question/32699... thanks

Syrine gravatar imageSyrine ( 2019-06-27 09:06:12 -0600 )edit

Your Answer

Please start posting anonymously - your entry will be published after you log in or create a new account.

Add Answer

Question Tools

2 followers

Stats

Asked: 2016-06-28 16:15:03 -0600

Seen: 2,182 times

Last updated: Jun 28 '16