introlab / rtabmap

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

GTSAM Exception caught #172

Open robotic-enthusiast opened 7 years ago

robotic-enthusiast commented 7 years ago

Hello,

I am using the latest RTABmap standalone (from source) on Ubuntu 16.04 (I have also downloaded the ROS packages, but not sure if it is relevant).

When trying to re-run a database with GTSAM as the graph optimization on the standalone rtabmap (no ROS), I am running into a similar issue of that from: http://official-rtab-map-forum.206.s1.nabble.com/Adding-more-loop-detection-in-post-processing-td2643.html#a2646 and http://official-rtab-map-forum.206.s1.nabble.com/GTSAM-Optimization-Error-td742.html

Is there any known solution to this?

[ERROR] (2017-02-22 17:55:10.130) OptimizerGTSAM.cpp:265::optimize() GTSAM exception caught: Indeterminant linear system detected while working near variable 58 (Symbol: 58).

Thrown when a linear system is ill-posed. The most common cause for this error is having underconstrained variables. Mathematically, the system is underdetermined. See the GTSAM Doxygen documentation at http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for more information. [ERROR] (2017-02-22 17:55:10.130) Rtabmap.cpp:3020::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...

Thank you in advance,

EDIT1: If it helps at all, I am running into this issue during multi-session mapping. After I physically place the robot in the same starting position, RTABmap stops and gives me this error.

matlabbe commented 7 years ago

In multi-session mapping, GTSAM fails sometimes to find a solution. I don't know exactly which contraints (which odometry links or loop closure links) in the graph are causing the problem. What I know is that this error may not show up if we change the root node used for optimization. For example, changing RGBD/OptimizeFromGraphEnd from true to false (or vice-versa). If you look at this code:

gtsam::GaussNewtonParams parameters;
parameters.relativeErrorTol = epsilon();
parameters.maxIterations = iterations();
gtsam::GaussNewtonOptimizer optimizer(graph, initialEstimate, parameters);
//gtsam::LevenbergMarquardtParams parametersLev;
//parametersLev.relativeErrorTol = epsilon();
//parametersLev.maxIterations = iterations();
//gtsam::LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parametersLev);
//gtsam::DoglegParams parametersDogleg;
//parametersDogleg.relativeErrorTol = epsilon();
//parametersDogleg.maxIterations = iterations();
//gtsam::DoglegOptimizer optimizer(graph, initialEstimate, parametersDogleg);

there are other optimization approaches that could be used (similar to g2o options). Maybe one of them may no throw this error. I will check to uncomment them and add a new parameter to select one of them for convenience.

Only with TORO I have always a solution in multi-session mapping. g2o gives often very weird optimizations.

cheers, Mathieu

robotic-enthusiast commented 7 years ago

Matlabbe,

Thank you for your comment!

If it helps, I have also found a relationship between some parameters and the GTSAM exception. Under Preferences -> Motion Estimation -> Visual Registration It seems that if we change the motion estimation approach from [3D to 3D] to [3D to 2D PnP] the error stops happening. This works for both, features matching and optical flow. I am not sure how accurate the results are though.

Cheers,

matlabbe commented 7 years ago

The difference that I can see in the generated links between [3D to 3D] and [3D to 2D] is that the covariance values may be little different. Note however that two runs with the same approach ([3D to 3D] or [3D to 2D]) on the same frames may give slightly different covariance values (because of the RANSAC process).

cheers

eric-schleicher commented 7 years ago

for what it's worth, I just encountered this same error processing a multi session.... but it was a 2nd order multi session e.g. one db file which had previously been created from 6 recordings 1.7gb, and another which had (in the new db, played through 3 datasets.

It got about 50% through the very large db before producting the error.

