introlab / rtabmap

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

Consistent rejection of Loop Closures #418

Open ayush-j9 opened 5 years ago

ayush-j9 commented 5 years ago

While creating the map, the new data is just getting overlayed on the previous one when my robot looks at the same place. Also, the pointcloud lifts above the ground when th map gets updated sometimes, although it says the loop cloures re rejected. Getting the following error consistently while trying to map the surrounding.

`[ WARN] (2019-06-26 15:09:04.195) Rtabmap.cpp:2936::process() Rejecting all added loop closures (3, first is 155 <-> 137) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 6.163492 (edge 72->74, type=0, abs error=23.730078 deg, stddev=0.067197). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [ WARN] (2019-06-26 15:09:04.195) Rtabmap.cpp:2946::process() Loop closure 155->137 rejected! [ WARN] (2019-06-26 15:09:04.195) Rtabmap.cpp:2946::process() Loop closure 155->144 rejected! [ WARN] (2019-06-26 15:09:04.195) Rtabmap.cpp:2946::process() Loop closure 155->66 rejected!

[ WARN] (2019-06-26 15:09:05.182) Rtabmap.cpp:2936::process() Rejecting all added loop closures (3, first is 156 <-> 137) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 5.901606 (edge 72->74, type=0, abs error=22.721789 deg, stddev=0.067197). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [ WARN] (2019-06-26 15:09:05.182) Rtabmap.cpp:2946::process() Loop closure 156->137 rejected! [ WARN] (2019-06-26 15:09:05.182) Rtabmap.cpp:2946::process() Loop closure 156->144 rejected! [ WARN] (2019-06-26 15:09:05.182) Rtabmap.cpp:2946::process() Loop closure 156->66 rejected!

[ WARN] (2019-06-26 15:09:06.236) Rtabmap.cpp:2936::process() Rejecting all added loop closures (3, first is 157 <-> 139) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 5.120492 (edge 96->97, type=0, abs error=20.546409 deg, stddev=0.070033). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation. [ WARN] (2019-06-26 15:09:06.236) Rtabmap.cpp:2946::process() Loop closure 157->139 rejected! [ WARN] (2019-06-26 15:09:06.236) Rtabmap.cpp:2946::process() Loop closure 157->144 rejected! [ WARN] (2019-06-26 15:09:06.236) Rtabmap.cpp:2946::process() Loop closure 157->66 rejected! `

I get this one time warning of a high value in an angular covariance value. I am using the odometry provided by claearpath on their robots. Also, I do not know how to play around with the covariance matrix. Getting the following warning: `/rtabmap/rtabmap subscribed to (approx sync): /odometry/filtered, /rtabmap/rgbd_image [ INFO] [1561576465.805519542]: rtabmap 0.19.4 started...

[ WARN] (2019-06-26 15:14:27.067) Memory.cpp:913::addSignatureToStm() Very large angular variance (15.603200) detected! Please fix odometry covariance, otherwise poor graph optimizations are expected and wrong loop closure detections creating a lot of errors in the map could be accepted. This message is only printed once.

^C[rtabmap/rtabmap-2] killing on exit [rtabmap/rgbd_sync-1] killing on exit rtabmap: Saving database/long-term memory... (located at /home/intern/.ros/rtabmap.db) rtabmap: 2D occupancy grid map saved. rtabmap: Saving database/long-term memory...done! (located at /home/intern/.ros/rtabmap.db, 1 MB)`

For reference, I am using a Realsense D435 and odometry as the inputs.

matlabbe commented 5 years ago

The first warnings about rejecting loop closures are ok, it means that a bad loop closure has been detected, which would have deformed the graph too much (assuming odometry error is always consistent to reality). If the loop closure is fine, it could mean that odometry drifted more in reality than its covariance. You can increase RGBD/OptimizeMaxError value to accept loop closures in this case. Setting RGBD/OptimizeMaxError to 0 would accept all loop closures.

The following warning is however a problem: Memory.cpp:913::addSignatureToStm() Very large angular variance (15.603200) detected! Please fix odometry covariance, otherwise poor graph optimizations are expected and wrong loop closure detections creating a lot of errors in the map could be accepted. This message is only printed once.**

This can be manually resolved by hard-coding odometry variance on rtabmap side. To do this, set those parameters to rtabmap node:

<param name="odom_frame_id" value="odom"/> <!-- adjust to actual odometry frame id -->
<param name="odom_tf_linear_variance" value="0.0001"/> <!-- adjust depending on real odom error -->
<param name="odom_tf_angular_variance" value="0.0005"/> <!-- adjust depending on real odom error -->

cheers, Mathieu