• Praktische Grundlagen der Informatik
  • Algorithmen und Datenstrukturen
  • Foundations for Robotic and AI
  • Übersicht Data Science:
  • Data Science / Machine Learning
  • Projekt: Deep Teaching
  • Alte Veranstaltungen:
  • Grundlagen der Informatik (NF)
  • Octave/Matlab Tutorial
  • Game Physik
  • Home
  • Lehre
  • Publikationen
  • Kontakt/Impressum

Observability¶

The Concept of Observability: Why "Seeing" isn't always "Knowing"¶

In our transition to the 8-state EKF, we added "hidden" states for accelerometer and gyroscope biases. Mathematically, these states exist in our vector $\mathbf{x}$, but a critical question remains: Does the information from our sensors actually reach these hidden states? In control theory, this is the problem of Observability. A system is observable if the current state can be determined from the output sensors in a finite amount of time. If a state is unobservable, the EKF can "guess," but the variance in the covariance matrix $P$ will grow forever because no measurement is providing a "correction" for that specific state.

Defining Observability in the Discrete EKF¶

In a linear discrete-time system, observability is determined by the Observability Matrix $\mathcal{O}$. For a system with $n$ states, the system is fully observable if $\mathcal{O}$ has full column rank ($rank = n$):

$$\mathcal{O} = \begin{bmatrix} \mathbf{J}_h \\ \mathbf{J}_h \mathbf{J}_f \\ \mathbf{J}_h \mathbf{J}_f^2 \\ \vdots \\ \mathbf{J}_h \mathbf{J}_f^{n-1} \end{bmatrix}$$

Because our EKF is non-linear, we evaluate Local Observability. We look at the Jacobians at our current estimate. Each row of this matrix represents a "layer" of information:

  • $\mathbf{J}_h$: What we see right now.
  • $\mathbf{J}_h \mathbf{J}_f$: What we expect to see at the next time step.
  • $\mathbf{J}_h \mathbf{J}_f^2$: How the measurements will change two steps from now.

If these rows are linearly independent, the EKF has enough unique "equations" to solve for all the "unknowns" (our 8 states).

Recap: Our 8-state system¶

$$\mathbf{J}_{h} = \begin{bmatrix} 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 \\ \frac{p_1}{d} & \frac{p_2}{d} & 0 & 0 & 0 & 0 & 0 & 0 \end{bmatrix}$$

and

$$\mathbf{J}_f = \begin{bmatrix} 1 & 0 & \Delta t & 0 & \frac{1}{2}\Delta t^2 (-\tilde{a}_1 s - \tilde{a}_2 c) & -\frac{1}{2}\Delta t^2 c & \frac{1}{2}\Delta t^2 s & 0 \\ 0 & 1 & 0 & \Delta t & \frac{1}{2}\Delta t^2 (\tilde{a}_1 c - \tilde{a}_2 s) & -\frac{1}{2}\Delta t^2 s & -\frac{1}{2}\Delta t^2 c & 0 \\ 0 & 0 & 1 & 0 & \Delta t (-\tilde{a}_1 s - \tilde{a}_2 c) & -\Delta t c & \Delta t s & 0 \\ 0 & 0 & 0 & 1 & \Delta t (\tilde{a}_1 c - \tilde{a}_2 s) & -\Delta t s & -\Delta t c & 0 \\ 0 & 0 & 0 & 0 & 1 & 0 & 0 & -\Delta t \\ 0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 & 0 & 1 \end{bmatrix}$$

Observing Heading ($\theta$) and Gyro Bias ($b_\omega$)¶

Let's isolate the Magnetometer's contribution. We look at the first row of $\mathbf{J}_h$ and its interaction with the 8-state $\mathbf{J}_f$.

  • Row 1 ($t=0$): The magnetometer directly observes $\theta$.$$\mathbf{r}_1 = \begin{bmatrix} 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 \end{bmatrix}$$

  • Row 2 ($t=1$): Multiplying $\mathbf{r}_1 \cdot \mathbf{J}_f$ effectively "grabs" the 5th row of the state transition matrix:$$\mathbf{r}_2 = \begin{bmatrix} 0 & 0 & 0 & 0 & 1 & 0 & 0 & -\Delta t \end{bmatrix}$$

Since we have two linearly independent rows, we can solve for both $\theta$ and $b_\omega$. The EKF "sees" that if the heading doesn't match the integrated gyro rate, the difference must be the gyro bias.

Observing Position ($p$), Velocity ($v$), and Accel Bias ($b_a$)¶

