AP_NavEKF3: Formatting and comment fixes

This commit is contained in:
Paul Riseborough 2020-11-25 11:43:07 +11:00 committed by Andrew Tridgell
parent be4d10a95e
commit 4884476c09
3 changed files with 5 additions and 5 deletions

View File

@ -452,7 +452,7 @@ void NavEKF3_core::FuseSideslip()
/*
* Fuse X and Y body axis specific forces using explicit algebraic equations generated with SymPy.
* See AP_NavEKF3/derivation/main.py for derivation
* Output for change reference: AP_NavEKF3/derivation/generated/acc_bf_generarted.cpp
* Output for change reference: AP_NavEKF3/derivation/generated/acc_bf_generated.cpp
*/
void NavEKF3_core::FuseDragForces()
{

View File

@ -1368,11 +1368,11 @@ void NavEKF3_core::SampleDragData(const imu_elements &imu)
const bool using_bcoef_x = bcoef_x > 1.0f;
const bool using_bcoef_y = bcoef_y > 1.0f;
const bool using_mcoef = mcoef > 0.001f;
if (!using_bcoef_x && !using_bcoef_y && !using_mcoef) {
if (!using_bcoef_x && !using_bcoef_y && !using_mcoef) {
// nothing to do
dragFusionEnabled = false;
return;
}
return;
}
dragFusionEnabled = true;

View File

@ -1271,7 +1271,7 @@ private:
drag_elements dragSampleDelayed;
drag_elements dragDownSampled; // down sampled from filter prediction rate to observation rate
uint8_t dragSampleCount; // number of drag specific force samples accumulated at the filter prediction rate
float dragSampleTimeDelta; // time integral across all samples used to form _drag_down_sampled (sec)
float dragSampleTimeDelta; // time integral across all samples used to form _drag_down_sampled (sec)
Vector2f innovDrag; // multirotor drag measurement innovation (m/sec**2)
Vector2f innovDragVar; // multirotor drag measurement innovation variance ((m/sec**2)**2)
Vector2f dragTestRatio; // drag innovation consistency check ratio