Understanding occupancy grid related parameters and concepts

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

Understanding occupancy grid related parameters and concepts

Jeonghwan Park
Hello Mathieu, grateful RTABMap user here.

First of all, i want to express my gratitude for open-sourcing such a competent package for everyone's use! My experiences confirm that RTABMap really is powerful in terms of both configurability and mapping/localization performance.

With that in mind, I wish to ask some questions about how to understand some parameters and concepts related to occupancy grids. My robot configuration includes a 2D lidar and RGB-D camera, and my goal is to create 2D occupancy grid map for navigation purposes.

1. About parameters "Grid/DepthDecimation" and "Grid/ScanDecimation". How does the decimation of RGB-D images and laser scans actually work, and what are their potential impacts on mapping/localization performance?

2. From my understanding, parameters such as "Grid/Footprint~", "Grid/MaxGroundAngle", "Grid/MaxGroundHeight" and "Grid/NormalsSegmentation" are valid only when RGB-D and/or 3D lidars participate in grid mapping. Is this correct?

3. When I set "Grid/Sensor" to 2, how are 2-D lidars and RGB-D cameras combined to formulate the grid map? Does the depth data from RGB-D cameras get projected to the ground to draw additional obstacles?

4. How can I best understand the "GridGlobal/ProbHit and ProbMiss" parameters?

5. I guess that "ICP/DownSamplingStep" and "ICP/VoxelSize" parameters are applied to original laser scans to be used for 2D lidar ICP odometry. Is this correct? And how can I best understand "Uniform Sampling" for scans?

6. Are the parameters with prefix "Mem/LaserScan" independent with similarly named parameters from Grid related parameters?

7. Is the parameter "RGBD/CreateOccupancyGrid" parameter unrelated with the "Grid/Sensor" parameter?

8. From my understanding, "Proximity detection" is a scan-matching based map matching technique where past scans are combined and compared with the current scan to establish connections between the current pose and the map. Is this correct?

9. About the "Reg/Strategy" parameter. Is this the switch for how to calculate the loop constraint? If a 2D lidar is available and this parameter is set to 1(ICP), Is the loop constraint calculated using scan matching instead of RGB-D data?

That was a lot of questions which demonstrates the configurability and versatility of RTABMap, I think! Mighty thanks for the development and support of RTABMap!
Reply | Threaded
Open this post in threaded view
|

Re: Understanding occupancy grid related parameters and concepts

matlabbe
Administrator
Hello, I hope my answers below will help you. We added many parameters over the years for every robot use cases that we came across. It can feel intimidating at first, thought it requires more often just tuning a parameter than changing code for a particular application.

Jeonghwan Park wrote
1. About parameters "Grid/DepthDecimation" and "Grid/ScanDecimation". How does the decimation of RGB-D images and laser scans actually work, and what are their potential impacts on mapping/localization performance?
They only impact the occupancy grid generation, not the trajectory/loop closures. For images, decimation is skipping ros/column of pixels, while for laser scan it skips a number of points of the scan. For example, decimation of image 640x480 by 2 will result in image 320x240 (actually 4 times less pixels). Decimation by 2 of a laser scan will result in half of the points. These parameters can be used to reduce processing power required to create the local occupancy grids.

Jeonghwan Park wrote
2. From my understanding, parameters such as "Grid/Footprint~", "Grid/MaxGroundAngle", "Grid/MaxGroundHeight" and "Grid/NormalsSegmentation" are valid only when RGB-D and/or 3D lidars participate in grid mapping. Is this correct?
Yes. With 2d laser scan, you can use Grid/RangeMin instead to ignore body parts.

Jeonghwan Park wrote
3. When I set "Grid/Sensor" to 2, how are 2-D lidars and RGB-D cameras combined to formulate the grid map? Does the depth data from RGB-D cameras get projected to the ground to draw additional obstacles?
Both depth image and 2d laser scans are converted into 3D point clouds (possibly doing ray tracing from their respective sensor pose if Grid/RayTracing is true). They are assembled together before being projected to the ground. See pictures here for examples: https://github.com/introlab/rtabmap_ros/issues/717#issuecomment-1040987765

Jeonghwan Park wrote
4. How can I best understand the "GridGlobal/ProbHit and ProbMiss" parameters?
You can read "OctoMap: An Efficient Probabilistic 3D Mapping Framework Based on Octrees". They don't explicitly talk about the values of these parameters, but you can also find them here in their code. We apply the same logic for 2D occupancy grid (rtabmap publishes a map called "/grid_prob_map" so you can see the probabilities instead of thresholded version empty/obstacle) while setting them to OctoMap when used for the 3D occupancy grid.

Jeonghwan Park wrote
5. I guess that "ICP/DownSamplingStep" and "ICP/VoxelSize" parameters are applied to original laser scans to be used for 2D lidar ICP odometry. Is this correct? And how can I best understand "Uniform Sampling" for scans?
They are used in ICP registration. Downsampling step is the same as scan decimation above. ICP/VoxelSize when not null will enable the Voxel Filter, using this approach: https://pcl.readthedocs.io/projects/tutorials/en/master/voxel_grid.html#voxelgrid (keeping only one point inside each virtual voxel of the size requested).

Jeonghwan Park wrote
6. Are the parameters with prefix "Mem/LaserScan" independent with similarly named parameters from Grid related parameters?
The filtering parameters for Grid and ICP are applied inside their algorithm, it won't affect the scan saved in the database. However, Mem/ related parameters are done before saving the scans, so also before Grid and ICP are done. For example, if Mem/LaserScanVoxelSize=0.05 is set and ICP/VoxelSize=0.05 is set, ICP will still try to voxel filter the scan to 5 cm even if it received it already at 5 cm voxel. An optimization is to set ICP/VoxelSize=0 to avoid filtering two times.

Jeonghwan Park wrote
7. Is the parameter "RGBD/CreateOccupancyGrid" parameter unrelated with the "Grid/Sensor" parameter?
RGBD/CreateOccupancyGrid is a flag to create local occupancy grids or not (for example, when we use RTAB-Map for only 3D hand-held scanning, we disable occupancy grid to save CPU). Grid/Sensor is a parameter used when creating a local grid.

Jeonghwan Park wrote
8. From my understanding, "Proximity detection" is a scan-matching based map matching technique where past scans are combined and compared with the current scan to establish connections between the current pose and the map. Is this correct?
Yes. It is best explained with pictures in Section 3.3 of this paper: Long-Term Online Multi-Session Graph-Based SPLAM with Memory Management. The biggest difference between "proximity detection" and "loop closure detection" is that the former uses odometry to compare only past data nearby to current pose for possible local loop closures.

Jeonghwan Park wrote
9. About the "Reg/Strategy" parameter. Is this the switch for how to calculate the loop constraint? If a 2D lidar is available and this parameter is set to 1(ICP), Is the loop constraint calculated using scan matching instead of RGB-D data?
Yes. However, for loop closure detection (not proximity detection), to know a first approximate guess between the nodes required for ICP, we still do a visual constraint estimation before doing the scan refinement. For proximity detection, as we have already a guess from odometry, we apply ICP directly.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Understanding occupancy grid related parameters and concepts

Jeonghwan Park
Can't thank enough for the outstanding support!
Agree wholesome on the "it requires more often just tuning a parameter than changing code" part.