Now we look at the Distance sensor. To keep the math clean, let $c_1 = \frac{p_1}{d}$ and $c_2 = \frac{p_2}{d}$.

  • Row 1 ($t=0$):Detects position only.$$\mathbf{r}_1 = \begin{bmatrix} c_1 & c_2 & 0 & 0 & 0 & 0 & 0 & 0 \end{bmatrix}$$
  • Row 2 ($t=1$):Detects position and the velocity that moved the robot.$$\mathbf{r}_2 = \begin{bmatrix} c_1 & c_2 & c_1 \Delta t & c_2 \Delta t & \dots & \dots & \dots & 0 \end{bmatrix}$$
  • Row 3 ($t=2$):As we multiply by $\mathbf{J}_f$ again, the acceleration terms (containing $b_{a1}, b_{a2}$) finally "leak" into the measurement.$$\mathbf{r}_3 = \begin{bmatrix} c_1 & c_2 & 2c_1 \Delta t & 2c_2 \Delta t & \dots & -c_1 \Delta t^2 \cos\theta & -c_2 \Delta t^2 \sin\theta & 0 \end{bmatrix}$$

The Dilemma: Notice that $p_1$ and $p_2$ are always tied together in a single row. If the robot is stationary, $c_1$ and $c_2$ never change. We have two position unknowns but only one "type" of distance equation. Without motion or orientation, $p_1$ and $p_2$ are unobservable from a single beacon.

Rotational Symmetry: The Magnetometer as "The Glue"¶

Why can't a single distance sensor tell the difference between $p_1$ and $p_2$ effectively? It comes down to Rotational Symmetry.

If you only have a distance sensor, the robot exists on a "Circle of Probability." You could rotate the entire world—the robot's position, its velocity, and its heading—around the beacon, and the distance reading would remain exactly the same. Mathematically, the EKF cannot distinguish between these rotated versions of reality.

The Magnetometer is the "glue" that fixes this. By providing an absolute reference for $\theta$, it "pins" the robot's orientation to the world. Once $\theta$ is known:

  1. The EKF knows which direction "Velocity" is pushing.
  2. This separates the $p_1$ and $p_2$ components in the observability matrix.
  3. The "Rotational Symmetry" is broken, and the rank of the matrix reaches 8. Therefore, the system is fully observable.

Summary of ObservabilityConfigurationObservable StatesUnobservable "Modes"ResultDist OnlyDistance (Radial)Heading, Lateral PositionThe robot "drifts" along a circle.Mag OnlyHeading, Gyro BiasPosition, VelocityThe robot knows where it faces but not where it is.Dist + MagFull 8-StateNone (if moving/ZUPT used)Stable, calibrated navigation.

Conclusion: For a professional navigation filter, sensors are not just sources of data; they are mathematical constraints. The Magnetometer allows the Distance sensor to know which coordinate it is measuring, and together they allow the EKF to peer into the "hidden" world of sensor biases.

Summary of Observability: 8-State EKF Navigation¶

Configuration Rank ($\mathcal{O}$) Observable States Unobservable "Modes" Filter Behavior
Distance Only 6 - 7 Distance (Radial), Velocity (Radial) Absolute Heading ($\theta$), Gyro Bias ($b_\omega$) Robot drifts along a "circle of probability"; heading error grows indefinitely.
Magnetometer Only 2 - 3 Heading ($\theta$), Gyro Bias ($b_\omega$) All Positions ($p$), All Velocities ($v$), Accel Biases ($b_a$) Orientation is known, but position "hallucinates" drift as accel biases integrate.
Dist + Mag (Stationary) 3 - 5 $p$, $\theta$, $b_\omega$ Velocity ($v$), Accel Biases ($b_a$) Without motion, the EKF cannot distinguish between real velocity and accelerometer bias.
Dist + Mag (Moving) 8 All 8 States None Full Convergence. Maneuvers (turning/accelerating) break mathematical symmetry.
Dist + Mag + ZUPT 8 All 8 States None Optimal Calibration. Forcing $v=0$ allows biases to be isolated while standing still.

Note: For the 8-state filter to be healthy, the robot must either move (to expose $b_a$ through geometry changes) or use a Zero Velocity Update (ZUPT) to force the error into the bias states.

Key Takeaways¶

  • The "Motion Requirement": For the 8-state filter to be truly healthy, the robot must either move (to make $b_a$ observable) or use a ZUPT (to force observability during calibration).
  • The Covariance ($P$) Check: If you are unsure if a state is observable in your simulation, plot the diagonal of the $P$ matrix. If the variance for a state (like $\theta$) keeps growing despite having a distance sensor, that state is unobservable in that specific configuration.
  • Decoupling: Full observability (Rank 8) means the EKF can successfully "blame" the correct sensor for errors. For example, it can tell the difference between the robot being $10\text{ cm}$ off-course and the accelerometer having a $0.01\text{ m/s}^2$ bias.
Kontakt/Impressum