introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
970 stars 557 forks source link

Why is the map degrading with Ros2 humble? What can be done to improve the map and navigation in ros2-humble? Getting good map with ros2 galactic with same launch file #915

Open sagardhatrak opened 1 year ago

sagardhatrak commented 1 year ago

We have tested rtabmap using 3D point cloud generated from depth image and sensor fusion based wheel odometry, where rtabmap is generating good map with ros2-galactic, but the performance of map degrades in ros2-humble. Both experiments were carried out using same launch file. Figure.1 shows map generated using ros2 galactic and figure.2 shows the map generated using ros2 humble.

image

Figure 1: Map created using ros2 galactic

image

Figure 2: Map Created using ros2 humble

Following warnings occurs with ros2 humble: [rtabmap-2] [ WARN] (2023-03-22 12:06:28.680) RegistrationIcp.cpp:687::computeTransformationImpl() libpointmatcher icp...temporary maxDist=0.05 (Icp/MaxCorrespondenceDistance=1.500000, Icp/VoxelSize=0.050000) [rtabmap-2] [ WARN] (2023-03-22 12:06:28.680) RegistrationIcp.cpp:687::computeTransformationImpl() libpointmatcher icp...temporary maxDist=0.05 (Icp/MaxCorrespondenceDistance=1.500000, Icp/VoxelSize=0.050000) [rtabmap-2] [ WARN] (2023-03-22 12:06:29.724) Transform.cpp:547::getTransform() No transform found for stamp 1679466989.686860! Latest is 1676356365.767668 [rtabmap-2] [ WARN] (2023-03-22 12:06:29.789) RegistrationIcp.cpp:538::computeTransformationImpl() ICP PointToPlane ignored as structural complexity is too low (corridor-like environment): (from=0.099731 || to=0.000777) < 0.020000 (Icp/PointToPlaneMinComplexity). Second eigen value=0.116254. PointToPoint is done instead, orientation is still optimized but translation will be limited to direction of normals (To: n1=0.036769,0.453482,-0.890507 n2=-0.138902,-0.880140,-0.453938). [rtabmap-2] [ WARN] (2023-03-22 12:06:29.789) RegistrationIcp.cpp:687::computeTransformationImpl() libpointmatcher icp...temporary maxDist=0.05 (Icp/MaxCorrespondenceDistance=1.500000, Icp/VoxelSize=0.050000) [rtabmap-2] [ WARN] (2023-03-22 12:06:29.804) RegistrationIcp.cpp:538::computeTransformationImpl() ICP PointToPlane ignored as structural complexity is too low (corridor-like environment): (from=0.052720 || to=0.000777) < 0.020000 (Icp/PointToPlaneMinComplexity). Second eigen value=0.110298. PointToPoint is done instead, orientation is still optimized but translation will be limited to direction of normals (To: n1=-0.003341,0.454958,-0.890507 n2=-0.060791,-0.888957,-0.453938). [rtabmap-2] [ WARN] (2023-03-22 12:06:29.804) RegistrationIcp.cpp:687::computeTransformationImpl() libpointmatcher icp...temporary maxDist=0.05 (Icp/MaxCorrespondenceDistance=1.500000, Icp/VoxelSize=0.050000) [rtabmap-2] [ WARN] (2023-03-22 12:06:30.878) Transform.cpp:547::getTransform() No transform found for stamp 1679466990.823677! Latest is 1676356366.867737 [rtabmap-2] [ WARN] (2023-03-22 12:06:30.941) RegistrationIcp.cpp:538::computeTransformationImpl() ICP PointToPlane ignored as structural complexity is too low (corridor-like environment): (from=0.006356 || to=0.054323) < 0.020000 (Icp/PointToPlaneMinComplexity). Second eigen value=0.030839. PointToPoint is done instead, orientation is still optimized but translation will be limited to direction of normals (From: n1=0.978849,0.203895,0.016793 n2=0.011848,0.025450,-0.999606). [rtabmap-2] [ WARN] (2023-03-22 12:06:30.941) RegistrationIcp.cpp:687::computeTransformationImpl() libpointmatcher icp...temporary maxDist=0.05 (Icp/MaxCorrespondenceDistance=1.500000, Icp/VoxelSize=0.050000) [rtabmap-2] [ WARN] (2023-03-22 12:06:32.174) Transform.cpp:547::getTransform() No transform found for stamp 1679466992.162493! Latest is 1676356368.266858 [rtabmap-2] [ WARN] (2023-03-22 12:07:06.027) Transform.cpp:547::getTransform() No transform found for stamp 1679467025.988119! Latest is 1676356402.067587 [rtabmap-2] [ WARN] (2023-03-22 12:07:07.150) Rtabmap.cpp:3545::process() Rejecting all added loop closures (1, first is 143 <-> 59) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.035515 (edge 142->143, type=0, abs error=5.499903 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:07.150) Rtabmap.cpp:3570::process() Loop closure 143->59 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:12.425) Transform.cpp:547::getTransform() No transform found for stamp 1679467032.419553! Latest is 1676356408.468281 [rtabmap-2] [ WARN] (2023-03-22 12:07:14.910) Rtabmap.cpp:3521::process() Rejecting all added loop closures (1, first is 150 <-> 30) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.524003 (edge 149->150, type=0, abs error=0.111439 m, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:14.910) Rtabmap.cpp:3570::process() Loop closure 150->30 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:15.948) Rtabmap.cpp:3521::process() Rejecting all added loop closures (2, first is 151 <-> 31) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 9.257557 (edge 119->151, type=2, abs error=0.767216 m, stddev=0.082875). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:15.948) Rtabmap.cpp:3570::process() Loop closure 151->31 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:15.948) Rtabmap.cpp:3570::process() Loop closure 151->119 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:17.200) Rtabmap.cpp:3521::process() Rejecting all added loop closures (2, first is 152 <-> 31) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 11.438213 (edge 120->152, type=2, abs error=0.797484 m, stddev=0.069721). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:17.200) Rtabmap.cpp:3570::process() Loop closure 152->31 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:17.200) Rtabmap.cpp:3570::process() Loop closure 152->120 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:21.142) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 155 <-> 34) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 8.109493 (edge 33->34, type=0, abs error=14.693199 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:21.142) Rtabmap.cpp:3570::process() Loop closure 155->34 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:21.142) Rtabmap.cpp:3570::process() Loop closure 155->122 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:21.980) Transform.cpp:547::getTransform() No transform found for stamp 1679467041.953949! Latest is 1676356418.067116 [rtabmap-2] [ WARN] (2023-03-22 12:07:23.697) Rtabmap.cpp:3521::process() Rejecting all added loop closures (2, first is 157 <-> 40) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 10.331985 (edge 123->157, type=2, abs error=1.029480 m, stddev=0.099640). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:23.697) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 157 <-> 40) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 16.332392 (edge 123->157, type=2, abs error=29.485360 deg, stddev=0.031509). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:23.697) Rtabmap.cpp:3570::process() Loop closure 157->40 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:23.697) Rtabmap.cpp:3570::process() Loop closure 157->123 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:25.900) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 159 <-> 125) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 5.277404 (edge 41->42, type=0, abs error=9.561872 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:25.900) Rtabmap.cpp:3570::process() Loop closure 159->125 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:25.900) Rtabmap.cpp:3570::process() Loop closure 159->42 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:26.775) Transform.cpp:547::getTransform() No transform found for stamp 1679467046.742228! Latest is 1676356422.869324 [rtabmap-2] [ WARN] (2023-03-22 12:07:27.397) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 160 <-> 126) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.665064 (edge 41->42, type=0, abs error=6.640552 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:27.397) Rtabmap.cpp:3570::process() Loop closure 160->126 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:28.545) Rtabmap.cpp:3570::process() Loop closure 161->126 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:29.075) Transform.cpp:547::getTransform() No transform found for stamp 1679467049.056748! Latest is 1676356425.166900 [rtabmap-2] [ WARN] (2023-03-22 12:07:29.301) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 162 <-> 127) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.365401 (edge 41->42, type=0, abs error=6.097606 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:29.301) Rtabmap.cpp:3570::process() Loop closure 162->127 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:29.301) Rtabmap.cpp:3570::process() Loop closure 162->75 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:30.126) Transform.cpp:547::getTransform() No transform found for stamp 1679467050.080208! Latest is 1676356426.168253 [rtabmap-2] [ WARN] (2023-03-22 12:07:30.735) Rtabmap.cpp:3521::process() Rejecting all added loop closures (2, first is 163 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 12.386833 (edge 76->163, type=2, abs error=0.133050 m, stddev=0.010741). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:30.735) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 163 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.220627 (edge 41->42, type=0, abs error=5.835298 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:30.735) Rtabmap.cpp:3570::process() Loop closure 163->76 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:30.735) Rtabmap.cpp:3570::process() Loop closure 163->128 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:31.333) Transform.cpp:547::getTransform() No transform found for stamp 1679467051.098437! Latest is 1676356427.468084 [rtabmap-2] [ WARN] (2023-03-22 12:07:31.529) Rtabmap.cpp:3521::process() Rejecting all added loop closures (2, first is 164 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 11.385192 (edge 76->164, type=2, abs error=0.125353 m, stddev=0.011010). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:31.529) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 164 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.294198 (edge 41->42, type=0, abs error=5.968598 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:31.529) Rtabmap.cpp:3570::process() Loop closure 164->76 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:31.529) Rtabmap.cpp:3570::process() Loop closure 164->128 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:32.179) Transform.cpp:547::getTransform() No transform found for stamp 1679467052.158595! Latest is 1676356428.267322 [rtabmap-2] [ WARN] (2023-03-22 12:07:32.407) Rtabmap.cpp:3521::process() Rejecting all added loop closures (2, first is 165 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 28.184868 (edge 128->165, type=2, abs error=0.533211 m, stddev=0.018918). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:32.407) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 165 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.230057 (edge 41->42, type=0, abs error=5.852384 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:32.407) Rtabmap.cpp:3570::process() Loop closure 165->76 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:32.407) Rtabmap.cpp:3570::process() Loop closure 165->128 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:33.274) Transform.cpp:547::getTransform() No transform found for stamp 1679467053.249616! Latest is 1676356429.367103 [rtabmap-2] [ WARN] (2023-03-22 12:07:33.454) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 166 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.268434 (edge 41->42, type=0, abs error=5.921917 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:33.454) Rtabmap.cpp:3570::process() Loop closure 166->76 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:34.275) Transform.cpp:547::getTransform() No transform found for stamp 1679467054.270035! Latest is 1676356430.366807 [rtabmap-2] [ WARN] (2023-03-22 12:07:34.507) Rtabmap.cpp:3545::process() Rejecting all added loop closures (2, first is 167 <-> 76) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 3.224336 (edge 41->42, type=0, abs error=5.842018 deg, stddev=0.031623). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [rtabmap-2] [ WARN] (2023-03-22 12:07:34.507) Rtabmap.cpp:3570::process() Loop closure 167->76 rejected! [rtabmap-2] [ WARN] (2023-03-22 12:07:34.507) Rtabmap.cpp:3570::process() Loop closure 167->128 rejected!

