From 564879594ebb8d31c6400461b96f5dc442f14533 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 29 Oct 2024 11:22:47 -0400 Subject: [PATCH] AP_NavEKF3: fix computation of rho --- libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp index c188681f0e614..5f6fd0808a5f8 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp @@ -485,7 +485,7 @@ void NavEKF3_core::FuseDragForces() ZERO_FARRAY(Kfusion); Vector24 Hfusion; // Observation Jacobians const ftype R_ACC = sq(fmaxF(frontend->_dragObsNoise, 0.5f)); - const ftype density_ratio = sqrtF(dal.get_EAS2TAS()); + const ftype density_ratio = 1.0f/sq(dal.get_EAS2TAS()); const ftype rho = fmaxF(1.225f * density_ratio, 0.1f); // air density // get latest estimated orientation