Christian,

The persistence parameter keeps the obstacle in the costmap for X seconds no matter what clearing information is observed, and the marking sensor always takes precedence. If you've found the costmap behaves otherwise... its a bug, and you can file a ticket against me.

Hope all is well,

Eitan

On Mon, Jul 26, 2010 at 10:57 AM, Christian Verbeek <verbeek@servicerobotics.eu> wrote:
Dear Eitan,

Then the next question is: Who is stronger. The marking or the clearing sensor? When my IR sees an obstacle and I set observation_persistence=10 I would expect the obstacle to be in the costmap for at least 10s. Or does the clearing sensor remove the obstacle as soon as the dense point cloud is published? The same question applies to the laser clearing IR readings.

Regards
Christian

Am 26.07.2010 19:29, schrieb Eitan Marder-Eppstein:
Christian,

The reason that your IR sensors do not clear out of the costmap is that they are at a different height than the laser and you've chosen (implicitly by not setting the "map_type" parameter) to use a 3D voxel grid as your underlying map structure. So, the laser will never clear out IR hits because it lies strictly above them. Your IR sensors can clear out old hits, but with only 9 points to raytrace to... its quite likely that many old hits will not be seen through and thus are not safe to clear.

You have two options to clear these hits:

1) If you want your laser to be able to clear out hits from your IR sensors once they are no longer observed, you could switch to the "map_type" parameter to use "costmap": see http://www.ros.org/wiki/costmap_2d#Map_type_parameters. This will use a 2D representation of the world where everything is assumed to be on the same plane.

2) You can continue using the 3D voxel grid and write your own sensor that publishes a dense point cloud at the height of the IR sensors and is only used for clearing. This sensor could publish the cloud at whatever rate you want your IR hits to clear out.

Both of these options aren't strictly safe, consider the case where you see an object with IR, move a little bit, clear that object out, don't see it again, and hit it, but should probably help you do what you want.

Hope this helps,

Eitan

On Mon, Jul 26, 2010 at 6:34 AM, Christian Verbeek <verbeek@servicerobotics.eu> wrote:
Dear all,

my robot is equipped with a laser rangefinder and 9 infrared distances
sensors. The rangefinder is scanning at z=0.2 while the infrared sensors
are scanning at z=0.05. So it absolutely makes sense to put the readings
of the infrared sensors into the local costmap to avoid obstacles not
seen by the rangefinder.

I publish a point cloud with 9 points in it (the distances read from the
9 infrared sensors mapped to the base frame). The maximum range of the
infrared sensors is 0.4m.

My costmap_common_params.yaml look like this

observation_sources: laser_scan_sensor ir_sensors

laser_scan_sensor: {sensor_frame: laser_link, data_type: LaserScan,
topic: scan, marking: true, clearing: true}
ir_sensors: {sensor_frame: base_link, data_type: PointCloud, topic:
ir_sensors, marking: true, clearing: true, obstacle_range: 0.4,
raytrace_range: 0.4, observation_persistence: 0.0 }

The obstacles detected by the infrared sensors are correctly put into
the costmap. The problem is that the marker cells aren't cleared. So
when I move around my robot the robot is surrounded by occupied cells
and path planning does not work any more.

What can I do?

Regards
Christian


_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users

_______________________________________________ ros-users mailing list ros-users@code.ros.org https://code.ros.org/mailman/listinfo/ros-users


_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users