david-m-rosen / SE-Sync

An implementation of the SE-Sync algorithm for synchronization over the special Euclidean group.
GNU Lesser General Public License v3.0
383 stars 83 forks source link

sometimes sesync may output incorrect results #25

Closed wmj-ustc closed 2 years ago

wmj-ustc commented 2 years ago

Thank you very much for your excellent work. SeSync is efficient and accurate for pose graph optimization in most cases, but it sometimes outputs incorrect results for my input pose graph data, I am not sure is there something wrong with the input data. the adapted matlab code and c++ interface are attached. Thank you. matlab__.zip main.zip

the corresponding optimization results are as follows:

Loaded 1124 measurements between 259 poses from file

set opts Constructing SE-Sync problem instance ... CHOLMOD warning: matrix not positive definite. file: d:\libs\slam\suitesparse\suitesparse\cholmod\supernodal\t_cholmod_super_numeric.c line: 911 elapsed computation time: 0.011 seconds

========= SE-Sync ==========

ALGORITHM SETTINGS:

SE-Sync settings: SE-Sync problem formulation: Simplified Initial level of Riemannian staircase: 5 Maximum level of Riemannian staircase: 6 Number of Lanczos vectors to use in minimum eigenvalue computation: 20 Maximum number of iterations for eigenvalue computation: 10000 Tolerance for accepting an eigenvalue as numerically nonnegative in optimality verification: 1e-05 Using Cholesky decomposition to compute orthogonal projections Initialization method: chordal Running SE-Sync with 4 threads

Riemannian trust-region settings: Stopping tolerance for norm of Riemannian gradient: 0.01 Stopping tolerance for norm of preconditioned Riemannian gradient: 0.0001 Stopping tolerance for relative function decrease: 1e-07 Stopping tolerance for the norm of an accepted update step: 0.001 Maximum number of trust-region iterations: 1000 Maximum number of truncated conjugate gradient iterations per outer iteration: 10000 STPCG fractional gradient tolerance (kappa): 0.1 STPCG target q-superlinear convergence rate (1 + theta): 1.5 Preconditioning the truncated conjugate gradient method using regularized Cholesky preconditioner with maximum condition number 1e+06

INITIALIZATION: Computing chordal initialization ... elapsed computation time: 0.168 seconds SE-Sync initialization finished; elapsed time: 0.169 seconds

Initial objective value: -26060.9 | isnormal(not nan/inf): 1

====== RIEMANNIAN STAIRCASE (level r = 5) ======

Truncated-Newton trust-region optimization:

Iter: 0, time: 0.000e+00, f: -2.606e+04, |g|: 1.329e+04, |M^{-1}g|: -nan(ind), Delta: 1.000e+00, inner iters: 10000, |h|: -nan(ind), |h|_M: -nan(ind), df: -nan(ind), rho: -nan(ind). Step REJECTED!

Optimization finished! Algorithm exceeded maximum allowed computation time: (6.495e+01 > 2.000e+01 seconds) Final objective value: -2.606e+04 Norm of Riemannian gradient: 1.329e+04 Norm of preconditioned Riemannian gradient: -nan(ind) Total elapsed computation time: 6.495e+01 seconds

Found first-order critical point with value F(Y) = -26060.9! Elapsed computation time: 64.952 seconds

Checking second order optimality ... Saddle point detected! Minimum eigenvalue: -0.171269. Elapsed computation time: 0.045 seconds (44 matrix-vector multiplications). Computing escape direction ...

===== END RIEMANNIAN STAIRCASE =====

WARNING: Algorithm exhausted the allotted computation time before finding global optimum!

Rounding solution ... elapsed computation time: 0.01 seconds

SDP RESULTS: Value of dual SDP solution F(Y): -26060.9 Norm of Riemannian gradient grad F(Y): 13291 Value of primal SDP solution tr(Lambda): -26060.9 Minimum eigenvalue of certificate matrix S - Lambda: -0.171269 SDP duality gap: -1.45519e-11

SE-SYNCHRONIZATION RESULTS: Value of rounded pose estimates F(x): -26060.9 Suboptimality bound F(x) - tr(Lambda) of recovered pose estimate: -1.0994e-08

Total elapsed computation time: 65.241 seconds

===== END SE-SYNC =====

Saving final poses to file: poses.txt

david-m-rosen commented 2 years ago

Hi @wmj-ustc,

Thanks for your interest in the project :-). First, a minor clarification (just to avoid any confusion among folks who might be watching this issue): SE-Sync does not compute "wrong answers" -- indeed, that was the entire point of developing the method ;-P. While it is true that the semidefinite relaxation that SE-Sync employs may fail to be exact in some (high-noise) cases (so that the feasible point it returns may not be globally optimal), the algorithm is capable of detecting (and will report) this automatically -- for example, you can see this in the following lines in the output:

Saddle point detected! Minimum eigenvalue: -0.171269. Elapsed computation time: 0.045 seconds (44 matrix-vector multiplications).

WARNING: Algorithm exhausted the allotted computation time before finding global optimum!

As for what might be going wrong: I unfortunately don't have the bandwidth to debug any modifications that you might have made to the code(?), but just looking at the output that you supplied, I would definitely suspect some kind of problem with the input data. In particular, the line:

Initial objective value: -26060.9

shows that the value of the chordal initialization is somehow negative. This is mathematically impossible, since the objective matrix is always positive-semidefinite by construction. So I would strongly suspect one of the following issues:

Hope this helps!

wmj-ustc commented 2 years ago

Thanks so much for your prompt reply. The supplied pose graph is definitely disconnected.