Full SLAM via information matrices: sparsity, Taylor expansion, construct-reduce-solve, and data association.
EKF SLAM (Chapter 10) maintains a covariance matrix Σt that becomes dense as landmarks correlate. Updating this dense matrix costs O(N2) per step. Can we do better?
The information form is the dual of the covariance form. Instead of μ and Σ, it maintains:
The EIF SLAM algorithm exploits this sparsity to solve the full SLAM problem: estimating the entire robot path x1:t and the map m simultaneously. It accumulates information lazily (cheap) and resolves it into estimates at the end (one-time cost).
Think of the information matrix as a graph of constraints. Each non-zero off-diagonal block represents a constraint between two variables (poses or landmarks):
• Motion constraints link consecutive poses xt-1 and xt.
• Measurement constraints link a pose xt to the landmark mj it observed.
Each constraint says: "these two variables should satisfy this geometric relationship." The information matrix accumulates all constraints into a single linear system.
The key difference from EKF SLAM: EKF SLAM processes information eagerly, updating the dense covariance at each step (expensive). EIF SLAM accumulates information lazily, adding constraints to the sparse information matrix (cheap). Resolution into actual pose/map estimates happens only at the end.
Why is Ω sparse in full SLAM? The log-posterior decomposes as a sum of independent terms:
Each term involves only a few variables: xt-1 and xt for motion, or xt and mj for measurement. After linearization, each term contributes a local quadratic to the information matrix, affecting only the rows/columns of the involved variables.
Important caveat: this sparsity holds for full SLAM only. In online SLAM, integrating out past poses destroys the sparsity by introducing links between landmarks that were observed at the same (now-eliminated) pose. This is why the EKF's covariance is dense.
EIF SLAM has three phases, run iteratively until convergence:
| Phase | What It Does | Complexity |
|---|---|---|
| Construct | Build Ω and ξ from linearized motion/measurement models | O(T) — linear in time steps |
| Reduce | Eliminate landmark variables, leaving only poses | O(T) — linear |
| Solve | Invert the reduced system to get poses; back-substitute for landmarks | O(T3) worst case, but exploits sparsity |
EIF construct builds Ω and ξ by processing all data sequentially:
Initialization: Set Ωx0,x0 = ∞ · I to fix the initial pose at the origin. This anchors the coordinate system.
For each control ut: Linearize the motion model at the current estimate. Add a quadratic constraint between xt-1 and xt to Ω and ξ.
For each measurement zti: Linearize the measurement model. Add a quadratic constraint between xt and mj to Ω and ξ.
The result: a large sparse matrix Ω and vector ξ, defined over all poses and all landmarks. If the environment has 10,000 poses and 500 landmarks, the matrix is 31,500 × 31,500, but most of it is zero.
After construction, Ω contains both pose and landmark variables. The Reduce step eliminates all landmark variables, leaving a system defined only over poses.
This is variable elimination (Schur complement): for each landmark mj, compute the set of poses τ(j) that observed it, then update the submatrix connecting those poses:
and similarly for ξ̃. Then remove the rows/columns for mj.
After reducing all landmarks, the remaining system involves only the T+1 poses. For environments without loops, this system is tridiagonal (each pose linked only to its predecessor). With loops, it's still sparse.
The Solve step recovers the actual estimates from the reduced information system:
1. Pose recovery: Invert the reduced matrix Ω̃ (poses only) to get Σ̃ = Ω̃-1. Compute pose means: μ0:t = Σ̃ ξ̃.
2. Landmark recovery: For each landmark j, compute its position from the recovered poses: μj = Ωj,j-1(ξj + Ωj,τ(j) μτ(j)).
Landmark recovery is cheap: each landmark's estimate is computed independently from the recovered poses, in O(1) per landmark.
Unknown correspondences in EIF SLAM are handled similarly to EKF SLAM: maximum likelihood correspondence. For each measurement, find the landmark that minimizes the Mahalanobis distance.
The challenge: computing Mahalanobis distances in the information form requires access to the covariance (the inverse of Ω), which is expensive to compute for the full system. In practice, local submatrices are extracted and inverted.
As with EKF SLAM, wrong correspondences can be devastating. The iterative nature of EIF SLAM provides a partial defense: after each iteration, the improved estimates may reveal and correct earlier association errors.
How does EIF SLAM compare to EKF SLAM?
| Aspect | EKF SLAM | EIF SLAM |
|---|---|---|
| Problem type | Online SLAM | Full SLAM |
| Representation | Dense covariance (3+3N)2 | Sparse information matrix |
| Per-step cost | O(N2) | O(1) per constraint (lazy) |
| Total cost | O(TN2) | O(T) + solve cost |
| Incremental? | Yes | No (batch) |
| Max landmarks | ~1,000 | ~100,000+ |
| Concept | Key Idea |
|---|---|
| Information form | Ω = Σ-1; naturally sparse for full SLAM |
| Constraint graph | Non-zero entries = direct constraints between variables |
| Construct | Build Ω lazily by adding local constraints; O(T) |
| Reduce | Eliminate landmarks via variable elimination; O(T) |
| Solve | Invert reduced system for poses; back-substitute for landmarks |
| Iteration | Repeat 2-3 times to improve linearization |