feat(falcon): v0.19.7 — true-velocity odometry + hover bistability characterization#52
Conversation
…aracterization
Builds on v0.19.6's frame fix with a deterministic velocity source
(gz OdometryPublisher) + a velocity-cascade altitude controller.
HONEST OUTCOME: reliable tight hover is NOT achieved. The controller
demonstrably CAN hold a perfect hover (alt-only: final 0.012 m, rms
0.016 m — ±2 cm for the last 5 s) but the gz full-hover is bistable:
the same config gives 0.02 m one run and a grounded 1.97 m the next.
The verified mixer + controller are correct; the issue is reliability
(startup basin), not capability.
Shipped (real, reliable):
- True body velocity via gz-sim-odometry-publisher-system →
/model/quad/odometry (100 Hz gz.msgs.Odometry). Bridge defines a
minimal local Odometry (twist-only; gz-transport-rs 0.1.0 lacks
the wrapper), subscribes, converts ENU→NED, exposes via the new
Physics::velocity_ned() trait method. Replaces finite-diff-of-NavSat
(noisy/lagged → non-deterministic inner loop).
- Velocity-cascade altitude (alt-rate): outer P (alt err →
bounded climb-rate target) + inner P (rate err → thrust) +
conditional windup-guarded integral + thrust clamp 0.88 to
reserve torque headroom.
- PosController tuned for the 2 kg body (hover_thrust 0.5→0.72).
Three coupled root causes of the bistability (→ v0.19.8 design items,
not gain-tuning):
1. startup tip-over (alt-only, no attitude control) →
deterministic startup sequencing / attitude-hold-from-t0.
2. mixer thrust/torque limit cycle (alt-rate): rate-PID torque near
thrust saturation makes relay-mix-quad's priority-preserving
saturation steal thrust → ±1 m oscillation → relay-mix-quad
should reserve a hover thrust floor (VERIFIED change + Verus
contract).
3. EKF attitude during vertical accel (full cascade): Mahony
accel-as-gravity tilts during climb → relay-ekf accel
down-weighting at high |a|.
Verification:
- cargo test --workspace → green; -p falcon-sitl-gz --features
gazebo → 9/9.
- frame-check oracle (v0.19.6) still AGREE on roll + pitch.
- odometry subscriber delivers true velocity.
- rivet validate → PASS.
Claiming a gain set "works" when it passes 1 run in 3 would violate
the project's falsification discipline. The reliable PASS is gated on
the three design changes above; the largest (mixer thrust floor) is a
verified-component change deserving its own oracle-gated release.
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
ac81f23 to
a2e9847
Compare
|
running 13 tests test result: ok. 13 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 0.04s running 0 tests test result: ok. 0 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 0.00s running 13 tests test result: ok. 13 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 0.00s running 0 tests test result: ok. 0 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 0.00s running 13 tests test result: ok. 13 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 0.61s running 0 tests test result: ok. 0 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 0.00s running 17 tests test result: ok. 17 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 0.07s --- scenario: step ---
|
| count | |
|---|---|
| Passed | 33 |
| Failed | -8 |
| Skipped (bench-only — needs hardware / sim) | 7 |
| Skipped (no steps) | 8 |
Failed artifacts
Bench-only artifacts (not run by CI)
FV-FALCON-SIM-005— gz-transport NavSat + Home projection — position-dependent loops (v0.18.1)FV-FALCON-ARCH-001— spar AADL architectural model — falcon cascade (v0.13)FV-FALCON-COV-001— witness MC/DC structural coverage — falcon pipeline wired (v0.13)FV-FALCON-SIM-001— PX4-SITL end-to-end loop — recipe + preset + smoke (v0.14.0)FV-FALCON-ARCH-002— spar codegen --format wit recheck — works at v0.10.0 (v0.15.0)FV-FALCON-COV-003— witness MC/DC on real Rust source — Geofence subject (v0.14.1)FV-FALCON-GEO-003— Geofence safety path — miri UB/overflow check (v0.12, AI substitute)
Source of truth: artifacts/verification/FV-FALCON-*.yaml.
…op hover is gz-only now) The v0.19.7 PosController retune (hover_thrust 0.5→0.72 for the 2 kg gz airframe) makes the default closed-loop hover correctly FAIL on MockPhysics — a ~500 g model that ignores attitude torque, so it can't hover via the cascade. FV-FALCON-SIM-003's bare 'cargo run -p falcon-sitl-gz' smoke step (default = mock + hover) therefore exited 1, failing the verification gate. Fix: the mock smoke runs --scenario=open-loop-climb (pure collective- thrust climb), the scenario MockPhysics can execute end-to-end. The closed-loop hover is exercised against real gz in FV-FALCON-SIM-013 (bench-only). The default binary scenario is unchanged (gz hover is the headline); only the mock smoke step is made scenario-explicit. Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
Summary
Builds on v0.19.6's frame fix with a deterministic velocity source (gz
OdometryPublisher) + a velocity-cascade altitude controller.Honest outcome: reliable tight hover is NOT achieved. The controller demonstrably can hold a perfect hover (alt-only: final 0.012 m, rms 0.016 m — ±2 cm for 5 s) but the gz full-hover is bistable — the same config gives 0.02 m one run and a grounded 1.97 m the next. The verified mixer + controller are correct; the issue is reliability (startup basin), not capability.
Shipped (real, reliable)
gz-sim-odometry-publisher-system→/model/quad/odometry. Bridge defines a minimal localOdometry(twist-only; gz-transport-rs 0.1.0 lacks the wrapper), subscribes, ENU→NED, exposes via newPhysics::velocity_ned(). Replaces the noisy/lagged finite-diff-of-NavSat.Three coupled root causes (→ v0.19.8 design items, not gain-tuning)
relay-mix-quad's priority-preserving saturation steal thrust → ±1 m oscillation →relay-mix-quadshould reserve a hover thrust floor (verified change + Verus contract).relay-ekfaccel down-weighting at high |a|.Verification
cargo test --workspace→ green;-p falcon-sitl-gz --features gazebo→ 9/9.rivet validate→ PASS.Why ship an honest partial
Claiming a gain set "works" when it passes 1 run in 3 would violate the project's falsification discipline. v0.19.7 delivers the deterministic velocity infrastructure + a controller that can hover + a precise three-cause bistability diagnosis. The reliable PASS is gated on the three design changes above; the largest (mixer thrust floor) is a verified-component change deserving its own oracle-gated release.
🤖 Generated with Claude Code