MIT-SPARK / Kimera

Index repo for Kimera code
BSD 2-Clause "Simplified" License
1.79k stars 229 forks source link

Incorrect naming of 'fixed lag smoother' #15

Closed catproof closed 1 year ago

catproof commented 2 years ago

In the paper 'On-Manifold Preintegration for Real-Time Visual–Inertial Odometry' which Kimera supposedly implements, it identifies itself as an 'incremental smoothing' SLAM algorithm: "We design a VIO system that enables fast incremental smoothing and computes the optimal maximum a posteriori (MAP) estimate in real time". It makes a clear distinction in Sections 2.B and 2.C on the differences between fixed lag smoothing and incremental smoothing.

The papers on Kimera repeatedly mention it's SLAM system as being 'fixed lag', but I believe this is incorrect. In the code, I see that 'incremental smoothing' is mentioned many times instead of 'fixed lag'. For instance, in the VioBackend.cpp file it shows this:

`#ifdef INCREMENTAL_SMOOTHER gtsam::ISAM2Params isam_param; BackendParams::setIsam2Params(backend_params, &isam_param);

smoother_ = VIO::make_unique(backendparams.horizon, isam_param);

else // BATCH SMOOTHER

gtsam::LevenbergMarquardtParams lmParams; lmParams.setlambdaInitial(0.0); // same as GN lmParams.setlambdaLowerBound(0.0); // same as GN lmParams.setlambdaUpperBound(0.0); // same as GN) smoother_ = VIO::makeunique(vioParams.horizon, lmParams);

endif`

It seems that here in the code, 'incremental smoother' refers to the 'fixed lag smoother' (incorrectly?) mentioned in your paper, and 'batch smoother' refers to the 'full smoother' mentioned in your paper.

ssemenova commented 1 year ago

Did you ever get a resolution to this?

lucacarlone commented 1 year ago

thanks for the comments! The statements in the papers are indeed correct so let me explain. The key factor to pay attention to is that some of the names you mention refer to the estimation problems we solve (i.e., fixed-lag smoothing vs. full smoothing) and some others refer to the GTSAM solvers used to compute a solution to the resulting estimation/optimization problems (i.e., batch vs. incremental).

Let me start with the estimation problems: a fixed-lag smoother is an estimator that estimates states in a receding horizon, while a full smoother estimates the states from time 0 to the current time t.

In GTSAM, there is a further distinction about the solvers that you use to compute the estimates. In particular, a batch solver solves the optimization problem to compute an estimate from scratch (e.g., using Gauss-Newton or Levenberg-Marquardt). On the other hand, an incremental solver (e.g., iSAM2) reuses computation from the previous steps to speed up the estimation process.

Now, in the paper 'On-Manifold Preintegration for Real-Time Visual–Inertial Odometry' we proposed the use of an incremental full-smoother; in other words, we use an incremental solver (iSAM2) to estimate all states from time 0 and the current time t. While iSAM2 has a lot of cleverness to keep the computation low by working incrementally, the compute time is not guaranteed to be bounded and can still "spike" at certain times.

Therefore, in the Kimera paper 'Kimera: an Open-Source Library for Real-Time Metric-Semantic Localization and Mapping' we use a slightly different approach: we use a fixed-lag smoother (and only estimate the states in a receding horizon, typically 5-10 seconds), and then we pass the result to pose graph optimization (more specifically, Kimera-RPGO or Kimera-PGMO) to compute a global estimate of a subset of poses from time 0 to the current time (also accounting for loop closures).

Now note that while Kimera-VIO solves a fixed-lag smoothing problem, we can still decide which solver to use to solve it. GTSAM again provides 2 options: we can solve the fixed-lag smoothing problem using a batch solver (this is what is called a ('BatchFixedLagSmoother" in GTSAM) or we can solve the fixed-lag smoothing problem using ISAM2 (this is what is called an "IncrementalFixedLagSmoother" in GTSAM). In Kimera, at some point we supported both (see ifdef above) -- however, the batch version is slower and does not lead to substantially better results in many cases, so the default option is to use the incremental fixed-lag smoother (I believe the BatchFixedLagSmoother is no longer supported, but @marcusabate might know better).

I hope this helps!

lucacarlone commented 1 year ago

closing for lack of activity -- feel free to reopen if you have more questions!