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>
2015-01-02 04:07:42 -04:00
# include <AP_Nav_Common.h>
2015-03-10 04:00:32 -03:00
# include <GCS_MAVLink.h>
2015-04-24 03:45:08 -03:00
# include <AP_RangeFinder.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 ;
2015-02-05 02:34:27 -04:00
# if defined(MATH_CHECK_INDEXES) && (MATH_CHECK_INDEXES == 1)
2014-01-03 00:37:19 -04:00
typedef VectorN < ftype , 2 > Vector2 ;
typedef VectorN < ftype , 3 > Vector3 ;
2015-04-07 18:00:40 -03:00
typedef VectorN < ftype , 4 > Vector4 ;
2015-01-08 20:05:07 -04:00
typedef VectorN < ftype , 5 > Vector5 ;
2014-01-03 00:37:19 -04:00
typedef VectorN < ftype , 6 > Vector6 ;
typedef VectorN < ftype , 8 > Vector8 ;
2015-01-08 20:05:07 -04:00
typedef VectorN < ftype , 9 > Vector9 ;
typedef VectorN < ftype , 10 > Vector10 ;
2014-01-03 00:37:19 -04:00
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-08-25 04:58:42 -03:00
typedef VectorN < ftype , 31 > Vector31 ;
typedef VectorN < ftype , 34 > Vector34 ;
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 ;
2014-08-25 04:58:42 -03:00
typedef VectorN < VectorN < ftype , 34 > , 22 > Matrix34_50 ;
2015-01-08 20:05:07 -04:00
typedef VectorN < uint32_t , 50 > Vector_u32_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 ] ;
2015-04-07 18:00:40 -03:00
typedef ftype Vector4 [ 4 ] ;
2015-01-08 20:05:07 -04:00
typedef ftype Vector5 [ 5 ] ;
2014-01-03 00:37:19 -04:00
typedef ftype Vector6 [ 6 ] ;
typedef ftype Vector8 [ 8 ] ;
2015-01-08 20:05:07 -04:00
typedef ftype Vector9 [ 9 ] ;
typedef ftype Vector10 [ 10 ] ;
2014-01-03 00:37:19 -04:00
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-08-25 04:58:42 -03:00
typedef ftype Vector34 [ 34 ] ;
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-08-25 04:58:42 -03:00
typedef ftype Matrix34_50 [ 34 ] [ 50 ] ;
2015-01-08 20:05:07 -04:00
typedef uint32_t Vector_u32_50 [ 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
2015-04-17 06:22:51 -03:00
NavEKF ( const AP_AHRS * ahrs , AP_Baro & baro , const RangeFinder & rng ) ;
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
2015-03-28 14:51:38 -03:00
bool 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
2015-03-28 14:51:38 -03:00
bool InitialiseFilterBootstrap ( void ) ;
2014-01-30 18:25:40 -04:00
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
2015-04-29 07:18:37 -03:00
// Return the last calculated NED position relative to the reference point (m).
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
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-10-31 19:06:04 -03:00
// This returns the specific forces in the NED frame
void getAccelNED ( Vector3f & accelNED ) const ;
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 ) ;
2015-06-23 19:53:04 -03:00
// Resets the baro so that it reads zero at the current height
// Resets the EKF height to zero
// Adjusts the EKf origin height so that the EKF height + origin height is the same as before
// Returns true if the height datum reset has been performed
// If using a range finder for height no reset is performed and it returns false
bool resetHeightDatum ( void ) ;
2014-11-15 16:03:17 -04:00
// Commands the EKF to not use GPS.
2014-11-12 06:04:58 -04:00
// This command must be sent prior to arming as it will only be actioned when the filter is in static mode
// This command is forgotten by the EKF each time it goes back into static mode (eg the vehicle disarms)
2014-11-15 16:03:17 -04:00
// Returns 0 if command rejected
// Returns 1 if attitude, vertical velocity and vertical position will be provided
// Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided
2014-11-12 06:04:58 -04:00
uint8_t setInhibitGPS ( void ) ;
2014-11-15 21:41:27 -04:00
// return the horizontal speed limit in m/s set by optical flow sensor limits
// return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
void getEkfControlLimits ( float & ekfGndSpdLimit , float & ekfNavVelGainScaler ) const ;
2014-11-15 02:44:25 -04:00
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
2015-03-16 16:05:45 -03:00
// Return estimated magnetometer offsets
// Return true if magnetometer offsets are valid
bool getMagOffsets ( Vector3f & magOffsets ) const ;
2015-04-29 06:54:50 -03:00
// Return the last calculated latitude, longitude and height in WGS-84
2015-05-02 04:32:57 -03:00
// If a calculated location isn't available, return a raw GPS measurement
// The status will return true if a calculation or raw measurement is available
// The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
2014-01-01 21:15:22 -04:00
bool getLLH ( struct Location & loc ) const ;
2014-01-30 17:47:33 -04:00
2015-01-07 22:43:41 -04:00
// return the latitude and longitude and height used to set the NED origin
// All NED positions calculated by the filter are relative to this location
// Returns false if the origin has not been set
bool getOriginLLH ( struct Location & loc ) const ;
// set the latitude and longitude and height used to set the NED origin
// All NED positions calcualted by the filter will be relative to this location
// The origin cannot be set if the filter is in a flight mode (eg vehicle armed)
// Returns false if the filter has rejected the attempt to set the origin
bool setOriginLLH ( struct Location & loc ) ;
2014-11-30 05:26:11 -04:00
// return estimated height above ground level
// return false if ground height is not being estimated.
bool getHAGL ( float & HAGL ) const ;
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-08-25 04:58:42 -03:00
// write the raw optical flow measurements
// rawFlowQuality is a measured of quality between 0 and 255, with 255 being the best quality
2014-11-12 01:33:05 -04:00
// rawFlowRates are the optical flow rates in rad/sec about the X and Y sensor axes.
// rawGyroRates are the sensor rotation rates in rad/sec measured by the sensors internal gyro
// The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
2014-08-25 04:58:42 -03:00
// msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
2015-04-17 06:22:51 -03:00
void writeOptFlowMeas ( uint8_t & rawFlowQuality , Vector2f & rawFlowRates , Vector2f & rawGyroRates , uint32_t & msecFlowMeas ) ;
2014-08-25 04:58:42 -03:00
// return data for debugging optical flow fusion
2015-01-03 19:27:07 -04:00
void getFlowDebug ( float & varFlow , float & gndOffset , float & flowInnovX , float & flowInnovY , float & auxInnov , float & HAGL , float & rngInnov , float & range , float & gndOffsetErr ) const ;
2014-08-25 04:58:42 -03:00
2015-04-20 19:41:42 -03:00
// called by vehicle code to specify that a takeoff is happening
// causes the EKF to compensate for expected barometer errors due to ground effect
void setTakeoffExpected ( bool val ) ;
// called by vehicle code to specify that a touchdown is expected to happen
// causes the EKF to compensate for expected barometer errors due to ground effect
void setTouchdownExpected ( bool val ) ;
2015-01-28 02:02:59 -04:00
2014-05-12 04:35:22 -03:00
/*
return the filter fault status as a bitmasked integer
2014-11-01 04:04:18 -03:00
0 = quaternions are NaN
1 = velocities are NaN
2014-05-12 04:35:22 -03:00
2 = badly conditioned X magnetometer fusion
3 = badly conditioned Y magnetometer fusion
2014-11-01 04:04:18 -03:00
5 = badly conditioned Z magnetometer fusion
6 = badly conditioned airspeed fusion
7 = badly conditioned synthetic sideslip fusion
7 = filter is not initialised
2014-05-12 04:35:22 -03:00
*/
2014-10-14 04:24:32 -03:00
void getFilterFaults ( uint8_t & faults ) const ;
2014-05-12 04:35:22 -03:00
2014-11-01 04:04:18 -03:00
/*
return filter timeout status as a bitmasked integer
0 = position measurement timeout
1 = velocity measurement timeout
2 = height measurement timeout
3 = magnetometer measurement timeout
5 = unassigned
6 = unassigned
7 = unassigned
7 = unassigned
*/
void getFilterTimeouts ( uint8_t & timeouts ) const ;
2014-11-14 01:22:16 -04:00
/*
2015-01-02 04:07:42 -04:00
return filter status flags
2014-11-14 01:22:16 -04:00
*/
2015-01-02 04:07:42 -04:00
void getFilterStatus ( nav_filter_status & status ) const ;
2014-11-14 01:22:16 -04:00
2015-03-10 04:00:32 -03:00
// send an EKF_STATUS_REPORT message to GCS
void send_status_report ( mavlink_channel_t chan ) ;
2015-04-22 23:57:59 -03:00
// provides the height limit to be observed by the control loops
// returns false if no height limiting is required
// this is needed to ensure the vehicle does not fly too high when using optical flow navigation
bool getHeightControlLimit ( float & height ) const ;
2015-04-27 08:42:28 -03:00
// provides the quaternion that was used by the INS calculation to rotate from the previous orientation to the orientaion at the current time step
// returns a zero rotation quaternion if the INS calculation was not performed on that time step.
Quaternion getDeltaQuaternion ( void ) const ;
2015-06-23 04:36:11 -03:00
// return the amount of yaw angle change due to the last yaw angle reset in radians
// returns true if a reset yaw angle has been updated and not queried
// this function should not have more than one client
bool getLastYawResetAngle ( float & yawAng ) ;
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 ;
2015-04-17 06:22:51 -03:00
const RangeFinder & _rng ;
2014-01-30 17:47:33 -04:00
2014-08-25 04:58:42 -03:00
// the states are available in two forms, either as a Vector34, or
2014-04-04 07:30:16 -03:00
// broken down as individual elements. Both are equivalent (same
// memory)
2014-08-25 04:58:42 -03:00
Vector34 states ;
2014-04-04 07:30:16 -03:00
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
2014-08-25 04:58:42 -03:00
Vector3f omega ; // 31 .. 33
2014-04-04 07:30:16 -03:00
} & 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
2015-04-27 14:16:34 -03:00
// helper functions for readIMUData
bool readDeltaVelocity ( uint8_t ins_index , Vector3f & dVel , float & dVel_dt ) ;
bool readDeltaAngle ( uint8_t ins_index , Vector3f & dAng ) ;
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-12-31 21:01:22 -04:00
void InitialiseVariables ( ) ;
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-12-21 05:41:40 -04:00
// return true if the vehicle code has requested the filter to be ready for flight
bool getVehicleArmStatus ( void ) const ;
2014-02-18 19:52:57 -04:00
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-08-25 04:58:42 -03:00
// Check for filter divergence
void checkDivergence ( void ) ;
// Calculate weighting that is applied to IMU1 accel data to blend data from IMU's 1 and 2
void calcIMU_Weighting ( float K1 , float K2 ) ;
2014-12-19 23:44:14 -04:00
// return true if optical flow data is available
bool optFlowDataPresent ( void ) const ;
2014-08-25 04:58:42 -03:00
// return true if we should use the range finder sensor
bool useRngFinder ( void ) const ;
// determine when to perform fusion of optical flow measurements
void SelectFlowFusion ( ) ;
// recall omega (angular rate vector) average from time specified by msec to current time
// this is useful for motion compensation of optical flow measurements
void RecallOmega ( Vector3f & omegaAvg , uint32_t msecStart , uint32_t msecEnd ) ;
2015-01-03 16:56:20 -04:00
// Estimate terrain offset using a single state EKF
void EstimateTerrainOffset ( ) ;
2014-08-25 04:58:42 -03:00
// fuse optical flow measurements into the main filter
void FuseOptFlow ( ) ;
2014-12-28 20:27:45 -04:00
// Check arm status and perform required checks and mode changes
void performArmingChecks ( ) ;
2015-01-07 22:43:41 -04:00
// Set the NED origin to be used until the next filter reset
void setOrigin ( ) ;
2015-04-20 19:41:42 -03:00
// determine if a takeoff is expected so that we can compensate for expected barometer errors due to ground effect
bool getTakeoffExpected ( ) ;
// determine if a touchdown is expected so that we can compensate for expected barometer errors due to ground effect
bool getTouchdownExpected ( ) ;
2015-01-28 02:02:59 -04:00
2015-03-13 21:07:43 -03:00
// Assess GPS data quality and return true if good enough to align the EKF
bool calcGpsGoodToAlign ( void ) ;
2015-04-17 06:22:51 -03:00
// Read the range finder and take new measurements if available
// Apply a median filter to range finder data
void readRangeFinder ( ) ;
2015-04-17 06:31:00 -03:00
// check if the vehicle has taken off during optical flow navigation by looking at inertial and range finder data
void detectOptFlowTakeoff ( void ) ;
2015-05-19 02:52:13 -03:00
// align the NE earth magnetic field states with the published declination
void alignMagStateDeclination ( ) ;
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-08-25 04:58:42 -03:00
AP_Int8 _gndGradientSigma ; // RMS terrain gradient percentage assumed by the terrain height estimation.
AP_Float _flowNoise ; // optical flow rate measurement noise
AP_Int8 _flowInnovGate ; // Number of standard deviations applied to optical flow innovation consistency check
AP_Int8 _msecFLowDelay ; // effective average delay of optical flow measurements rel to IMU (msec)
AP_Int8 _rngInnovGate ; // Number of standard deviations applied to range finder innovation consistency check
2014-11-10 06:50:49 -04:00
AP_Float _maxFlowRate ; // Maximum flow rate magnitude that will be accepted by the filter
2014-10-31 21:47:55 -03:00
AP_Int8 _fallback ; // EKF-to-DCM fallback strictness. 0 = trust EKF more, 1 = fallback more conservatively.
2015-04-05 21:37:59 -03:00
AP_Int8 _altSource ; // Primary alt source during optical flow navigation. 0 = use Baro, 1 = use range finder.
2014-01-29 04:03:07 -04:00
// Tuning parameters
2014-12-31 21:01:22 -04:00
const float gpsNEVelVarAccScale ; // Scale factor applied to NE velocity measurement variance due to manoeuvre acceleration
const float gpsDVelVarAccScale ; // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration
const float gpsPosVarAccScale ; // Scale factor applied to horizontal position measurement variance due to manoeuvre acceleration
const float msecHgtDelay ; // Height measurement delay (msec)
const uint16_t msecMagDelay ; // Magnetometer measurement delay (msec)
const uint16_t msecTasDelay ; // Airspeed measurement delay (msec)
const uint16_t gpsRetryTimeUseTAS ; // GPS retry time with airspeed measurements (msec)
const uint16_t gpsRetryTimeNoTAS ; // GPS retry time without airspeed measurements (msec)
2015-01-15 08:03:42 -04:00
const uint16_t gpsFailTimeWithFlow ; // If we have no GPs for longer than this and we have optical flow, then we will switch across to using optical flow (msec)
2014-12-31 21:01:22 -04:00
const uint16_t hgtRetryTimeMode0 ; // Height retry time with vertical velocity measurement (msec)
const uint16_t hgtRetryTimeMode12 ; // Height retry time without vertical velocity measurement (msec)
const uint16_t tasRetryTime ; // True airspeed timeout and retry interval (msec)
const uint32_t magFailTimeLimit_ms ; // number of msec before a magnetometer failing innovation consistency checks is declared failed (msec)
const float magVarRateScale ; // scale factor applied to magnetometer variance due to angular rate
2015-03-20 16:14:43 -03:00
const float gyroBiasNoiseScaler ; // scale factor applied to gyro bias state process noise when on ground
const float accelBiasNoiseScaler ; // scale factor applied to accel bias state process noise when on ground
2014-12-31 21:01:22 -04:00
const uint16_t msecGpsAvg ; // average number of msec between GPS measurements
const uint16_t msecHgtAvg ; // average number of msec between height measurements
const uint16_t msecMagAvg ; // average number of msec between magnetometer measurements
const uint16_t msecBetaAvg ; // average number of msec between synthetic sideslip measurements
const uint16_t msecBetaMax ; // maximum number of msec between synthetic sideslip measurements
const uint16_t msecFlowAvg ; // average number of msec between optical flow measurements
const float dtVelPos ; // number of seconds between position and velocity corrections. This should be a multiple of the imu update interval.
const float covTimeStepMax ; // maximum time (sec) between covariance prediction updates
const float covDelAngMax ; // maximum delta angle between covariance prediction updates
const uint32_t TASmsecMax ; // maximum allowed interval between airspeed measurement updates
const float DCM33FlowMin ; // If Tbn(3,3) is less than this number, optical flow measurements will not be fused as tilt is too high.
const float fScaleFactorPnoise ; // Process noise added to focal length scale factor state variance at each time step
const uint8_t flowTimeDeltaAvg_ms ; // average interval between optical flow measurements (msec)
const uint32_t flowIntervalMax_ms ; // maximum allowable time between flow fusion events
2014-01-30 18:16:58 -04:00
2015-04-20 19:41:42 -03:00
// ground effect tuning parameters
const uint16_t gndEffectTimeout_ms ; // time in msec that ground effect mode is active after being activated
const float gndEffectBaroScaler ; // scaler applied to the barometer observation variance when ground effect mode is active
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-12-19 05:58:10 -04:00
bool tasHealth ; // boolean true if true airspeed 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-12-19 05:58:10 -04:00
bool tasTimeout ; // boolean true if true airspeed measurements have failed for too long and have timed out
2014-10-30 04:27:35 -03:00
bool badMag ; // boolean true if the magnetometer is declared to be producing bad data
2014-12-19 05:58:10 -04:00
bool badIMUdata ; // boolean true if the bad IMU data is detected
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
2015-01-08 20:05:07 -04:00
Vector_u32_50 statetimeStamp ; // time stamp for each state vector stored
2014-01-30 18:25:40 -04:00
Vector3f correctedDelAng ; // delta angles about the xyz body axes corrected for errors (rad)
2015-04-23 18:05:57 -03:00
Quaternion correctedDelAngQuat ; // quaternion representation of correctedDelAng
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)
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)
2015-03-21 19:19:30 -03:00
ftype dtIMUavg ; // expected time between IMU measurements (sec)
ftype dtIMUactual ; // time lapsed since the last IMU measurement (sec)
2014-01-30 18:25:40 -04:00
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-10-30 04:27:35 -03:00
bool manoeuvring ; // boolean true when the flight vehicle is performing horizontal changes in velocity
uint32_t airborneDetectTime_ms ; // last time flight movement was detected
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
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
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-08-25 04:58:42 -03:00
uint32_t MAGmsecPrev ; // time stamp of last compass fusion step
uint32_t HGTmsecPrev ; // time stamp of last height measurement fusion step
2014-12-28 20:53:54 -04:00
bool constPosMode ; // true when fusing a constant position to maintain attitude reference for planned operation without GPS or optical flow data
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
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
2014-12-19 05:58:10 -04:00
uint16_t hgtRetryTime ; // time allowed without use of height measurements before a height timeout is declared
2015-04-14 02:51:29 -03:00
uint32_t lastVelPassTime ; // time stamp when GPS velocity measurement last passed innovation consistency check (msec)
uint32_t lastPosPassTime ; // time stamp when GPS position measurement last passed innovation consistency check (msec)
2015-04-15 03:09:04 -03:00
uint32_t lastPosFailTime ; // time stamp when GPS position measurement last failed innovation consistency check (msec)
2015-04-14 02:51:29 -03:00
uint32_t lastHgtPassTime ; // time stamp when height measurement last passed innovation consistency check (msec)
uint32_t lastTasPassTime ; // time stamp when airspeed measurement last passed innovation consistency check (msec)
2014-01-18 17:48:12 -04:00
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-10-16 02:55:09 -03:00
uint32_t timeAtLastAuxEKF_ms ; // last time the auxilliary filter was run to fuse range or optical flow measurements
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-12-21 17:10:30 -04:00
uint32_t ekfStartTime_ms ; // time the EKF was started (msec)
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
2015-01-06 00:21:23 -04:00
Vector2f lastKnownPositionNE ; // last known position
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-12-02 04:32:59 -04:00
bool firstArmComplete ; // true when first transition out of static mode has been performed after start up
2015-02-22 02:43:17 -04:00
bool firstMagYawInit ; // true when the first post takeoff initialisation of earth field and yaw angle has been performed
bool secondMagYawInit ; // true when the second post takeoff initialisation of earth field and yaw angle has been performed
2014-11-14 01:22:16 -04:00
bool flowTimeout ; // true when optical flow measurements have time out
2014-12-20 19:56:50 -04:00
Vector2f gpsVelGlitchOffset ; // Offset applied to the GPS velocity when the gltch radius is being decayed back to zero
2014-12-21 05:41:40 -04:00
bool gpsNotAvailable ; // bool true when valid GPS data is not available
bool vehicleArmed ; // true when the vehicle is disarmed
bool prevVehicleArmed ; // vehicleArmed from previous frame
2015-01-07 22:43:41 -04:00
struct Location EKF_origin ; // LLH origin of the NED axis system - do not change unless filter is reset
bool validOrigin ; // true when the EKF origin is valid
2015-01-27 07:33:18 -04:00
float gpsSpdAccuracy ; // estimated speed accuracy in m/s returned by the UBlox GPS receiver
2015-03-13 21:07:43 -03:00
uint32_t lastGpsVelFail_ms ; // time of last GPS vertical velocity consistency check fail
2015-03-16 19:18:40 -03:00
Vector3f lastMagOffsets ; // magnetometer offsets returned by compass object from previous update
2015-04-15 03:09:04 -03:00
bool gpsAidingBad ; // true when GPS position measurements have been consistently rejected by the filter
uint32_t lastGpsAidBadTime_ms ; // time in msec gps aiding was last detected to be bad
2015-04-20 11:23:56 -03:00
float posDownAtArming ; // flight vehicle vertical position at arming used as a reference point
2015-05-07 20:06:40 -03:00
bool highYawRate ; // true when the vehicle is doing rapid yaw rotation where gyro scel factor errors could cause loss of heading reference
float yawRateFilt ; // filtered yaw rate used to determine when the vehicle is doing rapid yaw rotation where gyro scel factor errors could cause loss of heading reference
2015-06-16 03:16:34 -03:00
bool useGpsVertVel ; // true if GPS vertical velocity should be used
2015-06-23 04:36:11 -03:00
float yawResetAngle ; // Change in yaw angle due to last in-flight yaw reset in radians. A positive value means the yaw angle has increased.
bool yawResetAngleWaiting ; // true when the yaw reset angle has been updated and has not been retrieved via the getLastYawResetAngle() function
2014-08-23 23:02:29 -03:00
// Used by smoothing of state corrections
2015-01-08 20:05:07 -04:00
Vector10 gpsIncrStateDelta ; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next GPS measurement
Vector10 hgtIncrStateDelta ; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next height measurement
Vector10 magIncrStateDelta ; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next magnetometer measurement
2014-08-23 23:02:29 -03:00
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-08-25 04:58:42 -03:00
// variables added for optical flow fusion
bool newDataFlow ; // true when new optical flow data has arrived
2014-12-20 06:30:06 -04:00
bool flowFusePerformed ; // true when optical flow fusion has been performed in that time step
bool flowDataValid ; // true while optical flow data is still fresh
2014-08-25 04:58:42 -03:00
state_elements statesAtFlowTime ; // States at the middle of the optical flow sample period
bool fuseOptFlowData ; // this boolean causes the last optical flow measurement to be fused
2015-01-03 16:56:20 -04:00
float auxFlowObsInnov ; // optical flow rate innovation from 1-state terrain offset estimator
float auxFlowObsInnovVar ; // innovation variance for optical flow observations from 1-state terrain offset estimator
2015-01-08 20:05:07 -04:00
Vector2 flowRadXYcomp ; // motion compensated optical flow angular rates(rad/sec)
Vector2 flowRadXY ; // raw (non motion compensated) optical flow angular rates (rad/sec)
2014-12-19 23:44:14 -04:00
uint32_t flowValidMeaTime_ms ; // time stamp from latest valid flow measurement (msec)
2015-04-05 21:37:59 -03:00
uint32_t rngValidMeaTime_ms ; // time stamp from latest valid range measurement (msec)
2014-08-25 04:58:42 -03:00
uint32_t flowMeaTime_ms ; // time stamp from latest flow measurement (msec)
uint8_t flowQuality ; // unsigned integer representing quality of optical flow data. 255 is maximum quality.
2015-01-02 18:12:23 -04:00
uint32_t gndHgtValidTime_ms ; // time stamp from last terrain offset state update (msec)
2014-08-25 04:58:42 -03:00
Vector3f omegaAcrossFlowTime ; // body angular rates averaged across the optical flow sample period
Matrix3f Tnb_flow ; // transformation matrix from nav to body axes at the middle of the optical flow sample period
Matrix3f Tbn_flow ; // transformation matrix from body to nav axes at the middle of the optical flow sample period
2015-01-08 20:05:07 -04:00
Vector2 varInnovOptFlow ; // optical flow innovations variances (rad/sec)^2
Vector2 innovOptFlow ; // optical flow LOS innovations (rad/sec)
2015-01-03 16:56:20 -04:00
float Popt ; // Optical flow terrain height state covariance (m^2)
float terrainState ; // terrain position state (m)
2014-08-25 04:58:42 -03:00
float prevPosN ; // north position at last measurement
float prevPosE ; // east position at last measurement
state_elements statesAtRngTime ; // States at the range finder measurement time
bool fuseRngData ; // true when fusion of range data is demanded
float varInnovRng ; // range finder observation innovation variance (m^2)
float innovRng ; // range finder observation innovation (m)
float rngMea ; // range finder measurement (m)
bool inhibitGndState ; // true when the terrain position state is to remain constant
2015-01-05 20:34:20 -04:00
uint32_t prevFlowFuseTime_ms ; // time both flow measurement components passed their innovation consistency checks
2015-01-08 20:05:07 -04:00
Vector2 flowTestRatio ; // square of optical flow innovations divided by fail threshold used by main filter where >1.0 is a fail
2015-01-03 16:56:20 -04:00
float auxFlowTestRatio ; // sum of squares of optical flow innovation divided by fail threshold used by 1-state terrain offset estimator
2014-08-25 04:58:42 -03:00
float R_LOS ; // variance of optical flow rate measurements (rad/sec)^2
float auxRngTestRatio ; // square of range finder innovations divided by fail threshold used by main filter where >1.0 is a fail
2014-08-16 05:41:54 -03:00
Vector2f flowGyroBias ; // bias error of optical flow sensor gyro output
2014-09-02 07:01:44 -03:00
uint8_t flowUpdateCount ; // count of the number of minor state corrections using optical flow data
uint8_t flowUpdateCountMax ; // limit on the number of minor state corrections using optical flow data
float flowUpdateCountMaxInv ; // floating point inverse of flowUpdateCountMax
2015-01-08 20:05:07 -04:00
Vector10 flowIncrStateDelta ; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next magnetometer measurement
2014-09-10 06:31:51 -03:00
bool newDataRng ; // true when new valid range finder data has arrived.
2014-12-28 20:53:54 -04:00
bool constVelMode ; // true when fusing a constant velocity to maintain attitude reference when either optical flow or GPS measurements are lost after arming
bool lastConstVelMode ; // last value of holdVelocity
2014-10-28 21:56:39 -03:00
Vector2f heldVelNE ; // velocity held when no aiding is available
2015-01-01 21:00:49 -04:00
enum AidingMode { AID_ABSOLUTE = 0 , // GPS aiding is being used (optical flow may also be used) so position estimates are absolute.
AID_NONE = 1 , // no aiding is being used so only attitude and height estimates are available. Either constVelMode or constPosMode must be used to constrain tilt drift.
AID_RELATIVE = 2 // only optical flow aiding is being used so position estimates will be relative
} ;
AidingMode PV_AidingMode ; // Defines the preferred mode for aiding of velocity and position estimates from the INS
2015-01-03 16:56:20 -04:00
bool gndOffsetValid ; // true when the ground offset state can still be considered valid
2015-01-05 20:34:20 -04:00
bool flowXfailed ; // true when the X optical flow measurement has failed the innovation consistency check
2015-04-17 06:31:00 -03:00
// Range finder
2015-04-05 21:37:59 -03:00
float baroHgtOffset ; // offset applied when baro height used as a backup height reference if range-finder fails
2015-04-17 06:27:02 -03:00
float rngOnGnd ; // Expected range finder reading in metres when vehicle is on ground
2015-04-17 06:31:00 -03:00
// Movement detector
bool takeOffDetected ; // true when takeoff for optical flow navigation has been detected
float rangeAtArming ; // range finder measurement when armed
uint32_t timeAtArming_ms ; // time in msec that the vehicle armed
2014-08-25 04:58:42 -03:00
2015-04-20 19:41:42 -03:00
// IMU processing
2015-04-27 14:16:34 -03:00
float dtDelVel1 ;
float dtDelVel2 ;
2015-02-17 09:19:59 -04:00
2015-04-20 19:41:42 -03:00
// baro ground effect
2015-04-27 18:26:11 -03:00
bool expectGndEffectTakeoff ; // external state from ArduCopter - takeoff expected
uint32_t takeoffExpectedSet_ms ; // system time at which expectGndEffectTakeoff was set
bool expectGndEffectTouchdown ; // external state from ArduCopter - touchdown expected
uint32_t touchdownExpectedSet_ms ; // system time at which expectGndEffectTouchdown was set
2015-04-20 23:04:06 -03:00
float meaHgtAtTakeOff ; // height measured at commencement of takeoff
2015-04-20 19:41:42 -03:00
2015-07-09 04:59:40 -03:00
// monitoring IMU quality
uint32_t lastClipCount1 ; // previous value of clip counter for IMU 1
uint32_t lastClipCount2 ; // previous value of clip counter for IMU 2
float clipRateFilt1 ; // filtered clip rate for IMU 1
float clipRateFilt2 ; // filtered clip rate for IMU 2
2014-08-25 04:58:42 -03:00
// states held by optical flow fusion across time steps
// optical flow X,Y motion compensated rate measurements are fused across two time steps
// to level computational load as this can be an expensive operation
struct {
uint8_t obsIndex ;
2015-04-07 18:00:40 -03:00
Vector4 SH_LOS ;
Vector10 SK_LOS ;
2014-08-25 04:58:42 -03:00
ftype q0 ;
ftype q1 ;
ftype q2 ;
ftype q3 ;
ftype vn ;
ftype ve ;
ftype vd ;
ftype pd ;
2015-01-08 20:05:07 -04:00
Vector2 losPred ;
2014-08-25 04:58:42 -03:00
} flow_state ;
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 ;
2015-01-08 20:05:07 -04:00
Vector9 SH_MAG ;
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 ;
2014-08-25 04:58:42 -03:00
perf_counter_t _perf_OpticalFlowEKF ;
perf_counter_t _perf_FuseOptFlow ;
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 ;
2015-06-30 03:07:51 -03:00
// vehicle specific initial gyro bias uncertainty
float InitialGyroBiasUncertainty ( 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