floateas2tas;///< equivalent to true airspeed factor
uint64_ttime_us;///< timestamp of the measurement (uSec)
};
structflowSample{
uint8_tquality;// quality indicator between 0 and 255
Vector2fflowRadXY;// measured delta angle of the image about the X and Y body axes (rad), RH rotaton is positive
Vector2fflowRadXYcomp;// measured delta angle of the image about the X and Y body axes after removal of body rotation (rad), RH rotation is positive
Vector3fgyroXYZ;// measured delta angle of the inertial frame about the body axes obtained from rate gyro measurements (rad), RH rotation is positive
floatdt;// amount of integration time (sec)
uint64_ttime_us;// timestamp in microseconds of the integration period mid-point
uint8_tquality;///< quality indicator between 0 and 255
Vector2fflowRadXY;///< measured delta angle of the image about the X and Y body axes (rad), RH rotaton is positive
Vector2fflowRadXYcomp;///< measured delta angle of the image about the X and Y body axes after removal of body rotation (rad), RH rotation is positive
Vector3fgyroXYZ;///< measured delta angle of the inertial frame about the body axes obtained from rate gyro measurements (rad), RH rotation is positive
floatdt;///< amount of integration time (sec)
uint64_ttime_us;///< timestamp of the integration period mid-point (uSec)
};
structextVisionSample{
Vector3fposNED;// measured NED position relative to the local origin (m)
Quatfquat;// measured quaternion orientation defining rotation from NED to body frame
floatposErr;// 1-Sigma spherical position accuracy (m)
floatangErr;// 1-Sigma angular error (rad)
uint64_ttime_us;// timestamp of the measurement in microseconds
Vector3fposNED;///< measured NED position relative to the local origin (m)
Quatfquat;///< measured quaternion orientation defining rotation from NED to body frame
floatposErr;///< 1-Sigma spherical position accuracy (m)
floatangErr;///< 1-Sigma angular error (rad)
uint64_ttime_us;///< timestamp of the measurement (uSec)
};
structdragSample{
Vector2faccelXY;// measured specific force along the X and Y body axes (m/s**2)
uint64_ttime_us;// timestamp in microseconds of the measurement
Vector2faccelXY;///< measured specific force along the X and Y body axes (m/sec**2)
uint64_ttime_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)
structparameters{
// measurement source control
int32_tfusion_mode{MASK_USE_GPS};// bitmasked integer that selects which aiding sources will be used
int32_tvdist_sensor_type{VDIST_SENSOR_BARO};// selects the primary source for height data
int32_tsensor_interval_min_ms{20};// minimum time of arrival difference between non IMU sensor updates. Sets the size of the observation buffers.
int32_tfusion_mode{MASK_USE_GPS};///< bitmasked integer that selects which aiding sources will be used
int32_tvdist_sensor_type{VDIST_SENSOR_BARO};///< selects the primary source for height data
int32_tsensor_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
floatmin_delay_ms{0.0f};// used to a set a minimum buffer length independent of specified sensor delays
floatmag_delay_ms{0.0f};// magnetometer measurement delay relative to the IMU (msec)
floatbaro_delay_ms{0.0f};// barometer height measurement delay relative to the IMU (msec)
floatgps_delay_ms{110.0f};// GPS measurement delay relative to the IMU (msec)
floatairspeed_delay_ms{100.0f};// airspeed measurement delay relative to the IMU (msec)
floatflow_delay_ms{5.0f};// optical flow measurement delay relative to the IMU (msec) - this is to the middle of the optical flow integration interval
floatrange_delay_ms{5.0f};// range finder measurement delay relative to the IMU (msec)
floatev_delay_ms{100.0f};// off-board vision measurement delay relative to the IMU (msec)
floatmin_delay_ms{0.0f};///< Maximmum time delay of any sensor used to increse buffer length to handle large timing jitter (mSec)
floatmag_delay_ms{0.0f};///< magnetometer measurement delay relative to the IMU (mSec)
floatbaro_delay_ms{0.0f};///< barometer height measurement delay relative to the IMU (mSec)
floatgps_delay_ms{110.0f};///< GPS measurement delay relative to the IMU (mSec)
floatairspeed_delay_ms{100.0f};///< airspeed measurement delay relative to the IMU (mSec)
floatflow_delay_ms{5.0f};///< optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval
floatrange_delay_ms{5.0f};///< range finder measurement delay relative to the IMU (mSec)
floatev_delay_ms{100.0f};///< off-board vision measurement delay relative to the IMU (mSec)
// input noise
floatgyro_noise{1.5e-2f};// IMU angular rate noise used for covariance prediction (rad/sec)
floataccel_noise{3.5e-1f};// IMU acceleration noise use for covariance prediction (m/sec/sec)
floatgyro_noise{1.5e-2f};///< IMU angular rate noise used for covariance prediction (rad/sec)
floataccel_noise{3.5e-1f};///< IMU acceleration noise use for covariance prediction (m/sec**2)
// process noise
floatgyro_bias_p_noise{1.0e-3f};// process noise for IMU rate gyro bias prediction (rad/sec**2)
floataccel_bias_p_noise{6.0e-3f};// process noise for IMU accelerometer bias prediction (m/sec**3)
floatmage_p_noise{1.0e-3f};// process noise for earth magnetic field prediction (Guass/sec)
floatmagb_p_noise{1.0e-4};// process noise for body magnetic field prediction (Guass/sec)
floatwind_vel_p_noise{1.0e-1f};// process noise for wind velocity prediction (m/sec/sec)
floatterrain_p_noise{5.0f};// process noise for terrain offset (m/sec)
floatterrain_gradient{0.5f};// gradient of terrain used to estimate process noise due to changing position (m/m)
floatgyro_bias_p_noise{1.0e-3f};///< process noise for IMU rate gyro bias prediction (rad/sec**2)
floataccel_bias_p_noise{6.0e-3f};///< process noise for IMU accelerometer bias prediction (m/sec**3)
floatmage_p_noise{1.0e-3f};///< process noise for earth magnetic field prediction (Gauss/sec)
floatmagb_p_noise{1.0e-4};///< process noise for body magnetic field prediction (Gauss/sec)
floatwind_vel_p_noise{1.0e-1f};///< process noise for wind velocity prediction (m/sec**2)
floatterrain_p_noise{5.0f};///< process noise for terrain offset (m/sec)
floatterrain_gradient{0.5f};///< gradient of terrain used to estimate process noise due to changing position (m/m)
// initialization errors
floatswitch_on_gyro_bias{0.1f};// 1-sigma gyro bias uncertainty at switch on (rad/sec)
floatswitch_on_accel_bias{0.2f};// 1-sigma accelerometer bias uncertainty at switch on (m/s**2)
floatinitial_tilt_err{0.1f};// 1-sigma tilt error after initial alignment using gravity vector (rad)
floatinitial_wind_uncertainty{1.0f};// 1-sigma initial uncertainty in wind velocity (m/s)
floatswitch_on_gyro_bias{0.1f};///< 1-sigma gyro bias uncertainty at switch on (rad/sec)
floatswitch_on_accel_bias{0.2f};///< 1-sigma accelerometer bias uncertainty at switch on (m/sec**2)
floatinitial_tilt_err{0.1f};///< 1-sigma tilt error after initial alignment using gravity vector (rad)
floatinitial_wind_uncertainty{1.0f};///< 1-sigma initial uncertainty in wind velocity (m/sec)
// position and velocity fusion
floatgps_vel_noise{5.0e-1f};// observation noise for gps velocity fusion (m/sec)
floatgps_pos_noise{0.5f};// observation noise for gps position fusion (m)
floatpos_noaid_noise{10.0f};// observation noise for non-aiding position fusion (m)
floatbaro_noise{2.0f};// observation noise for barometric height fusion (m)
floatbeta_avg_ft_us{1000000.0f};///< The average time between synthetic sideslip measurements (uSec)
// range finder fusion
floatrange_noise{0.1f};// observation noise for range finder measurements (m)
floatrange_innov_gate{5.0f};// range finder fusion innovation consistency gate size (STD)
floatrng_gnd_clearance{0.1f};// minimum valid value for range when on ground (m)
floatrng_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.
floatrange_noise_scaler{0.0f};// scaling from range measurement to noise (m/m)
floatvehicle_variance_scaler{0.0f};// gain applied to vehicle height variance used in calculation of height above ground observation variance
floatmax_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)
floatmax_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_trange_aid{0};// allow switching primary height source to range finder if certian conditions are met
floatrange_aid_innov_gate{1.0f};// gate size used for innovation consistency checks for range aid fusion
floatrange_noise{0.1f};///< observation noise for range finder measurements (m)
floatrange_innov_gate{5.0f};///< range finder fusion innovation consistency gate size (STD)
floatrng_gnd_clearance{0.1f};///< minimum valid value for range when on ground (m)
floatrng_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.
floatrange_noise_scaler{0.0f};///< scaling from range measurement to noise (m/m)
floatvehicle_variance_scaler{0.0f};///< gain applied to vehicle height variance used in calculation of height above ground observation variance
floatmax_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)
floatmax_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_trange_aid{0};///< allow switching primary height source to range finder if certian conditions are met
floatrange_aid_innov_gate{1.0f};///< gate size used for innovation consistency checks for range aid fusion
floatflow_noise{0.15f};// observation noise for optical flow LOS rate measurements (rad/sec)
floatflow_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_tflow_qual_min{1};// minimum acceptable quality integer from the flow sensor
floatflow_rate_max{2.5f};// maximum valid optical flow rate (rad/sec)
floatflow_noise{0.15f};///< observation noise for optical flow LOS rate measurements (rad/sec)
floatflow_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_tflow_qual_min{1};///< minimum acceptable quality integer from the flow sensor
floatreq_gdop{2.0f};///< maximum acceptable geometric dilution of precision
floatreq_hdrift{0.3f};///< maximum acceptable horizontal drift speed (m/s)
floatreq_vdrift{0.5f};///< maximum acceptable vertical drift speed (m/s)
// XYZ offset of sensors in body axes (m)
Vector3fimu_pos_body;// xyz position of IMU in body frame (m)
Vector3fgps_pos_body;// xyz position of the GPS antenna in body frame (m)
Vector3frng_pos_body;// xyz position of range sensor in body frame (m)
Vector3fflow_pos_body;// xyz position of range sensor focal point in body frame (m)
Vector3fev_pos_body;// xyz position of VI-sensor focal point in body frame (m)
Vector3fimu_pos_body;///< xyz position of IMU in body frame (m)
Vector3fgps_pos_body;///< xyz position of the GPS antenna in body frame (m)
Vector3frng_pos_body;///< xyz position of range sensor in body frame (m)
Vector3fflow_pos_body;///< xyz position of range sensor focal point in body frame (m)
Vector3fev_pos_body;///< xyz position of VI-sensor focal point in body frame (m)
// output complementary filter tuning
floatvel_Tau{0.25f};// velocity state correction time constant (1/sec)
floatpos_Tau{0.25f};// postion state correction time constant (1/sec)
floatvel_Tau{0.25f};///< velocity state correction time constant (1/sec)
floatpos_Tau{0.25f};///< postion state correction time constant (1/sec)
// accel bias learning control
floatacc_bias_lim{0.4f};// maximum accel bias magnitude (m/s/s)
floatacc_bias_learn_acc_lim{25.0f};// learning is disabled if the magnitude of the IMU acceleration vector is greater than this (m/sec**2)
floatacc_bias_learn_gyr_lim{3.0f};// learning is disabled if the magnitude of the IMU angular rate vector is greater than this (rad/sec)
floatacc_bias_learn_tc{0.5f};// time constant used to control the decaying envelope filters applied to the accel and gyro magnitudes (sec)
floatacc_bias_lim{0.4f};///< maximum accel bias magnitude (m/sec**2)
floatacc_bias_learn_acc_lim{25.0f};///< learning is disabled if the magnitude of the IMU acceleration vector is greater than this (m/sec**2)
floatacc_bias_learn_gyr_lim{3.0f};///< learning is disabled if the magnitude of the IMU angular rate vector is greater than this (rad/sec)
floatacc_bias_learn_tc{0.5f};///< time constant used to control the decaying envelope filters applied to the accel and gyro magnitudes (sec)
unsignedno_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)
unsignedno_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)
unsignedno_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)
unsignedno_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
floatdrag_noise{2.5f};// observation noise for drag specific force measurements (m/sec**2)
floatbcoef_x{25.0f};// ballistic coefficient along the X-axis (kg/m**2)
floatbcoef_y{25.0f};// ballistic coefficient along the Y-axis (kg/m**2)
floatdrag_noise{2.5f};///< observation noise for drag specific force measurements (m/sec**2)
floatbcoef_x{25.0f};///< ballistic coefficient along the X-axis (kg/m**2)
floatbcoef_y{25.0f};///< ballistic coefficient along the Y-axis (kg/m**2)
// control of accel error detection and mitigation (IMU clipping)
floatvert_innov_test_lim{4.5f};// Number of standard deviations allowed before the combined vertical velocity and position test is declared as failed
intbad_acc_reset_delay_us{500000};// Continuous time that the vertical position and velocity innovation test must fail before the states are reset (usec)
floatvert_innov_test_lim{4.5f};///< Number of standard deviations allowed before the combined vertical velocity and position test is declared as failed
intbad_acc_reset_delay_us{500000};///< Continuous time that the vertical position and velocity innovation test must fail before the states are reset (uSec)
};
structstateSample{
Quatfquat_nominal;// quaternion defining the rotaton from earth to body frame
Vector3fvel;// NED velocity in earth frame in m/s
Vector3fpos;// NED position in earth frame in m
Vector3fgyro_bias;// delta angle bias estimate in rad
Vector3faccel_bias;// delta velocity bias estimate in m/s
Vector3fmag_I;// NED earth magnetic field in gauss
Vector3fmag_B;// magnetometer bias estimate in body frame in gauss
Vector2fwind_vel;// wind velocity in m/s
Quatfquat_nominal;///< quaternion defining the rotaton from earth to body frame
Vector3fvel;///< NED velocity in earth frame in m/s
Vector3fpos;///< NED position in earth frame in m
Vector3fgyro_bias;///< delta angle bias estimate in rad
Vector3faccel_bias;///< delta velocity bias estimate in m/s
Vector3fmag_I;///< NED earth magnetic field in gauss
Vector3fmag_B;///< magnetometer bias estimate in body frame in gauss
Vector2fwind_vel;///< wind velocity in m/s
};
unionfault_status_u{
struct{
boolbad_mag_x:1;// 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error
boolbad_mag_y:1;// 1 - true if the fusion of the magnetometer Y-axis has encountered a numerical error
boolbad_mag_z:1;// 2 - true if the fusion of the magnetometer Z-axis has encountered a numerical error
boolbad_mag_hdg:1;// 3 - true if the fusion of the magnetic heading has encountered a numerical error
boolbad_mag_decl:1;// 4 - true if the fusion of the magnetic declination has encountered a numerical error
boolbad_airspeed:1;// 5 - true if fusion of the airspeed has encountered a numerical error
boolbad_sideslip:1;// 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
boolbad_optflow_X:1;// 7 - true if fusion of the optical flow X axis has encountered a numerical error
boolbad_optflow_Y:1;// 8 - true if fusion of the optical flow Y axis has encountered a numerical error
boolbad_vel_N:1;// 9 - true if fusion of the North velocity has encountered a numerical error
boolbad_vel_E:1;// 10 - true if fusion of the East velocity has encountered a numerical error
boolbad_vel_D:1;// 11 - true if fusion of the Down velocity has encountered a numerical error
boolbad_pos_N:1;// 12 - true if fusion of the North position has encountered a numerical error
boolbad_pos_E:1;// 13 - true if fusion of the East position has encountered a numerical error
boolbad_pos_D:1;// 14 - true if fusion of the Down position has encountered a numerical error
boolbad_acc_bias:1;// 15 - true if bad delta velocity bias estimates have been detected
boolbad_mag_x:1;///< 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error
boolbad_mag_y:1;///< 1 - true if the fusion of the magnetometer Y-axis has encountered a numerical error
boolbad_mag_z:1;///< 2 - true if the fusion of the magnetometer Z-axis has encountered a numerical error
boolbad_mag_hdg:1;///< 3 - true if the fusion of the magnetic heading has encountered a numerical error
boolbad_mag_decl:1;///< 4 - true if the fusion of the magnetic declination has encountered a numerical error
boolbad_airspeed:1;///< 5 - true if fusion of the airspeed has encountered a numerical error
boolbad_sideslip:1;///< 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
boolbad_optflow_X:1;///< 7 - true if fusion of the optical flow X axis has encountered a numerical error
boolbad_optflow_Y:1;///< 8 - true if fusion of the optical flow Y axis has encountered a numerical error
boolbad_vel_N:1;///< 9 - true if fusion of the North velocity has encountered a numerical error
boolbad_vel_E:1;///< 10 - true if fusion of the East velocity has encountered a numerical error
boolbad_vel_D:1;///< 11 - true if fusion of the Down velocity has encountered a numerical error
boolbad_pos_N:1;///< 12 - true if fusion of the North position has encountered a numerical error
boolbad_pos_E:1;///< 13 - true if fusion of the East position has encountered a numerical error
boolbad_pos_D:1;///< 14 - true if fusion of the Down position has encountered a numerical error
boolbad_acc_bias:1;///< 15 - true if bad delta velocity bias estimates have been detected
}flags;
uint16_tvalue;
@ -358,18 +358,18 @@ union fault_status_u {
@@ -358,18 +358,18 @@ union fault_status_u {
// define structure used to communicate innovation test failures
unioninnovation_fault_status_u{
struct{
boolreject_vel_NED:1;// 0 - true if velocity observations have been rejected
boolreject_pos_NE:1;// 1 - true if horizontal position observations have been rejected
boolreject_pos_D:1;// 2 - true if true if vertical position observations have been rejected
boolreject_mag_x:1;// 3 - true if the X magnetometer observation has been rejected
boolreject_mag_y:1;// 4 - true if the Y magnetometer observation has been rejected
boolreject_mag_z:1;// 5 - true if the Z magnetometer observation has been rejected
boolreject_yaw:1;// 6 - true if the yaw observation has been rejected
boolreject_airspeed:1;// 7 - true if the airspeed observation has been rejected
boolreject_sideslip:1;// 8 - true if the synthetic sideslip observation has been rejected
boolreject_hagl:1;// 9 - true if the height above ground observation has been rejected
boolreject_optflow_X:1;// 10 - true if the X optical flow observation has been rejected
boolreject_optflow_Y:1;// 11 - true if the Y optical flow observation has been rejected
boolreject_vel_NED:1;///< 0 - true if velocity observations have been rejected
boolreject_pos_NE:1;///< 1 - true if horizontal position observations have been rejected
boolreject_pos_D:1;///< 2 - true if true if vertical position observations have been rejected
boolreject_mag_x:1;///< 3 - true if the X magnetometer observation has been rejected
boolreject_mag_y:1;///< 4 - true if the Y magnetometer observation has been rejected
boolreject_mag_z:1;///< 5 - true if the Z magnetometer observation has been rejected
boolreject_yaw:1;///< 6 - true if the yaw observation has been rejected
boolreject_airspeed:1;///< 7 - true if the airspeed observation has been rejected
boolreject_sideslip:1;///< 8 - true if the synthetic sideslip observation has been rejected
boolreject_hagl:1;///< 9 - true if the height above ground observation has been rejected
boolreject_optflow_X:1;///< 10 - true if the X optical flow observation has been rejected
boolreject_optflow_Y:1;///< 11 - true if the Y optical flow observation has been rejected
}flags;
uint16_tvalue;
@ -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
uniongps_check_fail_status_u{
struct{
uint16_tfix:1;// 0 - true if the fix type is insufficient (no 3D solution)
uint16_tnsats:1;// 1 - true if number of satellites used is insufficient
uint16_tgdop:1;// 2 - true if geometric dilution of precision is insufficient
uint16_thacc:1;// 3 - true if reported horizontal accuracy is insufficient
uint16_tvacc:1;// 4 - true if reported vertical accuracy is insufficient
uint16_tsacc:1;// 5 - true if reported speed accuracy is insufficient
uint16_thdrift:1;// 6 - true if horizontal drift is excessive (can only be used when stationary on ground)
uint16_tvdrift:1;// 7 - true if vertical drift is excessive (can only be used when stationary on ground)
uint16_thspeed:1;// 8 - true if horizontal speed is excessive (can only be used when stationary on ground)
uint16_tvspeed:1;// 9 - true if vertical speed error is excessive
uint16_tfix:1;///< 0 - true if the fix type is insufficient (no 3D solution)
uint16_tnsats:1;///< 1 - true if number of satellites used is insufficient
uint16_tgdop:1;///< 2 - true if geometric dilution of precision is insufficient
uint16_thacc:1;///< 3 - true if reported horizontal accuracy is insufficient
uint16_tvacc:1;///< 4 - true if reported vertical accuracy is insufficient
uint16_tsacc:1;///< 5 - true if reported speed accuracy is insufficient
uint16_thdrift:1;///< 6 - true if horizontal drift is excessive (can only be used when stationary on ground)
uint16_tvdrift:1;///< 7 - true if vertical drift is excessive (can only be used when stationary on ground)
uint16_thspeed:1;///< 8 - true if horizontal speed is excessive (can only be used when stationary on ground)
uint16_tvspeed:1;///< 9 - true if vertical speed error is excessive
}flags;
uint16_tvalue;
};
@ -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
unionfilter_control_status_u{
struct{
uint32_ttilt_align:1;// 0 - true if the filter tilt alignment is complete
uint32_tyaw_align:1;// 1 - true if the filter yaw alignment is complete
uint32_tgps:1;// 2 - true if GPS measurements are being fused
uint32_topt_flow:1;// 3 - true if optical flow measurements are being fused
uint32_tmag_hdg:1;// 4 - true if a simple magnetic yaw heading is being fused
uint32_tmag_3D:1;// 5 - true if 3-axis magnetometer measurement are being fused
uint32_tmag_dec:1;// 6 - true if synthetic magnetic declination measurements are being fused
uint32_tin_air:1;// 7 - true when the vehicle is airborne
uint32_twind:1;// 8 - true when wind velocity is being estimated
uint32_tbaro_hgt:1;// 9 - true when baro height is being fused as a primary height reference
uint32_trng_hgt:1;// 10 - true when range finder height is being fused as a primary height reference
uint32_tgps_hgt:1;// 11 - true when GPS height is being fused as a primary height reference
uint32_tev_pos:1;// 12 - true when local position data from external vision is being fused
uint32_tev_yaw:1;// 13 - true when yaw data from external vision measurements is being fused
uint32_tev_hgt:1;// 14 - true when height data from external vision measurements is being fused
uint32_tfuse_beta:1;// 15 - true when synthetic sideslip measurements are being fused
uint32_tupdate_mag_states_only:1;// 16 - true when only the magnetometer states are updated by the magnetometer
uint32_tfixed_wing:1;// 17 - true when the vehicle is operating as a fixed wing vehicle
uint32_ttilt_align:1;///< 0 - true if the filter tilt alignment is complete
uint32_tyaw_align:1;///< 1 - true if the filter yaw alignment is complete
uint32_tgps:1;///< 2 - true if GPS measurements are being fused
uint32_topt_flow:1;///< 3 - true if optical flow measurements are being fused
uint32_tmag_hdg:1;///< 4 - true if a simple magnetic yaw heading is being fused
uint32_tmag_3D:1;///< 5 - true if 3-axis magnetometer measurement are being fused
uint32_tmag_dec:1;///< 6 - true if synthetic magnetic declination measurements are being fused
uint32_tin_air:1;///< 7 - true when the vehicle is airborne
uint32_twind:1;///< 8 - true when wind velocity is being estimated
uint32_tbaro_hgt:1;///< 9 - true when baro height is being fused as a primary height reference
uint32_trng_hgt:1;///< 10 - true when range finder height is being fused as a primary height reference
uint32_tgps_hgt:1;///< 11 - true when GPS height is being fused as a primary height reference
uint32_tev_pos:1;///< 12 - true when local position data from external vision is being fused
uint32_tev_yaw:1;///< 13 - true when yaw data from external vision measurements is being fused
uint32_tev_hgt:1;///< 14 - true when height data from external vision measurements is being fused
uint32_tfuse_beta:1;///< 15 - true when synthetic sideslip measurements are being fused
uint32_tupdate_mag_states_only:1;///< 16 - true when only the magnetometer states are updated by the magnetometer
uint32_tfixed_wing:1;///< 17 - true when the vehicle is operating as a fixed wing vehicle
}flags;
uint32_tvalue;
};
unionekf_solution_status{
struct{
uint16_tattitude:1;// 0 - True if the attitude estimate is good
uint16_tvelocity_horiz:1;// 1 - True if the horizontal velocity estimate is good
uint16_tvelocity_vert:1;// 2 - True if the vertical velocity estimate is good
uint16_tpos_horiz_rel:1;// 3 - True if the horizontal position (relative) estimate is good
uint16_tpos_horiz_abs:1;// 4 - True if the horizontal position (absolute) estimate is good
uint16_tpos_vert_abs:1;// 5 - True if the vertical position (absolute) estimate is good
uint16_tpos_vert_agl:1;// 6 - True if the vertical position (above ground) estimate is good
uint16_tconst_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_tpred_pos_horiz_rel:1;// 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
uint16_tpred_pos_horiz_abs:1;// 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
uint16_tgps_glitch:1;// 10 - True if the EKF has detected a GPS glitch
uint16_taccel_error:1;// 11 - True if the EKF has detected bad accelerometer data
uint16_tattitude:1;///< 0 - True if the attitude estimate is good
uint16_tvelocity_horiz:1;///< 1 - True if the horizontal velocity estimate is good
uint16_tvelocity_vert:1;///< 2 - True if the vertical velocity estimate is good
uint16_tpos_horiz_rel:1;///< 3 - True if the horizontal position (relative) estimate is good
uint16_tpos_horiz_abs:1;///< 4 - True if the horizontal position (absolute) estimate is good
uint16_tpos_vert_abs:1;///< 5 - True if the vertical position (absolute) estimate is good
uint16_tpos_vert_agl:1;///< 6 - True if the vertical position (above ground) estimate is good
uint16_tconst_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_tpred_pos_horiz_rel:1;///< 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
uint16_tpred_pos_horiz_abs:1;///< 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
uint16_tgps_glitch:1;///< 10 - True if the EKF has detected a GPS glitch
uint16_taccel_error:1;///< 11 - True if the EKF has detected bad accelerometer data
staticconstexprfloat_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_tvelNE_counter;// number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_tvelD_counter;// number of vertical velocity reset events (allow to wrap if count exceeds 255)
uint8_tposNE_counter;// number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_tposD_counter;// number of vertical position reset events (allow to wrap if count exceeds 255)
uint8_tquat_counter;// number of quaternion reset events (allow to wrap if count exceeds 255)
Vector2fvelNE_change;// North East velocity change due to last reset (m)
floatvelD_change;// Down velocity change due to last reset (m/s)
Vector2fposNE_change;// North, East position change due to last reset (m)
floatposD_change;// Down position change due to last reset (m)
Quatfquat_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_tvelNE_counter;///< number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_tvelD_counter;///< number of vertical velocity reset events (allow to wrap if count exceeds 255)
uint8_tposNE_counter;///< number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_tposD_counter;///< number of vertical position reset events (allow to wrap if count exceeds 255)
uint8_tquat_counter;///< number of quaternion reset events (allow to wrap if count exceeds 255)
Vector2fvelNE_change;///< North East velocity change due to last reset (m)
floatvelD_change;///< Down velocity change due to last reset (m/sec)
Vector2fposNE_change;///< North, East position change due to last reset (m)
floatposD_change;///< Down position change due to last reset (m)
Quatfquat_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