Browse Source

EKF: Update class variable documentation and make compatible with Doxygen

master
Paul Riseborough 8 years ago
parent
commit
aec01ce59c
  1. 500
      EKF/common.h
  2. 256
      EKF/ekf.h

500
EKF/common.h

@ -53,303 +53,303 @@ using matrix::wrap_pi; @@ -53,303 +53,303 @@ using matrix::wrap_pi;
struct gps_message {
uint64_t time_usec;
int32_t lat; // Latitude in 1E-7 degrees
int32_t lon; // Longitude in 1E-7 degrees
int32_t alt; // Altitude in 1E-3 meters (millimeters) above MSL
uint8_t fix_type; // 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time
float eph; // GPS horizontal position accuracy in m
float epv; // GPS vertical position accuracy in m
float sacc; // GPS speed accuracy in m/s
float vel_m_s; // GPS ground speed (m/s)
float vel_ned[3]; // GPS ground speed NED
bool vel_ned_valid; // GPS ground speed is valid
uint8_t nsats; // number of satellites used
float gdop; // geometric dilution of precision
int32_t lat; ///< Latitude in 1E-7 degrees
int32_t lon; ///< Longitude in 1E-7 degrees
int32_t alt; ///< Altitude in 1E-3 meters (millimeters) above MSL
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time
float eph; ///< GPS horizontal position accuracy in m
float epv; ///< GPS vertical position accuracy in m
float sacc; ///< GPS speed accuracy in m/s
float vel_m_s; ///< GPS ground speed (m/sec)
float vel_ned[3]; ///< GPS ground speed NED
bool vel_ned_valid; ///< GPS ground speed is valid
uint8_t nsats; ///< number of satellites used
float gdop; ///< geometric dilution of precision
};
struct flow_message {
uint8_t quality; // Quality of Flow data
Vector2f flowdata; // Flow data received
Vector3f gyrodata; // Gyro data from flow sensor
uint32_t dt; // integration time of flow samples
uint8_t quality; ///< Quality of Flow data
Vector2f flowdata; ///< Optical flow rates about the X and Y body axes (rad/sec)
Vector3f gyrodata; ///< Gyro rates about the XYZ body axes (rad/sec)
uint32_t dt; ///< integration time of flow samples (sec)
};
struct ext_vision_message {
Vector3f posNED; // measured NED position relative to the local origin (m)
Quatf quat; // measured quaternion orientation defining rotation from NED to body frame
float posErr; // 1-Sigma spherical position accuracy (m)
float angErr; // 1-Sigma angular error (rad)
Vector3f posNED; ///< measured NED position relative to the local origin (m)
Quatf quat; ///< measured quaternion orientation defining rotation from NED to body frame
float posErr; ///< 1-Sigma spherical position accuracy (m)
float angErr; ///< 1-Sigma angular error (rad)
};
struct outputSample {
Quatf quat_nominal; // nominal quaternion describing vehicle attitude
Vector3f vel; // NED velocity estimate in earth frame in m/s
Vector3f pos; // NED position estimate in earth frame in m/s
uint64_t time_us; // timestamp in microseconds
Quatf quat_nominal; ///< nominal quaternion describing vehicle attitude
Vector3f vel; ///< NED velocity estimate in earth frame (m/sec)
Vector3f pos; ///< NED position estimate in earth frame (m/sec)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct outputVert {
float vel_d; // D velocity calculated using alternative algorithm
float vel_d_integ; // Integral of vel_d
float dt; // delta time in seconds
uint64_t time_us; // timestamp in microseconds
float vel_d; ///< D velocity calculated using alternative algorithm (m/sec)
float vel_d_integ; ///< Integral of vel_d (m)
float dt; ///< delta time (sec)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct imuSample {
Vector3f delta_ang; // delta angle in body frame (integrated gyro measurements)
Vector3f delta_vel; // delta velocity in body frame (integrated accelerometer measurements)
float delta_ang_dt; // delta angle integration period in seconds
float delta_vel_dt; // delta velocity integration period in seconds
uint64_t time_us; // timestamp in microseconds
Vector3f delta_ang; ///< delta angle in body frame (integrated gyro measurements) (rad)
Vector3f delta_vel; ///< delta velocity in body frame (integrated accelerometer measurements) (m/sec)
float delta_ang_dt; ///< delta angle integration period (sec)
float delta_vel_dt; ///< delta velocity integration period (sec)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct gpsSample {
Vector2f pos; // NE earth frame gps horizontal position measurement in m
float hgt; // gps height measurement in m
Vector3f vel; // NED earth frame gps velocity measurement in m/s
float hacc; // 1-std horizontal position error m
float vacc; // 1-std vertical position error m
float sacc; // 1-std speed error m/s
uint64_t time_us; // timestamp in microseconds
Vector2f pos; ///< NE earth frame gps horizontal position measurement (m)
float hgt; ///< gps height measurement (m)
Vector3f vel; ///< NED earth frame gps velocity measurement (m/sec)
float hacc; ///< 1-std horizontal position error (m)
float vacc; ///< 1-std vertical position error (m)
float sacc; ///< 1-std speed error (m/sec)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct magSample {
Vector3f mag; // NED magnetometer body frame measurements
uint64_t time_us; // timestamp in microseconds
Vector3f mag; ///< NED magnetometer body frame measurements (Gauss)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct baroSample {
float hgt{0.0f}; // barometer height above sea level measurement in m
uint64_t time_us{0}; // timestamp in microseconds
float hgt{0.0f}; ///< pressure altitude above sea level (m)
uint64_t time_us{0}; ///< timestamp of the measurement (uSec)
};
struct rangeSample {
float rng; // range (distance to ground) measurement in m
uint64_t time_us; // timestamp in microseconds
float rng; ///< range (distance to ground) measurement (m)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct airspeedSample {
float true_airspeed; // true airspeed measurement in m/s
float eas2tas; // equivalent to true airspeed factor
uint64_t time_us; // timestamp in microseconds
float true_airspeed; ///< true airspeed measurement (m/sec)
float eas2tas; ///< equivalent to true airspeed factor
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct flowSample {
uint8_t quality; // quality indicator between 0 and 255
Vector2f flowRadXY; // measured delta angle of the image about the X and Y body axes (rad), RH rotaton is positive
Vector2f flowRadXYcomp; // measured delta angle of the image about the X and Y body axes after removal of body rotation (rad), RH rotation is positive
Vector3f gyroXYZ; // measured delta angle of the inertial frame about the body axes obtained from rate gyro measurements (rad), RH rotation is positive
float dt; // amount of integration time (sec)
uint64_t time_us; // timestamp in microseconds of the integration period mid-point
uint8_t quality; ///< quality indicator between 0 and 255
Vector2f flowRadXY; ///< measured delta angle of the image about the X and Y body axes (rad), RH rotaton is positive
Vector2f flowRadXYcomp; ///< measured delta angle of the image about the X and Y body axes after removal of body rotation (rad), RH rotation is positive
Vector3f gyroXYZ; ///< measured delta angle of the inertial frame about the body axes obtained from rate gyro measurements (rad), RH rotation is positive
float dt; ///< amount of integration time (sec)
uint64_t time_us; ///< timestamp of the integration period mid-point (uSec)
};
struct extVisionSample {
Vector3f posNED; // measured NED position relative to the local origin (m)
Quatf quat; // measured quaternion orientation defining rotation from NED to body frame
float posErr; // 1-Sigma spherical position accuracy (m)
float angErr; // 1-Sigma angular error (rad)
uint64_t time_us; // timestamp of the measurement in microseconds
Vector3f posNED; ///< measured NED position relative to the local origin (m)
Quatf quat; ///< measured quaternion orientation defining rotation from NED to body frame
float posErr; ///< 1-Sigma spherical position accuracy (m)
float angErr; ///< 1-Sigma angular error (rad)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
struct dragSample {
Vector2f accelXY; // measured specific force along the X and Y body axes (m/s**2)
uint64_t time_us; // timestamp in microseconds of the measurement
Vector2f accelXY; ///< measured specific force along the X and Y body axes (m/sec**2)
uint64_t time_us; ///< timestamp of the measurement (uSec)
};
// Integer definitions for vdist_sensor_type
#define VDIST_SENSOR_BARO 0 // Use baro height
#define VDIST_SENSOR_GPS 1 // Use GPS height
#define VDIST_SENSOR_RANGE 2 // Use range finder height
#define VDIST_SENSOR_EV 3 // USe external vision
#define VDIST_SENSOR_BARO 0 ///< Use baro height
#define VDIST_SENSOR_GPS 1 ///< Use GPS height
#define VDIST_SENSOR_RANGE 2 ///< Use range finder height
#define VDIST_SENSOR_EV 3 ///< Use external vision
// Bit locations for mag_declination_source
#define MASK_USE_GEO_DECL (1<<0) // set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value
#define MASK_SAVE_GEO_DECL (1<<1) // set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library
#define MASK_FUSE_DECL (1<<2) // set to true if the declination is always fused as an observation to constrain drift when 3-axis fusion is performed
#define MASK_USE_GEO_DECL (1<<0) ///< set to true to use the declination from the geo library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value
#define MASK_SAVE_GEO_DECL (1<<1) ///< set to true to set the EKF2_MAG_DECL parameter to the value returned by the geo library
#define MASK_FUSE_DECL (1<<2) ///< set to true if the declination is always fused as an observation to constrain drift when 3-axis fusion is performed
// Bit locations for fusion_mode
#define MASK_USE_GPS (1<<0) // set to true to use GPS data
#define MASK_USE_OF (1<<1) // set to true to use optical flow data
#define MASK_INHIBIT_ACC_BIAS (1<<2) // set to true to inhibit estimation of accelerometer delta velocity bias
#define MASK_USE_EVPOS (1<<3) // set to true to use external vision NED position data
#define MASK_USE_EVYAW (1<<4) // set to true to use exernal vision quaternion data for yaw
#define MASK_USE_DRAG (1<<5) // set to true to use the multi-rotor drag model to estimate wind
#define MASK_USE_GPS (1<<0) ///< set to true to use GPS data
#define MASK_USE_OF (1<<1) ///< set to true to use optical flow data
#define MASK_INHIBIT_ACC_BIAS (1<<2) ///< set to true to inhibit estimation of accelerometer delta velocity bias
#define MASK_USE_EVPOS (1<<3) ///< set to true to use external vision NED position data
#define MASK_USE_EVYAW (1<<4) ///< set to true to use exernal vision quaternion data for yaw
#define MASK_USE_DRAG (1<<5) ///< set to true to use the multi-rotor drag model to estimate wind
// Integer definitions for mag_fusion_type
#define MAG_FUSE_TYPE_AUTO 0 // The selection of either heading or 3D magnetometer fusion will be automatic
#define MAG_FUSE_TYPE_HEADING 1 // Simple yaw angle fusion will always be used. This is less accurate, but less affected by earth field distortions. It should not be used for pitch angles outside the range from -60 to +60 deg
#define MAG_FUSE_TYPE_3D 2 // Magnetometer 3-axis fusion will always be used. This is more accurate, but more affected by localised earth field distortions
#define MAG_FUSE_TYPE_AUTO 0 ///< The selection of either heading or 3D magnetometer fusion will be automatic
#define MAG_FUSE_TYPE_HEADING 1 ///< Simple yaw angle fusion will always be used. This is less accurate, but less affected by earth field distortions. It should not be used for pitch angles outside the range from -60 to +60 deg
#define MAG_FUSE_TYPE_3D 2 ///< Magnetometer 3-axis fusion will always be used. This is more accurate, but more affected by localised earth field distortions
// Maximum sensor intervals in usec
#define GPS_MAX_INTERVAL 5e5
#define BARO_MAX_INTERVAL 2e5
#define RNG_MAX_INTERVAL 2e5
#define EV_MAX_INTERVAL 2e5
#define GPS_MAX_INTERVAL 5e5 ///< Maximum allowable time interval between GPS measurements (uSec)
#define BARO_MAX_INTERVAL 2e5 ///< Maximum allowable time interval between pressure altitude measurements (uSec)
#define RNG_MAX_INTERVAL 2e5 ///< Maximum allowable time interval between range finder measurements (uSec)
#define EV_MAX_INTERVAL 2e5 ///< Maximum allowable time interval between external vision system measurements (uSec)
// bad accelerometer detection and mitigation
#define BADACC_PROBATION 10E6 // Number of usec that accel data declared bad must continuously pass checks to be declared good
#define BADACC_BIAS_PNOISE 4.9f // The delta velocity process noise is set to this when accel data is declared bad (m/s**2)
#define BADACC_PROBATION 10E6 ///< Period of time that accel data declared bad must continuously pass checks to be declared good again (uSec)
#define BADACC_BIAS_PNOISE 4.9f ///< The delta velocity process noise is set to this when accel data is declared bad (m/sec**2)
struct parameters {
// measurement source control
int32_t fusion_mode{MASK_USE_GPS}; // bitmasked integer that selects which aiding sources will be used
int32_t vdist_sensor_type{VDIST_SENSOR_BARO};// selects the primary source for height data
int32_t sensor_interval_min_ms{20}; // minimum time of arrival difference between non IMU sensor updates. Sets the size of the observation buffers.
int32_t fusion_mode{MASK_USE_GPS}; ///< bitmasked integer that selects which aiding sources will be used
int32_t vdist_sensor_type{VDIST_SENSOR_BARO}; ///< selects the primary source for height data
int32_t sensor_interval_min_ms{20}; ///< minimum time of arrival difference between non IMU sensor updates. Sets the size of the observation buffers. (mSec)
// measurement time delays
float min_delay_ms{0.0f}; // used to a set a minimum buffer length independent of specified sensor delays
float mag_delay_ms{0.0f}; // magnetometer measurement delay relative to the IMU (msec)
float baro_delay_ms{0.0f}; // barometer height measurement delay relative to the IMU (msec)
float gps_delay_ms{110.0f}; // GPS measurement delay relative to the IMU (msec)
float airspeed_delay_ms{100.0f}; // airspeed measurement delay relative to the IMU (msec)
float flow_delay_ms{5.0f}; // optical flow measurement delay relative to the IMU (msec) - this is to the middle of the optical flow integration interval
float range_delay_ms{5.0f}; // range finder measurement delay relative to the IMU (msec)
float ev_delay_ms{100.0f}; // off-board vision measurement delay relative to the IMU (msec)
float min_delay_ms{0.0f}; ///< Maximmum time delay of any sensor used to increse buffer length to handle large timing jitter (mSec)
float mag_delay_ms{0.0f}; ///< magnetometer measurement delay relative to the IMU (mSec)
float baro_delay_ms{0.0f}; ///< barometer height measurement delay relative to the IMU (mSec)
float gps_delay_ms{110.0f}; ///< GPS measurement delay relative to the IMU (mSec)
float airspeed_delay_ms{100.0f}; ///< airspeed measurement delay relative to the IMU (mSec)
float flow_delay_ms{5.0f}; ///< optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval
float range_delay_ms{5.0f}; ///< range finder measurement delay relative to the IMU (mSec)
float ev_delay_ms{100.0f}; ///< off-board vision measurement delay relative to the IMU (mSec)
// input noise
float gyro_noise{1.5e-2f}; // IMU angular rate noise used for covariance prediction (rad/sec)
float accel_noise{3.5e-1f}; // IMU acceleration noise use for covariance prediction (m/sec/sec)
float gyro_noise{1.5e-2f}; ///< IMU angular rate noise used for covariance prediction (rad/sec)
float accel_noise{3.5e-1f}; ///< IMU acceleration noise use for covariance prediction (m/sec**2)
// process noise
float gyro_bias_p_noise{1.0e-3f}; // process noise for IMU rate gyro bias prediction (rad/sec**2)
float accel_bias_p_noise{6.0e-3f}; // process noise for IMU accelerometer bias prediction (m/sec**3)
float mage_p_noise{1.0e-3f}; // process noise for earth magnetic field prediction (Guass/sec)
float magb_p_noise{1.0e-4}; // process noise for body magnetic field prediction (Guass/sec)
float wind_vel_p_noise{1.0e-1f}; // process noise for wind velocity prediction (m/sec/sec)
float terrain_p_noise{5.0f}; // process noise for terrain offset (m/sec)
float terrain_gradient{0.5f}; // gradient of terrain used to estimate process noise due to changing position (m/m)
float gyro_bias_p_noise{1.0e-3f}; ///< process noise for IMU rate gyro bias prediction (rad/sec**2)
float accel_bias_p_noise{6.0e-3f}; ///< process noise for IMU accelerometer bias prediction (m/sec**3)
float mage_p_noise{1.0e-3f}; ///< process noise for earth magnetic field prediction (Gauss/sec)
float magb_p_noise{1.0e-4}; ///< process noise for body magnetic field prediction (Gauss/sec)
float wind_vel_p_noise{1.0e-1f}; ///< process noise for wind velocity prediction (m/sec**2)
float terrain_p_noise{5.0f}; ///< process noise for terrain offset (m/sec)
float terrain_gradient{0.5f}; ///< gradient of terrain used to estimate process noise due to changing position (m/m)
// initialization errors
float switch_on_gyro_bias{0.1f}; // 1-sigma gyro bias uncertainty at switch on (rad/sec)
float switch_on_accel_bias{0.2f}; // 1-sigma accelerometer bias uncertainty at switch on (m/s**2)
float initial_tilt_err{0.1f}; // 1-sigma tilt error after initial alignment using gravity vector (rad)
float initial_wind_uncertainty{1.0f}; // 1-sigma initial uncertainty in wind velocity (m/s)
float switch_on_gyro_bias{0.1f}; ///< 1-sigma gyro bias uncertainty at switch on (rad/sec)
float switch_on_accel_bias{0.2f}; ///< 1-sigma accelerometer bias uncertainty at switch on (m/sec**2)
float initial_tilt_err{0.1f}; ///< 1-sigma tilt error after initial alignment using gravity vector (rad)
float initial_wind_uncertainty{1.0f}; ///< 1-sigma initial uncertainty in wind velocity (m/sec)
// position and velocity fusion
float gps_vel_noise{5.0e-1f}; // observation noise for gps velocity fusion (m/sec)
float gps_pos_noise{0.5f}; // observation noise for gps position fusion (m)
float pos_noaid_noise{10.0f}; // observation noise for non-aiding position fusion (m)
float baro_noise{2.0f}; // observation noise for barometric height fusion (m)
float baro_innov_gate{5.0f}; // barometric height innovation consistency gate size (STD)
float posNE_innov_gate{5.0f}; // GPS horizontal position innovation consistency gate size (STD)
float vel_innov_gate{5.0f}; // GPS velocity innovation consistency gate size (STD)
float hgt_reset_lim{0.0f}; // The maximum 1-sigma uncertainty in height that can be tolerated before the height state is reset (m)
float gps_vel_noise{5.0e-1f}; ///< minimum allowed observation noise for gps velocity fusion (m/sec)
float gps_pos_noise{0.5f}; ///< minimum allowed observation noise for gps position fusion (m)
float pos_noaid_noise{10.0f}; ///< observation noise for non-aiding position fusion (m)
float baro_noise{2.0f}; ///< observation noise for barometric height fusion (m)
float baro_innov_gate{5.0f}; ///< barometric height innovation consistency gate size (STD)
float posNE_innov_gate{5.0f}; ///< GPS horizontal position innovation consistency gate size (STD)
float vel_innov_gate{5.0f}; ///< GPS velocity innovation consistency gate size (STD)
float hgt_reset_lim{0.0f}; ///< The maximum 1-sigma uncertainty in height that can be tolerated before the height state is reset (m)
// magnetometer fusion
float mag_heading_noise{3.0e-1f}; // measurement noise used for simple heading fusion (rad)
float mag_noise{5.0e-2f}; // measurement noise used for 3-axis magnetoemeter fusion (Gauss)
float mag_declination_deg{0.0f}; // magnetic declination (degrees)
float heading_innov_gate{2.6f}; // heading fusion innovation consistency gate size (STD)
float mag_innov_gate{3.0f}; // magnetometer fusion innovation consistency gate size (STD)
int32_t mag_declination_source{7}; // bitmask used to control the handling of declination data
int32_t mag_fusion_type{0}; // integer used to specify the type of magnetometer fusion used
float mag_acc_gate{0.5f}; // when in auto select mode, heading fusion will be used when manoeuvre accel is lower than this (m/s**2)
float mag_yaw_rate_gate{0.25f}; // yaw rate threshold used by mode select logic (rad/sec)
float mag_heading_noise{3.0e-1f}; ///< measurement noise used for simple heading fusion (rad)
float mag_noise{5.0e-2f}; ///< measurement noise used for 3-axis magnetoemeter fusion (Gauss)
float mag_declination_deg{0.0f}; ///< magnetic declination (degrees)
float heading_innov_gate{2.6f}; ///< heading fusion innovation consistency gate size (STD)
float mag_innov_gate{3.0f}; ///< magnetometer fusion innovation consistency gate size (STD)
int32_t mag_declination_source{7}; ///< bitmask used to control the handling of declination data
int32_t mag_fusion_type{0}; ///< integer used to specify the type of magnetometer fusion used
float mag_acc_gate{0.5f}; ///< when in auto select mode, heading fusion will be used when manoeuvre accel is lower than this (m/sec**2)
float mag_yaw_rate_gate{0.25f}; ///< yaw rate threshold used by mode select logic (rad/sec)
// airspeed fusion
float tas_innov_gate{5.0f}; // True Airspeed Innovation consistency gate size in standard deciation
float eas_noise{1.4f}; // EAS measurement noise standard deviation used for airspeed fusion [m/s]
float tas_innov_gate{5.0f}; ///< True Airspeed innovation consistency gate size (STD)
float eas_noise{1.4f}; ///< EAS measurement noise standard deviation used for airspeed fusion (m/s)
// synthetic sideslip fusion
float beta_innov_gate{5.0f}; // synthetic sideslip innovation consistency gate size in standard deviation (STD)
float beta_noise{0.3f}; // synthetic sideslip noise (rad)
float beta_avg_ft_us{1000000.0f}; // The average time between synthetic sideslip measurements (usec)
float beta_innov_gate{5.0f}; ///< synthetic sideslip innovation consistency gate size in standard deviation (STD)
float beta_noise{0.3f}; ///< synthetic sideslip noise (rad)
float beta_avg_ft_us{1000000.0f}; ///< The average time between synthetic sideslip measurements (uSec)
// range finder fusion
float range_noise{0.1f}; // observation noise for range finder measurements (m)
float range_innov_gate{5.0f}; // range finder fusion innovation consistency gate size (STD)
float rng_gnd_clearance{0.1f}; // minimum valid value for range when on ground (m)
float rng_sens_pitch{0.0f}; // Pitch offset of the range sensor (rad). Sensor points out along Z axis when offset is zero. Positive rotation is RH about Y axis.
float range_noise_scaler{0.0f}; // scaling from range measurement to noise (m/m)
float vehicle_variance_scaler{0.0f}; // gain applied to vehicle height variance used in calculation of height above ground observation variance
float max_hagl_for_range_aid{5.0f}; // maximum height above ground for which we allow to use the range finder as height source (if range_aid == 1)
float max_vel_for_range_aid{1.0f}; // maximum ground velocity for which we allow to use the range finder as height source (if range_aid == 1)
int32_t range_aid{0}; // allow switching primary height source to range finder if certian conditions are met
float range_aid_innov_gate{1.0f}; // gate size used for innovation consistency checks for range aid fusion
float range_noise{0.1f}; ///< observation noise for range finder measurements (m)
float range_innov_gate{5.0f}; ///< range finder fusion innovation consistency gate size (STD)
float rng_gnd_clearance{0.1f}; ///< minimum valid value for range when on ground (m)
float rng_sens_pitch{0.0f}; ///< Pitch offset of the range sensor (rad). Sensor points out along Z axis when offset is zero. Positive rotation is RH about Y axis.
float range_noise_scaler{0.0f}; ///< scaling from range measurement to noise (m/m)
float vehicle_variance_scaler{0.0f}; ///< gain applied to vehicle height variance used in calculation of height above ground observation variance
float max_hagl_for_range_aid{5.0f}; ///< maximum height above ground for which we allow to use the range finder as height source (if range_aid == 1)
float max_vel_for_range_aid{1.0f}; ///< maximum ground velocity for which we allow to use the range finder as height source (if range_aid == 1)
int32_t range_aid{0}; ///< allow switching primary height source to range finder if certian conditions are met
float range_aid_innov_gate{1.0f}; ///< gate size used for innovation consistency checks for range aid fusion
// vision position fusion
float ev_innov_gate{5.0f}; // vision estimator fusion innovation consistency gate size (STD)
float ev_innov_gate{5.0f}; ///< vision estimator fusion innovation consistency gate size (STD)
// optical flow fusion
float flow_noise{0.15f}; // observation noise for optical flow LOS rate measurements (rad/sec)
float flow_noise_qual_min{0.5f}; // observation noise for optical flow LOS rate measurements when flow sensor quality is at the minimum useable (rad/sec)
int32_t flow_qual_min{1}; // minimum acceptable quality integer from the flow sensor
float flow_innov_gate{3.0f}; // optical flow fusion innovation consistency gate size (STD)
float flow_rate_max{2.5f}; // maximum valid optical flow rate (rad/sec)
float flow_noise{0.15f}; ///< observation noise for optical flow LOS rate measurements (rad/sec)
float flow_noise_qual_min{0.5f}; ///< observation noise for optical flow LOS rate measurements when flow sensor quality is at the minimum useable (rad/sec)
int32_t flow_qual_min{1}; ///< minimum acceptable quality integer from the flow sensor
float flow_innov_gate{3.0f}; ///< optical flow fusion innovation consistency gate size (STD)
float flow_rate_max{2.5f}; ///< maximum valid optical flow rate (rad/sec)
// these parameters control the strictness of GPS quality checks used to determine if the GPS is
// good enough to set a local origin and commence aiding
int32_t gps_check_mask{21}; // bitmask used to control which GPS quality checks are used
float req_hacc{5.0f}; // maximum acceptable horizontal position error
float req_vacc{8.0f}; // maximum acceptable vertical position error
float req_sacc{1.0f}; // maximum acceptable speed error
int32_t req_nsats{6}; // minimum acceptable satellite count
float req_gdop{2.0f}; // maximum acceptable geometric dilution of precision
float req_hdrift{0.3f}; // maximum acceptable horizontal drift speed
float req_vdrift{0.5f}; // maximum acceptable vertical drift speed
int32_t gps_check_mask{21}; ///< bitmask used to control which GPS quality checks are used
float req_hacc{5.0f}; ///< maximum acceptable horizontal position error (m)
float req_vacc{8.0f}; ///< maximum acceptable vertical position error (m)
float req_sacc{1.0f}; ///< maximum acceptable speed error (m/s)
int32_t req_nsats{6}; ///< minimum acceptable satellite count
float req_gdop{2.0f}; ///< maximum acceptable geometric dilution of precision
float req_hdrift{0.3f}; ///< maximum acceptable horizontal drift speed (m/s)
float req_vdrift{0.5f}; ///< maximum acceptable vertical drift speed (m/s)
// XYZ offset of sensors in body axes (m)
Vector3f imu_pos_body; // xyz position of IMU in body frame (m)
Vector3f gps_pos_body; // xyz position of the GPS antenna in body frame (m)
Vector3f rng_pos_body; // xyz position of range sensor in body frame (m)
Vector3f flow_pos_body; // xyz position of range sensor focal point in body frame (m)
Vector3f ev_pos_body; // xyz position of VI-sensor focal point in body frame (m)
Vector3f imu_pos_body; ///< xyz position of IMU in body frame (m)
Vector3f gps_pos_body; ///< xyz position of the GPS antenna in body frame (m)
Vector3f rng_pos_body; ///< xyz position of range sensor in body frame (m)
Vector3f flow_pos_body; ///< xyz position of range sensor focal point in body frame (m)
Vector3f ev_pos_body; ///< xyz position of VI-sensor focal point in body frame (m)
// output complementary filter tuning
float vel_Tau{0.25f}; // velocity state correction time constant (1/sec)
float pos_Tau{0.25f}; // postion state correction time constant (1/sec)
float vel_Tau{0.25f}; ///< velocity state correction time constant (1/sec)
float pos_Tau{0.25f}; ///< postion state correction time constant (1/sec)
// accel bias learning control
float acc_bias_lim{0.4f}; // maximum accel bias magnitude (m/s/s)
float acc_bias_learn_acc_lim{25.0f}; // learning is disabled if the magnitude of the IMU acceleration vector is greater than this (m/sec**2)
float acc_bias_learn_gyr_lim{3.0f}; // learning is disabled if the magnitude of the IMU angular rate vector is greater than this (rad/sec)
float acc_bias_learn_tc{0.5f}; // time constant used to control the decaying envelope filters applied to the accel and gyro magnitudes (sec)
float acc_bias_lim{0.4f}; ///< maximum accel bias magnitude (m/sec**2)
float acc_bias_learn_acc_lim{25.0f}; ///< learning is disabled if the magnitude of the IMU acceleration vector is greater than this (m/sec**2)
float acc_bias_learn_gyr_lim{3.0f}; ///< learning is disabled if the magnitude of the IMU angular rate vector is greater than this (rad/sec)
float acc_bias_learn_tc{0.5f}; ///< time constant used to control the decaying envelope filters applied to the accel and gyro magnitudes (sec)
unsigned no_gps_timeout_max{7000000}; // maximum time we allow dead reckoning while both gps position and velocity measurements are being
// rejected before attempting to reset the states to the GPS measurement (usec)
unsigned no_aid_timeout_max{1000000}; // maximum lapsed time from last fusion of measurements that constrain drift before
// the EKF will report that it is dead-reckoning (usec)
unsigned no_gps_timeout_max{7000000}; ///< maximum time we allow dead reckoning while both gps position and velocity measurements are being
///< rejected before attempting to reset the states to the GPS measurement (uSec)
unsigned no_aid_timeout_max{1000000}; ///< maximum lapsed time from last fusion of measurements that constrain drift before
///< the EKF will report that it is dead-reckoning (uSec)
// multi-rotor drag specific force fusion
float drag_noise{2.5f}; // observation noise for drag specific force measurements (m/sec**2)
float bcoef_x{25.0f}; // ballistic coefficient along the X-axis (kg/m**2)
float bcoef_y{25.0f}; // ballistic coefficient along the Y-axis (kg/m**2)
float drag_noise{2.5f}; ///< observation noise for drag specific force measurements (m/sec**2)
float bcoef_x{25.0f}; ///< ballistic coefficient along the X-axis (kg/m**2)
float bcoef_y{25.0f}; ///< ballistic coefficient along the Y-axis (kg/m**2)
// control of accel error detection and mitigation (IMU clipping)
float vert_innov_test_lim{4.5f}; // Number of standard deviations allowed before the combined vertical velocity and position test is declared as failed
int bad_acc_reset_delay_us{500000}; // Continuous time that the vertical position and velocity innovation test must fail before the states are reset (usec)
float vert_innov_test_lim{4.5f}; ///< Number of standard deviations allowed before the combined vertical velocity and position test is declared as failed
int bad_acc_reset_delay_us{500000}; ///< Continuous time that the vertical position and velocity innovation test must fail before the states are reset (uSec)
};
struct stateSample {
Quatf quat_nominal; // quaternion defining the rotaton from earth to body frame
Vector3f vel; // NED velocity in earth frame in m/s
Vector3f pos; // NED position in earth frame in m
Vector3f gyro_bias; // delta angle bias estimate in rad
Vector3f accel_bias; // delta velocity bias estimate in m/s
Vector3f mag_I; // NED earth magnetic field in gauss
Vector3f mag_B; // magnetometer bias estimate in body frame in gauss
Vector2f wind_vel; // wind velocity in m/s
Quatf quat_nominal; ///< quaternion defining the rotaton from earth to body frame
Vector3f vel; ///< NED velocity in earth frame in m/s
Vector3f pos; ///< NED position in earth frame in m
Vector3f gyro_bias; ///< delta angle bias estimate in rad
Vector3f accel_bias; ///< delta velocity bias estimate in m/s
Vector3f mag_I; ///< NED earth magnetic field in gauss
Vector3f mag_B; ///< magnetometer bias estimate in body frame in gauss
Vector2f wind_vel; ///< wind velocity in m/s
};
union fault_status_u {
struct {
bool bad_mag_x: 1; // 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error
bool bad_mag_y: 1; // 1 - true if the fusion of the magnetometer Y-axis has encountered a numerical error
bool bad_mag_z: 1; // 2 - true if the fusion of the magnetometer Z-axis has encountered a numerical error
bool bad_mag_hdg: 1; // 3 - true if the fusion of the magnetic heading has encountered a numerical error
bool bad_mag_decl: 1; // 4 - true if the fusion of the magnetic declination has encountered a numerical error
bool bad_airspeed: 1; // 5 - true if fusion of the airspeed has encountered a numerical error
bool bad_sideslip: 1; // 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
bool bad_optflow_X: 1; // 7 - true if fusion of the optical flow X axis has encountered a numerical error
bool bad_optflow_Y: 1; // 8 - true if fusion of the optical flow Y axis has encountered a numerical error
bool bad_vel_N: 1; // 9 - true if fusion of the North velocity has encountered a numerical error
bool bad_vel_E: 1; // 10 - true if fusion of the East velocity has encountered a numerical error
bool bad_vel_D: 1; // 11 - true if fusion of the Down velocity has encountered a numerical error
bool bad_pos_N: 1; // 12 - true if fusion of the North position has encountered a numerical error
bool bad_pos_E: 1; // 13 - true if fusion of the East position has encountered a numerical error
bool bad_pos_D: 1; // 14 - true if fusion of the Down position has encountered a numerical error
bool bad_acc_bias: 1; // 15 - true if bad delta velocity bias estimates have been detected
bool bad_mag_x: 1; ///< 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error
bool bad_mag_y: 1; ///< 1 - true if the fusion of the magnetometer Y-axis has encountered a numerical error
bool bad_mag_z: 1; ///< 2 - true if the fusion of the magnetometer Z-axis has encountered a numerical error
bool bad_mag_hdg: 1; ///< 3 - true if the fusion of the magnetic heading has encountered a numerical error
bool bad_mag_decl: 1; ///< 4 - true if the fusion of the magnetic declination has encountered a numerical error
bool bad_airspeed: 1; ///< 5 - true if fusion of the airspeed has encountered a numerical error
bool bad_sideslip: 1; ///< 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
bool bad_optflow_X: 1; ///< 7 - true if fusion of the optical flow X axis has encountered a numerical error
bool bad_optflow_Y: 1; ///< 8 - true if fusion of the optical flow Y axis has encountered a numerical error
bool bad_vel_N: 1; ///< 9 - true if fusion of the North velocity has encountered a numerical error
bool bad_vel_E: 1; ///< 10 - true if fusion of the East velocity has encountered a numerical error
bool bad_vel_D: 1; ///< 11 - true if fusion of the Down velocity has encountered a numerical error
bool bad_pos_N: 1; ///< 12 - true if fusion of the North position has encountered a numerical error
bool bad_pos_E: 1; ///< 13 - true if fusion of the East position has encountered a numerical error
bool bad_pos_D: 1; ///< 14 - true if fusion of the Down position has encountered a numerical error
bool bad_acc_bias: 1; ///< 15 - true if bad delta velocity bias estimates have been detected
} flags;
uint16_t value;
@ -358,18 +358,18 @@ union fault_status_u { @@ -358,18 +358,18 @@ union fault_status_u {
// define structure used to communicate innovation test failures
union innovation_fault_status_u {
struct {
bool reject_vel_NED: 1; // 0 - true if velocity observations have been rejected
bool reject_pos_NE: 1; // 1 - true if horizontal position observations have been rejected
bool reject_pos_D: 1; // 2 - true if true if vertical position observations have been rejected
bool reject_mag_x: 1; // 3 - true if the X magnetometer observation has been rejected
bool reject_mag_y: 1; // 4 - true if the Y magnetometer observation has been rejected
bool reject_mag_z: 1; // 5 - true if the Z magnetometer observation has been rejected
bool reject_yaw: 1; // 6 - true if the yaw observation has been rejected
bool reject_airspeed: 1; // 7 - true if the airspeed observation has been rejected
bool reject_sideslip: 1; // 8 - true if the synthetic sideslip observation has been rejected
bool reject_hagl: 1; // 9 - true if the height above ground observation has been rejected
bool reject_optflow_X: 1; // 10 - true if the X optical flow observation has been rejected
bool reject_optflow_Y: 1; // 11 - true if the Y optical flow observation has been rejected
bool reject_vel_NED: 1; ///< 0 - true if velocity observations have been rejected
bool reject_pos_NE: 1; ///< 1 - true if horizontal position observations have been rejected
bool reject_pos_D: 1; ///< 2 - true if true if vertical position observations have been rejected
bool reject_mag_x: 1; ///< 3 - true if the X magnetometer observation has been rejected
bool reject_mag_y: 1; ///< 4 - true if the Y magnetometer observation has been rejected
bool reject_mag_z: 1; ///< 5 - true if the Z magnetometer observation has been rejected
bool reject_yaw: 1; ///< 6 - true if the yaw observation has been rejected
bool reject_airspeed: 1; ///< 7 - true if the airspeed observation has been rejected
bool reject_sideslip: 1; ///< 8 - true if the synthetic sideslip observation has been rejected
bool reject_hagl: 1; ///< 9 - true if the height above ground observation has been rejected
bool reject_optflow_X: 1; ///< 10 - true if the X optical flow observation has been rejected
bool reject_optflow_Y: 1; ///< 11 - true if the Y optical flow observation has been rejected
} flags;
uint16_t value;
@ -378,16 +378,16 @@ union innovation_fault_status_u { @@ -378,16 +378,16 @@ union innovation_fault_status_u {
// publish the status of various GPS quality checks
union gps_check_fail_status_u {
struct {
uint16_t fix : 1; // 0 - true if the fix type is insufficient (no 3D solution)
uint16_t nsats : 1; // 1 - true if number of satellites used is insufficient
uint16_t gdop : 1; // 2 - true if geometric dilution of precision is insufficient
uint16_t hacc : 1; // 3 - true if reported horizontal accuracy is insufficient
uint16_t vacc : 1; // 4 - true if reported vertical accuracy is insufficient
uint16_t sacc : 1; // 5 - true if reported speed accuracy is insufficient
uint16_t hdrift : 1; // 6 - true if horizontal drift is excessive (can only be used when stationary on ground)
uint16_t vdrift : 1; // 7 - true if vertical drift is excessive (can only be used when stationary on ground)
uint16_t hspeed : 1; // 8 - true if horizontal speed is excessive (can only be used when stationary on ground)
uint16_t vspeed : 1; // 9 - true if vertical speed error is excessive
uint16_t fix : 1; ///< 0 - true if the fix type is insufficient (no 3D solution)
uint16_t nsats : 1; ///< 1 - true if number of satellites used is insufficient
uint16_t gdop : 1; ///< 2 - true if geometric dilution of precision is insufficient
uint16_t hacc : 1; ///< 3 - true if reported horizontal accuracy is insufficient
uint16_t vacc : 1; ///< 4 - true if reported vertical accuracy is insufficient
uint16_t sacc : 1; ///< 5 - true if reported speed accuracy is insufficient
uint16_t hdrift : 1; ///< 6 - true if horizontal drift is excessive (can only be used when stationary on ground)
uint16_t vdrift : 1; ///< 7 - true if vertical drift is excessive (can only be used when stationary on ground)
uint16_t hspeed : 1; ///< 8 - true if horizontal speed is excessive (can only be used when stationary on ground)
uint16_t vspeed : 1; ///< 9 - true if vertical speed error is excessive
} flags;
uint16_t value;
};
@ -395,42 +395,42 @@ union gps_check_fail_status_u { @@ -395,42 +395,42 @@ union gps_check_fail_status_u {
// bitmask containing filter control status
union filter_control_status_u {
struct {
uint32_t tilt_align : 1; // 0 - true if the filter tilt alignment is complete
uint32_t yaw_align : 1; // 1 - true if the filter yaw alignment is complete
uint32_t gps : 1; // 2 - true if GPS measurements are being fused
uint32_t opt_flow : 1; // 3 - true if optical flow measurements are being fused
uint32_t mag_hdg : 1; // 4 - true if a simple magnetic yaw heading is being fused
uint32_t mag_3D : 1; // 5 - true if 3-axis magnetometer measurement are being fused
uint32_t mag_dec : 1; // 6 - true if synthetic magnetic declination measurements are being fused
uint32_t in_air : 1; // 7 - true when the vehicle is airborne
uint32_t wind : 1; // 8 - true when wind velocity is being estimated
uint32_t baro_hgt : 1; // 9 - true when baro height is being fused as a primary height reference
uint32_t rng_hgt : 1; // 10 - true when range finder height is being fused as a primary height reference
uint32_t gps_hgt : 1; // 11 - true when GPS height is being fused as a primary height reference
uint32_t ev_pos : 1; // 12 - true when local position data from external vision is being fused
uint32_t ev_yaw : 1; // 13 - true when yaw data from external vision measurements is being fused
uint32_t ev_hgt : 1; // 14 - true when height data from external vision measurements is being fused
uint32_t fuse_beta : 1; // 15 - true when synthetic sideslip measurements are being fused
uint32_t update_mag_states_only : 1; // 16 - true when only the magnetometer states are updated by the magnetometer
uint32_t fixed_wing : 1; // 17 - true when the vehicle is operating as a fixed wing vehicle
uint32_t tilt_align : 1; ///< 0 - true if the filter tilt alignment is complete
uint32_t yaw_align : 1; ///< 1 - true if the filter yaw alignment is complete
uint32_t gps : 1; ///< 2 - true if GPS measurements are being fused
uint32_t opt_flow : 1; ///< 3 - true if optical flow measurements are being fused
uint32_t mag_hdg : 1; ///< 4 - true if a simple magnetic yaw heading is being fused
uint32_t mag_3D : 1; ///< 5 - true if 3-axis magnetometer measurement are being fused
uint32_t mag_dec : 1; ///< 6 - true if synthetic magnetic declination measurements are being fused
uint32_t in_air : 1; ///< 7 - true when the vehicle is airborne
uint32_t wind : 1; ///< 8 - true when wind velocity is being estimated
uint32_t baro_hgt : 1; ///< 9 - true when baro height is being fused as a primary height reference
uint32_t rng_hgt : 1; ///< 10 - true when range finder height is being fused as a primary height reference
uint32_t gps_hgt : 1; ///< 11 - true when GPS height is being fused as a primary height reference
uint32_t ev_pos : 1; ///< 12 - true when local position data from external vision is being fused
uint32_t ev_yaw : 1; ///< 13 - true when yaw data from external vision measurements is being fused
uint32_t ev_hgt : 1; ///< 14 - true when height data from external vision measurements is being fused
uint32_t fuse_beta : 1; ///< 15 - true when synthetic sideslip measurements are being fused
uint32_t update_mag_states_only : 1; ///< 16 - true when only the magnetometer states are updated by the magnetometer
uint32_t fixed_wing : 1; ///< 17 - true when the vehicle is operating as a fixed wing vehicle
} flags;
uint32_t value;
};
union ekf_solution_status {
struct {
uint16_t attitude : 1; // 0 - True if the attitude estimate is good
uint16_t velocity_horiz : 1; // 1 - True if the horizontal velocity estimate is good
uint16_t velocity_vert : 1; // 2 - True if the vertical velocity estimate is good
uint16_t pos_horiz_rel : 1; // 3 - True if the horizontal position (relative) estimate is good
uint16_t pos_horiz_abs : 1; // 4 - True if the horizontal position (absolute) estimate is good
uint16_t pos_vert_abs : 1; // 5 - True if the vertical position (absolute) estimate is good
uint16_t pos_vert_agl : 1; // 6 - True if the vertical position (above ground) estimate is good
uint16_t const_pos_mode : 1; // 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
uint16_t pred_pos_horiz_rel : 1; // 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
uint16_t pred_pos_horiz_abs : 1; // 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
uint16_t gps_glitch : 1; // 10 - True if the EKF has detected a GPS glitch
uint16_t accel_error : 1; // 11 - True if the EKF has detected bad accelerometer data
uint16_t attitude : 1; ///< 0 - True if the attitude estimate is good
uint16_t velocity_horiz : 1; ///< 1 - True if the horizontal velocity estimate is good
uint16_t velocity_vert : 1; ///< 2 - True if the vertical velocity estimate is good
uint16_t pos_horiz_rel : 1; ///< 3 - True if the horizontal position (relative) estimate is good
uint16_t pos_horiz_abs : 1; ///< 4 - True if the horizontal position (absolute) estimate is good
uint16_t pos_vert_abs : 1; ///< 5 - True if the vertical position (absolute) estimate is good
uint16_t pos_vert_agl : 1; ///< 6 - True if the vertical position (above ground) estimate is good
uint16_t const_pos_mode : 1; ///< 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
uint16_t pred_pos_horiz_rel : 1; ///< 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
uint16_t pred_pos_horiz_abs : 1; ///< 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
uint16_t gps_glitch : 1; ///< 10 - True if the EKF has detected a GPS glitch
uint16_t accel_error : 1; ///< 11 - True if the EKF has detected bad accelerometer data
} flags;
uint16_t value;
};

256
EKF/ekf.h

@ -137,7 +137,7 @@ public: @@ -137,7 +137,7 @@ public:
void get_pos_var(Vector3f &pos_var);
// return an array containing the output predictor angular, velocity and position tracking
// error magnitudes (rad), (m/s), (m)
// error magnitudes (rad), (m/sec), (m)
void get_output_tracking_error(float error[3]);
/*
@ -208,177 +208,173 @@ public: @@ -208,177 +208,173 @@ public:
private:
static constexpr uint8_t _k_num_states{24};
static constexpr float _k_earth_rate{0.000072921f};
static constexpr float _gravity_mss{9.80665f};
static constexpr uint8_t _k_num_states{24}; ///< number of EKF states
static constexpr float _k_earth_rate{0.000072921f}; ///< earth spin rate (rad/sec)
static constexpr float _gravity_mss{9.80665f}; ///< average earth gravity at sea level (m/sec**2)
// reset event monitoring
// structure containing velocity, position, height and yaw reset information
struct {
uint8_t velNE_counter; // number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_t velD_counter; // number of vertical velocity reset events (allow to wrap if count exceeds 255)
uint8_t posNE_counter; // number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_t posD_counter; // number of vertical position reset events (allow to wrap if count exceeds 255)
uint8_t quat_counter; // number of quaternion reset events (allow to wrap if count exceeds 255)
Vector2f velNE_change; // North East velocity change due to last reset (m)
float velD_change; // Down velocity change due to last reset (m/s)
Vector2f posNE_change; // North, East position change due to last reset (m)
float posD_change; // Down position change due to last reset (m)
Quatf quat_change; // quaternion delta due to last reset - multiply pre-reset quaternion by this to get post-reset quaternion
} _state_reset_status{};
float _dt_ekf_avg{0.001f * FILTER_UPDATE_PERIOD_MS}; // average update rate of the ekf
float _dt_update{0.01f}; // delta time since last ekf update. This time can be used for filters
// which run at the same rate as the Ekf::update() function
stateSample _state{}; // state struct of the ekf running at the delayed time horizon
bool _filter_initialised{false}; // true when the EKF sttes and covariances been initialised
bool _earth_rate_initialised{false}; // true when we know the earth rotatin rate (requires GPS)
bool _fuse_height{false}; // baro height data should be fused
bool _fuse_pos{false}; // gps position data should be fused
bool _fuse_hor_vel{false}; // gps horizontal velocity measurement should be fused
bool _fuse_vert_vel{false}; // gps vertical velocity measurement should be fused
uint8_t velNE_counter; ///< number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_t velD_counter; ///< number of vertical velocity reset events (allow to wrap if count exceeds 255)
uint8_t posNE_counter; ///< number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_t posD_counter; ///< number of vertical position reset events (allow to wrap if count exceeds 255)
uint8_t quat_counter; ///< number of quaternion reset events (allow to wrap if count exceeds 255)
Vector2f velNE_change; ///< North East velocity change due to last reset (m)
float velD_change; ///< Down velocity change due to last reset (m/sec)
Vector2f posNE_change; ///< North, East position change due to last reset (m)
float posD_change; ///< Down position change due to last reset (m)
Quatf quat_change; ///< quaternion delta due to last reset - multiply pre-reset quaternion by this to get post-reset quaternion
} _state_reset_status{}; ///< reset event monitoring structure containing velocity, position, height and yaw reset information
float _dt_ekf_avg{0.001f * FILTER_UPDATE_PERIOD_MS}; ///< average update rate of the ekf
float _dt_update{0.01f}; ///< delta time since last ekf update. This time can be used for filters which run at the same rate as the Ekf::update() function. (sec)
stateSample _state{}; ///< state struct of the ekf running at the delayed time horizon
bool _filter_initialised{false}; ///< true when the EKF sttes and covariances been initialised
bool _earth_rate_initialised{false}; ///< true when we know the earth rotatin rate (requires GPS)
bool _fuse_height{false}; ///< true when baro height data should be fused
bool _fuse_pos{false}; ///< true when gps position data should be fused
bool _fuse_hor_vel{false}; ///< true when gps horizontal velocity measurement should be fused
bool _fuse_vert_vel{false}; ///< true when gps vertical velocity measurement should be fused
// booleans true when fresh sensor data is available at the fusion time horizon
bool _gps_data_ready{false};
bool _mag_data_ready{false};
bool _baro_data_ready{false};
bool _range_data_ready{false};
bool _flow_data_ready{false};
bool _ev_data_ready{false};
bool _tas_data_ready{false};
bool _gps_data_ready{false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused
bool _mag_data_ready{false}; ///< true when new magnetometer data has fallen behind the fusion time horizon and is available to be fused
bool _baro_data_ready{false}; ///< true when new baro height data has fallen behind the fusion time horizon and is available to be fused
bool _range_data_ready{false}; ///< true when new range finder data has fallen behind the fusion time horizon and is available to be fused
bool _flow_data_ready{false}; ///< true when new optical flow data has fallen behind the fusion time horizon and is available to be fused
bool _ev_data_ready{false}; ///< true when new external vision system data has fallen behind the fusion time horizon and is available to be fused
bool _tas_data_ready{false}; ///< true when new true airspeed data has fallen behind the fusion time horizon and is available to be fused
uint64_t _time_last_fake_gps{0}; // last time in us at which we have faked gps measurement for static mode
uint64_t _time_last_fake_gps{0}; ///< last time we faked GPS position measurements to constrain tilt errors during operation without external aiding (uSec)
uint64_t _time_last_pos_fuse{0}; // time the last fusion of horizontal position measurements was performed (usec)
uint64_t _time_last_vel_fuse{0}; // time the last fusion of velocity measurements was performed (usec)
uint64_t _time_last_hgt_fuse{0}; // time the last fusion of height measurements was performed (usec)
uint64_t _time_last_of_fuse{0}; // time the last fusion of optical flow measurements were performed (usec)
uint64_t _time_last_arsp_fuse{0}; // time the last fusion of airspeed measurements were performed (usec)
uint64_t _time_last_beta_fuse{0}; // time the last fusion of synthetic sideslip measurements were performed (usec)
Vector2f _last_known_posNE; // last known local NE position vector (m)
float _last_disarmed_posD{0.0f}; // vertical position recorded at arming (m)
float _imu_collection_time_adj{0.0f}; // the amount of time the IMU collection needs to be advanced to meet the target set by FILTER_UPDATE_PERIOD_MS (sec)
uint64_t _time_last_pos_fuse{0}; ///< time the last fusion of horizontal position measurements was performed (uSec)
uint64_t _time_last_vel_fuse{0}; ///< time the last fusion of velocity measurements was performed (uSec)
uint64_t _time_last_hgt_fuse{0}; ///< time the last fusion of height measurements was performed (uSec)
uint64_t _time_last_of_fuse{0}; ///< time the last fusion of optical flow measurements were performed (uSec)
uint64_t _time_last_arsp_fuse{0}; ///< time the last fusion of airspeed measurements were performed (uSec)
uint64_t _time_last_beta_fuse{0}; ///< time the last fusion of synthetic sideslip measurements were performed (uSec)
Vector2f _last_known_posNE; ///< last known local NE position vector (m)
float _last_disarmed_posD{0.0f}; ///< vertical position recorded at arming (m)
float _imu_collection_time_adj{0.0f}; ///< the amount of time the IMU collection needs to be advanced to meet the target set by FILTER_UPDATE_PERIOD_MS (sec)
uint64_t _time_acc_bias_check{0}; // last time the accel bias check passed (usec)
uint64_t _delta_time_baro_us{0}; // delta time between two consecutive delayed baro samples from the buffer (usec)
uint64_t _time_acc_bias_check{0}; ///< last time the accel bias check passed (uSec)
uint64_t _delta_time_baro_us{0}; ///< delta time between two consecutive delayed baro samples from the buffer (uSec)
Vector3f _earth_rate_NED; // earth rotation vector (NED) in rad/s
Vector3f _earth_rate_NED; ///< earth rotation vector (NED) in rad/s
Dcmf _R_to_earth; // transformation matrix from body frame to earth frame from last EKF predition
Dcmf _R_to_earth; ///< transformation matrix from body frame to earth frame from last EKF predition
// used by magnetometer fusion mode selection
Vector2f _accel_lpf_NE; // Low pass filtered horizontal earth frame acceleration (m/s**2)
float _yaw_delta_ef{0.0f}; // Recent change in yaw angle measured about the earth frame D axis (rad)
float _yaw_rate_lpf_ef{0.0f}; // Filtered angular rate about earth frame D axis (rad/sec)
bool _mag_bias_observable{false}; // true when there is enough rotation to make magnetometer bias errors observable
bool _yaw_angle_observable{false}; // true when there is enough horizontal acceleration to make yaw observable
uint64_t _time_yaw_started{0}; // last system time in usec that a yaw rotation moaneouvre was detected
Vector2f _accel_lpf_NE; ///< Low pass filtered horizontal earth frame acceleration (m/sec**2)
float _yaw_delta_ef{0.0f}; ///< Recent change in yaw angle measured about the earth frame D axis (rad)
float _yaw_rate_lpf_ef{0.0f}; ///< Filtered angular rate about earth frame D axis (rad/sec)
bool _mag_bias_observable{false}; ///< true when there is enough rotation to make magnetometer bias errors observable
bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable
uint64_t _time_yaw_started{0}; ///< last system time in usec that a yaw rotation moaneouvre was detected
float P[_k_num_states][_k_num_states] {}; // state covariance matrix
float P[_k_num_states][_k_num_states] {}; ///< state covariance matrix
float _vel_pos_innov[6] {}; // innovations: 0-2 vel, 3-5 pos
float _vel_pos_innov_var[6] {}; // innovation variances: 0-2 vel, 3-5 pos
float _vel_pos_innov[6] {}; ///< NED velocity and position innovations: 0-2 vel (m/sec), 3-5 pos (m**2)
float _vel_pos_innov_var[6] {}; ///< NED velocity and position innovation variances: 0-2 vel ((m/sec)**2), 3-5 pos (m**2)
float _mag_innov[3] {}; // earth magnetic field innovations
float _mag_innov_var[3] {}; // earth magnetic field innovation variance
float _mag_innov[3] {}; ///< earth magnetic field innovations (Gauss)
float _mag_innov_var[3] {}; ///< earth magnetic field innovation variance (Gauss**2)
float _airspeed_innov{0.0f}; // airspeed measurement innovation
float _airspeed_innov_var{0.0f}; // airspeed measurement innovation variance
float _airspeed_innov{0.0f}; ///< airspeed measurement innovation (m/sec)
float _airspeed_innov_var{0.0f}; ///< airspeed measurement innovation variance ((m/sec)**2)
float _beta_innov{0.0f}; // synthetic sideslip measurement innovation
float _beta_innov_var{0.0f}; // synthetic sideslip measurement innovation variance
float _beta_innov{0.0f}; ///< synthetic sideslip measurement innovation (rad)
float _beta_innov_var{0.0f}; ///< synthetic sideslip measurement innovation variance (rad**2)
float _drag_innov[2] {}; // multirotor drag measurement innovation
float _drag_innov_var[2] {}; // multirotor drag measurement innovation variance
float _drag_innov[2] {}; ///< multirotor drag measurement innovation (m/sec**2)
float _drag_innov_var[2] {}; ///< multirotor drag measurement innovation variance ((m/sec**2)**2)
float _heading_innov{0.0f}; // heading measurement innovation
float _heading_innov_var{0.0f}; // heading measurement innovation variance
float _heading_innov{0.0f}; ///< heading measurement innovation (rad)
float _heading_innov_var{0.0f}; ///< heading measurement innovation variance (rad**2)
// optical flow processing
float _flow_innov[2] {}; // flow measurement innovation
float _flow_innov_var[2] {}; // flow innovation variance
Vector3f _flow_gyro_bias; // bias errors in optical flow sensor rate gyro outputs
Vector3f _imu_del_ang_of; // bias corrected delta angle measurements accumulated across the same time frame as the optical flow rates
float _delta_time_of{0.0f}; // time in sec that _imu_del_ang_of was accumulated over
float _flow_innov[2] {}; ///< flow measurement innovation (rad/sec)
float _flow_innov_var[2] {}; ///< flow innovation variance ((rad/sec)**2)
Vector3f _flow_gyro_bias; ///< bias errors in optical flow sensor rate gyro outputs (rad/sec)
Vector3f _imu_del_ang_of; ///< bias corrected delta angle measurements accumulated across the same time frame as the optical flow rates (rad)
float _delta_time_of{0.0f}; ///< time in sec that _imu_del_ang_of was accumulated over (sec)
float _mag_declination{0.0f}; // magnetic declination used by reset and fusion functions (rad)
float _mag_declination{0.0f}; ///< magnetic declination used by reset and fusion functions (rad)
// output predictor states
Vector3f _delta_angle_corr; // delta angle correction vector
imuSample _imu_down_sampled{}; // down sampled imu data (sensor rate -> filter update rate)
Quatf _q_down_sampled; // down sampled quaternion (tracking delta angles between ekf update steps)
Vector3f _vel_err_integ; // integral of velocity tracking error
Vector3f _pos_err_integ; // integral of position tracking error
float _output_tracking_error[3] {}; // contains the magnitude of the angle, velocity and position track errors (rad, m/s, m)
Vector3f _delta_angle_corr; ///< delta angle correction vector (rad)
imuSample _imu_down_sampled{}; ///< down sampled imu data (sensor rate -> filter update rate)
Quatf _q_down_sampled; ///< down sampled quaternion (tracking delta angles between ekf update steps)
Vector3f _vel_err_integ; ///< integral of velocity tracking error (m)
Vector3f _pos_err_integ; ///< integral of position tracking error (m.s)
float _output_tracking_error[3] {}; ///< contains the magnitude of the angle, velocity and position track errors (rad, m/s, m)
// variables used for the GPS quality checks
float _gpsDriftVelN{0.0f}; // GPS north position derivative (m/s)
float _gpsDriftVelE{0.0f}; // GPS east position derivative (m/s)
float _gps_drift_velD{0.0f}; // GPS down position derivative (m/s)
float _gps_velD_diff_filt{0.0f}; // GPS filtered Down velocity (m/s)
float _gps_velN_filt{0.0f}; // GPS filtered North velocity (m/s)
float _gps_velE_filt{0.0f}; // GPS filtered East velocity (m/s)
uint64_t _last_gps_fail_us{0}; // last system time in usec that the GPS failed it's checks
float _gpsDriftVelN{0.0f}; ///< GPS north position derivative (m/sec)
float _gpsDriftVelE{0.0f}; ///< GPS east position derivative (m/sec)
float _gps_drift_velD{0.0f}; ///< GPS down position derivative (m/sec)
float _gps_velD_diff_filt{0.0f}; ///< GPS filtered Down velocity (m/sec)
float _gps_velN_filt{0.0f}; ///< GPS filtered North velocity (m/sec)
float _gps_velE_filt{0.0f}; ///< GPS filtered East velocity (m/sec)
uint64_t _last_gps_fail_us{0}; ///< last system time in usec that the GPS failed it's checks
// Variables used to publish the WGS-84 location of the EKF local NED origin
uint64_t _last_gps_origin_time_us{0}; // time the origin was last set (uSec)
float _gps_alt_ref{0.0f}; // WGS-84 height (m)
uint64_t _last_gps_origin_time_us{0}; ///< time the origin was last set (uSec)
float _gps_alt_ref{0.0f}; ///< WGS-84 height (m)
// Variables used to initialise the filter states
uint32_t _hgt_counter{0}; // number of height samples read during initialisation
float _rng_filt_state{0.0f}; // filtered height measurement
uint32_t _mag_counter{0}; // number of magnetometer samples read during initialisation
uint32_t _ev_counter{0}; // number of exgernal vision samples read during initialisation
uint64_t _time_last_mag{0}; // measurement time of last magnetomter sample
Vector3f _mag_filt_state; // filtered magnetometer measurement
Vector3f _delVel_sum; // summed delta velocity
float _hgt_sensor_offset{0.0f}; // set as necessary if desired to maintain the same height after a height reset (m)
float _baro_hgt_offset{0.0f}; // baro height reading at the local NED origin (m)
uint32_t _hgt_counter{0}; ///< number of height samples read during initialisation
float _rng_filt_state{0.0f}; ///< filtered height measurement (m)
uint32_t _mag_counter{0}; ///< number of magnetometer samples read during initialisation
uint32_t _ev_counter{0}; ///< number of external vision samples read during initialisation
uint64_t _time_last_mag{0}; ///< measurement time of last magnetomter sample (uSec)
Vector3f _mag_filt_state; ///< filtered magnetometer measurement (Gauss)
Vector3f _delVel_sum; ///< summed delta velocity (m/sec)
float _hgt_sensor_offset{0.0f}; ///< set as necessary if desired to maintain the same height after a height reset (m)
float _baro_hgt_offset{0.0f}; ///< baro height reading at the local NED origin (m)
// Variables used to control activation of post takeoff functionality
float _last_on_ground_posD{0.0f}; // last vertical position when the in_air status was false (m)
bool _flt_mag_align_complete{true}; // true when the in-flight mag field alignment has been completed
uint64_t _time_last_movement{0}; // last system time in usec that sufficient movement to use 3-axis magnetometer fusion was detected
float _saved_mag_variance[6] {}; // magnetic field state variances that have been saved for use at the next initialisation (Ga**2)
float _last_on_ground_posD{0.0f}; ///< last vertical position when the in_air status was false (m)
bool _flt_mag_align_complete{true}; ///< true when the in-flight mag field alignment has been completed
uint64_t _time_last_movement{0}; ///< last system time that sufficient movement to use 3-axis magnetometer fusion was detected (uSec)
float _saved_mag_variance[6] {}; ///< magnetic field state variances that have been saved for use at the next initialisation (Gauss**2)
gps_check_fail_status_u _gps_check_fail_status{};
// variables used to inhibit accel bias learning
bool _accel_bias_inhibit{false}; // true when the accel bias learning is being inhibited
float _accel_mag_filt{0.0f}; // acceleration magnitude after application of a decaying envelope filter (m/sec**2)
float _ang_rate_mag_filt{0.0f}; // angular rate magnitude after application of a decaying envelope filter (rad/sec)
Vector3f _prev_dvel_bias_var; // saved delta velocity XYZ bias variances (m/sec)**2
bool _accel_bias_inhibit{false}; ///< true when the accel bias learning is being inhibited
float _accel_mag_filt{0.0f}; ///< acceleration magnitude after application of a decaying envelope filter (m/sec**2)
float _ang_rate_mag_filt{0.0f}; ///< angular rate magnitude after application of a decaying envelope filter (rad/sec)
Vector3f _prev_dvel_bias_var; ///< saved delta velocity XYZ bias variances (m/sec)**2
// Terrain height state estimation
float _terrain_vpos{0.0f}; // estimated vertical position of the terrain underneath the vehicle in local NED frame (m)
float _terrain_var{1e4f}; // variance of terrain position estimate (m^2)
float _hagl_innov{0.0f}; // innovation of the last height above terrain measurement (m)
float _hagl_innov_var{0.0f}; // innovation variance for the last height above terrain measurement (m^2)
uint64_t _time_last_hagl_fuse; // last system time in usec that the hagl measurement failed it's checks
bool _terrain_initialised{false}; // true when the terrain estimator has been intialised
float _sin_tilt_rng{0.0f}; // sine of the range finder tilt rotation about the Y body axis
float _cos_tilt_rng{0.0f}; // cosine of the range finder tilt rotation about the Y body axis
float _R_rng_to_earth_2_2{0.0f}; // 2,2 element of the rotation matrix from sensor frame to earth frame
bool _range_data_continuous{false}; // true when we are receiving range finder data faster than a 2Hz average
float _dt_last_range_update_filt_us{0.0f}; // filtered value of the delta time elapsed since the last range measurement came into
// the filter (microseconds)
float _terrain_vpos{0.0f}; ///< estimated vertical position of the terrain underneath the vehicle in local NED frame (m)
float _terrain_var{1e4f}; ///< variance of terrain position estimate (m**2)
float _hagl_innov{0.0f}; ///< innovation of the last height above terrain measurement (m)
float _hagl_innov_var{0.0f}; ///< innovation variance for the last height above terrain measurement (m**2)
uint64_t _time_last_hagl_fuse; ///< last system time that the hagl measurement failed it's checks (uSec)
bool _terrain_initialised{false}; ///< true when the terrain estimator has been intialised
float _sin_tilt_rng{0.0f}; ///< sine of the range finder tilt rotation about the Y body axis
float _cos_tilt_rng{0.0f}; ///< cosine of the range finder tilt rotation about the Y body axis
float _R_rng_to_earth_2_2{0.0f}; ///< 2,2 element of the rotation matrix from sensor frame to earth frame
bool _range_data_continuous{false}; ///< true when we are receiving range finder data faster than a 2Hz average
float _dt_last_range_update_filt_us{0.0f}; ///< filtered value of the delta time elapsed since the last range measurement came into the filter (uSec)
// height sensor fault status
bool _baro_hgt_faulty{false}; // true if valid baro data is unavailable for use
bool _gps_hgt_faulty{false}; // true if valid gps height data is unavailable for use
bool _rng_hgt_faulty{false}; // true if valid rnage finder height data is unavailable for use
int _primary_hgt_source{VDIST_SENSOR_BARO}; // priary source of height data set at initialisation
bool _baro_hgt_faulty{false}; ///< true if valid baro data is unavailable for use
bool _gps_hgt_faulty{false}; ///< true if valid gps height data is unavailable for use
bool _rng_hgt_faulty{false}; ///< true if valid rnage finder height data is unavailable for use
int _primary_hgt_source{VDIST_SENSOR_BARO}; ///< specifies primary source of height data
// imu fault status
uint64_t _time_bad_vert_accel{0}; // last time a bad vertical accel was detected (usec)
uint64_t _time_good_vert_accel{0}; // last time a good vertical accel was detected (usec)
bool _bad_vert_accel_detected{false}; // true when bad vertical accelerometer data has been detected
uint64_t _time_bad_vert_accel{0}; ///< last time a bad vertical accel was detected (uSec)
uint64_t _time_good_vert_accel{0}; ///< last time a good vertical accel was detected (uSec)
bool _bad_vert_accel_detected{false}; ///< true when bad vertical accelerometer data has been detected
// variables used to control range aid functionality
bool _in_range_aid_mode;
// variables used to control range aid functionality
bool _in_range_aid_mode; ///< true when range finder is to be used as the height reference instead of the primary height sensor
// update the real time complementary filter states. This includes the prediction
// and the correction step

Loading…
Cancel
Save