[ros-users] Clearing cells in Costmap2DROS

Eitan Marder-Eppstein eitan at willowgarage.com
Wed Sep 29 16:59:46 UTC 2010


Sabrina,

A few questions that will help me understand your problem a little better:

1)  When you say that one PointCloud contains freespace information, do you
mean that it is just the unfiltered information from your sensor? Including
points on the ground? Is it generated from the same sensor as marking
information?

2) What kind of sensor are you using on your robot and how is it configured?
Is it a planar laser? An actuated sensor of some sort? Mounted pointed at
the ground? Etc.

3) Have you tried setting the minimum and maximum obstacle heights
differently for your clearing and marking sources? Typically, I'll be quite
liberal in setting the threshold on an observation source that clears}

Hope this helps,

Eitan

On Wed, Sep 29, 2010 at 7:32 AM, <sabrinakliegl at innok.de> wrote:

> Just an update:
>
> I am now using two point clouds as observation sources - one
> containing all points belonging to obstacles and the other containing
> freespace. With these settings (in costmap_common.yaml):
>
> observation_sources: obstacle_pcl free_pcl
>
> obstacle_pcl: {sensor_frame: base_link, data_type: PointCloud, topic:
> /obstacle_points, marking: true, clearing: false}
> free_pcl: {sensor_frame: base_link, data_type: PointCloud, topic:
> /free_points, marking: false, clearing: true}
>
> Again, the obstacles are marked correctly in the the costmap. But the
> cells of the costmap are not cleared with points from free_pcl...
>
> Any ideas how to clear the cells? Thank you in advance.
>
> Sabrina
>
> Zitat von sabrinakliegl at innok.de:
>
> > Hi,
> >
> > I am testing move_base with sensor data from our stereo vision sensor.
> > Thus, I have a PointCloud as observation source for the costmap. I
> > want to use the parameters ~<name>/max_obstacle_height (=0.7) and
> > ~<name>/<source_name>/min_obstacle_height (=0.05) to mark the
> > appropriate obstacles in the costmap - assuming that the costmap
> > considers values smaller than min_obstacle_height as ground (= free
> > space).
> >
> > This seems to work for a static environment generally. But as soon as
> > e.g. somebody walks through the picture, his trace is marked as
> > obstacle cells. After the person leaves the picture I would expect the
> > costmap to clear these cells, because the corresponding "z"-values
> > from the point cloud are less than min_obstacle_height. Instead the
> > cost map obviously ignores values smaller than min_obstacle_height.
> >
> > Is there any way to use the values smaller than min_obstacle_height to
> > clear the former obstacle cells?
> >
> > Regards,
> > Sabrina
> >
> >
> > _______________________________________________
> > ros-users mailing list
> > ros-users at code.ros.org
> > https://code.ros.org/mailman/listinfo/ros-users
> >
>
>
>
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100929/4846ea61/attachment-0003.html>


More information about the ros-users mailing list