Costmap generation:3d to 2d projection

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Costmap generation:3d to 2d projection

valerylo
Hi Mathieu,
I am currently working with several ZED camera in order to generate a global costmap for a turtlebot. I would like to precisely understand how the 2d costmap is generated from the pointcloud (or the 3d map) in RTABmap.
I read this paper:
https://introlab.3it.usherbrooke.ca/mediawiki-introlab/images/7/7a/Labbe18JFR_preprint.pdf
that explain a lot, but not enough to understand this point.

I also played with the parameters of the node, in particular with: Grid: MaxObstacleHeight, but I am not totally sure about how it is defined and what it does.

i ask this question because I would like to ignore the obstacles higher than my robot. For exemple it should be able to go under a table. I already have good result but I would like to properly understand the algorithms behind to improve the map.
Reply | Threaded
Open this post in threaded view
|

Re: Costmap generation:3d to 2d projection

matlabbe
Administrator
Hi,

Figure 7 of the paper summarizes the approach:


As you are using a stereo camera, the pipeline by default is:
Grid/FromDepth=true
    |->Stereo disparity to point cloud 
        |->Filtering and ground segmentation
            |->Grid/3d=false
                |->Grid/RayTracing=False
                    |->2d local occupancy grid.

When doing:
$ rtabmap --params  | grep Grid/
you will see more specific parameters (e.g., noise filtering, footprint filtering) that were not shown in the paper. The segmentation approach explained in the paper, based on surface's normals, is selected by the parameter: Grid/NormalsSegmentation=True (default). If the robot is moving on a 2D plane, you may use a more simpler way to segment the ground and obstacles by setting Grid/NormalsSegmentation=False. For example, if you set:
Grid/NormalsSegmentation=False
Grid/MaxGroundHeight=0.03
Grid/MaxObstacleHeight=1
Everything below 3 cm is segmented as ground, and only obstacles between 3 cm and 1 meter are projected as obstacles in the 2d map. Others parameters you may play with are Grid/RangeMax (default 5 meters), which is the maximum range of the local occupancy grid, and Grid/CellSize (default 0.05 m), which is the grid's cell size.

We assume z=0 corresponds to /base_footprint frame of the robot.

Local occupancy grids are assembled depending on the pose graph into the global occupancy grid (Figure 8 of the paper).

cheers,
Mathieu