mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Prevent possible race condition re-zeroing state variances
This commit is contained in:
parent
7adaea6019
commit
f38fccd57c
|
@ -59,8 +59,10 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
||||||
bool setWindInhibit = (!useAirspeed() && !assume_zero_sideslip()) || onGround || (PV_AidingMode == AID_NONE);
|
bool setWindInhibit = (!useAirspeed() && !assume_zero_sideslip()) || onGround || (PV_AidingMode == AID_NONE);
|
||||||
if (!inhibitWindStates && setWindInhibit) {
|
if (!inhibitWindStates && setWindInhibit) {
|
||||||
inhibitWindStates = true;
|
inhibitWindStates = true;
|
||||||
|
updateStateIndexLim();
|
||||||
} else if (inhibitWindStates && !setWindInhibit) {
|
} else if (inhibitWindStates && !setWindInhibit) {
|
||||||
inhibitWindStates = false;
|
inhibitWindStates = false;
|
||||||
|
updateStateIndexLim();
|
||||||
// set states and variances
|
// set states and variances
|
||||||
if (yawAlignComplete && useAirspeed()) {
|
if (yawAlignComplete && useAirspeed()) {
|
||||||
// if we have airspeed and a valid heading, set the wind states to the reciprocal of the vehicle heading
|
// if we have airspeed and a valid heading, set the wind states to the reciprocal of the vehicle heading
|
||||||
|
@ -106,8 +108,10 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
||||||
bool setMagInhibit = !magCalRequested || magCalDenied;
|
bool setMagInhibit = !magCalRequested || magCalDenied;
|
||||||
if (!inhibitMagStates && setMagInhibit) {
|
if (!inhibitMagStates && setMagInhibit) {
|
||||||
inhibitMagStates = true;
|
inhibitMagStates = true;
|
||||||
|
updateStateIndexLim();
|
||||||
} else if (inhibitMagStates && !setMagInhibit) {
|
} else if (inhibitMagStates && !setMagInhibit) {
|
||||||
inhibitMagStates = false;
|
inhibitMagStates = false;
|
||||||
|
updateStateIndexLim();
|
||||||
if (magFieldLearned) {
|
if (magFieldLearned) {
|
||||||
// if we have already learned the field states, then retain the learned variances
|
// if we have already learned the field states, then retain the learned variances
|
||||||
P[16][16] = earthMagFieldVar.x;
|
P[16][16] = earthMagFieldVar.x;
|
||||||
|
@ -137,6 +141,8 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
||||||
if (tiltAlignComplete && inhibitDelVelBiasStates) {
|
if (tiltAlignComplete && inhibitDelVelBiasStates) {
|
||||||
// activate the states
|
// activate the states
|
||||||
inhibitDelVelBiasStates = false;
|
inhibitDelVelBiasStates = false;
|
||||||
|
updateStateIndexLim();
|
||||||
|
|
||||||
// set the initial covariance values
|
// set the initial covariance values
|
||||||
P[13][13] = sq(ACCEL_BIAS_LIM_SCALER * frontend->_accBiasLim * dtEkfAvg);
|
P[13][13] = sq(ACCEL_BIAS_LIM_SCALER * frontend->_accBiasLim * dtEkfAvg);
|
||||||
P[14][14] = P[13][13];
|
P[14][14] = P[13][13];
|
||||||
|
@ -146,6 +152,8 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
||||||
if (tiltAlignComplete && inhibitDelAngBiasStates) {
|
if (tiltAlignComplete && inhibitDelAngBiasStates) {
|
||||||
// activate the states
|
// activate the states
|
||||||
inhibitDelAngBiasStates = false;
|
inhibitDelAngBiasStates = false;
|
||||||
|
updateStateIndexLim();
|
||||||
|
|
||||||
// set the initial covariance values
|
// set the initial covariance values
|
||||||
P[10][10] = sq(radians(InitialGyroBiasUncertainty() * dtEkfAvg));
|
P[10][10] = sq(radians(InitialGyroBiasUncertainty() * dtEkfAvg));
|
||||||
P[11][11] = P[10][10];
|
P[11][11] = P[10][10];
|
||||||
|
@ -159,8 +167,13 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
||||||
finalInflightMagInit = false;
|
finalInflightMagInit = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Adjust the indexing limits used to address the covariance, states and other EKF arrays to avoid unnecessary operations
|
updateStateIndexLim();
|
||||||
// if we are not using those states
|
}
|
||||||
|
|
||||||
|
// Adjust the indexing limits used to address the covariance, states and other EKF arrays to avoid unnecessary operations
|
||||||
|
// if we are not using those states
|
||||||
|
void NavEKF3_core::updateStateIndexLim()
|
||||||
|
{
|
||||||
if (inhibitWindStates) {
|
if (inhibitWindStates) {
|
||||||
if (inhibitMagStates) {
|
if (inhibitMagStates) {
|
||||||
if (inhibitDelVelBiasStates) {
|
if (inhibitDelVelBiasStates) {
|
||||||
|
|
|
@ -766,6 +766,9 @@ private:
|
||||||
|
|
||||||
// update timing statistics structure
|
// update timing statistics structure
|
||||||
void updateTimingStatistics(void);
|
void updateTimingStatistics(void);
|
||||||
|
|
||||||
|
// Update the state index limit based on which states are active
|
||||||
|
void updateStateIndexLim(void);
|
||||||
|
|
||||||
// Variables
|
// Variables
|
||||||
bool statesInitialised; // boolean true when filter states have been initialised
|
bool statesInitialised; // boolean true when filter states have been initialised
|
||||||
|
@ -853,8 +856,8 @@ private:
|
||||||
float tasTestRatio; // sum of squares of true airspeed innovation divided by fail threshold
|
float tasTestRatio; // sum of squares of true airspeed innovation divided by fail threshold
|
||||||
bool inhibitWindStates; // true when wind states and covariances are to remain constant
|
bool inhibitWindStates; // true when wind states and covariances are to remain constant
|
||||||
bool inhibitMagStates; // true when magnetic field states are inactive
|
bool inhibitMagStates; // true when magnetic field states are inactive
|
||||||
bool inhibitDelVelBiasStates; // true when delta velocity bias states are inactive
|
bool inhibitDelVelBiasStates; // true when IMU delta velocity bias states are inactive
|
||||||
bool inhibitDelAngBiasStates;
|
bool inhibitDelAngBiasStates; // true when IMU delta angle bias states are inactive
|
||||||
bool gpsNotAvailable; // bool true when valid GPS data is not available
|
bool gpsNotAvailable; // bool true when valid GPS data is not available
|
||||||
struct Location EKF_origin; // LLH origin of the NED axis system
|
struct Location EKF_origin; // LLH origin of the NED axis system
|
||||||
bool validOrigin; // true when the EKF origin is valid
|
bool validOrigin; // true when the EKF origin is valid
|
||||||
|
|
Loading…
Reference in New Issue