Why is the map degrading with Ros2 humble? What can be done to improve the map and navigation in ros2-humble? As we are getting good results with ros2 galactic.

matlabbe commented 1 year ago

Can you share databases of both experiments?

sagardhatrak commented 1 year ago

Sorry for the delay. The databases with humble and galactic are attached with below link.

https://drive.google.com/drive/folders/1EAKO8ZezzT0HRIKoTDilLVnOpVmGvTe0?usp=share_link

This issue could be due to wrong loop closure; more wrong loop closures occur in the humble compared to the galactic.

matlabbe commented 1 year ago

Well, the point cloud range is too small and sparse. Without RGB image, the proximity loop closures are mostly meaningless, even increasing errors in the map. For example, these two point clouds of a loop closure don't have enough geometry complexity and overlap. Without RGB to get visual feature, ICP will never give good transform. Screenshot from 2023-04-16 19-18-34

With that setup, it would be better to disable proximity detection. Here without (first) and with (second) loop closure optimization:

Screenshot from 2023-04-16 19-19-43 Screenshot from 2023-04-16 19-19-51

Map looks a lot better without loop closures.

sagardhatrak commented 1 year ago

Thank you very much for guidance..

What does “the point cloud range is too small” means? Which parameter is used to disable proximity detection? Why is the generated map more stable in galactic than humble? Will it help to improve accuracy by removing such wrong loop closures for optimization? How can we detect such false loop closures and remove such loop closures? Is there any other alternative approach in rtabmap to work with point cloud for map generation?

matlabbe commented 1 year ago

What does “the point cloud range is too small” means?

Range looks under 3-4 meters.

Which parameter is used to disable proximity detection?

RGBD/ProximityBySpace set to false.

Why is the generated map more stable in galactic than humble?

I feel both are unstable.

Will it help to improve accuracy by removing such wrong loop closures for optimization?

As I shown above, yes disabling loop closure detection helps in that dataset.

How can we detect such false loop closures and remove such loop closures?

With that kind of point cloud data without images, all loop closures will be wrong. Otherwise, you could decrease RGBD/OptimizeMaxError (default 3) to reject them is you can assume that odometry is good with low covariance.

Is there any other alternative approach in rtabmap to work with point cloud for map generation?

Do you have only that point cloud sensor? no camera? no 2d lidar?

sagardhatrak commented 1 year ago

Thank you, Ok. We have 2D lidar, but we want to do it using point cloud only.