This repository has been archived by the owner on May 1, 2024. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 509
EKF: Add Emergency yaw recovery using EKF-GSF estimator #766
Merged
priseborough
merged 37 commits into
PX4:master
from
priseborough:yawEKFGSF-refactor-rebased
Mar 5, 2020
Merged
Changes from all commits
Commits
Show all changes
37 commits
Select commit
Hold shift + click to select a range
195f167
EKF: Use common rate vector calculation for offset corrections
priseborough af84e30
EKF: Remove duplicate matrix entry calculations
priseborough 14e1924
EKF: Create a EKF-GSF yaw estimator class
priseborough c8c1904
EKF: add emergency yaw reset functionality
priseborough a566eb0
EKF: remove un-used function
priseborough c59daad
EKF: Ensure required constants are defined for all builds
priseborough e9dd2ef
EKF: Fix CI build error
priseborough 6734251
Revert "EKF: remove un-used function"
priseborough 1608afa
EKF: Replace in-lined Tait-Bryan 312 conversions with function call
priseborough ca2a0e5
EKF: Remove unnecessary update of external vision rotation matrix
priseborough dbb5230
EKF: Use const
priseborough a9a2004
EKF: use const
priseborough b254488
EKF: don't use class variable as a temporary variable
priseborough bdc2b47
EKF: update comments
priseborough 7279978
EKF: Improve efficiency of yaw reset
priseborough 7f62269
EKF: use const
priseborough 22e316a
EKF: remove un-used struct element
priseborough be72afe
EKF: more descriptive function name
priseborough 3ae091e
EKF: use existing matrix row operator
priseborough 26fad77
EKF: remove unnecessary rotation matrix update
priseborough c449153
EKF: Use square matrix type
priseborough e7b9843
EKF: Improve protection for bad innovation covariance
priseborough 94132c5
EKF: Use matrix library operations
priseborough 68303f9
EKF: Replace memcpy with better alternative
priseborough 9a46329
EKF: Split EKF-GSF yaw reset function
priseborough 78ea53b
EKF: Use common function for quaternion state and covariance yaw reset
priseborough d1a85a7
EKF: Replace inlined matrix operation
priseborough 3d58ca5
EKF: Use const
priseborough 14035f7
EKF: Change accessor function name
priseborough 7032c73
EKF: Use const
priseborough 1c5ac7c
EKF: Don't create unnecessary duplicate variable locations
priseborough c6216eb
EKF: Remove duplicate covariance innovation inverse
priseborough 9b69745
EKF: Don't create unnecessary duplicate variable locations
priseborough d6aa205
EKF: Rely on geo library to provide gravity
priseborough b31a21e
EKF: Improve protection from bad updates
priseborough 37572b3
EKF: Reduce effect of vibration on yaw estimator AHRS
priseborough 5270fde
EKF: Improve yaw estimator AHRS accuracy during manoeuvre transients
priseborough File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Large diffs are not rendered by default.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,153 @@ | ||
#pragma once | ||
|
||
#include <geo/geo.h> | ||
#include <matrix/math.hpp> | ||
#include <mathlib/mathlib.h> | ||
|
||
using matrix::AxisAnglef; | ||
using matrix::Dcmf; | ||
using matrix::Eulerf; | ||
using matrix::Matrix3f; | ||
using matrix::Quatf; | ||
using matrix::Vector2f; | ||
using matrix::Vector3f; | ||
using matrix::wrap_pi; | ||
|
||
#define N_MODELS_EKFGSF 5 | ||
|
||
#ifndef M_PI_F | ||
#define M_PI_F 3.14159265f | ||
#endif | ||
|
||
#ifndef M_PI_2_F | ||
#define M_PI_2_F 1.57079632f | ||
#endif | ||
|
||
#ifndef M_TWOPI_INV | ||
#define M_TWOPI_INV 0.159154943f | ||
#endif | ||
|
||
class EKFGSF_yaw | ||
{ | ||
public: | ||
// Constructor | ||
EKFGSF_yaw(); | ||
|
||
// Update Filter States - this should be called whenever new IMU data is available | ||
void update(const Vector3f del_ang, // IMU delta angle rotation vector meassured in body frame (rad) | ||
const Vector3f del_vel, // IMU delta velocity vector meassured in body frame (m/s) | ||
const float del_ang_dt, // time interval that del_ang was integrated over (sec) | ||
const float del_vel_dt, // time interval that del_vel was integrated over (sec) | ||
bool run_EKF, // set to true when flying or movement is suitable for yaw estimation | ||
float airspeed); // true airspeed used for centripetal accel compensation - set to 0 when not required. | ||
|
||
void setVelocity(Vector2f velocity, // NE velocity measurement (m/s) | ||
float accuracy); // 1-sigma accuracy of velocity measurement (m/s) | ||
|
||
// get solution data for logging | ||
bool getLogData(float *yaw_composite, | ||
float *yaw_composite_variance, | ||
float yaw[N_MODELS_EKFGSF], | ||
float innov_VN[N_MODELS_EKFGSF], | ||
float innov_VE[N_MODELS_EKFGSF], | ||
float weight[N_MODELS_EKFGSF]); | ||
|
||
// get yaw estimate and the corresponding variance | ||
// return false if no yaw estimate available | ||
bool getYawData(float *yaw, float *yaw_variance); | ||
|
||
private: | ||
// Parameters - these could be made tuneable | ||
const float _gyro_noise{1.0e-1f}; // yaw rate noise used for covariance prediction (rad/sec) | ||
const float _accel_noise{2.0f}; // horizontal accel noise used for covariance prediction (m/sec**2) | ||
const float _tilt_gain{0.2f}; // gain from tilt error to gyro correction for complementary filter (1/sec) | ||
const float _gyro_bias_gain{0.04f}; // gain applied to integral of gyro correction for complementary filter (1/sec) | ||
const float _weight_min{0.0f}; // minimum value of an individual model weighting | ||
|
||
// Declarations used by the bank of N_MODELS_EKFGSF AHRS complementary filters | ||
|
||
Vector3f _delta_ang; // IMU delta angle (rad) | ||
Vector3f _delta_vel; // IMU delta velocity (m/s) | ||
float _delta_ang_dt; // _delta_ang integration time interval (sec) | ||
float _delta_vel_dt; // _delta_vel integration time interval (sec) | ||
float _true_airspeed; // true airspeed used for centripetal accel compensation (m/s) | ||
|
||
struct _ahrs_ekf_gsf_struct{ | ||
Dcmf R; // matrix that rotates a vector from body to earth frame | ||
Vector3f gyro_bias; // gyro bias learned and used by the quaternion calculation | ||
bool aligned{false}; // true when AHRS has been aligned | ||
float vel_NE[2] {}; // NE velocity vector from last GPS measurement (m/s) | ||
bool fuse_gps = false; // true when GPS should be fused on that frame | ||
float accel_dt = 0; // time step used when generating _simple_accel_FR data (sec) | ||
}; | ||
_ahrs_ekf_gsf_struct _ahrs_ekf_gsf[N_MODELS_EKFGSF]; | ||
bool _ahrs_ekf_gsf_tilt_aligned = false;// true the initial tilt alignment has been calculated | ||
float _ahrs_accel_fusion_gain; // gain from accel vector tilt error to rate gyro correction used by AHRS calculation | ||
Vector3f _ahrs_accel; // low pass filtered body frame specific force vector used by AHRS calculation (m/s/s) | ||
float _ahrs_accel_norm; // length of _ahrs_accel specific force vector used by AHRS calculation (m/s/s) | ||
|
||
// calculate the gain from gravity vector misalingment to tilt correction to be used by all AHRS filters | ||
void ahrsCalcAccelGain(); | ||
|
||
// update specified AHRS rotation matrix using IMU and optionally true airspeed data | ||
void ahrsPredict(const uint8_t model_index); | ||
|
||
// align all AHRS roll and pitch orientations using IMU delta velocity vector | ||
void ahrsAlignTilt(); | ||
|
||
// align all AHRS yaw orientations to initial values | ||
void ahrsAlignYaw(); | ||
|
||
// Efficient propagation of a delta angle in body frame applied to the body to earth frame rotation matrix | ||
Matrix3f ahrsPredictRotMat(Matrix3f &R, Vector3f &g); | ||
|
||
// Declarations used by a bank of N_MODELS_EKFGSF EKFs | ||
|
||
struct _ekf_gsf_struct{ | ||
matrix::Vector3f X; // Vel North (m/s), Vel East (m/s), yaw (rad)s | ||
matrix::SquareMatrix<float, 3> P; // covariance matrix | ||
float W = 0.0f; // weighting | ||
priseborough marked this conversation as resolved.
Show resolved
Hide resolved
|
||
matrix::SquareMatrix<float, 2> S; // innovation covariance matrix | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think we could get away without storing S, but only its inverse. Just an idea. |
||
matrix::SquareMatrix<float, 2> S_inverse; // inverse of the innovation covariance matrix | ||
float S_det_inverse; // inverse of the innovation covariance matrix determinant | ||
matrix::Vector2f innov; // Velocity N,E innovation (m/s) | ||
}; | ||
_ekf_gsf_struct _ekf_gsf[N_MODELS_EKFGSF]; | ||
bool _vel_data_updated; // true when velocity data has been updated | ||
bool _run_ekf_gsf; // true when operating condition is suitable for to run the GSF and EKF models and fuse velocity data | ||
Vector2f _vel_NE; // NE velocity observations (m/s) | ||
float _vel_accuracy; // 1-sigma accuracy of velocity observations (m/s) | ||
bool _ekf_gsf_vel_fuse_started; // true when the EKF's have started fusing velocity data and the prediction and update processing is active | ||
|
||
// initialise states and covariance data for the GSF and EKF filters | ||
void initialiseEKFGSF(); | ||
|
||
// predict state and covariance for the specified EKF using inertial data | ||
void predictEKF(const uint8_t model_index); | ||
|
||
// update state and covariance for the specified EKF using a NE velocity measurement | ||
// return false if update failed | ||
bool updateEKF(const uint8_t model_index); | ||
|
||
inline float sq(float x) { return x * x; }; | ||
|
||
// converts Tait-Bryan 312 sequence of rotations from frame 1 to frame 2 | ||
// to the corresponding rotation matrix that rotates from frame 2 to frame 1 | ||
// rot312(0) - First rotation is a RH rotation about the Z axis (rad) | ||
// rot312(1) - Second rotation is a RH rotation about the X axis (rad) | ||
// rot312(2) - Third rotation is a RH rotation about the Y axis (rad) | ||
// See http://www.atacolorado.com/eulersequences.doc | ||
Dcmf taitBryan312ToRotMat(const Vector3f &rot312); | ||
|
||
// Declarations used by the Gaussian Sum Filter (GSF) that combines the individual EKF yaw estimates | ||
|
||
float _gsf_yaw; // yaw estimate (rad) | ||
float _gsf_yaw_variance; // variance of yaw estimate (rad^2) | ||
|
||
// return the probability of the state estimate for the specified EKF assuming a gaussian error distribution | ||
float gaussianDensity(const uint8_t model_index) const; | ||
|
||
// update the inverse of the innovation covariance matrix | ||
void updateInnovCovMatInv(const uint8_t model_index); | ||
|
||
}; |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
If some of them are not define else where, I would define them as
const float/int