New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
"GTSAM exception caught: Indeterminant linear system detected while working near variable" then crash #1057
Comments
It seems you are using rtabmap 0.20.18: In that code, the poses fed to optimization are taken for For the |
Thanks for the response. Yes, I'm using rtabmap 0.20.18. Ok, thanks for the clarification about the code. In my case, sometimes the odometry is not at the origin when the rtabmap starts. Could it be the problem? The Here is the log of a local loop closure that doesn't crash however warns about "Indeterminant linear system".
Here is the log of the local loop closure made just before the loop closure that crashes:
Here is the log of the local loop closure that crashes:
Hope these are useful. |
For the |
Hi, thanks for the response.
I'm using ROS noetic, so the actual master branch is not compatible with the system I'm working on.
As a result the Optimizer stopped crashing. It is rejecting the loop closures instead, as shown below:
Do you have any thoughts about this behavior? EDIT: I also noted that, this behavior occurs mostly when detected apriltags (landmarks). |
The master branch should work on Noetic (this is the main platform I am developing on). Otherwise, please report the compatibility issue. For:
That update introlab/rtabmap#1030 is also required. I'll suggest to use latest master branch in case there are other small commits depending on that. Remove rtabmap binaries and rebuild rtabmap and rtabmap_ros from source:
Otherwise, it seems GTSAM really doesn't like the constraints you are providing. In your case, do you have |
Just confirming that even if odometry pose is large, GTSAM should be able to converge correctly. Here I reset odometry to x=10000 and y=8000:
Maybe the tag detection is too wrong to correctly converge. |
…er) (#1156) * tuning localization priors (for introlab/rtabmap_ros#1057) * Set prior error value to same than old default value
I updated the code with a change for landmark constraints in localization mode that could help with your issue (see introlab/rtabmap#1156). You may give a try. If the issue is still there, you may increase this new parameter called |
Thanks for the update. Apparently the landmark constraints are the problem. I'm not using an external node to detect the apriltags. I will try the suggested version and parameters. Thanks again. EDIT: I'm using apriltag_ros built from source. Is there a specific version which I should use? |
Hello there, I have some updates to share. As mentioned by me in the previous comment, when I set A few time ago I was using the 0.20.16-noetic version, and it worked just fine. Then, I decided to try it again. As a result the crashes and GTSAM warnings disappeared. Then I decided to look for which commit between versions 0.20.16-noetic and 0.20.18-noetic introduced this behavior in my stack. Then, I found out that the commit fcec981 introduced this issue to my stack. I'm trying to understand what was the purpose of that change, and why it is necessary for the SLAM 2D. The version 0.20.16-noetic is working just fine. Is there any parameter that I should re-parametize to also get it working with the versions 0.20.18-noetic and later? Thanks for your time. |
I will try to reproduce the issue that this commit was fixing, I don't remember on top of my head what was the issue addressed there. In your case, if I understand, if you change this line by: _graphOptimizer->getConnectedGraph(signature->id(), poses, constraints, posesOut, edgeConstraintsOut); Would it fix your issue? |
Yes, it would fix my issue. |
There is the code flipping the tag pose with
Well, this works well if we don't change Another note, could you also show the covariance set in your odometry topic (assuming it is called
I saw some GTSAM indeterminant errors while testing on the simulator and it was caused by bad covariance. |
Here is the odometry data at the instant in which the fatal error crashes the system:
EDIT: |
…trolab/rtabmap_ros#1057). Transform: Fixed is3DoF() and is 4DoF()
The odometry topic covariance looks fine, but if you are using
which should not cause that issue with those default values. In the commit above, I updated the code to remove the last argument of |
Hi, I have some updates again. I made the tests with the commit above and finally the issue was solved. Thanks for the help and explanations about this awesome package/library. |
Hi everyone, I'm working in a project with ROS1 in which we use Rtabmap for localization in a previously mapped environment. I'm using the localization_pose to feed my localization stack. Recently I have experienced problems with GTSAM which warns for "inderteminant linear systems". Eventually, it also crashes with the following FATAL ERROR.
By setting the "--udebug --logconsole" arguments I was able to see some information about the problem. However something very strange took my attemption, which are the following debug messages:
The above logs, show the constraints used in the optmization. However the last line took my attemption. In the referred line we can see that the pose of the node 1058 is very distant (in terms of xyz) from the other nodes of the graph. Then, I was looking in the code and found these debug messages in the Rtabmap library. I noticed that the odom pose is not being transformed to the same frame of the graph nodes before optimization, as shown in the following lines:
https://github.com/introlab/rtabmap_ros/blob/3293f2b51a42cdcd4f531576e3d787f149ac2e1b/rtabmap_slam/src/CoreWrapper.cpp#L2026C6-L2030
Based in my knowledge of optimization, I thought it would be better for the optimization problem (in terms of speed and accuracy) if the initial guess was near to the minimum. I understand that the mapCorrection output is being used to generate the mapToOdom information. However, in my point of view, it would be better for the optimization problem, if the odom pose was transformed to the map frame with the last map->odom transform before passing it to the optimizer. Then the mapCorrection output could be used to correct the last map->odom TF from /tf.
I would appreciate any comments and clarifications on this.
Thank you!
The text was updated successfully, but these errors were encountered: