Skip to content

Instantly share code, notes, and snippets.

@sritchie
Last active June 2, 2026 20:09
Show Gist options
  • Select an option

  • Save sritchie/9400bd7eb602aebfca39851ad45e0914 to your computer and use it in GitHub Desktop.

Select an option

Save sritchie/9400bd7eb602aebfca39851ad45e0914 to your computer and use it in GitHub Desktop.
log_308 analysis: EKFQ-diagnostic states on first 416 Hz flight (N720AK, 2026-06-02, 51 min)

log_308 — First flight with EKFQ-diagnostic states logged

Aircraft: N720AK, RV-10 Date: 2026-06-02 Duration: 51.4 min Log rate: 416 Hz Rows: 1,282,972 Log integrity: zero drops (drops=0 dbg_drops=0 paused_drops=0 throughout the .dbg) Algorithm: EKFQ (confirmed by finite values in ekf* columns — under Madgwick these are NaN)

This is the first real-flight test of the six EKFQ-diagnostic states landed in PR #678 (gyro biases bp/bq/br, vertical-accel bias b_az, sideslip β, yaw). The goal was to find out whether the now-exposed bias states are physically meaningful enough to use in a downstream P2-style "bias-corrected gyro rates on the wire" cleanup.

Companion analysis: β vs lateral-G as a slip-skid ball signal — same flight, different question.

Flight envelope

IAS 0 → 127 kt
Palt 4900 → 9650 ft
Pitch -13.9° → +15.6°
Roll -56.1° → +48.1°

Regime breakdown:

Regime Samples Duration
Ground (IAS < 20) 521,643 20.9 min
Taxi (5 ≤ IAS < 30) 490,387 19.6 min
Climb (IAS ≥ 60, VSI > 300) 239,554 9.6 min
Cruise (IAS ≥ 80, |VSI| < 200) 120,885 4.8 min
Descend (IAS ≥ 60, VSI < -300) 262,235 10.5 min

What the new states reveal

b_az — works as intended ✅

Converges within ~30 s of takeoff to ≈ -0.3 m/s² (≈ -0.03 g). Steady-state cruise: mean -0.44 m/s², std 0.20 m/s². That's a plausible accelerometer bias for a MEMS IMU at flight temperature. No tuning issue. This is the only bias state in the filter that behaves like an actual bias.

β — works as intended ✅

Stays within ±2° in coordinated flight, settles around -0.23° in cruise. Spikes visibly during the obvious roll maneuvers (31-35 min). Gated off below TAS = 12 m/s as expected. Looks correct.

yaw — drifts as expected, no mag ✅

Walks through ±180° (atan2 range). Final 60 s average: 107.8° ± 6.9°. There's no magnetometer in OnSpeed, so this is a relative-yaw signal, not compass heading. As designed.

bp vs bq/br asymmetry — structural ✅ but...

State Range across flight Behavior
bp (roll-rate bias) [-0.0005, +0.0004] deg/s Effectively nailed at the zero-mean prior
bq (pitch-rate bias) [-1.7?, +1.72] deg/s Spikes ±1 deg/s during turns/maneuvers
br (yaw-rate bias) [-1.1?, +1.14] deg/s Similar to bq

Tracing the EKFQ correct step (EKFQ.cpp:548-610):

  • ax_pred = -2g(q1q3 - q0q2) + tasDot — no bp coupling
  • ay_pred = -2g(q2q3 + q0q1) + tas·r_c where r_c = yawRate - br — couples br
  • az_pred = -g·R22 - tas·q_c where q_c = pitchRate - bq — couples bq

bp is structurally unobservable. Roll rate produces no centripetal accel observable in body ay/az under coordinated flight, so the filter has no information channel to estimate bp. The zero-mean prior is the only thing acting on it. This isn't a bug — it's a consequence of "accelerometer residuals after centripetal compensation are the only update source."

bq is not a bias — it's a fast residual sink ❌

This is the headline finding.

Look at bq in the overview plot. It's near-zero on the ground, then slams ±1 deg/s during turns/pull-ups, then returns toward zero between maneuvers within seconds. That's not bias behavior. Real MEMS gyro bias drift is on a minutes-to-hours timescale.

The cumulative ∫bq dt over the flight is -25° while pitch is centered at 0. If bq were a real gyro bias, attitude would have drifted by 25° relative to truth — but obviously it didn't (the pre/post-flight pitch numbers are within 0.4° of each other).

The likely cause: q_bias = 0.0806 (rad/s)²/s is ~5 orders of magnitude too large for actual gyro bias dynamics.

  • Real MEMS gyros: bias drift < 0.1 deg/s per minute → q_bias ≈ 3e-6 (rad/s)²/s would be physically appropriate
  • This config allows bp/bq/br to drift by sqrt(0.0806) ≈ 0.28 rad/s ≈ 16 deg/s per second of process noise
  • The zero-mean prior (r_bias_prior = 3.6e-4 (rad/s)², std ≈ 1.1 deg/s) pulls back to zero, but the Q is so loose that the filter happily uses bq as a fast attitude-correction lever

This is the Optuna substrate's fault — it was tuned for "minimize cruise-AOA loss vs VN-300 truth" and likely found that a fast-bq let the filter respond faster to pitch maneuvers. But the resulting "bias" doesn't mean anything physical.

Pitch drift across the flight

Measurement Value
Pre-takeoff ground pitch (123k samples, IAS ≤ 5.5) -0.5392°
Post-landing ground pitch (3.5k samples, IAS ≤ 5.5) -0.1067°
Net drift +0.4325°
Duration ~44 min
Drift rate +0.010°/min

That's half of flight 274's reported +0.019°/min. Either PR #663 (exact-exp quaternion propagation) cut it in half, or this is run-to-run variation, or pre/post taxiway slopes differ subtly. More flights needed to separate signal from noise.

What this means for Layer-3 follow-ups

Finding What it means Action
bq/br Q-noise too high — they act as residual sinks, not biases Optuna found a perverse local optimum. Filter resolves attitude correctly but the bias states don't carry physical meaning. Re-tune q_bias against this (and future) flights using a loss that constrains bias-drift bandwidth, not just cruise-AOA loss.
bp is unobservable Roll-rate bias structurally can't be estimated from accel residuals alone in this filter. Accept it. Could add a slow-mode observability path if it ever matters.
Pitch drift ~0.010°/min, halved from flight 274 PR #663 plausibly helps; or this is run-to-run noise. Need more flights to separate signal from noise.
b_az converges cleanly to ~-0.3 m/s² The vertical-accel bias is the only bias state that works as intended. No action — confirms the EKF infrastructure is correct, just q_bias for gyros is wrong.
Zero log drops at 416 Hz over 51 min The lock-free snapshot + universal writer architecture is solid at the experimental log rate. Confirms PR #647 / #670 / #671 etc. are production-ready.

Concrete next steps

  1. Don't ship P2 (bias-corrected gyro rates on the wire) yet. The bp/bq/br numbers aren't physically meaningful. P2 would replace the 30-sample RunningMean with rate − bias, but if bias is a fast residual sink rather than a real bias, the corrected rate would be worse than the running mean. Block P2 on q_bias re-tune.
  2. b_az IS usable. P3 (subtract from EarthVerticalG log column) and the b_az portion of P8 (bias-corrected gOnsetFilter input) are both fine to proceed with — though as noted earlier they're trivially derivable from existing columns, so probably not worth a firmware PR.
  3. Re-run Optuna substrate with this log (and ideally another) using a loss that includes a bq smoothness / bandwidth penalty. Goal: bias states that look bias-shaped, not residual-sink-shaped. Track the trade-off vs cruise-AOA loss.
  4. Collect more 416 Hz logs with EKFQ-diag on before any bias-correction PRs. We need to see whether bq's bad behavior is reproducible across flights and whether it scales with maneuver intensity.

Bug hunt: are there straight-up EKFQ bugs that could cause this?

Looking at EKFQ on actual origin/master (post-PR #663 exact-exp map, post-#678 diagnostics):

Verified non-bugs

  • Quaternion integration is the exact exponential map, not first-order Euler. q ← q ⊗ exp(½ω·dt) with sinc Taylor expansion in the small-angle limit. Unit-preserving by construction. The renormalise after the step is just float-roundoff shedding. Not a source of drift.
  • The H matrix on the accel-z row has H[BQ] = +tas and the accel-y row has H[BR] = -tas, both correct centripetal-comp couplings. H[BP] legitimately doesn't appear in any accel measurement — that's the structural unobservability finding above, not a bug.
  • The β dynamics gate on tas > tas_min_mps = 12 m/s is correctly preventing pitot-noise-driven β estimation at low speed.

Possible concerns worth a second look

  • Coupling between bq and quaternion via the predict step's F matrix. The F-row for Q0..Q3 includes qb_q*_b{p,q,r} = ∓half_dt · q* entries (coupling each quaternion component to each gyro bias). At 416 Hz dt is small, so any single-frame coupling is small. But when bq is allowed to swing ±1 deg/s by an overly loose q_bias, that swing feeds back into the quaternion's covariance prediction and may amplify quaternion-bq cross-correlations. Diagnostic to add: plot P[Q0][BQ] (or any quat-bq covariance term) over time — if it grows unbounded or oscillates, that's a sign the cross-coupling is excited by the q_bias setting.
  • The TAS feed to the centripetal terms is tas_ · compFadeIn_ (faded by the IAS-gate rising-edge ramp). When IAS just becomes alive, TAS ramps from 0 to its true value over ~0.5 s. During that ramp, the +tas·q_c term in az_pred is artificially small, so the filter under-uses bq for that ~0.5 s. Probably fine — it's a brief transient — but worth noting that bq's behavior near IAS-alive transitions may look different from steady-state.
  • The bq prior is applied alongside the accel measurements in the same batch. The Cholesky update jointly solves for all states given all observations. With r_bias_prior = 3.6e-4 (rad/s)² (std ≈ 1.1 deg/s), the prior is weak; the accel measurements dominate when their residual is large. Hence: when az-residual is big, bq swings to absorb it; when the maneuver stops, the prior slowly pulls it back. This is the smoking-gun mechanism of "bq behaves like a residual sink not a bias." Not a code bug; a tuning consequence.

What I'd actually look at next

Not a bug hunt — more a modeling adequacy question. The bq term as currently structured can absorb any az-residual that the quaternion attitude doesn't already explain. In steady level flight that's noise (and bq stays small). In a sustained pull-up or descent, az ≠ -g·R22, and the residual gets split between attitude correction (the four quat H entries) and a "fake bias" correction (the BQ H entry). The filter has no way to know which is which without longer time-scale evidence — and q_bias being huge tells it "bias can change fast, so use BQ liberally."

A real fix isn't a code change; it's either:

  1. Add a magnetometer so attitude has an independent reference and the filter no longer needs to use BQ as a slack variable. (Not happening soon — no hardware.)
  2. Re-tune q_bias MUCH tighter so BQ can only change on minutes-timescale. Optuna will then have to find another way to fit cruise-AOA — possibly by relaxing r_az or by accepting larger residuals during pull-ups. The trade-off may degrade the AOA estimate during maneuvers.
  3. Add a maneuver-detection gate that disables BQ updates when pitch-rate or load-factor exceeds a threshold. Keeps BQ as a slow-drift estimator; doesn't let it absorb maneuver-driven residuals.

Option 2 is the cheap experiment. Re-running Optuna with bounded q_bias (e.g., 1e-6 to 1e-4 instead of the current 1e-8 to 1e-2 search range) would tell us whether the cruise-AOA degradation is meaningful.

Tuning rate-mismatch concern: was Optuna tuned at 208 Hz?

The Optuna substrate (ekfq_pipeline/tune_ekf.py) runs against a recorded log replayed through host_main. If the training log was 208 Hz and this flight is 416 Hz, the per-frame Q is q_bias × dt, halved relative to training. The per-second integrated Q is rate-invariant in principle, but the per-frame interplay between predict and the joint Cholesky correct is not — at 2× rate, the filter gets 2× more accel updates per second to slam BQ around. So 416 Hz operation would make BQ swing twice as fast as it did at the training rate, amplifying the existing tuning weakness rather than causing it.

Action: re-tune Optuna at 416 Hz before drawing conclusions about whether the bq residual-sink behavior is reducible to per-frame Q. If the same Optuna run at 416 Hz also lands on q_bias ≈ 0.08, the cause is the objective function (cruise-AOA loss rewarding fast-bq) not the rate. If it lands much smaller, the cause is per-frame Q scaling, and we get a cleaner fix.


Plots

Full-flight overview

overview

Pay attention to:

  • Gyro bias panel (3rd row): bp is invisible (stuck near zero); bq and br swing wildly during the in-flight portion (~18-50 min) and return to zero on the ground.
  • b_az panel (4th row): starts with a transient spike at takeoff, then settles around -0.3 m/s² for the rest of the flight.
  • β panel (5th row): zero on the ground (TAS gate), small ±2° excursions in flight.
  • yaw panel (6th row): wraps at ±180° because of atan2. Not a compass — no magnetometer in OnSpeed.

Bias convergence — first 10 min

bias convergence

This is the engine-warm-up + taxi phase. IAS < 12 m/s, so β-dynamics are gated off and stay at exactly zero. b_az converges quickly (~30 s) to its steady-state value. Gyro biases are all clamped near zero because there's no flight maneuvering to drive the centripetal terms.

bq vs pitch drift

bq vs pitch

Top panel: pitch (blue, left axis) vs ∫bq dt (red, right axis). The integrated bias would, if bq were a real gyro bias, predict 25° of pitch drift over the flight — but pitch obviously didn't drift 25°. This is the visual evidence that bq is functioning as a fast residual sink, not a slow bias estimator.

Bottom panel: raw bq, ±1.5 deg/s during maneuvering. The spikiness and rapid return to zero between maneuvers is the give-away that this isn't a bias state in the conventional sense — it's a degree of freedom the filter is using to absorb az-residuals.

"""
log_308 analysis — first real flight with EKFQ-diagnostic states logged.
Goals:
1. Verify the new ekf* columns carry sensible data over a 51-min, 416 Hz flight.
2. Plot bias-state convergence: bp/bq/br + b_az over time.
3. Identify steady-state magnitudes of each bias.
4. Look for pitch drift correlated with bq (the flight-274 hypothesis).
5. Sanity-check β stays near zero in coordinated flight.
6. Report yaw drift rate (no mag, so the rate is the signal of interest).
"""
from pathlib import Path
import sys
import numpy as np
import pandas as pd
import matplotlib.pyplot as plt
from matplotlib.gridspec import GridSpec
LOG_PATH = Path("/Users/sritchie/Library/CloudStorage/GoogleDrive-sritchie09@gmail.com/"
".shortcut-targets-by-id/1JEHdf2zPb_F1R0v-s94Ia2RZNGjPCk2n/"
"Flight Test Data/N720AK RV-10 Data/6-2-2026/2 June 26 Cockpit/"
"log_308.csv")
OUT_DIR = Path(__file__).parent
# Columns we actually need for this analysis. Skip the wide EFIS / VN-300
# columns we don't care about — that's 75% of the row width.
USECOLS = [
"timeStampUs", "IAS", "Palt", "AngleofAttack", "Pitch", "Roll",
"RollRate", "PitchRate", "YawRate", "VerticalG", "LateralG",
"EarthVerticalG", "FlightPath", "VSI", "Altitude", "DerivedAOA",
"ekfBpDps", "ekfBqDps", "ekfBrDps",
"ekfBAzMps2", "ekfBetaDeg", "ekfYawDeg",
]
def load():
print(f"Loading {LOG_PATH.name} ({LOG_PATH.stat().st_size / 1e6:.0f} MB)…", flush=True)
df = pd.read_csv(LOG_PATH, usecols=USECOLS, low_memory=False)
print(f" {len(df):,} rows, {len(df.columns)} cols", flush=True)
df["t_s"] = (df["timeStampUs"] - df["timeStampUs"].iloc[0]) / 1e6
df["t_min"] = df["t_s"] / 60.0
return df
def regime_masks(df):
"""Coarse flight regimes by IAS."""
ias = df["IAS"]
return {
"ground": ias < 20,
"taxi": (ias >= 5) & (ias < 30),
"climb": (ias >= 60) & (df["VSI"] > 300),
"cruise": (ias >= 80) & (df["VSI"].abs() < 200),
"descend": (ias >= 60) & (df["VSI"] < -300),
}
def report_basic_stats(df):
print("\n=== Basic stats ===")
print(f"Duration: {df['t_s'].iloc[-1]:.1f} s = {df['t_min'].iloc[-1]:.2f} min")
print(f"Rows: {len(df):,}")
rate = len(df) / df["t_s"].iloc[-1]
print(f"Effective rate: {rate:.1f} Hz")
print(f"IAS min/max: {df['IAS'].min():.1f} / {df['IAS'].max():.1f} kt")
print(f"Palt min/max: {df['Palt'].min():.0f} / {df['Palt'].max():.0f} ft")
print(f"Pitch min/max: {df['Pitch'].min():.2f}° / {df['Pitch'].max():.2f}°")
print(f"Roll min/max: {df['Roll'].min():.2f}° / {df['Roll'].max():.2f}°")
masks = regime_masks(df)
print("\nRegime row counts:")
for name, m in masks.items():
secs = m.sum() / rate
print(f" {name:10s} {m.sum():>9,} ({secs/60:5.1f} min)")
def report_bias_stats(df):
print("\n=== EKFQ bias-state final values ===")
# Average over the last 60 s of flight to get a settled estimate
tail_mask = df["t_s"] > (df["t_s"].iloc[-1] - 60)
tail = df[tail_mask]
for col in ["ekfBpDps", "ekfBqDps", "ekfBrDps", "ekfBAzMps2", "ekfBetaDeg", "ekfYawDeg"]:
mean = tail[col].mean()
std = tail[col].std()
print(f" {col:14s} mean = {mean:+8.4f} std = {std:7.4f}")
print("\n=== Cruise-segment bias stats (IAS≥80, |VSI|<200) ===")
cruise = df[regime_masks(df)["cruise"]]
if len(cruise) > 100:
for col in ["ekfBpDps", "ekfBqDps", "ekfBrDps", "ekfBAzMps2", "ekfBetaDeg"]:
mean = cruise[col].mean()
std = cruise[col].std()
print(f" {col:14s} mean = {mean:+8.4f} std = {std:7.4f}")
print(f" cruise samples: {len(cruise):,}")
else:
print(f" not enough cruise data ({len(cruise)} samples)")
def report_pitch_drift_at_rest(df):
"""Flight-274 hypothesis check: does pitch drift while iasAlive=false?
Look at any ground segment (IAS < 20 kt) longer than 30 s and compute
the pitch drift rate during that segment.
"""
print("\n=== Pitch drift at rest (flight-274 hypothesis) ===")
rate = len(df) / df["t_s"].iloc[-1]
ground = df["IAS"] < 20
# Find contiguous ground segments
in_seg = False
segs = []
seg_start = 0
for i, g in enumerate(ground):
if g and not in_seg:
seg_start = i
in_seg = True
elif not g and in_seg:
if i - seg_start > 30 * rate: # > 30 seconds
segs.append((seg_start, i))
in_seg = False
if in_seg and len(ground) - seg_start > 30 * rate:
segs.append((seg_start, len(ground)))
print(f" Found {len(segs)} ground segments ≥30 s")
for k, (a, b) in enumerate(segs):
seg = df.iloc[a:b]
dt_min = (seg["t_s"].iloc[-1] - seg["t_s"].iloc[0]) / 60.0
if dt_min < 0.5:
continue
# Fit linear slope to pitch
t = seg["t_s"].values
p = seg["Pitch"].values
slope_per_s, intercept = np.polyfit(t, p, 1)
slope_per_min = slope_per_s * 60.0
# Mean bq during this segment
bq_mean = seg["ekfBqDps"].mean()
bq_final = seg["ekfBqDps"].iloc[-1]
print(f" Seg {k}: t={seg['t_min'].iloc[0]:6.2f}-{seg['t_min'].iloc[-1]:6.2f} min "
f"({dt_min:5.2f} min) "
f"pitch slope = {slope_per_min:+7.4f}°/min "
f"bq mean = {bq_mean:+7.4f} deg/s final = {bq_final:+7.4f}")
def plot_overview(df):
"""Wide overview of the whole flight."""
print("\nPlotting overview…")
# Downsample to ~10 Hz for plotting (the original is 416 Hz, way more
# than a screen can show)
rate = len(df) / df["t_s"].iloc[-1]
stride = max(1, int(rate / 10))
d = df.iloc[::stride].copy()
fig = plt.figure(figsize=(16, 18))
gs = GridSpec(7, 1, hspace=0.32)
ax = fig.add_subplot(gs[0])
ax.plot(d["t_min"], d["IAS"], lw=0.6, color="tab:blue", label="IAS (kt)")
ax2 = ax.twinx()
ax2.plot(d["t_min"], d["Palt"], lw=0.5, color="tab:orange", alpha=0.6, label="Palt (ft)")
ax.set_ylabel("IAS (kt)", color="tab:blue")
ax2.set_ylabel("Palt (ft)", color="tab:orange")
ax.set_title("log_308 — N720AK RV-10, 2026-06-02, 51.4 min, 416 Hz")
ax.grid(True, alpha=0.3)
ax = fig.add_subplot(gs[1])
ax.plot(d["t_min"], d["Pitch"], lw=0.5, label="Pitch (°)")
ax.plot(d["t_min"], d["Roll"], lw=0.5, label="Roll (°)", alpha=0.7)
ax.legend(loc="upper right", fontsize=8)
ax.set_ylabel("Attitude (°)")
ax.grid(True, alpha=0.3)
ax = fig.add_subplot(gs[2])
ax.plot(d["t_min"], d["ekfBpDps"], lw=0.6, label="bp (roll-rate bias)", color="tab:red")
ax.plot(d["t_min"], d["ekfBqDps"], lw=0.6, label="bq (pitch-rate bias)", color="tab:green")
ax.plot(d["t_min"], d["ekfBrDps"], lw=0.6, label="br (yaw-rate bias)", color="tab:purple")
ax.axhline(0, color="k", lw=0.5, alpha=0.5)
ax.legend(loc="upper right", fontsize=8)
ax.set_ylabel("Gyro bias (deg/s)")
ax.grid(True, alpha=0.3)
ax = fig.add_subplot(gs[3])
ax.plot(d["t_min"], d["ekfBAzMps2"], lw=0.6, color="tab:brown")
ax.axhline(0, color="k", lw=0.5, alpha=0.5)
ax.set_ylabel("b_az (m/s²)")
ax.grid(True, alpha=0.3)
ax = fig.add_subplot(gs[4])
ax.plot(d["t_min"], d["ekfBetaDeg"], lw=0.6, color="tab:olive")
ax.axhline(0, color="k", lw=0.5, alpha=0.5)
ax.set_ylabel("β sideslip (°)")
ax.grid(True, alpha=0.3)
ax = fig.add_subplot(gs[5])
ax.plot(d["t_min"], d["ekfYawDeg"], lw=0.6, color="tab:cyan")
ax.set_ylabel("yaw (° atan2)")
ax.grid(True, alpha=0.3)
ax = fig.add_subplot(gs[6])
ax.plot(d["t_min"], d["VSI"], lw=0.5, label="VSI (fpm)", color="tab:blue")
ax.axhline(0, color="k", lw=0.5, alpha=0.5)
ax.set_xlabel("Time (min)")
ax.set_ylabel("VSI (fpm)")
ax.grid(True, alpha=0.3)
out = OUT_DIR / "overview.png"
plt.savefig(out, dpi=120, bbox_inches="tight")
print(f" -> {out}")
plt.close(fig)
def plot_bias_convergence(df):
"""Zoom-in on the first 10 min showing how biases settle from init."""
print("\nPlotting bias convergence (first 10 min)…")
early = df[df["t_min"] < 10].copy()
rate = len(df) / df["t_s"].iloc[-1]
stride = max(1, int(rate / 20))
d = early.iloc[::stride]
fig, axes = plt.subplots(4, 1, figsize=(14, 10), sharex=True)
axes[0].plot(d["t_min"], d["IAS"], lw=0.7, color="tab:blue")
axes[0].set_ylabel("IAS (kt)")
axes[0].grid(True, alpha=0.3)
axes[0].set_title("Bias convergence — first 10 min of log_308")
axes[1].plot(d["t_min"], d["ekfBpDps"], lw=0.6, label="bp", color="tab:red")
axes[1].plot(d["t_min"], d["ekfBqDps"], lw=0.6, label="bq", color="tab:green")
axes[1].plot(d["t_min"], d["ekfBrDps"], lw=0.6, label="br", color="tab:purple")
axes[1].legend(loc="upper right")
axes[1].set_ylabel("Gyro biases (deg/s)")
axes[1].grid(True, alpha=0.3)
axes[1].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[2].plot(d["t_min"], d["ekfBAzMps2"], lw=0.6, color="tab:brown")
axes[2].set_ylabel("b_az (m/s²)")
axes[2].grid(True, alpha=0.3)
axes[2].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[3].plot(d["t_min"], d["ekfBetaDeg"], lw=0.6, color="tab:olive")
axes[3].set_xlabel("Time (min)")
axes[3].set_ylabel("β (°)")
axes[3].grid(True, alpha=0.3)
axes[3].axhline(0, color="k", lw=0.4, alpha=0.5)
out = OUT_DIR / "bias_convergence_first_10min.png"
plt.savefig(out, dpi=120, bbox_inches="tight")
print(f" -> {out}")
plt.close(fig)
def plot_bq_vs_pitch_drift(df):
"""Are pitch drifts correlated with bq?"""
print("\nPlotting bq vs pitch...")
rate = len(df) / df["t_s"].iloc[-1]
stride = max(1, int(rate / 5)) # 5 Hz is plenty
d = df.iloc[::stride].copy()
fig, axes = plt.subplots(2, 1, figsize=(14, 7), sharex=True)
axes[0].plot(d["t_min"], d["Pitch"], lw=0.5, color="tab:blue", label="Pitch (°)")
# Cumulative bq * dt would integrate to a pitch-error if uncorrected
bq_integrated_deg = (d["ekfBqDps"].fillna(0).cumsum() / 5.0) # 5 Hz sample → /5
ax2 = axes[0].twinx()
ax2.plot(d["t_min"], bq_integrated_deg, lw=0.5, color="tab:red", alpha=0.7,
label="∫bq dt (cumulative)")
axes[0].set_ylabel("Pitch (°)", color="tab:blue")
ax2.set_ylabel("∫bq (deg)", color="tab:red")
axes[0].legend(loc="upper left", fontsize=8)
ax2.legend(loc="upper right", fontsize=8)
axes[0].grid(True, alpha=0.3)
axes[1].plot(d["t_min"], d["ekfBqDps"], lw=0.5, color="tab:green")
axes[1].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[1].set_xlabel("Time (min)")
axes[1].set_ylabel("bq (deg/s)")
axes[1].grid(True, alpha=0.3)
out = OUT_DIR / "bq_vs_pitch.png"
plt.savefig(out, dpi=120, bbox_inches="tight")
print(f" -> {out}")
plt.close(fig)
if __name__ == "__main__":
df = load()
report_basic_stats(df)
report_bias_stats(df)
report_pitch_drift_at_rest(df)
plot_overview(df)
plot_bias_convergence(df)
plot_bq_vs_pitch_drift(df)
print("\nDone.")

β vs lateral-G as the slip-skid ball signal

A follow-up question from the main log_308 analysis: now that EKFQ's β state is observable, would it make a better ball-driving signal than the lateral-G OnSpeed ships today? Same flight data; new strata.

What other systems do

The reverse-engineering audits at ~/code/onspeed/{g3x,dynon}-audit cover this:

  • Garmin G3X: the slip-skid ball widget on the GDU is derived from body-frame lateral acceleration, not from a sideslip channel. Garmin's GSU 25C EKF doesn't appear to carry β as a state at all; β is reconstructed post-hoc when needed. The ball is only smoothed by the EKF Kalman gain on the body-Y accel state — no extra display-side LP. (G3X_SMOOTHING.md:230-280)
  • Dynon SkyView: has a dedicated SlipSkidBall::set_ahrs_data class on the GDU that reads the adahrs_data_t field at offset +0x84. The audit's wire-format analysis shows it's lateral-G filtered with a 16-sample MA. There's also a separate 32-sample MA on a computed sideslip channel, but the audit team found no evidence it actually drives the displayed ball.
  • OnSpeed today: ball-substitute readout in /indexer uses the EMA-smoothed body-frame lateral-G (α≈0.06 at IMU rate, ~280 ms τ at 416 Hz). Same convention as Dynon and Garmin: the ball is a pendulum and the pendulum signal is body-Y accel.

Net: nobody uses β to drive the ball. Two big-name EFIS vendors converged on lateral-G with a producer-side filter and no display-side smoothing.

Sign convention reminder (load-bearing)

  • Positive LatG in body frame ⇒ airframe centripetally accelerating LEFT ⇒ pendulum-ball displaces LEFT in the cockpit ⇒ pilot needs LEFT rudder ("step on the ball" = step on the side the ball is on).
  • Positive β (aerodynamic convention) ⇒ nose yawed RIGHT of velocity vector ⇒ relative wind hits the right cheek ⇒ pilot needs LEFT rudder.

So in coordinated flight both signals read ~0, and in a real slip both signals have the SAME sign.

What log_308 actually shows

Per-regime signal statistics

(Same flight, sliced by attitude regime; in-flight defined as IAS > 60.)

Regime n β mean β std LatG mean LatG std
Coordinated cruise (|Roll|, |Pitch| < 5°, |RollRate| < 5°/s) 343 k -0.139° 0.77° +0.0571 g 0.167 g
Steady LEFT turn (Roll < -20°, |RollRate| < 2°/s) 59 k -1.776° 1.40° +0.0656 g 0.170 g
Steady RIGHT turn (Roll > +20°, |RollRate| < 2°/s) 15 k +2.449° 0.96° +0.0675 g 0.174 g
Dynamic LEFT (RollRate < -10°/s) 10 k -1.188° 2.26° +0.0738 g 0.216 g
Dynamic RIGHT (RollRate > +10°/s) 11 k -0.115° 1.54° +0.0405 g 0.172 g

The installation-bias finding

LatG carries a +0.0571 g installation bias seen in coordinated cruise. That's arctan(0.057) ≈ 3.27° of right-side mounting tilt. Same offset shows up in both left-turn (+0.0656 g) and right-turn (+0.0675 g) means — both are within ~0.01 g of the cruise bias, consistent with no real slip on top of the mount-offset.

That's small enough that a pre-flight "level the ball" zero-cal kills it. Both Dynon and Garmin assume installation-zero-cal is the pilot's job; the firmware just publishes raw lateral-G.

After subtracting the cruise bias: LatG_corrected ≈ +0.008 g in left turns, +0.010 g in right turns — both directions read essentially zero slip, which matches what you'd expect from a competent RV-10 pilot flying coordinated turns.

The β asymmetry finding

β does NOT center on zero in coordinated turns, even after the LatG bias is gone:

  • Left turns: β = -1.78° (nose-yawed-LEFT-of-velocity, would call for LEFT rudder — but you weren't slipping, so this is artifact)
  • Right turns: β = +2.45° (nose-yawed-RIGHT-of-velocity, RIGHT rudder — same artifact)

The signs disagree with LatG_corrected (which says ~0 in both directions). β consistently reads non-zero during steady turns. Not by a tiny amount — almost two degrees in left turns, almost two-and-a-half in right turns.

Sign-agreement test

For each turn regime, does β's mean and LatG_corrected's mean point the same direction?

Regime β mean LatG_corrected mean Verdict
left_steady -1.78° +0.0085 g DISAGREE
right_steady +2.45° +0.0104 g AGREE (both positive)
left_dynamic -1.19° +0.0167 g DISAGREE
right_dynamic -0.12° -0.0166 g AGREE (both negative)

In the dynamic regimes the agreement looks better, but β's mean is small enough (-1.19° to -0.12°) that the agreement is probably noise rather than signal.

Why β is biased away from zero (the load-bearing mechanism)

From EKFQ.cpp:240-245:

β̇ ≈ (ay_raw + g·R21) / TAS − r_c

In a coordinated turn, the physical balance is:

  • r_c = (g·R21)/TAS (turn rate matches gravity-tilt-induced lateral specific force)
  • ay_raw = 0 (no body-frame slip-induced accel)
  • ⇒ β̇ = 0, β stays at whatever it was

In log_308 we have ay_raw actually carrying a +0.057 g installation bias (not zero) plus whatever real ay-residual the maneuver produces. So in a steady coordinated turn:

  • (ay_raw + g·R21)/TAS ≈ (0.057×9.81 + g·R21)/TAS
  • r_c matches only the g·R21 term (because the aircraft really is coordinating)
  • The leftover 0.057×9.81/TAS ≈ 0.56/TAS rad/s ≈ 0.026°/s drives β toward a non-zero steady state

The actual β value is determined by how the EKFQ batch correct step balances the β-residual against the br-bias-state's residual against the β=0 weak prior. In effect, part of the IMU lateral installation bias gets absorbed into br (which we already know is unreliable per the main log_308 analysis), and part of it surfaces as β instead of being cleanly attributable.

That's why β looks structurally biased: it can't tell "real slip" from "IMU lateral installation tilt" without help.

LatG suffers from the same physical cause (the IMU tilt) but in a clean DC way that's calibratable with one bench measurement. β filters it through br (which has its own tuning problems) and ends up worse.

What this means for using β on the wire

Property LatG (status quo) β (proposed P4)
Installation calibration Pre-flight "level the ball" zeroes it. Stable forever after. Filter-dependent. β's zero shifts with br's state. Re-cal at every algorithm change or every Optuna re-tune.
Steady-turn zero Yes, after cal No (log_308 evidence: ~-1.8° in left, +2.5° in right)
Dynamic response EMA-smoothed (α=0.06, ~280 ms τ) EKF-Kalman-smoothed (faster, but jittery on the bottom panel below)
Symmetric across turn direction Yes No (-1.8° vs +2.5° asymmetry)
Industry baseline Garmin uses this. Dynon uses this. Neither does.
Physical-truth signal during a real slip Indirect (centripetal-tied) but pilot-trained-on-it for a century Direct (the actual aerodynamic angle)

Concrete recommendation

β is NOT a better ball signal than LatG as currently implemented. Reasons:

  1. β picks up the same IMU installation bias LatG does, but routes it through br (which we already showed is mis-tuned).
  2. β doesn't center on zero in coordinated turns — left/right asymmetry of ~4°.
  3. β depends on EKFQ tuning; calibrating it means recalibrating the whole filter.
  4. Both Garmin and Dynon converged on lateral-G as the ball signal. That's a strong industry prior.

What P4 (β on the M5 wire) is still good for:

  1. Spin recovery cue (the original P4 motivation — F/A-18 SRM design uses β as input). The cue cares about trends and large deflections, not zero-calibration accuracy.
  2. Numeric diagnostic readout ("β = +2°") on the M5/indexer during Optuna re-tune flights. Lets the pilot see whether bias re-tuning makes β look more symmetric across turn directions.
  3. Cross-check with the ball. A pilot seeing the ball say "coordinated" but the β corner readout saying +3° has a free heads-up that something is miscalibrated (IMU mounting, or filter, or pilot's perception).

P4 is still worth doing, but frame it as a diagnostic + spin-cue enabler, not a "fix the ball" PR. The ball stays driven by LatG; the install-zero-cal procedure for LatG is the right place to spend effort if we want the ball to be more honest.

Plots

Histograms by turn direction

histograms

Top row: β distributions in steady left vs right turns. Both miss zero by a degree or more, in opposite directions. That's the asymmetry argument.

Bottom row: LatG distributions with the +0.0571 g coordinated-cruise bias subtracted. Both center cleanly on zero. LatG-after-bench-cal is the symmetric-zero signal; β isn't.

Time-window through a heavy maneuvering segment

window

A 4-minute window with multiple roll reversals. Panels top-to-bottom:

  1. Roll — the maneuver shape (banks ±30°)
  2. RollRate — the maneuver dynamics
  3. LatG raw (light red) + α=0.06 EMA (dark red) — what OnSpeed ships today. EMA looks like a usable ball signal: stays near zero except during real lateral-G excursions.
  4. β — slower-moving than LatG; biased per-direction but otherwise tracks turn entries
  5. atan2(ay, az) vs β overlay — the audit-recommended "gravity tilt angle" pure inclinometer geometry sits at the same scale as β. Big tearing during banked maneuvers (because atan2 of two body-frame accels mixes centripetal with slip), much noisier than β. β does well at filtering the centripetal-vs-slip distinction.

Scatter: β vs LatG, colored by Roll

scatter

Each point is an in-flight sample (IAS > 60). Color = roll angle (blue = left bank, red = right bank). The dashed gray vertical line marks the LatG installation bias.

What to see:

  • The cloud sits to the right of x=0 and above the bias line — that's the installation offset showing up as a constant LatG shift.
  • Blue (left-bank) points fall BELOW β=0; red (right-bank) points fall ABOVE β=0. β's asymmetry in action.
  • No tight diagonal — if β were a strictly-better version of LatG-for-slip, we'd see a tight line at y = constant·x. Instead the relationship is loose and Roll-stratified.
"""
log_308 — β (EKFQ sideslip) vs lateral-G as a slip-skid ball signal.
Sign convention (corrected):
- Positive LatG (body-frame ay) means airframe is centripetally accelerating
LEFT. The pendulum-ball lags, displacing LEFT in the cockpit. Pilot needs
LEFT rudder. "Step on the ball" = the side the ball moved to.
- Positive β (aerodynamic convention) means nose is yawed RIGHT of velocity
vector — relative wind hitting the right cheek. Pilot needs LEFT rudder.
- So in a coordinated maneuver both signals should be ≈ 0; in a slip both
signals should have the SAME sign.
What we find in log_308:
- LatG carries a ~+0.066 g installation bias (right-side mounting tilt) —
both turn directions show the same DC offset, only the spread differs.
- β behaves coherently across direction (negative in left turns, positive in
right turns) but is itself biased by the same IMU lateral installation
axis the EKFQ has no way to separate from real slip, and the bias enters
via the `br` (yaw-rate-bias) state that's already known to be flaky.
Conclusion: β is NOT a better ball signal than LatG. Use it for the
spin-recovery cue and as a diagnostic, not for the ball.
"""
from pathlib import Path
import numpy as np
import pandas as pd
import matplotlib.pyplot as plt
LOG_PATH = Path("/Users/sritchie/Library/CloudStorage/GoogleDrive-sritchie09@gmail.com/"
".shortcut-targets-by-id/1JEHdf2zPb_F1R0v-s94Ia2RZNGjPCk2n/"
"Flight Test Data/N720AK RV-10 Data/6-2-2026/2 June 26 Cockpit/"
"log_308.csv")
OUT_DIR = Path(__file__).parent
USECOLS = [
"timeStampUs", "IAS", "Pitch", "Roll", "RollRate", "PitchRate", "YawRate",
"VerticalG", "LateralG", "ForwardG",
"ekfBetaDeg", "TAS",
]
def load():
df = pd.read_csv(LOG_PATH, usecols=USECOLS, low_memory=False)
df["t_s"] = (df["timeStampUs"] - df["timeStampUs"].iloc[0]) / 1e6
df["t_min"] = df["t_s"] / 60.0
# Same α=0.06 EMA the wire ships
alpha = 0.0609
g = df["LateralG"].values.copy()
for i in range(1, len(g)):
g[i] = alpha * df["LateralG"].iloc[i] + (1 - alpha) * g[i - 1]
df["LateralG_EMA"] = g
# Audit-recommended atan2(ay, az) inclinometer (degrees)
df["inclinometer_deg"] = np.degrees(np.arctan2(df["LateralG"], df["VerticalG"]))
return df
def regimes(df):
flying = df[df["IAS"] > 60]
return {
"coord_cruise": flying[
(flying["RollRate"].abs() < 5)
& (flying["Pitch"].abs() < 5)
& (flying["Roll"].abs() < 5)
],
"left_steady": flying[(flying["Roll"] < -20) & (flying["RollRate"].abs() < 2)],
"right_steady": flying[(flying["Roll"] > 20) & (flying["RollRate"].abs() < 2)],
"left_dynamic": flying[(flying["RollRate"] < -10)],
"right_dynamic": flying[(flying["RollRate"] > 10)],
}
def report(df):
r = regimes(df)
print("\n=== Per-regime sign analysis ===")
for name, sub in r.items():
if len(sub) < 100:
continue
print(f"\n{name:20s} n={len(sub):>7,} "
f"β: {sub['ekfBetaDeg'].mean():+6.3f}° ±{sub['ekfBetaDeg'].std():4.2f} "
f"LatG: {sub['LateralG'].mean():+6.4f}g ±{sub['LateralG'].std():5.4f} "
f"LatG_EMA: {sub['LateralG_EMA'].mean():+6.4f}g")
print("\n=== Installation-bias estimate ===")
coord = r["coord_cruise"]
latg_bias = coord["LateralG"].mean()
incl_bias = coord["inclinometer_deg"].mean()
print(f"In coordinated cruise (n={len(coord):,}):")
print(f" LatG mean = {latg_bias:+.4f} g → installation tilt ≈ {np.degrees(np.arctan(latg_bias)):.2f}°")
print(f" atan2(ay,az) mean = {incl_bias:+.3f}° (same physical quantity, different units)")
print(f" β mean = {coord['ekfBetaDeg'].mean():+.3f}°")
# Sign agreement between β and LatG: are they driving the ball
# in the same direction in the same situations?
print("\n=== Sign-agreement test ===")
for name in ["left_steady", "right_steady", "left_dynamic", "right_dynamic"]:
sub = r[name]
if len(sub) < 100:
continue
# Subtract the coordinated-cruise installation bias before comparing
latg_corrected = sub["LateralG"] - latg_bias
beta_sign = np.sign(sub["ekfBetaDeg"].mean())
latg_sign = np.sign(latg_corrected.mean())
agree = "AGREE" if beta_sign == latg_sign or beta_sign == 0 or latg_sign == 0 else "DISAGREE"
print(f" {name:15s}: β_mean={sub['ekfBetaDeg'].mean():+6.3f}° "
f"LatG_corrected_mean={latg_corrected.mean():+7.4f}g {agree}")
def plot_direction_stratified(df):
"""Stack histograms of β and LatG for left vs right turns. The asymmetry
pattern tells us which signal is more usable as a ball driver."""
r = regimes(df)
coord = r["coord_cruise"]
latg_bias = coord["LateralG"].mean()
fig, axes = plt.subplots(2, 2, figsize=(13, 9))
# Row 0: β distribution per regime
for ax, (name, label, color) in zip(
axes[0],
[("left_steady", "Steady LEFT turn (Roll<-20°)", "tab:blue"),
("right_steady", "Steady RIGHT turn (Roll>20°)", "tab:red")],
):
sub = r[name]
ax.hist(sub["ekfBetaDeg"], bins=80, alpha=0.6, color=color)
ax.axvline(0, color="k", lw=0.5, alpha=0.5)
ax.axvline(sub["ekfBetaDeg"].mean(), color=color, lw=2,
label=f"mean={sub['ekfBetaDeg'].mean():+.2f}°")
ax.set_xlabel("β (°)")
ax.set_ylabel("count")
ax.set_title(f"{label}\nn={len(sub):,}")
ax.legend()
ax.grid(True, alpha=0.3)
# Row 1: LatG distribution per regime (with bias subtracted to show what
# ball-zero-cal would actually achieve)
for ax, (name, label, color) in zip(
axes[1],
[("left_steady", "Steady LEFT turn — LatG", "tab:blue"),
("right_steady", "Steady RIGHT turn — LatG", "tab:red")],
):
sub = r[name]
latg_corrected = sub["LateralG"] - latg_bias
ax.hist(latg_corrected, bins=80, alpha=0.6, color=color)
ax.axvline(0, color="k", lw=0.5, alpha=0.5)
ax.axvline(latg_corrected.mean(), color=color, lw=2,
label=f"mean={latg_corrected.mean():+.4f}g")
ax.set_xlabel(f"LatG (g), bias {latg_bias:+.4f}g removed")
ax.set_ylabel("count")
ax.set_title(f"{label}\nn={len(sub):,}")
ax.legend()
ax.grid(True, alpha=0.3)
fig.suptitle(
"β vs LatG: distributions by turn direction\n"
"Hypothesis check: if β is the better ball signal, its distributions"
" should center on zero with sign agreeing with LatG-corrected"
)
plt.tight_layout()
out = OUT_DIR / "beta_vs_lateralg_histograms.png"
plt.savefig(out, dpi=120, bbox_inches="tight")
plt.close(fig)
print(f" -> {out}")
def plot_time_window(df):
"""Time-window plot through a 4-min maneuvering segment, showing how the
three candidate ball signals (LatG raw, LatG EMA, β, atan2 inclinometer)
behave during real maneuvering."""
window = df[(df["t_min"] > 30) & (df["t_min"] < 34)].copy()
fig, axes = plt.subplots(5, 1, figsize=(15, 12), sharex=True)
axes[0].plot(window["t_min"], window["Roll"], lw=0.7, color="tab:blue")
axes[0].set_ylabel("Roll (°)")
axes[0].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[0].grid(True, alpha=0.3)
axes[0].set_title("4-min maneuvering window: candidate ball signals compared")
axes[1].plot(window["t_min"], window["RollRate"], lw=0.5, color="tab:purple")
axes[1].set_ylabel("RollRate (°/s)")
axes[1].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[1].grid(True, alpha=0.3)
# LatG raw + EMA — what OnSpeed ships today as the "ball signal"
axes[2].plot(window["t_min"], window["LateralG"], lw=0.3, alpha=0.4,
color="tab:red", label="LatG raw")
axes[2].plot(window["t_min"], window["LateralG_EMA"], lw=0.8,
color="tab:red", label="LatG α=0.06 EMA (wire)")
axes[2].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[2].set_ylabel("LatG (g)")
axes[2].legend(loc="upper right", fontsize=8)
axes[2].grid(True, alpha=0.3)
# β alone
axes[3].plot(window["t_min"], window["ekfBetaDeg"], lw=0.7, color="tab:olive")
axes[3].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[3].set_ylabel("β EKFQ (°)")
axes[3].grid(True, alpha=0.3)
# atan2(ay, az) — the audit's recommended cheap ball-physics signal
axes[4].plot(window["t_min"], window["inclinometer_deg"], lw=0.4,
color="tab:purple", label="atan2(ay,az) (°)")
axes[4].plot(window["t_min"], window["ekfBetaDeg"], lw=0.7,
color="tab:olive", label="β EKFQ (°)")
axes[4].axhline(0, color="k", lw=0.4, alpha=0.5)
axes[4].set_xlabel("t (min)")
axes[4].set_ylabel("angle (°)")
axes[4].legend(loc="upper right", fontsize=8)
axes[4].grid(True, alpha=0.3)
plt.tight_layout()
out = OUT_DIR / "beta_vs_lateralg_window.png"
plt.savefig(out, dpi=120, bbox_inches="tight")
plt.close(fig)
print(f" -> {out}")
def plot_scatter(df):
"""β vs LatG scatter colored by Roll. If β were a strict 'better' version
of LatG-as-slip-indicator, we'd see a tight diagonal line. Anything else
means the two signals encode different things."""
flying = df[df["IAS"] > 60].copy()
n = 50000
if len(flying) > n:
flying = flying.iloc[:: len(flying) // n]
fig, ax = plt.subplots(figsize=(9, 7))
sc = ax.scatter(flying["LateralG"], flying["ekfBetaDeg"],
s=2, alpha=0.25, c=flying["Roll"], cmap="coolwarm",
vmin=-45, vmax=45)
ax.axhline(0, color="k", lw=0.5, alpha=0.5)
ax.axvline(0, color="k", lw=0.5, alpha=0.5)
# Coordinated cruise bias
coord = regimes(df)["coord_cruise"]
latg_bias = coord["LateralG"].mean()
ax.axvline(latg_bias, color="gray", lw=1, ls="--", alpha=0.6,
label=f"coord LatG bias {latg_bias:+.4f}g")
ax.set_xlabel("LatG (g)")
ax.set_ylabel("β EKFQ (°)")
ax.set_title("β vs LatG in-flight, colored by Roll angle\n"
"(blue=left bank, red=right bank). Both at 0 = coordinated.")
plt.colorbar(sc, ax=ax, label="Roll (°)")
ax.legend(loc="upper left")
ax.grid(True, alpha=0.3)
out = OUT_DIR / "beta_vs_lateralg_scatter.png"
plt.savefig(out, dpi=120, bbox_inches="tight")
plt.close(fig)
print(f" -> {out}")
if __name__ == "__main__":
print("Loading…")
df = load()
report(df)
print("\nPlotting…")
plot_direction_stratified(df)
plot_time_window(df)
plot_scatter(df)
print("Done.")
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment