Skip to content

Commit

Permalink
AP_NavEKF3: fix computation of rho
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall committed Oct 29, 2024
1 parent a6f00a3 commit 6f80d9f
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 6f80d9f

Please sign in to comment.