introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.81k stars 788 forks source link

Modify the measurement range of Realsense D435 #414

Closed MattixLee closed 5 years ago

MattixLee commented 5 years ago

Hi, thank you for your work! I used RTAB-Map to map the scene, original pointclouds is shown in picture. It contains a lot of noise pointclouds. I found the following reasons for noise pointclouds, 1、The radiated noise point cloud in the image is a reconstructed remote scene. 2、Due to the strong ground reflection, the reflection of other objects on the ground becomes a noise point cloud in reconstruction.

For the first reason, I think part of the noise can be reduced by narrowing the measurement range of realsense d435, but I did not find how to modify the value. Point cloud filters can remove most of the noise pointclouds, it also would affect the scene we need.

For the second reason, because I need to reconstruct the ground, at present, only filtering methods can be used.

Could you help me solve this problem? Cheers, Lee 1

matlabbe commented 5 years ago

Is it the cloud from cloud_map topic, or a cloud generated with export action in rtabmapviz? For the first one, look at the "Grid/" parameters:

$ rtabmap --params | grep Grid/
Param: Grid/3D = "false"                                   [A 3D occupancy grid is required if you want an OctoMap (3D ray tracing). Set to false if you want only a 2D map, the cloud will be projected on xy plane. A 2D map can be still generated if checked, but it requires more memory and time to generate it. Ignored if laser scan is 2D and "Grid/FromDepth" is false.]
Param: Grid/CellSize = "0.05"                              [Resolution of the occupancy grid.]
Param: Grid/ClusterRadius = "0.1"                          [[Grid/NormalsSegmentation=true] Cluster maximum radius.]
Param: Grid/DepthDecimation = "4"                          [[Grid/DepthDecimation=true] Decimation of the depth image before creating cloud. Negative decimation is done from RGB size instead of depth size (if depth is smaller than RGB, it may be interpolated depending of the decimation value).]
Param: Grid/DepthRoiRatios = "0.0 0.0 0.0 0.0"             [[Grid/FromDepth=true] Region of interest ratios [left, right, top, bottom].]
Param: Grid/FlatObstacleDetected = "true"                  [[Grid/NormalsSegmentation=true] Flat obstacles detected.]
Param: Grid/FootprintHeight = "0.0"                        [Footprint height used to filter points over the footprint of the robot. Footprint length and width should be set.]
Param: Grid/FootprintLength = "0.0"                        [Footprint length used to filter points over the footprint of the robot.]
Param: Grid/FootprintWidth = "0.0"                         [Footprint width used to filter points over the footprint of the robot. Footprint length should be set.]
Param: Grid/FromDepth = "true"                             [Create occupancy grid from depth image(s), otherwise it is created from laser scan.]
Param: Grid/GroundIsObstacle = "false"                     [[Grid/3D=true] Ground segmentation (Grid/NormalsSegmentation) is ignored, all points are obstacles. Use this only if you want an OctoMap with ground identified as an obstacle (e.g., with an UAV).]
Param: Grid/MapFrameProjection = "false"                   [Projection in map frame. On a 3D terrain and a fixed local camera transform (the cloud is created relative to ground), you may want to disable this to do the projection in robot frame instead.]
Param: Grid/MaxGroundAngle = "45"                          [[Grid/NormalsSegmentation=true] Maximum angle (degrees) between point's normal to ground's normal to label it as ground. Points with higher angle difference are considered as obstacles.]
Param: Grid/MaxGroundHeight = "0.0"                        [Maximum ground height (0=disabled). Should be set if "Grid/NormalsSegmentation" is false.]
Param: Grid/MaxObstacleHeight = "0.0"                      [Maximum obstacles height (0=disabled).]
Param: Grid/MinClusterSize = "10"                          [[Grid/NormalsSegmentation=true] Minimum cluster size to project the points.]
Param: Grid/MinGroundHeight = "0.0"                        [Minimum ground height (0=disabled).]
Param: Grid/NoiseFilteringMinNeighbors = "5"               [Noise filtering minimum neighbors.]
Param: Grid/NoiseFilteringRadius = "0.0"                   [Noise filtering radius (0=disabled). Done after segmentation.]
Param: Grid/NormalK = "20"                                 [[Grid/NormalsSegmentation=true] K neighbors to compute normals.]
Param: Grid/NormalsSegmentation = "true"                   [Segment ground from obstacles using point normals, otherwise a fast passthrough is used.]
Param: Grid/PreVoxelFiltering = "true"                     [Input cloud is downsampled by voxel filter (voxel size is "Grid/CellSize") before doing segmentation of obstacles and ground.]
Param: Grid/RangeMax = "5.0"                               [Maximum range from sensor. 0=inf.]
Param: Grid/RangeMin = "0.0"                               [Minimum range from sensor.]
Param: Grid/RayTracing = "false"                           [Ray tracing is done for each occupied cell, filling unknown space between the sensor and occupied cells. If Grid/3D=true, RTAB-Map should be built with OctoMap support, otherwise 3D ray tracing is ignored.]
Param: Grid/Scan2dUnknownSpaceFilled = "false"             [Unknown space filled. Only used with 2D laser scans. Use Grid/RangeMax to set maximum range if laser scan max range is to set.]
Param: Grid/ScanDecimation = "1"                           [[Grid/FromDepth=false] Decimation of the laser scan before creating cloud.]

