2014-01-30 17:47:33 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
24 state EKF based on https : //github.com/priseborough/InertialNav
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_AHRS.h>
# include <AP_InertialSensor.h>
# include <AP_Baro.h>
# include <AP_AHRS.h>
# include <AP_Airspeed.h>
# include <AP_Compass.h>
2013-12-29 22:25:02 -04:00
# include <vectorN.h>
2014-01-30 17:47:33 -04:00
class NavEKF
{
public :
2013-12-29 22:25:02 -04:00
typedef VectorN < float , 2 > Vector2 ;
typedef VectorN < float , 6 > Vector6 ;
typedef VectorN < float , 8 > Vector8 ;
typedef VectorN < float , 24 > Vector24 ;
typedef VectorN < VectorN < float , 24 > , 24 > Matrix24 ;
typedef VectorN < VectorN < float , 50 > , 24 > Matrix24_50 ;
2014-01-30 17:47:33 -04:00
// Constructor
2013-12-29 03:37:55 -04:00
NavEKF ( const AP_AHRS & ahrs , AP_Baro & baro ) ;
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 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 ) ;
// fill in latitude, longitude and height of the reference point
void getRefLLH ( struct Location & loc ) ;
// return the last calculated NED position relative to the
// reference point (m). Return false if no position is available
bool getPosNED ( Vector3f & pos ) ;
2014-01-30 17:47:33 -04:00
// return the last calculated NED velocity (m/s)
2013-12-29 03:37:55 -04:00
void getVelNED ( Vector3f & vel ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
// return the last calculated latitude, longitude and height
bool getLLH ( struct Location & loc ) ;
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
void getEulerAngles ( Vector3f & eulers ) ;
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
void getRotationNEDToBody ( Matrix3f & mat ) ;
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
void getRotationBodyToNED ( Matrix3f & mat ) ;
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
void getQuaternion ( Quaternion & quat ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
private :
const AP_AHRS & _ahrs ;
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 ( ) ;
void FuseVelPosNED ( ) ;
void FuseMagnetometer ( ) ;
void FuseAirspeed ( ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void zeroRows ( Matrix24 & covMat , uint8_t first , uint8_t last ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void zeroCols ( Matrix24 & covMat , uint8_t first , uint8_t last ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void quatNorm ( Quaternion & quatOut , const Quaternion & quatIn ) ;
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
2013-12-29 22:25:02 -04:00
void RecallStates ( Vector24 & statesForFusion , uint32_t msec ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void quat2Tnb ( Matrix3f & Tnb , const Quaternion & quat ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void quat2Tbn ( Matrix3f & Tbn , const Quaternion & quat ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void calcEarthRateNED ( Vector3f & omega , float latitude ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void eul2quat ( Quaternion & quat , const Vector3f & eul ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void quat2eul ( Vector3f & eul , const Quaternion & quat ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
void calcvelNED ( Vector3f & velNED , float gpsCourse , float gpsGndSpd , float gpsVelD ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void calcposNE ( float lat , float lon ) ;
2014-01-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void calcllh ( float & lat , float & lon , float & hgt ) ;
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-30 17:47:33 -04:00
2013-12-29 03:37:55 -04:00
void SelectHgtFusion ( ) ;
void SelectTasFusion ( ) ;
void SelectMagFusion ( ) ;
bool statesInitialised ;
2013-12-29 22:25:02 -04:00
Matrix24 KH ; // intermediate result used for covariance updates
Matrix24 KHP ; // intermediate result used for covariance updates
Matrix24 P ; // covariance matrix
Vector24 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
Matrix24_50 storedStates ; // state vectors stored for the last 50 time steps
VectorN < uint32_t , 50 > statetimeStamp ; // 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
float 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)
2013-12-29 07:17:59 -04:00
float dtIMU ; // time lapsed since the last IMU measurement (sec)
float dt ; // time lapsed since the last covariance prediction (sec)
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)
2013-12-29 07:17:59 -04:00
float hgtMea ; // height measurement relative to reference point (m)
2013-12-29 22:25:02 -04:00
Vector24 statesAtVelTime ; // States at the effective time of velNED measurements
Vector24 statesAtPosTime ; // States at the effective time of posNE measurements
Vector24 statesAtHgtTime ; // States at the effective time of hgtMea measurement
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
2013-12-29 22:25:02 -04:00
Vector24 statesAtMagMeasTime ; // filter states at the effective time of compass measurements
2013-12-29 07:17:59 -04:00
float innovVtas ; // innovation output from fusion of airspeed measurements
float 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)
2013-12-29 22:25:02 -04:00
Vector24 statesAtVtasMeasTime ; // filter states at the effective measurement time
2013-12-29 03:37:55 -04:00
float latRef ; // WGS-84 latitude of reference point (rad)
float lonRef ; // WGS-84 longitude of reference point (rad)
float hgtRef ; // WGS-84 height of reference point (m)
2013-12-29 07:17:59 -04:00
Vector3f magBias ; // magnetometer bias vector in XYZ body axes
2013-12-29 22:25:02 -04:00
Vector3f eulerEst ; // Euler angles calculated from filter states
Vector3f eulerDif ; // difference between Euler angle estimated by EKF and the AHRS solution
2013-12-29 03:37:55 -04:00
const float covTimeStepMax ; // maximum time allowed between covariance predictions
const float covDelAngMax ; // maximum delta angle between covariance predictions
bool covPredStep ; // boolean set to true when a covariance prediction step has been performed
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
const uint32_t TASmsecTgt ; // target interval between TAS fusion steps
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
const uint32_t MAGmsecTgt ; // target interval between compass fusion steps
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-29 03:37:55 -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
float imuIn ;
2013-12-29 22:25:02 -04:00
Vector8 tempImu ;
2013-12-29 03:37:55 -04:00
uint32_t IMUmsec ;
// GPS input data variables
float gpsCourse ;
float gpsGndSpd ;
float gpsLat ;
float gpsLon ;
float gpsHgt ;
bool newDataGps ;
// Magnetometer input data variables
float magIn ;
2013-12-29 22:25:02 -04:00
Vector8 tempMag ;
Vector8 tempMagPrev ;
2013-12-29 03:37:55 -04:00
uint32_t MAGframe ;
uint32_t MAGtime ;
uint32_t lastMAGtime ;
bool newDataMag ;
2013-12-29 21:12:09 -04:00
Vector3f magDataPrev ;
// TAS input variables
bool newDataTas ;
float VtasMeasPrev ;
2013-12-29 03:37:55 -04:00
// AHRS input data variables
2013-12-29 22:25:02 -04:00
Vector3f ahrsEul ;
2013-12-29 03:37:55 -04:00
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
// to
2013-12-29 03:37:55 -04:00
struct {
float q0 ;
float q1 ;
float q2 ;
float q3 ;
float magN ;
float magE ;
float magD ;
float magXbias ;
float magYbias ;
float magZbias ;
uint8_t obsIndex ;
Matrix3f DCM ;
Vector3f MagPred ;
float R_MAG ;
float SH_MAG [ 9 ] ;
} 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 ;
2013-12-29 07:17:59 -04:00
// high precision time stamp for previous IMU data processing
2013-12-29 03:37:55 -04:00
uint32_t lastIMUusec ;
2013-12-29 07:17:59 -04:00
// time of alst GPS fix used to determine if new data has arrived
2013-12-29 03:37:55 -04:00
uint32_t lastFixTime ;
2014-01-30 17:47:33 -04:00
2013-12-29 22:25:02 -04:00
Vector3f lastAngRate ;
Vector3f lastAccel ;
2014-01-30 17:47:33 -04:00
} ;
2013-12-29 03:37:55 -04:00
# endif // AP_NavEKF