Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

EKF: Miscellaneous updates for EKF2 and EKF3 #6288

Closed
wants to merge 38 commits into from
Closed
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
38 commits
Select commit Hold shift + click to select a range
43622b2
AP_NavEKF3: Improve GPS reference height estimator
priseborough May 9, 2017
256b3ac
AP_NavEKF2: Improve GPS reference height estimator
priseborough May 9, 2017
e93e422
AP_NavEKF3: Fix initialisation of state inhibit flags
priseborough May 9, 2017
e6bac5e
AP_NavEKF3: add gyro bias state inhibit and rework index limit calcul…
priseborough May 9, 2017
804bdfe
AP_NavEKF3: Ensure Kalman gain calculatons respect deactivated states
priseborough May 9, 2017
ba5f6aa
AP_NavEKF3: Improve partitioning and efficiency of the covariance pre…
priseborough May 19, 2017
bc210ef
AP_NavEKF3: Prevent possible race condition re-zeroing state variances
priseborough May 19, 2017
e7be102
AP_NavEKF2: Revert auto-code to original form and remove micro optimi…
priseborough May 19, 2017
366e1f4
AP_NavEKF3: Add public accessor for state variances
priseborough May 21, 2017
6bab31e
DataFlash: Add logging for EKF3 state variances
priseborough May 21, 2017
31cd09b
DataFlash: reduce logging rate of ekf state variances
priseborough May 21, 2017
60d0fc7
AP_NavEKF3: Make target covariance time step larger
priseborough May 21, 2017
1651360
AP_NavEKF3: Raise lower limit on del vel bias state variances
priseborough May 21, 2017
700ba4a
AP_NavEKF3: fixes arising from review comments
priseborough May 22, 2017
280876c
AP_NavEKF3: Improve protection for badly conditioned dVel bias covari…
priseborough May 26, 2017
2343887
AP_NavEKF3: Report consistent origin, global and local height
priseborough May 29, 2017
c9bd13a
AP_NavEKF3: Explicitly define casting required to maintain precision
priseborough May 29, 2017
f200010
AP_NavEKF2: Add missing variance update to origin height Bayes filter
priseborough May 29, 2017
563e419
AP_NavEKF3: Fix indenting
priseborough May 29, 2017
615fd69
AP_NavEKF3: Fix comments
priseborough May 29, 2017
5d032fe
AP_NavEKF3: Use preferred data type for vector array operations
priseborough May 29, 2017
7924598
AP_NavEKF3: Fix delta velocity bias covariance constraints
priseborough May 29, 2017
ed7bd1c
AP_NavEKF3: Reduce loop operations in covariance prediction
priseborough May 29, 2017
890d63c
AP_NavEKF2: Explicitly define casting required to maintain precision
priseborough May 30, 2017
b2a3584
AP_NavEKF2: Report consistent origin, global and local height
priseborough May 30, 2017
724b836
AP_NavEKF2: Allow reporting of origin height for specified instance
priseborough May 30, 2017
600786d
AP_NavEKF3: Allow reporting of origin height for specified instance
priseborough May 30, 2017
344ce19
AP_AHRS: Update for compatibility with EKF interface change
priseborough May 30, 2017
c1b295b
DataFlash: Log EKF origin height
priseborough May 30, 2017
2ad5a39
DataFlash: remove repeated statement
priseborough May 31, 2017
def1e24
AP_NavEKF3: Ensure reported local height = global height - origin height
priseborough May 31, 2017
8fa4a19
AP_NavEKF2: Ensure reported local height = global height - origin height
priseborough May 31, 2017
a2e2c44
AP_NavEKF3: Update parameter descriptions
priseborough May 31, 2017
9f1cf74
AP_NavEKF2: Update parameter descriptions
priseborough May 31, 2017
ef5f0fd
AP_NavEKF3: Change default value of EK3_OGN_HGT_MASK
priseborough May 31, 2017
f79a38e
AP_NavEKF2: Change default value of EK2_OGN_HGT_MASK
priseborough May 31, 2017
2173665
Revert "AP_NavEKF2: Report consistent origin, global and local height"
priseborough Jun 6, 2017
6994e62
Revert "AP_NavEKF3: Report consistent origin, global and local height"
priseborough Jun 6, 2017
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 15 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,10 @@ void NavEKF3_core::setWindMagStateLearningMode()
bool setWindInhibit = (!useAirspeed() && !assume_zero_sideslip()) || onGround || (PV_AidingMode == AID_NONE);
if (!inhibitWindStates && setWindInhibit) {
inhibitWindStates = true;
updateStateIndexLim();
} else if (inhibitWindStates && !setWindInhibit) {
inhibitWindStates = false;
updateStateIndexLim();
// set states and variances
if (yawAlignComplete && useAirspeed()) {
// if we have airspeed and a valid heading, set the wind states to the reciprocal of the vehicle heading
Expand Down Expand Up @@ -106,8 +108,10 @@ void NavEKF3_core::setWindMagStateLearningMode()
bool setMagInhibit = !magCalRequested || magCalDenied;
if (!inhibitMagStates && setMagInhibit) {
inhibitMagStates = true;
updateStateIndexLim();
} else if (inhibitMagStates && !setMagInhibit) {
inhibitMagStates = false;
updateStateIndexLim();
if (magFieldLearned) {
// if we have already learned the field states, then retain the learned variances
P[16][16] = earthMagFieldVar.x;
Expand Down Expand Up @@ -137,6 +141,8 @@ void NavEKF3_core::setWindMagStateLearningMode()
if (tiltAlignComplete && inhibitDelVelBiasStates) {
// activate the states
inhibitDelVelBiasStates = false;
updateStateIndexLim();

// set the initial covariance values
P[13][13] = sq(ACCEL_BIAS_LIM_SCALER * frontend->_accBiasLim * dtEkfAvg);
P[14][14] = P[13][13];
Expand All @@ -146,6 +152,8 @@ void NavEKF3_core::setWindMagStateLearningMode()
if (tiltAlignComplete && inhibitDelAngBiasStates) {
// activate the states
inhibitDelAngBiasStates = false;
updateStateIndexLim();

// set the initial covariance values
P[10][10] = sq(radians(InitialGyroBiasUncertainty() * dtEkfAvg));
P[11][11] = P[10][10];
Expand All @@ -159,6 +167,13 @@ void NavEKF3_core::setWindMagStateLearningMode()
finalInflightMagInit = false;
}

updateStateIndexLim();
}

// 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()
{
// 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
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove this comment since it was added to the function above.

if (inhibitWindStates) {
Expand Down
7 changes: 5 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -766,6 +766,9 @@ class NavEKF3_core

// update timing statistics structure
void updateTimingStatistics(void);

// Update the stte index limit based on which states are active
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

stte -> state

void updateStateIndexLim(void);

// Variables
bool statesInitialised; // boolean true when filter states have been initialised
Expand Down Expand Up @@ -853,8 +856,8 @@ class NavEKF3_core
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 inhibitMagStates; // true when magnetic field states are inactive
bool inhibitDelVelBiasStates; // true when delta velocity bias states are inactive
bool inhibitDelAngBiasStates;
bool inhibitDelVelBiasStates; // true when IMU delta velocity bias states are inactive
bool inhibitDelAngBiasStates; // true when IMU delta angle bias states are inactive
bool gpsNotAvailable; // bool true when valid GPS data is not available
struct Location EKF_origin; // LLH origin of the NED axis system
bool validOrigin; // true when the EKF origin is valid
Expand Down