2014-01-30 17:47:33 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
2014-01-03 03:52:37 -04:00
21 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>
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
2013-12-30 06:41:28 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
# 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-03 00:37:19 -04:00
typedef VectorN < ftype , 21 > Vector21 ;
typedef VectorN < VectorN < ftype , 3 > , 3 > Matrix3 ;
2014-01-03 03:52:37 -04:00
typedef VectorN < VectorN < ftype , 21 > , 21 > Matrix21 ;
typedef VectorN < VectorN < ftype , 50 > , 21 > Matrix21_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-03 00:37:19 -04:00
typedef ftype Vector21 [ 21 ] ;
typedef ftype Matrix3 [ 3 ] [ 3 ] ;
2014-01-03 03:52:37 -04:00
typedef ftype Matrix21 [ 21 ] [ 21 ] ;
typedef ftype Matrix21_50 [ 21 ] [ 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-01-30 17:47:33 -04:00
// Initialise the filter states from the AHRS and magnetometer data (if present)
2013-12-29 03:37:55 -04:00
void InitialiseFilter ( void ) ;
2014-01-30 18:46:10 -04:00
// Reset the position and height states
void ResetPosition ( 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-01-02 01:16:16 -04:00
// return true if the filter is healthy
2014-01-03 20:16:19 -04:00
bool healthy ( void ) const ;
2014-01-02 01:16:16 -04:00
2013-12-29 03:37:55 -04:00
// fill in latitude, longitude and height of the reference point
2014-01-01 21:15:22 -04:00
void getRefLLH ( struct Location & loc ) const ;
2013-12-29 03:37:55 -04:00
2014-01-02 07:05:09 -04:00
// set latitude, longitude and height of the reference point
void setRefLLH ( int32_t lat , int32_t lng , int32_t alt_cm ) ;
2013-12-29 03:37:55 -04: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
2013-12-31 23:03:52 -04:00
// return bodyaxis gyro bias estimates in deg/hr
2014-01-01 21:15:22 -04:00
void getGyroBias ( Vector3f & gyroBias ) const ;
2013-12-31 17:54:56 -04:00
2013-12-31 23:03:52 -04:00
// return body axis accelerometer bias estimates in m/s^2
2014-01-01 21:15:22 -04:00
void getAccelBias ( Vector3f & accelBias ) const ;
2013-12-31 17:54:56 -04:00
2013-12-31 23:03:52 -04:00
// return the NED wind speed estimates in m/s
2014-01-01 21:15:22 -04:00
void getWind ( Vector3f & wind ) const ;
2014-01-30 18:11:54 -04:00
2013-12-31 23:03:52 -04:00
// return earth magnetic field estimates in measurement units
2014-01-01 21:15:22 -04:00
void getMagNED ( Vector3f & magNED ) const ;
2013-12-31 17:54:56 -04:00
2013-12-31 23:03:52 -04:00
// return body magnetic field estimates in measurement units
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
2013-12-29 03:37:55 -04:00
// get the transformation matrix from NED to XYD (body) axes
2014-01-01 21:15:22 -04:00
void getRotationNEDToBody ( Matrix3f & mat ) const ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
// get 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
2013-12-29 03:37:55 -04:00
// get 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
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
2013-12-29 03:37:55 -04:00
void UpdateStrapdownEquationsNED ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void CovariancePrediction ( ) ;
2014-01-03 03:52:37 -04:00
2014-01-03 15:59:47 -04:00
void ForceSymmetry ( ) ;
void ConstrainVariances ( ) ;
2014-01-02 22:10:38 -04:00
2013-12-29 03:37:55 -04:00
void FuseVelPosNED ( ) ;
2014-01-03 03:52:37 -04:00
2013-12-29 03:37:55 -04:00
void FuseMagnetometer ( ) ;
2014-01-03 03:52:37 -04:00
2013-12-29 03:37:55 -04:00
void FuseAirspeed ( ) ;
2014-01-30 17:47:33 -04:00
2014-01-03 03:52:37 -04:00
void zeroRows ( Matrix21 & covMat , uint8_t first , uint8_t last ) ;
2014-01-30 17:47:33 -04:00
2014-01-03 03:52:37 -04:00
void zeroCols ( Matrix21 & covMat , uint8_t first , uint8_t last ) ;
2014-01-30 17:47:33 -04:00
2014-01-01 21:15:22 -04:00
void quatNorm ( Quaternion & quatOut , const Quaternion & quatIn ) const ;
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
2013-12-29 03:37:55 -04:00
// recall state vector stored at closest time to the one specified by msec
2014-01-03 03:52:37 -04:00
void RecallStates ( Vector21 & statesForFusion , uint32_t msec ) ;
2014-01-30 17:47:33 -04:00
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-01-02 07:05:09 -04:00
void calcEarthRateNED ( Vector3f & omega , int32_t latitude ) const ;
2014-01-30 17:47:33 -04:00
2014-01-01 21:15:22 -04:00
void calcvelNED ( Vector3f & velNED , float gpsCourse , float gpsGndSpd , float gpsVelD ) const ;
2014-01-30 17:47:33 -04:00
2014-01-01 21:15:22 -04:00
void calcllh ( float & lat , float & lon , float & hgt ) const ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void OnGroundCheck ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void CovarianceInit ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void readIMUData ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void readGpsData ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void readHgtData ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void readMagData ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void readAirSpdData ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void SelectVelPosFusion ( ) ;
2014-01-03 03:52:37 -04:00
2013-12-29 03:37:55 -04:00
void SelectHgtFusion ( ) ;
void SelectTasFusion ( ) ;
void SelectMagFusion ( ) ;
bool statesInitialised ;
2014-01-01 08:15:37 -04:00
// Tuning Parameters
2014-01-05 02:28:21 -04:00
ftype _gpsHorizVelNoise ; // GPS horizontal velocity noise : m/s
ftype _gpsVertVelNoise ; // GPS vertical velocity noise : m/s
ftype _gpsHorizPosNoise ; // GPS horizontal position noise m
ftype _gpsVertPosNoise ; // GPS or Baro vertical position variance : m^2
2014-01-03 00:37:19 -04:00
ftype _gpsVelVarAccScale ; // scale factor applied to velocity variance due to Vdot
ftype _gpsPosVarAccScale ; // scale factor applied to position variance due to Vdot
2014-01-05 02:28:21 -04:00
ftype _magNoise ; // magnetometer measurement noise : gauss
ftype _magVarRateScale ; // scale factor applied to magnetometer variance due to angular rate
ftype _easNoise ; // equivalent airspeed noise : m/s
ftype _windStateNoise ; // rate of change of wind : m/s^2
2014-01-03 00:37:19 -04:00
ftype _wndVarHgtRateScale ; // scale factor applied to wind process noise from height rate
2014-01-05 02:28:21 -04:00
ftype _gyrNoise ; // gyro process noise : rad/s
2014-01-05 05:02:07 -04:00
ftype _accNoise ; // accelerometer process noise : m/s^2
2014-01-05 02:28:21 -04:00
ftype _dAngBiasNoise ; // gyro bias state noise : rad/s^2
ftype _magEarthNoise ; // earth magnetic field process noise : gauss/sec
ftype _magBodyNoise ; // earth magnetic field process noise : gauss/sec
2014-01-01 08:15:37 -04:00
2014-01-03 03:52:37 -04:00
Vector21 states ; // state matrix - 4 x quaternions, 3 x Vel, 3 x Pos, 3 x gyro bias, 3 x accel bias, 2 x wind vel, 3 x earth mag field, 3 x body mag field
2013-12-30 06:27:50 -04:00
2014-01-03 03:52:37 -04:00
Matrix21 KH ; // intermediate result used for covariance updates
Matrix21 KHP ; // intermediate result used for covariance updates
Matrix21 P ; // covariance matrix
Matrix21_50 storedStates ; // state vectors stored for the last 50 time steps
2013-12-30 06:27:50 -04:00
uint32_t statetimeStamp [ 50 ] ; // time stamp for each state vector stored
2013-12-29 03:37:55 -04:00
Vector3f correctedDelAng ; // delta angles about the xyz body axes corrected for errors (rad)
Vector3f correctedDelVel ; // delta velocities along the XYZ body axes corrected for errors (m/s)
2013-12-29 07:17:59 -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
Matrix3f prevTnb ; // previous nav to body transformation used for INS earth rotation compensation
2014-01-03 00:37:19 -04:00
ftype accNavMag ; // magnitude of navigation accel - used to adjust GPS obs variance (m/s^2)
2013-12-29 03:37:55 -04:00
Vector3f earthRateNED ; // earths angular rate vector in NED (rad/s)
Vector3f dVelIMU ; // delta velocity vector in XYZ body axes measured by the IMU (m/s)
Vector3f dAngIMU ; // delta angle vector in XYZ body axes measured by the IMU (rad)
2014-01-03 00:37:19 -04:00
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
2013-12-29 03:37:55 -04:00
bool onGround ; // boolean true when the flight vehicle is on the ground (not flying)
const bool useAirspeed ; // boolean true if airspeed data is being used
const bool useCompass ; // boolean true if magnetometer data is being used
const uint8_t fusionModeGPS ; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
2013-12-29 22:25:02 -04:00
Vector6 innovVelPos ; // innovation output for a group of measurements
Vector6 varInnovVelPos ; // innovation variance output for a group of measurements
2013-12-29 07:17:59 -04:00
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
2013-12-29 22:25:02 -04:00
Vector3f velNED ; // North, East, Down velocity measurements (m/s)
Vector2 posNE ; // North, East position measurements (m)
2014-01-03 00:37:19 -04:00
ftype hgtMea ; // height measurement relative to reference point (m)
2014-01-03 03:52:37 -04:00
Vector21 statesAtVelTime ; // States at the effective time of velNED measurements
Vector21 statesAtPosTime ; // States at the effective time of posNE measurements
Vector21 statesAtHgtTime ; // States at the effective time of hgtMea measurement
2013-12-29 22:25:02 -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
2013-12-29 03:37:55 -04:00
bool fuseMagData ; // boolean true when magnetometer data is to be fused
2013-12-29 07:17:59 -04:00
Vector3f magData ; // magnetometer flux readings in X,Y,Z body axes
2014-01-03 03:52:37 -04:00
Vector21 statesAtMagMeasTime ; // filter states at the effective time of compass measurements
2014-01-03 00:37:19 -04:00
ftype innovVtas ; // innovation output from fusion of airspeed measurements
ftype varInnovVtas ; // innovation variance output from fusion of airspeed measurements
2013-12-29 03:37:55 -04:00
bool fuseVtasData ; // boolean true when airspeed data is to be fused
float VtasMeas ; // true airspeed measurement (m/s)
2014-01-03 03:52:37 -04:00
Vector21 statesAtVtasMeasTime ; // filter states at the effective measurement time
2013-12-29 07:17:59 -04:00
Vector3f magBias ; // magnetometer bias vector in XYZ body axes
2014-01-03 00:37:19 -04:00
const ftype covTimeStepMax ; // maximum time allowed between covariance predictions
const ftype covDelAngMax ; // maximum delta angle between covariance predictions
2013-12-29 03:37:55 -04:00
bool covPredStep ; // boolean set to true when a covariance prediction step has been performed
2014-01-03 00:37:19 -04:00
const ftype yawVarScale ; // scale factor applied to yaw gyro errors when on ground
2013-12-30 04:58:24 -04:00
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
2013-12-29 03:37:55 -04:00
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
2013-12-30 04:58:24 -04:00
const uint32_t TASmsecMax ; // maximum allowed interval between TAS fusion steps
2013-12-29 03:37:55 -04:00
uint32_t MAGmsecPrev ; // time stamp of last compass fusion step
2013-12-30 04:58:24 -04:00
const uint32_t MAGmsecMax ; // maximum allowed interval between compass fusion steps
2013-12-29 03:37:55 -04:00
uint32_t HGTmsecPrev ; // time stamp of last height measurement fusion step
2013-12-30 04:58:24 -04:00
const uint32_t HGTmsecMax ; // maximum allowed interval between height measurement fusion steps
2013-12-31 17:54:56 -04:00
const bool fuseMeNow ; // boolean to force fusion whenever data arrives
2014-01-05 05:54:49 -04:00
bool staticMode ; // boolean to force position and velocity measurements to zero for pre-arm or bench testing
2013-12-30 06:27:50 -04:00
// last time compass was updated
uint32_t lastMagUpdate ;
// last time airspeed was updated
uint32_t lastAirspeedUpdate ;
2014-01-03 03:52:37 -04:00
2013-12-29 07:17:59 -04:00
// Estimated time delays (msec) for different measurements relative to IMU
2013-12-29 03:37:55 -04:00
const uint32_t msecVelDelay ;
const uint32_t msecPosDelay ;
const uint32_t msecHgtDelay ;
const uint32_t msecMagDelay ;
const uint32_t msecTasDelay ;
// IMU input data variables
uint32_t IMUmsec ;
// GPS input data variables
2014-01-03 00:37:19 -04:00
ftype gpsCourse ;
ftype gpsGndSpd ;
2013-12-29 03:37:55 -04:00
bool newDataGps ;
// Magnetometer input data variables
2014-01-03 00:37:19 -04:00
ftype magIn ;
2013-12-29 03:37:55 -04:00
bool newDataMag ;
2013-12-29 21:12:09 -04:00
// TAS input variables
bool newDataTas ;
2013-12-29 03:37:55 -04:00
2014-01-05 05:54:49 -04:00
// HGT input variables
bool newDataHgt ;
uint32_t lastHgtUpdate ;
2013-12-29 07:17:59 -04:00
// Time stamp when vel, pos or height measurements last failed checks
2013-12-29 03:37:55 -04:00
uint32_t velFailTime ;
uint32_t posFailTime ;
uint32_t hgtFailTime ;
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-03 03:52:37 -04:00
// to
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-29 07:17:59 -04:00
// State vector storage index
2013-12-29 03:37:55 -04:00
uint8_t storeIndex ;
2014-01-02 20:47:09 -04:00
// time of last GPS fix used to determine if new data has arrived
uint32_t lastFixTime_ms ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
Vector3f lastAngRate ;
Vector3f lastAccel ;
2013-12-30 06:27:50 -04:00
// CovariancePrediction variables
2014-01-03 03:52:37 -04:00
Matrix21 nextP ;
Vector21 processNoise ;
Vector14 SF ;
2013-12-30 06:27:50 -04:00
Vector8 SG ;
Vector11 SQ ;
2014-01-03 03:52:37 -04:00
Vector8 SPP ;
2013-12-30 06:27:50 -04:00
2013-12-30 06:41:28 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// 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 ;
# endif
2014-01-30 17:47:33 -04:00
} ;
2013-12-30 06:41:28 -04:00
# if CONFIG_HAL_BOARD != HAL_BOARD_PX4
# define perf_begin(x)
# define perf_end(x)
# endif
2013-12-29 03:37:55 -04:00
# endif // AP_NavEKF