[ERROR] (2017-03-15 14:47:59) OptimizerGTSAM.cpp:265::rtabmap::OptimizerGTSAM::optimize() GTSAM exception caught: 
Indeterminant linear system detected while working near variable
2198 (Symbol: 2198).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[ERROR] (2017-03-15 14:47:59) Rtabmap.cpp:3027::rtabmap::Rtabmap::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...
[ERROR] (2017-03-15 14:48:00) OptimizerGTSAM.cpp:265::rtabmap::OptimizerGTSAM::optimize() GTSAM exception caught: 
Indeterminant linear system detected while working near variable
2198 (Symbol: 2198).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[ERROR] (2017-03-15 14:48:00) Rtabmap.cpp:3027::rtabmap::Rtabmap::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...
[ERROR] (2017-03-15 14:48:00) OptimizerGTSAM.cpp:265::rtabmap::OptimizerGTSAM::optimize() GTSAM exception caught: 
Indeterminant linear system detected while working near variable
2198 (Symbol: 2198).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[ERROR] (2017-03-15 14:48:00) Rtabmap.cpp:3027::rtabmap::Rtabmap::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...
[ERROR] (2017-03-15 14:48:01) OptimizerGTSAM.cpp:265::rtabmap::OptimizerGTSAM::optimize() GTSAM exception caught: 
Indeterminant linear system detected while working near variable
2198 (Symbol: 2198).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[ERROR] (2017-03-15 14:48:01) Rtabmap.cpp:3027::rtabmap::Rtabmap::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...
[ERROR] (2017-03-15 14:48:01) OptimizerGTSAM.cpp:265::rtabmap::OptimizerGTSAM::optimize() GTSAM exception caught: 
Indeterminant linear system detected while working near variable
2198 (Symbol: 2198).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[ERROR] (2017-03-15 14:48:01) Rtabmap.cpp:3027::rtabmap::Rtabmap::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...
[ERROR] (2017-03-15 14:48:02) OptimizerGTSAM.cpp:265::rtabmap::OptimizerGTSAM::optimize() GTSAM exception caught: 
Indeterminant linear system detected while working near variable
2198 (Symbol: 2198).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[ERROR] (2017-03-15 14:48:02) Rtabmap.cpp:3027::rtabmap::Rtabmap::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...
[ERROR] (2017-03-15 14:48:07) OptimizerGTSAM.cpp:265::rtabmap::OptimizerGTSAM::optimize() GTSAM exception caught: 
Indeterminant linear system detected while working near variable
2198 (Symbol: 2198).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[ERROR] (2017-03-15 14:48:07) Rtabmap.cpp:3027::rtabmap::Rtabmap::optimizeCurrentMap() Failed to optimize the graph! returning empty optimized poses...
paulsammut commented 6 years ago

Hello! I'm also experiencing this issue but not in multisession.

My setup:

OptimizerGTSAM.cpp:340::optimize() GTSAM exception caught:
Indeterminant linear system detected while working near variable
5605 (Symbol: 5605). Thrown when a linear system is ill-posed. 

Solutions Attempted:

Software: rtabmap: 0.15.0 rtabmap-ros: 0.14.0 Ubuntu 16.04 ROS Kinetic

Settings:

<!-- MAPPING MODE -->
<param name="Mem/IncrementalMemory" type="string"   value="true"/>
<param name="Rtabmap/DetectionRate" type="string"   value="2"/>
<param name="Grid/DepthMin"         type="double"   value="0.2"/>
<param name="Grid/DepthMax"         type="double"   value="2.5"/>

<param name="Grid/CellSize"             type="double"   value="0.05"/>
<param name="GridGlobal/MinSize"        type="double"   value="40"/>
<param name="Grid/MaxGroundHeight"      type="string"   value="0.50"/>       
<param name="Grid/MaxGroundAngle"       type="double"   value="80"/>
<param name="Grid/MaxObstacleHeight"    type="double"   value="2"/>
<param name="Grid/MinClusterSize"       type="int"      value="20"/>

<param name="Grid/FootprintLength"      type="double"   value="0.7"/>
<param name="Grid/FootprintWidth"       type="double"   value="0.9"/>
<param name="Grid/FootprintHeight"      type="double"   value="2"/>

<!-- Disableing this uses the simple passthrough -->
<param name="Grid/NormalsSegmentation"  type="bool"     value="false"/>

<!-- RTAB-Map's parameters -->
<param name="Rtabmap/TimeThr"                   type="string"   value="1200"/>
<param name="Kp/MaxFeatures"                    type="string"   value="200"/>
<param name="Kp/RoiRatios"                      type="string"   value="0.03 0.03 0.04 0.04"/>
<param name="Kp/DetectorStrategy"               type="string"   value="0"/>

<!-- use SURF -->
<param name="Kp/NNStrategy"                     type="string"   value="1"/>

<!-- kdTree -->
<param name="SURF/HessianThreshold"             type="string"   value="1000"/>

<!-- 3D->2D (PnP) -->
<param name="RGBD/OptimizeMaxError"             type="double"   value="4.000"  />
<param name="RGBD/OptimizeFromGraphEnd"         type="string"   value="false"/>
<param name="RGBD/LoopClosureReextractFeatures" type="string"   value="true"/>
<param name="Grid/MaxGroundHeight"              type="double"   value="0.18"/>

<param name="Vis/MinInliers"                    type="string"   value="10"/>
<param name="Vis/InlierDistance"                type="string"   value="0.1"/>
<param name="Viz/EstimationType"                type="int"      value="1"/>
<param name="Vis/MaxFeatures"                   type="int"      value="1000"/>

<!-- Force 2d mode -->
<param name="Reg/Force3DoF"                                     value="true" />
<param name="Optimizer/Slam2D"                                  value="true" />

<!-- RGBD Settings -->
<param name="RBGD/Enabled"          type="string"   value="true"/>

<param name="subscribe_stereo"      type="bool"     value="false"/>
<param name="subscribe_depth"       type="bool"     value="true"/>
<param name="subscribe_scan_cloud"  type="bool"     value="false"/>
<param name="stereo_approx_sync"    type="bool"     value="true"/>

<param name="frame_id"              type="string"   value="base_link"/>

<param name="queue_size"            type="int"      value="30"/>

Here is a link (dropbox share, should be fast) to the 2GB database: gtsam_error_db

Should I try any different settings in the mapping run? Do you think any of these databases are salvageable? Thanks!

-Paul

matlabbe commented 6 years ago

Thx for sharing the database, I could use it to get deeper in the problem. When re-processing the database, the graph is correctly built as new data are added. The final graph created online is good. However, when closing the database and reloading it, the graph should be re-optimized from raw odometry poses. Normally it should be okay, but sometimes like with this database, GTSAM is not able to converge again to last online solution. In the commit above (bfb3a58c014b9a360f08b671eb8ab3c5d2418b83), I added a second step when graph optimization fails like that. It will try to re-optimize incrementally the graph like during the online SLAM. This process is not super fast, but it would be done only to get the first optimized graph. It works 100% of the time with the database you linked (new error messages will show up when this happens): screenshot from 2018-02-13 16-45-52 180213183134855

Well, that commit is done in devel branch and will only be available with next rtabmap release. For the current version in master branch, you would have to try with TORO and variance ignored, while optimization is not as good as with GTSAM: screenshot from 2018-02-13 14-12-06

cheers, Mathieu

paulsammut commented 6 years ago

Thanks a million! I checked out the devel branch, recompiled and your fix is working with my old databases. I'll look into compiling with TORO when I'm feeling like experimenting, but this fix is fine if GTSAM gives better loop closures.

If it helps you find the problem here is a link to a db with the exact same parameters as the other one, but does not exhibit the GTSAM optimizer error. Its only difference is that it is much smaller than the other one.

Thanks again!

matlabbe commented 6 years ago

TORO is built-in to RTAB-Map, so no need to recompile. TORO can be used by setting parameter Optimizer/Strategy to 0 (see top right on the last screenshot of the previous post).

Nice that it worked on all your databases. However, this workaround may fail when memory management is enabled or in multi-session. I'll keep this issue opened. I'll link this to issue #213 too: saving last optimized poses (while saving the occupancy grid map) could be used as first guess directly without having to incrementally do optimization again, the incremental optimization approach would be a backward compatibility workaround with old databases.

I think the more complex the graph is, the more chance that GTSAM fails to converge and/or to converge to global optimum. So in larger maps this problem would happen more often.