2014-01-30 17:47:33 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
2014-03-08 16:51:45 -04:00
22 state EKF based on https : //github.com/priseborough/InertialNav
2014-01-30 17:47:33 -04:00
Converted from Matlab to C + + by Paul Riseborough
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
# ifndef AP_NavEKF
# define AP_NavEKF
# include <AP_Math.h>
# include <AP_InertialSensor.h>
# include <AP_Baro.h>
# include <AP_Airspeed.h>
# include <AP_Compass.h>
2014-01-30 18:16:58 -04:00
# include <AP_Param.h>
2013-12-30 06:27:50 -04:00
// #define MATH_CHECK_INDEXES 1
2013-12-29 22:25:02 -04:00
# include <vectorN.h>
2014-01-30 17:47:33 -04:00
2014-03-31 14:54:01 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
2013-12-30 06:41:28 -04:00
# include <systemlib/perf_counter.h>
# endif
2013-12-30 06:27:50 -04:00
2014-01-01 21:15:22 -04:00
class AP_AHRS ;
2014-01-30 17:47:33 -04:00
class NavEKF
{
public :
2014-01-03 00:37:19 -04:00
typedef float ftype ;
2013-12-30 06:27:50 -04:00
# if MATH_CHECK_INDEXES
2014-01-03 00:37:19 -04:00
typedef VectorN < ftype , 2 > Vector2 ;
typedef VectorN < ftype , 3 > Vector3 ;
typedef VectorN < ftype , 6 > Vector6 ;
typedef VectorN < ftype , 8 > Vector8 ;
typedef VectorN < ftype , 11 > Vector11 ;
typedef VectorN < ftype , 13 > Vector13 ;
2014-01-03 03:52:37 -04:00
typedef VectorN < ftype , 14 > Vector14 ;
2014-01-30 18:25:40 -04:00
typedef VectorN < ftype , 15 > Vector15 ;
typedef VectorN < ftype , 22 > Vector22 ;
2014-01-03 00:37:19 -04:00
typedef VectorN < VectorN < ftype , 3 > , 3 > Matrix3 ;
2014-01-30 18:25:40 -04:00
typedef VectorN < VectorN < ftype , 22 > , 22 > Matrix22 ;
typedef VectorN < VectorN < ftype , 50 > , 22 > Matrix22_50 ;
2013-12-30 06:27:50 -04:00
# else
2014-01-03 00:37:19 -04:00
typedef ftype Vector2 [ 2 ] ;
typedef ftype Vector3 [ 3 ] ;
typedef ftype Vector6 [ 6 ] ;
typedef ftype Vector8 [ 8 ] ;
typedef ftype Vector11 [ 11 ] ;
typedef ftype Vector13 [ 13 ] ;
2014-01-03 03:52:37 -04:00
typedef ftype Vector14 [ 14 ] ;
2014-01-30 18:25:40 -04:00
typedef ftype Vector15 [ 15 ] ;
typedef ftype Vector22 [ 22 ] ;
2014-02-26 04:01:51 -04:00
typedef ftype Vector31 [ 31 ] ;
2014-01-03 00:37:19 -04:00
typedef ftype Matrix3 [ 3 ] [ 3 ] ;
2014-01-30 18:25:40 -04:00
typedef ftype Matrix22 [ 22 ] [ 22 ] ;
2014-02-26 04:01:51 -04:00
typedef ftype Matrix31_50 [ 31 ] [ 50 ] ;
2013-12-30 06:27:50 -04:00
# endif
2013-12-29 22:25:02 -04:00
2014-01-03 03:52:37 -04:00
// Constructor
2014-01-01 21:15:22 -04:00
NavEKF ( const AP_AHRS * ahrs , AP_Baro & baro ) ;
2014-01-03 03:52:37 -04:00
2014-03-11 06:18:01 -03:00
// This function is used to initialise the filter whilst moving, using the AHRS DCM solution
// It should NOT be used to re-initialise after a timeout as DCM will also be corrupted
2014-01-20 15:52:27 -04:00
void InitialiseFilterDynamic ( void ) ;
2013-12-29 03:37:55 -04:00
2014-01-20 15:52:27 -04:00
// Initialise the states from accelerometer and magnetometer data (if present)
// This method can only be used when the vehicle is static
2014-01-30 18:25:40 -04:00
void InitialiseFilterBootstrap ( void ) ;
2014-01-30 17:47:33 -04:00
// Update Filter States - this should be called whenever new IMU data is available
2013-12-29 03:37:55 -04:00
void UpdateFilter ( void ) ;
2014-03-11 06:18:01 -03:00
// Check basic filter health metrics and return a consolidated health status
2014-01-03 20:16:19 -04:00
bool healthy ( void ) const ;
2014-01-02 01:16:16 -04:00
2014-01-30 18:25:40 -04:00
// return true if filter is dead-reckoning height
bool HeightDrifting ( void ) const ;
// return true if filter is dead-reckoning position
bool PositionDrifting ( void ) const ;
2014-03-11 06:18:01 -03:00
// return the last calculated NED position relative to the reference point (m).
// return false if no position is available
2014-01-01 21:15:22 -04:00
bool getPosNED ( Vector3f & pos ) const ;
2013-12-29 03:37:55 -04:00
2013-12-31 23:03:52 -04:00
// return NED velocity in m/s
2014-01-01 21:15:22 -04:00
void getVelNED ( Vector3f & vel ) const ;
2014-01-30 17:47:33 -04:00
2014-03-11 06:18:01 -03:00
// return body axis gyro bias estimates in rad/sec
2014-01-01 21:15:22 -04:00
void getGyroBias ( Vector3f & gyroBias ) const ;
2013-12-31 17:54:56 -04:00
2014-10-28 22:21:42 -03:00
// reset body axis gyro bias estimates
void resetGyroBias ( void ) ;
2014-10-30 03:42:47 -03:00
// return weighting of first IMU in blending function
void getIMU1Weighting ( float & ret ) const ;
// return the individual Z-accel bias estimates in m/s^2
void getAccelZBias ( float & zbias1 , float & zbias2 ) const ;
2013-12-31 17:54:56 -04:00
2014-03-11 06:18:01 -03:00
// return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
2014-01-01 21:15:22 -04:00
void getWind ( Vector3f & wind ) const ;
2014-01-30 18:11:54 -04:00
2014-03-11 06:18:01 -03:00
// return earth magnetic field estimates in measurement units / 1000
2014-01-01 21:15:22 -04:00
void getMagNED ( Vector3f & magNED ) const ;
2013-12-31 17:54:56 -04:00
2014-03-11 06:18:01 -03:00
// return body magnetic field estimates in measurement units / 1000
2014-01-01 21:15:22 -04:00
void getMagXYZ ( Vector3f & magXYZ ) const ;
2013-12-31 17:54:56 -04:00
2013-12-29 03:37:55 -04:00
// return the last calculated latitude, longitude and height
2014-01-01 21:15:22 -04:00
bool getLLH ( struct Location & loc ) const ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
// return the Euler roll, pitch and yaw angle in radians
2014-01-01 21:15:22 -04:00
void getEulerAngles ( Vector3f & eulers ) const ;
2014-01-30 17:47:33 -04:00
2014-03-11 06:18:01 -03:00
// return the transformation matrix from XYZ (body) to NED axes
2014-01-01 21:15:22 -04:00
void getRotationBodyToNED ( Matrix3f & mat ) const ;
2014-01-30 17:47:33 -04:00
2014-03-11 06:18:01 -03:00
// return the quaternions defining the rotation from NED to XYZ (body) axes
2014-01-01 21:15:22 -04:00
void getQuaternion ( Quaternion & quat ) const ;
2014-01-30 17:47:33 -04:00
2014-01-30 18:25:40 -04:00
// return the innovations for the NED Pos, NED Vel, XYZ Mag and Vtas measurements
void getInnovations ( Vector3f & velInnov , Vector3f & posInnov , Vector3f & magInnov , float & tasInnov ) const ;
2014-03-31 18:15:28 -03:00
// return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements
2014-04-02 17:46:56 -03:00
void getVariances ( float & velVar , float & posVar , float & hgtVar , Vector3f & magVar , float & tasVar , Vector2f & offset ) const ;
2014-01-30 18:25:40 -04:00
2014-08-24 08:00:24 -03:00
// should we use the compass? This is public so it can be used for
// reporting via ahrs.use_compass()
bool use_compass ( void ) const ;
2014-05-12 04:35:22 -03:00
/*
return the filter fault status as a bitmasked integer
2014-10-14 04:24:32 -03:00
0 = unassigned
1 = unassigned
2014-05-12 04:35:22 -03:00
2 = badly conditioned X magnetometer fusion
3 = badly conditioned Y magnetometer fusion
4 = badly conditioned Z magnetometer fusion
5 = badly conditioned airspeed fusion
6 = badly conditioned synthetic sideslip fusion
7 = unassigned
return normalised delta gyro bias length used for divergence test
*/
2014-10-14 04:24:32 -03:00
void getFilterFaults ( uint8_t & faults ) const ;
2014-05-12 04:35:22 -03:00
2014-01-20 01:47:56 -04:00
static const struct AP_Param : : GroupInfo var_info [ ] ;
2013-12-29 03:37:55 -04:00
private :
2014-01-01 21:15:22 -04:00
const AP_AHRS * _ahrs ;
2013-12-29 03:37:55 -04:00
AP_Baro & _baro ;
2014-01-30 17:47:33 -04:00
2014-04-04 07:30:16 -03:00
// the states are available in two forms, either as a Vector27, or
// broken down as individual elements. Both are equivalent (same
// memory)
Vector31 states ;
struct state_elements {
Quaternion quat ; // 0..3
Vector3f velocity ; // 4..6
Vector3f position ; // 7..9
Vector3f gyro_bias ; // 10..12
float accel_zbias1 ; // 13
Vector2f wind_vel ; // 14..15
Vector3f earth_magfield ; // 16..18
Vector3f body_magfield ; // 19..21
float accel_zbias2 ; // 22
Vector3f vel1 ; // 23 .. 25
float posD1 ; // 26
Vector3f vel2 ; // 27 .. 29
float posD2 ; // 30
} & state ;
2014-01-29 02:58:54 -04:00
// update the quaternion, velocity and position states using IMU measurements
2013-12-29 03:37:55 -04:00
void UpdateStrapdownEquationsNED ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// calculate the predicted state covariance matrix
2013-12-29 03:37:55 -04:00
void CovariancePrediction ( ) ;
2014-01-03 03:52:37 -04:00
2014-01-29 02:58:54 -04:00
// force symmetry on the state covariance matrix
2014-01-03 15:59:47 -04:00
void ForceSymmetry ( ) ;
2014-02-18 04:27:23 -04:00
// copy covariances across from covariance prediction calculation and fix numerical errors
void CopyAndFixCovariances ( ) ;
2014-03-11 06:18:01 -03:00
// constrain variances (diagonal terms) in the state covariance matrix
2014-01-03 15:59:47 -04:00
void ConstrainVariances ( ) ;
2014-01-02 22:10:38 -04:00
2014-01-29 02:58:54 -04:00
// constrain states
2014-01-30 18:25:40 -04:00
void ConstrainStates ( ) ;
2014-01-29 02:58:54 -04:00
// fuse selected position, velocity and height measurements
2013-12-29 03:37:55 -04:00
void FuseVelPosNED ( ) ;
2014-01-03 03:52:37 -04:00
2014-01-29 02:58:54 -04:00
// fuse magnetometer measurements
2013-12-29 03:37:55 -04:00
void FuseMagnetometer ( ) ;
2014-01-03 03:52:37 -04:00
2014-01-29 02:58:54 -04:00
// fuse true airspeed measurements
2013-12-29 03:37:55 -04:00
void FuseAirspeed ( ) ;
2014-01-30 17:47:33 -04:00
2014-03-11 06:18:01 -03:00
// fuse sythetic sideslip measurement of zero
2014-03-06 05:43:24 -04:00
void FuseSideslip ( ) ;
2014-01-29 02:58:54 -04:00
// zero specified range of rows in the state covariance matrix
2014-01-30 18:25:40 -04:00
void zeroRows ( Matrix22 & covMat , uint8_t first , uint8_t last ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// zero specified range of columns in the state covariance matrix
2014-01-30 18:25:40 -04:00
void zeroCols ( Matrix22 & covMat , uint8_t first , uint8_t last ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
// store states along with system time stamp in msces
void StoreStates ( void ) ;
2014-01-30 17:47:33 -04:00
2014-02-16 07:32:17 -04:00
// Reset the stored state history and store the current state
void StoreStatesReset ( void ) ;
2013-12-29 03:37:55 -04:00
// recall state vector stored at closest time to the one specified by msec
2014-04-04 07:30:16 -03:00
void RecallStates ( state_elements & statesForFusion , uint32_t msec ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// calculate nav to body quaternions from body to nav rotation matrix
2014-01-01 21:15:22 -04:00
void quat2Tbn ( Matrix3f & Tbn , const Quaternion & quat ) const ;
2014-01-30 17:47:33 -04:00
2014-03-11 06:18:01 -03:00
// calculate the NED earth spin vector in rad/sec
2014-01-02 07:05:09 -04:00
void calcEarthRateNED ( Vector3f & omega , int32_t latitude ) const ;
2014-01-30 17:47:33 -04:00
2014-03-11 06:18:01 -03:00
// calculate whether the flight vehicle is on the ground or flying from height, airspeed and GPS speed
2014-04-25 07:32:13 -03:00
void SetFlightAndFusionModes ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// initialise the covariance matrix
2014-03-24 04:34:05 -03:00
void CovarianceInit ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// update IMU delta angle and delta velocity measurements
2013-12-29 03:37:55 -04:00
void readIMUData ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// check for new valid GPS data and update stored measurement if available
2013-12-29 03:37:55 -04:00
void readGpsData ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// check for new altitude measurement data and update stored measurement if available
2013-12-29 03:37:55 -04:00
void readHgtData ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// check for new magnetometer data and update store measurements if available
2013-12-29 03:37:55 -04:00
void readMagData ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// check for new airspeed data and update stored measurements if available
2013-12-29 03:37:55 -04:00
void readAirSpdData ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-29 02:58:54 -04:00
// determine when to perform fusion of GPS position and velocity measurements
2013-12-29 03:37:55 -04:00
void SelectVelPosFusion ( ) ;
2014-01-03 03:52:37 -04:00
2014-01-29 02:58:54 -04:00
// determine when to perform fusion of true airspeed measurements
2013-12-29 03:37:55 -04:00
void SelectTasFusion ( ) ;
2014-03-10 00:18:40 -03:00
// determine when to perform fusion of synthetic sideslp measurements
void SelectBetaFusion ( ) ;
2014-01-29 02:58:54 -04:00
// determine when to perform fusion of magnetometer measurements
2013-12-29 03:37:55 -04:00
void SelectMagFusion ( ) ;
2014-01-29 02:58:54 -04:00
// force alignment of the yaw angle using GPS velocity data
2014-03-24 04:34:05 -03:00
void alignYawGPS ( ) ;
2014-04-10 05:05:49 -03:00
// Forced alignment of the wind velocity states so that they are set to the reciprocal of
// the ground speed and scaled to 6 m/s. This is used when launching a fly-forward vehicle without an airspeed sensor
// on the assumption that launch will be into wind and 6 is representative global average at height
// http://maps.google.com/gallery/details?id=zJuaSgXp_WLc.kTBytKPmNODY&hl=en
void setWindVelStates ( ) ;
2014-03-24 04:34:05 -03:00
// initialise the earth magnetic field states using declination and current attitude and magnetometer meaasurements
// and return attitude quaternion
Quaternion calcQuatAndFieldStates ( float roll , float pitch ) ;
2014-01-30 18:25:40 -04:00
2014-01-29 02:58:54 -04:00
// zero stored variables
2014-01-30 18:25:40 -04:00
void ZeroVariables ( ) ;
2013-12-29 03:37:55 -04:00
2014-01-29 02:58:54 -04:00
// reset the horizontal position states uing the last GPS measurement
2014-01-20 15:41:41 -04:00
void ResetPosition ( void ) ;
2014-01-29 02:58:54 -04:00
// reset velocity states using the last GPS measurement
2014-01-20 15:41:41 -04:00
void ResetVelocity ( void ) ;
2014-01-29 02:58:54 -04:00
// reset the vertical position state using the last height measurement
2014-01-20 15:41:41 -04:00
void ResetHeight ( void ) ;
2014-02-18 18:19:46 -04:00
// return true if we should use the airspeed sensor
bool useAirspeed ( void ) const ;
2014-01-20 15:41:41 -04:00
2014-03-11 06:18:01 -03:00
// return true if the vehicle code has requested use of static mode
// in static mode, position and height are constrained to zero, allowing an attitude
// reference to be initialised and maintained when on the ground and without GPS lock
2014-02-18 19:52:57 -04:00
bool static_mode_demanded ( void ) const ;
2014-03-31 18:15:28 -03:00
// decay GPS horizontal position offset to close to zero at a rate of 1 m/s
// this allows large GPS position jumps to be accomodated gradually
void decayGpsOffset ( void ) ;
2014-01-20 06:27:50 -04:00
// EKF Mavlink Tuneable Parameters
AP_Float _gpsHorizVelNoise ; // GPS horizontal velocity measurement noise : m/s
AP_Float _gpsVertVelNoise ; // GPS vertical velocity measurement noise : m/s
AP_Float _gpsHorizPosNoise ; // GPS horizontal position measurement noise m
AP_Float _baroAltNoise ; // Baro height measurement noise : m^2
AP_Float _magNoise ; // magnetometer measurement noise : gauss
AP_Float _easNoise ; // equivalent airspeed measurement noise : m/s
AP_Float _windVelProcessNoise ; // wind velocity state process noise : m/s^2
AP_Float _wndVarHgtRateScale ; // scale factor applied to wind process noise due to height rate
AP_Float _magEarthProcessNoise ; // earth magnetic field process noise : gauss/sec
AP_Float _magBodyProcessNoise ; // earth magnetic field process noise : gauss/sec
AP_Float _gyrNoise ; // gyro process noise : rad/s
AP_Float _accNoise ; // accelerometer process noise : m/s^2
AP_Float _gyroBiasProcessNoise ; // gyro bias state process noise : rad/s
AP_Float _accelBiasProcessNoise ; // accel bias state process noise : m/s^2
AP_Int16 _msecVelDelay ; // effective average delay of GPS velocity measurements rel to IMU (msec)
AP_Int16 _msecPosDelay ; // effective average delay of GPS position measurements rel to (msec)
AP_Int8 _fusionModeGPS ; // 0 = use 3D velocity, 1 = use 2D velocity, 2 = use no velocity
AP_Int8 _gpsVelInnovGate ; // Number of standard deviations applied to GPS velocity innovation consistency check
AP_Int8 _gpsPosInnovGate ; // Number of standard deviations applied to GPS position innovation consistency check
AP_Int8 _hgtInnovGate ; // Number of standard deviations applied to height innovation consistency check
AP_Int8 _magInnovGate ; // Number of standard deviations applied to magnetometer innovation consistency check
AP_Int8 _tasInnovGate ; // Number of standard deviations applied to true airspeed innovation consistency check
2014-04-25 07:32:13 -03:00
AP_Int8 _magCal ; // Sets activation condition for in-flight magnetometer calibration
2014-03-31 18:15:28 -03:00
AP_Int16 _gpsGlitchAccelMax ; // Maximum allowed discrepancy between inertial and GPS Horizontal acceleration before GPS data is ignored : cm/s^2
AP_Int8 _gpsGlitchRadiusMax ; // Maximum allowed discrepancy between inertial and GPS Horizontal position before GPS glitch is declared : m
2014-01-29 04:03:07 -04:00
// Tuning parameters
AP_Float _gpsNEVelVarAccScale ; // scale factor applied to NE velocity measurement variance due to Vdot
AP_Float _gpsDVelVarAccScale ; // scale factor applied to D velocity measurement variance due to Vdot
AP_Float _gpsPosVarAccScale ; // scale factor applied to position measurement variance due to Vdot
AP_Int16 _msecHgtDelay ; // effective average delay of height measurements rel to (msec)
AP_Int16 _msecMagDelay ; // effective average delay of magnetometer measurements rel to IMU (msec)
AP_Int16 _msecTasDelay ; // effective average delay of airspeed measurements rel to IMU (msec)
2014-01-22 02:32:28 -04:00
AP_Int16 _gpsRetryTimeUseTAS ; // GPS retry time following innovation consistency fail if TAS measurements are used (msec)
AP_Int16 _gpsRetryTimeNoTAS ; // GPS retry time following innovation consistency fail if no TAS measurements are used (msec)
AP_Int16 _hgtRetryTimeMode0 ; // height measurement retry time following innovation consistency fail if GPS fusion mode is = 0 (msec)
AP_Int16 _hgtRetryTimeMode12 ; // height measurement retry time following innovation consistency fail if GPS fusion mode is > 0 (msec)
2014-04-21 04:11:06 -03:00
uint32_t _magFailTimeLimit_ms ; // number of msec before a magnetometer failing innovation consistency checks is declared failed (msec)
2014-01-20 06:27:50 -04:00
float _gyroBiasNoiseScaler ; // scale factor applied to gyro bias state process variance when on ground
float _magVarRateScale ; // scale factor applied to magnetometer variance due to angular rate
2014-01-30 18:25:40 -04:00
uint16_t _msecGpsAvg ; // average number of msec between GPS measurements
uint16_t _msecHgtAvg ; // average number of msec between height measurements
2014-08-23 23:02:29 -03:00
uint16_t _msecMagAvg ; // average number of msec between magnetometer measurements
2014-03-10 00:18:40 -03:00
uint16_t _msecBetaAvg ; // maximum number of msec between synthetic sideslip measurements
float dtVelPos ; // average of msec between position and velocity corrections
2014-01-30 18:16:58 -04:00
2014-01-29 04:03:07 -04:00
// Variables
2014-01-30 18:25:40 -04:00
bool statesInitialised ; // boolean true when filter states have been initialised
2014-04-21 03:15:17 -03:00
bool velHealth ; // boolean true if velocity measurements have passed innovation consistency check
bool posHealth ; // boolean true if position measurements have passed innovation consistency check
bool hgtHealth ; // boolean true if height measurements have passed innovation consistency check
bool magHealth ; // boolean true if magnetometer has passed innovation consistency check
2014-01-30 18:25:40 -04:00
bool velTimeout ; // boolean true if velocity measurements have failed innovation consistency check and timed out
2014-04-21 03:15:17 -03:00
bool posTimeout ; // boolean true if position measurements have failed innovation consistency check and timed out
2014-01-30 18:25:40 -04:00
bool hgtTimeout ; // boolean true if height measurements have failed innovation consistency check and timed out
2014-04-21 03:15:17 -03:00
bool magTimeout ; // boolean true if magnetometer measurements have failed for too long and have timed out
2014-07-31 06:16:38 -03:00
bool magFailed ; // boolean true if the magnetometer has failed
2014-02-19 22:21:09 -04:00
2014-09-23 06:30:01 -03:00
float gpsNoiseScaler ; // Used to scale the GPS measurement noise and consistency gates to compensate for operation with small satellite counts
2014-02-26 04:01:51 -04:00
Vector31 Kfusion ; // Kalman gain vector
2014-01-30 18:25:40 -04:00
Matrix22 KH ; // intermediate result used for covariance updates
Matrix22 KHP ; // intermediate result used for covariance updates
Matrix22 P ; // covariance matrix
2014-04-04 07:30:16 -03:00
VectorN < state_elements , 50 > storedStates ; // state vectors stored for the last 50 time steps
2014-01-30 18:25:40 -04:00
uint32_t statetimeStamp [ 50 ] ; // time stamp for each state vector stored
Vector3f correctedDelAng ; // delta angles about the xyz body axes corrected for errors (rad)
2014-02-26 04:01:51 -04:00
Vector3f correctedDelVel12 ; // delta velocities along the XYZ body axes for weighted average of IMU1 and IMU2 corrected for errors (m/s)
Vector3f correctedDelVel1 ; // delta velocities along the XYZ body axes for IMU1 corrected for errors (m/s)
Vector3f correctedDelVel2 ; // delta velocities along the XYZ body axes for IMU2 corrected for errors (m/s)
2014-01-30 18:25:40 -04:00
Vector3f summedDelAng ; // corrected & summed delta angles about the xyz body axes (rad)
Vector3f summedDelVel ; // corrected & summed delta velocities along the XYZ body axes (m/s)
Vector3f prevDelAng ; // previous delta angle use for INS coning error compensation
2014-05-12 04:35:22 -03:00
Vector3f lastGyroBias ; // previous gyro bias vector used by filter divergence check
2014-01-30 18:25:40 -04:00
Matrix3f prevTnb ; // previous nav to body transformation used for INS earth rotation compensation
ftype accNavMag ; // magnitude of navigation accel - used to adjust GPS obs variance (m/s^2)
2014-03-06 02:13:22 -04:00
ftype accNavMagHoriz ; // magnitude of navigation accel in horizontal plane (m/s^2)
2014-01-30 18:25:40 -04:00
Vector3f earthRateNED ; // earths angular rate vector in NED (rad/s)
2014-02-26 04:01:51 -04:00
Vector3f dVelIMU1 ; // delta velocity vector in XYZ body axes measured by IMU1 (m/s)
Vector3f dVelIMU2 ; // delta velocity vector in XYZ body axes measured by IMU2 (m/s)
2014-01-30 18:25:40 -04:00
Vector3f dAngIMU ; // delta angle vector in XYZ body axes measured by the IMU (rad)
ftype dtIMU ; // time lapsed since the last IMU measurement (sec)
ftype dt ; // time lapsed since the last covariance prediction (sec)
ftype hgtRate ; // state for rate of change of height filter
bool onGround ; // boolean true when the flight vehicle is on the ground (not flying)
2014-03-09 14:39:59 -03:00
bool prevOnGround ; // value of onGround from previous update
2014-01-30 18:25:40 -04:00
Vector6 innovVelPos ; // innovation output for a group of measurements
Vector6 varInnovVelPos ; // innovation variance output for a group of measurements
bool fuseVelData ; // this boolean causes the velNED measurements to be fused
bool fusePosData ; // this boolean causes the posNE measurements to be fused
bool fuseHgtData ; // this boolean causes the hgtMea measurements to be fused
Vector3f velNED ; // North, East, Down velocity measurements (m/s)
2014-04-23 04:37:07 -03:00
Vector2f gpsPosNE ; // North, East position measurements (m)
2014-01-30 18:25:40 -04:00
ftype hgtMea ; // height measurement relative to reference point (m)
2014-04-04 07:30:16 -03:00
state_elements statesAtVelTime ; // States at the effective time of velNED measurements
state_elements statesAtPosTime ; // States at the effective time of posNE measurements
state_elements statesAtHgtTime ; // States at the effective time of hgtMea measurement
2014-01-30 18:25:40 -04:00
Vector3f innovMag ; // innovation output from fusion of X,Y,Z compass measurements
Vector3f varInnovMag ; // innovation variance output from fusion of X,Y,Z compass measurements
bool fuseMagData ; // boolean true when magnetometer data is to be fused
Vector3f magData ; // magnetometer flux readings in X,Y,Z body axes
2014-04-04 07:30:16 -03:00
state_elements statesAtMagMeasTime ; // filter states at the effective time of compass measurements
2014-01-30 18:25:40 -04:00
ftype innovVtas ; // innovation output from fusion of airspeed measurements
ftype varInnovVtas ; // innovation variance output from fusion of airspeed measurements
bool fuseVtasData ; // boolean true when airspeed data is to be fused
float VtasMeas ; // true airspeed measurement (m/s)
2014-04-04 07:30:16 -03:00
state_elements statesAtVtasMeasTime ; // filter states at the effective measurement time
2014-01-30 18:25:40 -04:00
Vector3f magBias ; // magnetometer bias vector in XYZ body axes
const ftype covTimeStepMax ; // maximum time allowed between covariance predictions
const ftype covDelAngMax ; // maximum delta angle between covariance predictions
bool covPredStep ; // boolean set to true when a covariance prediction step has been performed
bool magFusePerformed ; // boolean set to true when magnetometer fusion has been perfomred in that time step
bool magFuseRequired ; // boolean set to true when magnetometer fusion will be perfomred in the next time step
bool posVelFuseStep ; // boolean set to true when position and velocity fusion is being performed
bool tasFuseStep ; // boolean set to true when airspeed fusion is being performed
uint32_t TASmsecPrev ; // time stamp of last TAS fusion step
2014-03-10 00:18:40 -03:00
uint32_t BETAmsecPrev ; // time stamp of last synthetic sideslip fusion step
2014-01-30 18:25:40 -04:00
const uint32_t TASmsecMax ; // maximum allowed interval between TAS fusion steps
const bool fuseMeNow ; // boolean to force fusion whenever data arrives
bool staticMode ; // boolean to force position and velocity measurements to zero for pre-arm or bench testing
2014-02-16 07:32:17 -04:00
bool prevStaticMode ; // value of static mode from last update
2014-01-30 18:25:40 -04:00
uint32_t lastMagUpdate ; // last time compass was updated
Vector3f velDotNED ; // rate of change of velocity in NED frame
Vector3f velDotNEDfilt ; // low pass filtered velDotNED
uint32_t lastAirspeedUpdate ; // last time airspeed was updated
2014-09-05 17:33:47 -03:00
uint32_t imuSampleTime_ms ; // time that the last IMU value was taken
2014-01-30 18:25:40 -04:00
ftype gpsCourse ; // GPS ground course angle(rad)
ftype gpsGndSpd ; // GPS ground speed (m/s)
bool newDataGps ; // true when new GPS data has arrived
bool newDataMag ; // true when new magnetometer data has arrived
bool newDataTas ; // true when new airspeed data has arrived
2014-01-22 05:42:39 -04:00
bool tasDataWaiting ; // true when new airspeed data is waiting to be fused
2014-01-30 18:25:40 -04:00
bool newDataHgt ; // true when new height data has arrived
2014-02-22 23:27:08 -04:00
uint32_t lastHgtMeasTime ; // time of last height measurement used to determine if new data has arrived
uint32_t lastHgtTime_ms ; // time of last height update (msec) used to calculate timeout
2014-01-18 17:48:12 -04:00
uint32_t velFailTime ; // time stamp when GPS velocity measurement last failed covaraiance consistency check (msec)
uint32_t posFailTime ; // time stamp when GPS position measurement last failed covaraiance consistency check (msec)
uint32_t hgtFailTime ; // time stamp when height measurement last failed covaraiance consistency check (msec)
uint8_t storeIndex ; // State vector storage index
2014-03-21 06:56:32 -03:00
uint32_t lastStateStoreTime_ms ; // time of last state vector storage
2014-01-18 17:48:12 -04:00
uint32_t lastFixTime_ms ; // time of last GPS fix used to determine if new data has arrived
2014-01-25 17:49:25 -04:00
uint32_t secondLastFixTime_ms ; // time of second last GPS fix used to determine how long since last update
2014-04-21 03:15:17 -03:00
uint32_t lastHealthyMagTime_ms ; // time the magnetometer was last declared healthy
2014-01-30 18:25:40 -04:00
Vector3f lastAngRate ; // angular rate from previous IMU sample used for trapezoidal integrator
2014-02-26 04:01:51 -04:00
Vector3f lastAccel1 ; // acceleration from previous IMU1 sample used for trapezoidal integrator
Vector3f lastAccel2 ; // acceleration from previous IMU2 sample used for trapezoidal integrator
2014-01-30 18:25:40 -04:00
Matrix22 nextP ; // Predicted covariance matrix before addition of process noise to diagonals
Vector22 processNoise ; // process noise added to diagonals of predicted covariance matrix
Vector15 SF ; // intermediate variables used to calculate predicted covariance matrix
Vector8 SG ; // intermediate variables used to calculate predicted covariance matrix
Vector11 SQ ; // intermediate variables used to calculate predicted covariance matrix
Vector8 SPP ; // intermediate variables used to calculate predicted covariance matrix
2014-02-26 04:01:51 -04:00
float IMU1_weighting ; // Weighting applied to use of IMU1. Varies between 0 and 1.
2014-03-09 20:49:34 -03:00
bool yawAligned ; // true when the yaw angle has been aligned
2014-04-23 04:37:07 -03:00
Vector2f gpsPosGlitchOffsetNE ; // offset applied to GPS data in the NE direction to compensate for rapid changes in GPS solution
2014-03-31 18:15:28 -03:00
uint32_t lastDecayTime_ms ; // time of last decay of GPS position offset
float velTestRatio ; // sum of squares of GPS velocity innovation divided by fail threshold
float posTestRatio ; // sum of squares of GPS position innovation divided by fail threshold
float hgtTestRatio ; // sum of squares of baro height innovation divided by fail threshold
Vector3f magTestRatio ; // sum of squares of magnetometer innovations divided by fail threshold
float tasTestRatio ; // sum of squares of true airspeed innovation divided by fail threshold
2014-04-25 07:32:13 -03:00
bool inhibitWindStates ; // true when wind states and covariances are to remain constant
bool inhibitMagStates ; // true when magnetic field states and covariances are to remain constant
2014-08-23 23:02:29 -03:00
// Used by smoothing of state corrections
float gpsIncrStateDelta [ 10 ] ; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next GPS measurement
float hgtIncrStateDelta [ 10 ] ; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next height measurement
float magIncrStateDelta [ 10 ] ; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next magnetometer measurement
uint8_t gpsUpdateCount ; // count of the number of minor state corrections using GPS data
uint8_t gpsUpdateCountMax ; // limit on the number of minor state corrections using GPS data
float gpsUpdateCountMaxInv ; // floating point inverse of gpsFilterCountMax
uint8_t hgtUpdateCount ; // count of the number of minor state corrections using Baro data
uint8_t hgtUpdateCountMax ; // limit on the number of minor state corrections using Baro data
float hgtUpdateCountMaxInv ; // floating point inverse of hgtFilterCountMax
uint8_t magUpdateCount ; // count of the number of minor state corrections using Magnetometer data
uint8_t magUpdateCountMax ; // limit on the number of minor state corrections using Magnetometer data
float magUpdateCountMaxInv ; // floating point inverse of magFilterCountMax
2014-05-15 08:42:39 -03:00
struct {
bool bad_xmag : 1 ;
bool bad_ymag : 1 ;
bool bad_zmag : 1 ;
bool bad_airspeed : 1 ;
bool bad_sideslip : 1 ;
} faultStatus ;
2013-12-29 03:37:55 -04:00
2013-12-29 07:17:59 -04:00
// states held by magnetomter fusion across time steps
// magnetometer X,Y,Z measurements are fused across three time steps
2014-01-30 18:25:40 -04:00
// to level computational load as this is an expensive operation
2013-12-29 03:37:55 -04:00
struct {
2014-01-03 00:37:19 -04:00
ftype q0 ;
ftype q1 ;
ftype q2 ;
ftype q3 ;
ftype magN ;
ftype magE ;
ftype magD ;
ftype magXbias ;
ftype magYbias ;
ftype magZbias ;
2013-12-29 03:37:55 -04:00
uint8_t obsIndex ;
Matrix3f DCM ;
Vector3f MagPred ;
2014-01-03 00:37:19 -04:00
ftype R_MAG ;
ftype SH_MAG [ 9 ] ;
2013-12-29 03:37:55 -04:00
} mag_state ;
2013-12-30 06:27:50 -04:00
2014-03-31 14:54:01 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
2013-12-30 06:41:28 -04:00
// performance counters
perf_counter_t _perf_UpdateFilter ;
perf_counter_t _perf_CovariancePrediction ;
perf_counter_t _perf_FuseVelPosNED ;
perf_counter_t _perf_FuseMagnetometer ;
perf_counter_t _perf_FuseAirspeed ;
2014-03-06 05:43:24 -04:00
perf_counter_t _perf_FuseSideslip ;
2013-12-30 06:41:28 -04:00
# endif
2014-03-01 23:32:10 -04:00
2014-04-21 04:12:15 -03:00
// should we assume zero sideslip?
bool assume_zero_sideslip ( void ) const ;
2014-01-30 17:47:33 -04:00
} ;
2013-12-30 06:41:28 -04:00
2014-06-06 19:12:08 -03:00
# if CONFIG_HAL_BOARD != HAL_BOARD_PX4 && CONFIG_HAL_BOARD != HAL_BOARD_VRBRAIN
2013-12-30 06:41:28 -04:00
# define perf_begin(x)
# define perf_end(x)
# endif
2013-12-29 03:37:55 -04:00
# endif // AP_NavEKF