You could try to start with Grid/RangeMax parameter. You could filter the cloud based on height with Grid/MaxObstacleHeight. For fine tuning, Grid/NoiseFiltering* parameters could also be used.

If you are exporting with the GUI, similar options can be enabled in the Export panel.

cheers, Mathieu

MattixLee commented 5 years ago

Hi, Mathieu,

Thank you for your reply! I am using RTAB-Map(standalone) with realsense d435i , reconstructed pointclouds are shown in picture. The red-marked part of the image is the reconstructed remote scene, these pointclouds were noise for the scene that I wanted to reconstruct, so I did not want to reconstruct remote scene, it could improve the equality of mapping

I set Grid/RangeMax by rtabmap --Grid/RangeMax 0.5, the scene in the distance (> 0.5m) is still rebuilt, the pointclous that the scene in the distance (> 0.5m) generated would be noise pointclouds. Modification of parameter values has no effect on reconstructed point clouds,If my operation process is incomplete, please tell me the complete process.

My idea is whether we can't reconstruct the distant scene, scenes in the range are displayed only in the 3D map window, so the noise pointclouds would decrease.

In the depth image, the pixel value outside the range is set to 0. I think The reconstructed point cloud does not contain distant scenes (> 0.5m).
Inked1_LI

matlabbe commented 5 years ago

For the 3D Map view, parameters to adjust how clouds are generated are in Preferences -> 3D Rendering panel. For example under Map column, you can change Maximum Depth parameter. Note that those parameters can be also found in the "Export 3D clouds" dialog when clicking on "Regenerate clouds" and "Noise filtering" checkboxes, otherwise clouds from the 3D Map view are assembled directly.

cheers, Mathieu

MattixLee commented 5 years ago

Hi,Mathieu

Thank you very much for your patient answer! Your work (rtabmap) is so powerful.

3D cloud maximum depth in Regenerate clouds panel could effectively reduce the noise generated by remote scenes, I think this parameter should remove point clouds larger than 2 m from D435 while mapping(if the parameter value is set to 2m).I don't know if it is correct.

In first figure, the parameter of 2m . In second figure, the parameter of 4m. 2m 4m

I'm very sorry, but I have another question to ask. What is the difference between parameter Grid/RangeMax and parameter 3D cloud maximum depth in Regenerate clouds?

Thank you!

cheers,Lee

matlabbe commented 5 years ago

All Grid/ parameters refer to how the occupancy grid is created. For standalone, the occupancy grid is disabled by default (Preferences->Local occupancy grid->"Create local occupancy grid maps." is unchecked), as the purpose of the standalone version is more 3D hand-held scanning than robot navigation. For robot navigation under ROS, we need an occupancy grid (which is enabled by default on ROS). The occupancy grid is often lower resolution (5 cm voxel) than the point cloud you can generate with Export tool.

If you don't want to do "regenerate" all clouds each time you want to export the clouds from 3D Map view, you can find similar parameters in Preferences->3D Rendering to pre-filter the clouds shown in real-time, then export them directly.

Regards, Mathieu

MattixLee commented 5 years ago

Hi,Mathieu

Thank you very much!The problem has been solved.Your patient answers make me more interested in RTAB and let me know RTAB better.

cheers, Lee