mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF3: White space and comment fixes
This commit is contained in:
parent
7113387d27
commit
1018801522
@ -1141,7 +1141,7 @@ void NavEKF3_core::CovariancePrediction(Vector3f *rotVarVecPtr)
|
|||||||
const bool is_bias_observable = (fabsf(prevTnb[index][2]) > 0.8f) && onGround;
|
const bool is_bias_observable = (fabsf(prevTnb[index][2]) > 0.8f) && onGround;
|
||||||
|
|
||||||
if (!is_bias_observable && !dvelBiasAxisInhibit[index]) {
|
if (!is_bias_observable && !dvelBiasAxisInhibit[index]) {
|
||||||
// store variances to be reinstated wben learnign can commence later
|
// store variances to be reinstated wben learning can commence later
|
||||||
dvelBiasAxisVarPrev[index] = P[stateIndex][stateIndex];
|
dvelBiasAxisVarPrev[index] = P[stateIndex][stateIndex];
|
||||||
dvelBiasAxisInhibit[index] = true;
|
dvelBiasAxisInhibit[index] = true;
|
||||||
} else if (is_bias_observable && dvelBiasAxisInhibit[index]) {
|
} else if (is_bias_observable && dvelBiasAxisInhibit[index]) {
|
||||||
|
@ -1326,7 +1326,7 @@ private:
|
|||||||
|
|
||||||
// variables used to inhibit accel bias learning
|
// variables used to inhibit accel bias learning
|
||||||
bool inhibitDelVelBiasStates; // true when all IMU delta velocity bias states are de-activated
|
bool inhibitDelVelBiasStates; // true when all IMU delta velocity bias states are de-activated
|
||||||
bool dvelBiasAxisInhibit[3] {}; // true when IMU delta velocity bias states for a specific axis is de-activated
|
bool dvelBiasAxisInhibit[3] {}; // true when IMU delta velocity bias states for a specific axis is de-activated
|
||||||
Vector3f dvelBiasAxisVarPrev; // saved delta velocity XYZ bias variances (m/sec)**2
|
Vector3f dvelBiasAxisVarPrev; // saved delta velocity XYZ bias variances (m/sec)**2
|
||||||
|
|
||||||
#if EK3_FEATURE_EXTERNAL_NAV
|
#if EK3_FEATURE_EXTERNAL_NAV
|
||||||
|
Loading…
Reference in New Issue
Block a user