2015-11-19 13:08:04 -04:00
/****************************************************************************
*
2015-12-06 07:57:43 -04:00
* Copyright ( c ) 2015 Estimation and Control Library ( ECL ) . All rights reserved .
2015-11-19 13:08:04 -04:00
*
* Redistribution and use in source and binary forms , with or without
* modification , are permitted provided that the following conditions
* are met :
*
* 1. Redistributions of source code must retain the above copyright
* notice , this list of conditions and the following disclaimer .
* 2. Redistributions in binary form must reproduce the above copyright
* notice , this list of conditions and the following disclaimer in
* the documentation and / or other materials provided with the
* distribution .
* 3. Neither the name ECL nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission .
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* " AS IS " AND ANY EXPRESS OR IMPLIED WARRANTIES , INCLUDING , BUT NOT
* LIMITED TO , THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED . IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT , INDIRECT ,
* INCIDENTAL , SPECIAL , EXEMPLARY , OR CONSEQUENTIAL DAMAGES ( INCLUDING ,
* BUT NOT LIMITED TO , PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES ; LOSS
* OF USE , DATA , OR PROFITS ; OR BUSINESS INTERRUPTION ) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY , WHETHER IN CONTRACT , STRICT
* LIABILITY , OR TORT ( INCLUDING NEGLIGENCE OR OTHERWISE ) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE , EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/**
* @ file ekf . h
2015-12-06 07:57:43 -04:00
* Class for core functions for ekf attitude and position estimator .
2015-11-19 13:08:04 -04:00
*
2015-12-06 07:57:43 -04:00
* @ author Roman Bast < bapstroman @ gmail . com >
2016-01-28 06:52:39 -04:00
* @ author Paul Riseborough < p_riseborough @ live . com . au >
2015-11-19 13:08:04 -04:00
*
*/
2018-08-30 12:48:38 -03:00
# pragma once
2016-01-31 03:37:34 -04:00
# include "estimator_interface.h"
2015-11-19 13:08:04 -04:00
2016-01-31 03:37:34 -04:00
class Ekf : public EstimatorInterface
2015-11-19 13:08:04 -04:00
{
public :
2017-04-24 18:29:54 -03:00
Ekf ( ) = default ;
2019-03-09 12:57:35 -04:00
virtual ~ Ekf ( ) = default ;
2015-11-19 13:08:04 -04:00
2016-02-13 07:31:02 -04:00
// initialise variables to sane values (also interface class)
2019-10-21 06:09:58 -03:00
bool init ( uint64_t timestamp ) override ;
2016-02-13 07:31:02 -04:00
2019-10-21 06:12:14 -03:00
// set the internal states and status to their default value
void reset ( uint64_t timestamp ) override ;
2019-10-24 12:39:26 -03:00
void resetStatesAndCovariances ( ) override ;
void resetStates ( ) override ;
2016-02-13 07:31:02 -04:00
// should be called every time new data is pushed into the filter
2019-10-21 06:09:58 -03:00
bool update ( ) override ;
2015-11-19 13:08:04 -04:00
2019-10-15 09:49:05 -03:00
void getGpsVelPosInnov ( float hvel [ 2 ] , float & vvel , float hpos [ 2 ] , float & vpos ) ;
2016-01-12 02:30:53 -04:00
2019-10-15 09:49:05 -03:00
void getGpsVelPosInnovVar ( float hvel [ 2 ] , float & vvel , float hpos [ 2 ] , float & vpos ) ;
2017-11-20 20:00:16 -04:00
2019-10-15 09:51:17 -03:00
void getGpsVelPosInnovRatio ( float & hvel , float & vvel , float & hpos , float & vpos ) ;
2016-01-12 02:30:53 -04:00
2019-10-15 09:49:05 -03:00
void getEvVelPosInnov ( float hvel [ 2 ] , float & vvel , float hpos [ 2 ] , float & vpos ) ;
2016-01-12 02:30:53 -04:00
2019-10-15 09:49:05 -03:00
void getEvVelPosInnovVar ( float hvel [ 2 ] , float & vvel , float hpos [ 2 ] , float & vpos ) ;
2016-01-12 02:30:53 -04:00
2019-10-15 09:51:17 -03:00
void getEvVelPosInnovRatio ( float & hvel , float & vvel , float & hpos , float & vpos ) ;
2016-01-12 02:30:53 -04:00
2019-10-15 09:49:05 -03:00
void getAuxVelInnov ( float aux_vel_innov [ 2 ] ) ;
2016-03-11 07:52:38 -04:00
2019-10-15 09:49:05 -03:00
void getAuxVelInnovVar ( float aux_vel_innov [ 2 ] ) ;
2016-03-11 07:52:38 -04:00
2019-10-15 09:51:17 -03:00
void getAuxVelInnovRatio ( float & aux_vel_innov_ratio ) ;
2016-07-12 13:44:32 -03:00
2019-10-15 09:51:17 -03:00
void getFlowInnov ( float flow_innov [ 2 ] ) ;
2016-07-12 13:44:32 -03:00
2019-10-15 09:51:17 -03:00
void getFlowInnovVar ( float flow_innov_var [ 2 ] ) ;
2016-01-12 02:30:53 -04:00
2019-10-15 09:51:17 -03:00
void getFlowInnovRatio ( float & flow_innov_ratio ) ;
2016-03-07 05:14:15 -04:00
2019-10-15 09:51:17 -03:00
void getHeadingInnov ( float & heading_innov ) ;
2016-03-07 05:14:15 -04:00
2019-10-15 09:51:17 -03:00
void getHeadingInnovVar ( float & heading_innov_var ) ;
2017-04-09 20:21:29 -03:00
2019-10-15 09:51:17 -03:00
void getHeadingInnovRatio ( float & heading_innov_ratio ) ;
2017-04-09 20:21:29 -03:00
2019-10-15 09:51:17 -03:00
void getMagInnov ( float mag_innov [ 3 ] ) ;
void getMagInnovVar ( float mag_innov_var [ 3 ] ) ;
void getMagInnovRatio ( float & mag_innov_ratio ) ;
void getDragInnov ( float drag_innov [ 2 ] ) ;
void getDragInnovVar ( float drag_innov_var [ 2 ] ) ;
void getDragInnovRatio ( float drag_innov_ratio [ 2 ] ) ;
void getAirspeedInnov ( float & airspeed_innov ) ;
void getAirspeedInnovVar ( float & airspeed_innov_var ) ;
void getAirspeedInnovRatio ( float & airspeed_innov_ratio ) ;
void getBetaInnov ( float & beta_innov ) ;
void getBetaInnovVar ( float & beta_innov_var ) ;
void getBetaInnovRatio ( float & beta_innov_ratio ) ;
void getHaglInnov ( float & hagl_innov ) ;
void getHaglInnovVar ( float & hagl_innov_var ) ;
void getHaglInnovRatio ( float & hagl_innov_ratio ) ;
2016-03-07 05:14:15 -04:00
2016-01-12 02:30:53 -04:00
// get the state vector at the delayed time horizon
2019-10-21 06:09:58 -03:00
void get_state_delayed ( float * state ) override ;
2016-01-12 02:30:53 -04:00
2016-07-12 06:40:41 -03:00
// get the wind velocity in m/s
2019-10-21 06:09:58 -03:00
void get_wind_velocity ( float * wind ) override ;
2016-07-12 06:40:41 -03:00
2017-10-02 09:47:56 -03:00
// get the wind velocity var
2019-10-21 06:09:58 -03:00
void get_wind_velocity_var ( float * wind_var ) override ;
2017-10-02 09:47:56 -03:00
2017-08-06 20:19:48 -03:00
// get the true airspeed in m/s
2019-10-21 06:09:58 -03:00
void get_true_airspeed ( float * tas ) override ;
2017-08-06 20:19:48 -03:00
2019-03-09 12:57:35 -04:00
// get the full covariance matrix
matrix : : SquareMatrix < float , 24 > covariances ( ) const { return matrix : : SquareMatrix < float , _k_num_states > ( P ) ; }
2016-01-12 02:30:53 -04:00
// get the diagonal elements of the covariance matrix
2019-03-09 12:57:35 -04:00
matrix : : Vector < float , 24 > covariances_diagonal ( ) const { return covariances ( ) . diag ( ) ; }
// get the orientation (quaterion) covariances
matrix : : SquareMatrix < float , 4 > orientation_covariances ( ) const { return covariances ( ) . slice < 4 , 4 > ( 0 , 0 ) ; }
// get the linear velocity covariances
matrix : : SquareMatrix < float , 3 > velocity_covariances ( ) const { return covariances ( ) . slice < 3 , 3 > ( 4 , 4 ) ; }
// get the position covariances
matrix : : SquareMatrix < float , 3 > position_covariances ( ) const { return covariances ( ) . slice < 3 , 3 > ( 7 , 7 ) ; }
2016-01-12 02:30:53 -04:00
2016-01-31 04:01:44 -04:00
// ask estimator for sensor data collection decision and do any preprocessing if required, returns true if not defined
2019-10-21 06:09:58 -03:00
bool collect_gps ( const gps_message & gps ) override ;
2018-07-04 18:59:35 -03:00
2019-10-21 06:09:58 -03:00
bool collect_imu ( const imuSample & imu ) override ;
2016-01-29 21:15:18 -04:00
2016-01-31 16:36:58 -04:00
// get the ekf WGS-84 origin position and height and the system time it was last set
2016-12-27 19:38:05 -04:00
// return true if the origin is valid
2019-10-21 06:09:58 -03:00
bool get_ekf_origin ( uint64_t * origin_time , map_projection_reference_s * origin_pos , float * origin_alt ) override ;
2016-01-28 06:52:39 -04:00
2016-02-22 17:35:38 -04:00
// get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position
2019-10-21 06:09:58 -03:00
void get_ekf_gpos_accuracy ( float * ekf_eph , float * ekf_epv ) override ;
2016-02-22 17:35:38 -04:00
2017-02-23 18:25:39 -04:00
// get the 1-sigma horizontal and vertical position uncertainty of the ekf local position
2019-10-21 06:09:58 -03:00
void get_ekf_lpos_accuracy ( float * ekf_eph , float * ekf_epv ) override ;
2017-02-23 18:25:39 -04:00
2017-02-23 18:56:45 -04:00
// get the 1-sigma horizontal and vertical velocity uncertainty
2019-10-21 06:09:58 -03:00
void get_ekf_vel_accuracy ( float * ekf_evh , float * ekf_evv ) override ;
2017-02-23 18:56:45 -04:00
2018-05-19 15:16:08 -03:00
// get the vehicle control limits required by the estimator to keep within sensor limitations
2019-10-21 06:09:58 -03:00
void get_ekf_ctrl_limits ( float * vxy_max , float * vz_max , float * hagl_min , float * hagl_max ) override ;
2017-09-18 19:38:19 -03:00
2017-10-25 20:41:39 -03:00
/*
Reset all IMU bias states and covariances to initial alignment values .
Use when the IMU sensor has changed .
Returns true if reset performed , false if rejected due to less than 10 seconds lapsed since last reset .
*/
2019-10-21 06:09:58 -03:00
bool reset_imu_bias ( ) override ;
2017-10-25 20:41:39 -03:00
2019-10-21 06:09:58 -03:00
void get_vel_var ( Vector3f & vel_var ) override ;
2016-03-07 05:14:15 -04:00
2019-10-21 06:09:58 -03:00
void get_pos_var ( Vector3f & pos_var ) override ;
2016-03-07 05:14:15 -04:00
2016-08-13 20:08:44 -03:00
// return an array containing the output predictor angular, velocity and position tracking
2017-07-19 05:26:19 -03:00
// error magnitudes (rad), (m/sec), (m)
2019-10-21 06:09:58 -03:00
void get_output_tracking_error ( float error [ 3 ] ) override ;
2016-08-13 20:08:44 -03:00
2016-10-18 01:24:43 -03:00
/*
Returns following IMU vibration metrics in the following array locations
0 : Gyro delta angle coning metric = filtered length of ( delta_angle x prev_delta_angle )
1 : Gyro high frequency vibe = filtered length of ( delta_angle - prev_delta_angle )
2 : Accel high frequency vibe = filtered length of ( delta_velocity - prev_delta_velocity )
*/
2019-10-21 06:09:58 -03:00
void get_imu_vibe_metrics ( float vibe [ 3 ] ) override ;
2016-10-18 01:24:43 -03:00
2018-08-03 00:24:31 -03:00
/*
First argument returns GPS drift metrics in the following array locations
0 : Horizontal position drift rate ( m / s )
1 : Vertical position drift rate ( m / s )
2 : Filtered horizontal velocity ( m / s )
Second argument returns true when IMU movement is blocking the drift calculation
Function returns true if the metrics have been updated and not returned previously by this function
*/
2019-10-21 06:09:58 -03:00
bool get_gps_drift_metrics ( float drift [ 3 ] , bool * blocked ) override ;
2018-08-03 00:24:31 -03:00
2016-03-07 05:14:15 -04:00
// return true if the global position estimate is valid
2019-10-21 06:09:58 -03:00
bool global_position_is_valid ( ) override ;
2016-03-07 05:14:15 -04:00
2018-03-21 19:31:52 -03:00
// check if the EKF is dead reckoning horizontal velocity using inertial data only
void update_deadreckoning_status ( ) ;
2017-02-23 06:24:28 -04:00
2019-11-08 11:02:59 -04:00
bool isTerrainEstimateValid ( ) const override ;
2017-07-19 04:52:35 -03:00
2019-10-10 11:36:48 -03:00
void updateTerrainValidity ( ) ;
2018-04-09 05:35:15 -03:00
2017-07-19 04:52:35 -03:00
// get the estimated terrain vertical position relative to the NED origin
2019-10-21 06:09:58 -03:00
void getTerrainVertPos ( float * ret ) override ;
2016-03-07 05:14:15 -04:00
2019-02-06 09:49:16 -04:00
// get the terrain variance
float get_terrain_var ( ) const { return _terrain_var ; }
2019-03-18 11:20:33 -03:00
// get the accelerometer bias in m/s/s
2019-10-21 06:09:58 -03:00
void get_accel_bias ( float bias [ 3 ] ) override ;
2016-04-11 09:12:24 -03:00
2016-06-21 08:51:04 -03:00
// get the gyroscope bias in rad/s
2019-10-21 06:09:58 -03:00
void get_gyro_bias ( float bias [ 3 ] ) override ;
2016-06-21 08:51:04 -03:00
2016-04-16 00:38:40 -03:00
// get GPS check status
2019-10-21 06:09:58 -03:00
void get_gps_check_status ( uint16_t * val ) override ;
2016-04-16 00:38:40 -03:00
2016-05-25 05:24:31 -03:00
// return the amount the local vertical position changed in the last reset and the number of reset events
2019-10-21 06:09:58 -03:00
void get_posD_reset ( float * delta , uint8_t * counter ) override { * delta = _state_reset_status . posD_change ; * counter = _state_reset_status . posD_counter ; }
2016-05-23 06:57:05 -03:00
2016-05-25 05:24:31 -03:00
// return the amount the local vertical velocity changed in the last reset and the number of reset events
2019-10-21 06:09:58 -03:00
void get_velD_reset ( float * delta , uint8_t * counter ) override { * delta = _state_reset_status . velD_change ; * counter = _state_reset_status . velD_counter ; }
2016-05-23 06:57:05 -03:00
2016-05-25 05:24:31 -03:00
// return the amount the local horizontal position changed in the last reset and the number of reset events
2019-10-21 06:09:58 -03:00
void get_posNE_reset ( float delta [ 2 ] , uint8_t * counter ) override
2017-04-24 18:29:54 -03:00
{
2019-09-17 06:54:19 -03:00
_state_reset_status . posNE_change . copyTo ( delta ) ;
2016-06-06 04:40:32 -03:00
* counter = _state_reset_status . posNE_counter ;
}
2016-05-23 06:57:05 -03:00
2016-05-25 05:24:31 -03:00
// return the amount the local horizontal velocity changed in the last reset and the number of reset events
2019-10-21 06:09:58 -03:00
void get_velNE_reset ( float delta [ 2 ] , uint8_t * counter ) override
2017-04-24 18:29:54 -03:00
{
2019-09-17 06:54:19 -03:00
_state_reset_status . velNE_change . copyTo ( delta ) ;
2016-06-06 04:40:32 -03:00
* counter = _state_reset_status . velNE_counter ;
}
2016-04-21 19:30:46 -03:00
2016-05-25 05:24:31 -03:00
// return the amount the quaternion has changed in the last reset and the number of reset events
2019-10-21 06:09:58 -03:00
void get_quat_reset ( float delta_quat [ 4 ] , uint8_t * counter ) override
2016-05-23 08:07:35 -03:00
{
2019-09-17 06:54:19 -03:00
_state_reset_status . quat_change . copyTo ( delta_quat ) ;
2016-05-25 05:24:31 -03:00
* counter = _state_reset_status . quat_counter ;
2016-05-23 08:07:35 -03:00
}
2016-10-05 02:52:21 -03:00
// get EKF innovation consistency check status information comprising of:
// status - a bitmask integer containing the pass/fail status for each EKF measurement innovation consistency check
// Innovation Test Ratios - these are the ratio of the innovation to the acceptance threshold.
// A value > 1 indicates that the sensor measurement has exceeded the maximum acceptable level and has been rejected by the EKF
2019-03-18 11:20:33 -03:00
// Where a measurement type is a vector quantity, eg magnetometer, GPS position, etc, the maximum value is returned.
2019-10-15 09:51:17 -03:00
void get_innovation_test_status ( uint16_t & status , float & mag , float & gps_vel , float & gps_pos , float & ev_vel , float & ev_pos , float & hgt , float & tas , float & hagl , float & beta ) ;
2016-10-05 02:52:21 -03:00
2016-10-05 20:11:57 -03:00
// return a bitmask integer that describes which state estimates can be used for flight control
2019-10-21 06:09:58 -03:00
void get_ekf_soln_status ( uint16_t * status ) override ;
2016-10-05 20:11:57 -03:00
2019-08-28 04:56:43 -03:00
// return the quaternion defining the rotation from the External Vision to the EKF reference frame
2019-10-21 06:09:58 -03:00
void get_ev2ekf_quaternion ( float * quat ) override ;
2017-10-22 18:28:22 -03:00
2018-07-04 18:59:35 -03:00
// use the latest IMU data at the current time horizon.
Quatf calculate_quaternion ( ) const ;
2019-05-15 04:36:11 -03:00
// set minimum continuous period without GPS fail required to mark a healthy GPS status
void set_min_required_gps_health_time ( uint32_t time_us ) { _min_gps_health_time_us = time_us ; }
2015-11-19 13:08:04 -04:00
private :
2017-07-19 05:26:19 -03:00
static constexpr uint8_t _k_num_states { 24 } ; ///< number of EKF states
2015-12-07 04:26:30 -04:00
2016-05-23 06:56:25 -03:00
struct {
2017-07-19 05:26:19 -03:00
uint8_t velNE_counter ; ///< number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_t velD_counter ; ///< number of vertical velocity reset events (allow to wrap if count exceeds 255)
uint8_t posNE_counter ; ///< number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8_t posD_counter ; ///< number of vertical position reset events (allow to wrap if count exceeds 255)
uint8_t quat_counter ; ///< number of quaternion reset events (allow to wrap if count exceeds 255)
Vector2f velNE_change ; ///< North East velocity change due to last reset (m)
float velD_change ; ///< Down velocity change due to last reset (m/sec)
Vector2f posNE_change ; ///< North, East position change due to last reset (m)
float posD_change ; ///< Down position change due to last reset (m)
Quatf quat_change ; ///< quaternion delta due to last reset - multiply pre-reset quaternion by this to get post-reset quaternion
} _state_reset_status { } ; ///< reset event monitoring structure containing velocity, position, height and yaw reset information
2018-07-04 19:55:22 -03:00
float _dt_ekf_avg { FILTER_UPDATE_PERIOD_S } ; ///< average update rate of the ekf
2017-07-19 05:26:19 -03:00
float _dt_update { 0.01f } ; ///< delta time since last ekf update. This time can be used for filters which run at the same rate as the Ekf::update() function. (sec)
stateSample _state { } ; ///< state struct of the ekf running at the delayed time horizon
bool _filter_initialised { false } ; ///< true when the EKF sttes and covariances been initialised
bool _earth_rate_initialised { false } ; ///< true when we know the earth rotatin rate (requires GPS)
bool _fuse_height { false } ; ///< true when baro height data should be fused
bool _fuse_pos { false } ; ///< true when gps position data should be fused
bool _fuse_hor_vel { false } ; ///< true when gps horizontal velocity measurement should be fused
bool _fuse_vert_vel { false } ; ///< true when gps vertical velocity measurement should be fused
2017-11-20 20:00:16 -04:00
bool _fuse_hor_vel_aux { false } ; ///< true when auxiliary horizontal velocity measurement should be fused
2016-06-07 03:54:12 -03:00
2017-07-26 04:10:52 -03:00
// variables used when position data is being fused using a relative position odometry model
2017-10-22 18:28:22 -03:00
bool _fuse_hpos_as_odom { false } ; ///< true when the NE position data is being fused using an odometry assumption
Vector3f _pos_meas_prev ; ///< previous value of NED position measurement fused using odometry assumption (m)
2017-07-26 04:10:52 -03:00
Vector2f _hpos_pred_prev ; ///< previous value of NE position state used by odometry fusion (m)
bool _hpos_prev_available { false } ; ///< true when previous values of the estimate and measurement are available for use
2019-09-17 04:12:06 -03:00
Vector3f _ev_rot_vec_filt ; ///< filtered rotation vector defining the rotation EV to EKF reference, initiliazied to zero rotation (rad)
Dcmf _ev_rot_mat ; ///< transformation matrix that rotates observations from the EV to the EKF navigation frame, initialized with Identity
uint64_t _ev_rot_last_time_us { 0 } ; ///< previous time that the calculation of the EV to EKF rotation matrix was updated (uSec)
2019-09-23 05:28:06 -03:00
bool _ev_rot_mat_initialised { 0 } ; ///< _ev_rot_mat should only be initialised once in the beginning through the reset function
2017-07-26 04:10:52 -03:00
2016-06-07 03:54:12 -03:00
// booleans true when fresh sensor data is available at the fusion time horizon
2017-07-19 05:26:19 -03:00
bool _gps_data_ready { false } ; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused
bool _mag_data_ready { false } ; ///< true when new magnetometer data has fallen behind the fusion time horizon and is available to be fused
bool _baro_data_ready { false } ; ///< true when new baro height data has fallen behind the fusion time horizon and is available to be fused
bool _range_data_ready { false } ; ///< true when new range finder data has fallen behind the fusion time horizon and is available to be fused
2018-06-13 03:51:42 -03:00
bool _flow_data_ready { false } ; ///< true when the leading edge of the optical flow integration period has fallen behind the fusion time horizon
2017-07-19 05:26:19 -03:00
bool _ev_data_ready { false } ; ///< true when new external vision system data has fallen behind the fusion time horizon and is available to be fused
bool _tas_data_ready { false } ; ///< true when new true airspeed data has fallen behind the fusion time horizon and is available to be fused
2019-04-14 08:00:48 -03:00
bool _flow_for_terrain_data_ready { false } ; /// same flag as "_flow_data_ready" but used for separate terrain estimator
2017-04-24 18:29:54 -03:00
2019-10-15 09:49:05 -03:00
uint64_t _time_last_fake_pos { 0 } ; ///< last time we faked position measurements to constrain tilt errors during operation without external aiding (uSec)
2018-03-21 19:31:52 -03:00
uint64_t _time_ins_deadreckon_start { 0 } ; ///< amount of time we have been doing inertial only deadreckoning (uSec)
2018-04-18 22:03:50 -03:00
bool _using_synthetic_position { false } ; ///< true if we are using a synthetic position to constrain drift
2017-04-24 18:29:54 -03:00
2019-10-29 06:58:01 -03:00
// TODO: Split those into sensor and measurement specifics
uint64_t _time_last_hor_pos_fuse { 0 } ; ///< time the last fusion of horizontal position measurements was performed (uSec)
uint64_t _time_last_hgt_fuse { 0 } ; ///< time the last fusion of vertical position measurements was performed (uSec)
uint64_t _time_last_hor_vel_fuse { 0 } ; ///< time the last fusion of horizontal velocity measurements was performed (uSec)
uint64_t _time_last_ver_vel_fuse { 0 } ; ///< time the last fusion of verticalvelocity measurements was performed (uSec)
2017-10-22 18:28:22 -03:00
uint64_t _time_last_delpos_fuse { 0 } ; ///< time the last fusion of incremental horizontal position measurements was performed (uSec)
2017-07-19 05:26:19 -03:00
uint64_t _time_last_of_fuse { 0 } ; ///< time the last fusion of optical flow measurements were performed (uSec)
uint64_t _time_last_arsp_fuse { 0 } ; ///< time the last fusion of airspeed measurements were performed (uSec)
uint64_t _time_last_beta_fuse { 0 } ; ///< time the last fusion of synthetic sideslip measurements were performed (uSec)
2017-07-31 12:59:16 -03:00
uint64_t _time_last_rng_ready { 0 } ; ///< time the last range finder measurement was ready (uSec)
2019-10-15 09:49:05 -03:00
Vector2f _last_known_posNE { } ; ///< last known local NE position vector (m)
2017-07-19 05:26:19 -03:00
float _imu_collection_time_adj { 0.0f } ; ///< the amount of time the IMU collection needs to be advanced to meet the target set by FILTER_UPDATE_PERIOD_MS (sec)
2015-12-22 06:22:17 -04:00
2017-07-19 05:26:19 -03:00
uint64_t _time_acc_bias_check { 0 } ; ///< last time the accel bias check passed (uSec)
uint64_t _delta_time_baro_us { 0 } ; ///< delta time between two consecutive delayed baro samples from the buffer (uSec)
2017-02-27 00:50:24 -04:00
2017-10-25 20:41:39 -03:00
uint64_t _last_imu_bias_cov_reset_us { 0 } ; ///< time the last reset of IMU delta angle and velocity state covariances was performed (uSec)
2017-07-19 05:26:19 -03:00
Vector3f _earth_rate_NED ; ///< earth rotation vector (NED) in rad/s
2015-12-07 04:26:30 -04:00
2019-03-18 11:20:33 -03:00
Dcmf _R_to_earth ; ///< transformation matrix from body frame to earth frame from last EKF prediction
2015-12-07 04:26:30 -04:00
2017-05-16 05:50:19 -03:00
// used by magnetometer fusion mode selection
2017-07-19 05:26:19 -03:00
Vector2f _accel_lpf_NE ; ///< Low pass filtered horizontal earth frame acceleration (m/sec**2)
float _yaw_delta_ef { 0.0f } ; ///< Recent change in yaw angle measured about the earth frame D axis (rad)
float _yaw_rate_lpf_ef { 0.0f } ; ///< Filtered angular rate about earth frame D axis (rad/sec)
bool _mag_bias_observable { false } ; ///< true when there is enough rotation to make magnetometer bias errors observable
bool _yaw_angle_observable { false } ; ///< true when there is enough horizontal acceleration to make yaw observable
2019-03-18 11:20:33 -03:00
uint64_t _time_yaw_started { 0 } ; ///< last system time in usec that a yaw rotation manoeuvre was detected
2017-07-29 20:39:02 -03:00
uint8_t _num_bad_flight_yaw_events { 0 } ; ///< number of times a bad heading has been detected in flight and required a yaw reset
2019-03-18 11:20:33 -03:00
uint64_t _mag_use_not_inhibit_us { 0 } ; ///< last system time in usec before magnetometer use was inhibited
bool _mag_use_inhibit { false } ; ///< true when magnetometer use is being inhibited
bool _mag_use_inhibit_prev { false } ; ///< true when magnetometer use was being inhibited the previous frame
bool _mag_inhibit_yaw_reset_req { false } ; ///< true when magnetometer inhibit has been active for long enough to require a yaw reset when conditions improve.
2018-05-15 22:16:02 -03:00
float _last_static_yaw { 0.0f } ; ///< last yaw angle recorded when on ground motion checks were passing (rad)
2019-03-18 11:20:33 -03:00
bool _mag_yaw_reset_req { false } ; ///< true when a reset of the yaw using the magnetometer data has been requested
2019-01-21 17:58:01 -04:00
bool _mag_decl_cov_reset { false } ; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event.
2019-09-04 14:51:39 -03:00
bool _synthetic_mag_z_active { false } ; ///< true if we are generating synthetic magnetometer Z measurements
2017-05-11 20:14:39 -03:00
2017-07-19 05:26:19 -03:00
float P [ _k_num_states ] [ _k_num_states ] { } ; ///< state covariance matrix
2015-12-06 07:57:43 -04:00
2019-05-08 07:10:08 -03:00
Vector3f _delta_vel_bias_var_accum ; ///< kahan summation algorithm accumulator for delta velocity bias variance
Vector3f _delta_angle_bias_var_accum ; ///< kahan summation algorithm accumulator for delta angle bias variance
2016-03-07 05:14:15 -04:00
2019-10-29 06:58:01 -03:00
Vector3f _gps_vel_innov { } ; ///< GPS velocity innovations (m/sec)
Vector3f _gps_vel_innov_var { } ; ///< GPS velocity innovation variances ((m/sec)**2)
2019-10-15 09:49:05 -03:00
2019-10-29 06:58:01 -03:00
Vector3f _gps_pos_innov { } ; ///< GPS position innovations (m)
Vector3f _gps_pos_innov_var { } ; ///< GPS position innovation variances (m**2)
2019-10-15 09:49:05 -03:00
2019-10-29 06:58:01 -03:00
Vector3f _ev_vel_innov { } ; ///< external vision velocity innovations (m/sec)
Vector3f _ev_vel_innov_var { } ; ///< external vision velocity innovation variances ((m/sec)**2)
2019-10-15 09:49:05 -03:00
2019-10-29 06:58:01 -03:00
Vector3f _ev_pos_innov { } ; ///< external vision position innovations (m)
Vector3f _ev_pos_innov_var { } ; ///< external vision position innovation variances (m**2)
Vector3f _aux_vel_innov { } ; ///< horizontal auxiliary velocity innovations: (m/sec)
Vector3f _aux_vel_innov_var { } ; ///< horizontal auxiliary velocity innovation variances: ((m/sec)**2)
2019-10-15 09:51:17 -03:00
float _heading_innov { 0.0f } ; ///< heading measurement innovation (rad)
float _heading_innov_var { 0.0f } ; ///< heading measurement innovation variance (rad**2)
2017-07-19 05:26:19 -03:00
float _mag_innov [ 3 ] { } ; ///< earth magnetic field innovations (Gauss)
float _mag_innov_var [ 3 ] { } ; ///< earth magnetic field innovation variance (Gauss**2)
2016-03-07 05:14:15 -04:00
2019-10-15 09:51:17 -03:00
float _drag_innov [ 2 ] { } ; ///< multirotor drag measurement innovation (m/sec**2)
float _drag_innov_var [ 2 ] { } ; ///< multirotor drag measurement innovation variance ((m/sec**2)**2)
2017-07-19 05:26:19 -03:00
float _airspeed_innov { 0.0f } ; ///< airspeed measurement innovation (m/sec)
float _airspeed_innov_var { 0.0f } ; ///< airspeed measurement innovation variance ((m/sec)**2)
2016-03-11 07:52:38 -04:00
2017-07-19 05:26:19 -03:00
float _beta_innov { 0.0f } ; ///< synthetic sideslip measurement innovation (rad)
float _beta_innov_var { 0.0f } ; ///< synthetic sideslip measurement innovation variance (rad**2)
2016-07-12 13:44:32 -03:00
2019-10-15 09:51:17 -03:00
float _hagl_innov { 0.0f } ; ///< innovation of the last height above terrain measurement (m)
float _hagl_innov_var { 0.0f } ; ///< innovation variance for the last height above terrain measurement (m**2)
2016-03-07 05:14:15 -04:00
// optical flow processing
2017-07-19 05:26:19 -03:00
float _flow_innov [ 2 ] { } ; ///< flow measurement innovation (rad/sec)
float _flow_innov_var [ 2 ] { } ; ///< flow innovation variance ((rad/sec)**2)
Vector3f _flow_gyro_bias ; ///< bias errors in optical flow sensor rate gyro outputs (rad/sec)
Vector3f _imu_del_ang_of ; ///< bias corrected delta angle measurements accumulated across the same time frame as the optical flow rates (rad)
float _delta_time_of { 0.0f } ; ///< time in sec that _imu_del_ang_of was accumulated over (sec)
2018-04-09 05:35:15 -03:00
uint64_t _time_bad_motion_us { 0 } ; ///< last system time that on-ground motion exceeded limits (uSec)
uint64_t _time_good_motion_us { 0 } ; ///< last system time that on-ground motion was within limits (uSec)
2018-05-18 00:57:11 -03:00
bool _inhibit_flow_use { false } ; ///< true when use of optical flow and range finder is being inhibited
2018-06-12 02:52:34 -03:00
Vector2f _flowRadXYcomp ; ///< measured delta angle of the image about the X and Y body axes after removal of body rotation (rad), RH rotation is positive
2016-01-12 02:30:53 -04:00
2016-07-23 19:22:52 -03:00
// output predictor states
2017-07-19 05:26:19 -03:00
Vector3f _delta_angle_corr ; ///< delta angle correction vector (rad)
imuSample _imu_down_sampled { } ; ///< down sampled imu data (sensor rate -> filter update rate)
Quatf _q_down_sampled ; ///< down sampled quaternion (tracking delta angles between ekf update steps)
Vector3f _vel_err_integ ; ///< integral of velocity tracking error (m)
Vector3f _pos_err_integ ; ///< integral of position tracking error (m.s)
float _output_tracking_error [ 3 ] { } ; ///< contains the magnitude of the angle, velocity and position track errors (rad, m/s, m)
2015-12-10 11:36:10 -04:00
2016-01-31 04:01:44 -04:00
// variables used for the GPS quality checks
2017-07-19 05:26:19 -03:00
float _gpsDriftVelN { 0.0f } ; ///< GPS north position derivative (m/sec)
float _gpsDriftVelE { 0.0f } ; ///< GPS east position derivative (m/sec)
float _gps_drift_velD { 0.0f } ; ///< GPS down position derivative (m/sec)
float _gps_velD_diff_filt { 0.0f } ; ///< GPS filtered Down velocity (m/sec)
float _gps_velN_filt { 0.0f } ; ///< GPS filtered North velocity (m/sec)
float _gps_velE_filt { 0.0f } ; ///< GPS filtered East velocity (m/sec)
uint64_t _last_gps_fail_us { 0 } ; ///< last system time in usec that the GPS failed it's checks
2018-02-25 23:56:20 -04:00
uint64_t _last_gps_pass_us { 0 } ; ///< last system time in usec that the GPS passed it's checks
2018-05-18 00:57:11 -03:00
float _gps_error_norm { 1.0f } ; ///< normalised gps error
2019-05-15 04:36:11 -03:00
uint32_t _min_gps_health_time_us { 10000000 } ; ///< GPS is marked as healthy only after this amount of time
2019-05-29 19:53:29 -03:00
bool _gps_checks_passed { false } ; ///> true when all active GPS checks have passed
2016-01-28 06:52:39 -04:00
2016-01-31 04:01:44 -04:00
// Variables used to publish the WGS-84 location of the EKF local NED origin
2017-07-19 05:26:19 -03:00
uint64_t _last_gps_origin_time_us { 0 } ; ///< time the origin was last set (uSec)
float _gps_alt_ref { 0.0f } ; ///< WGS-84 height (m)
2016-01-28 06:52:39 -04:00
2016-02-23 22:57:27 -04:00
// Variables used to initialise the filter states
2017-07-19 05:26:19 -03:00
uint32_t _hgt_counter { 0 } ; ///< number of height samples read during initialisation
float _rng_filt_state { 0.0f } ; ///< filtered height measurement (m)
uint32_t _mag_counter { 0 } ; ///< number of magnetometer samples read during initialisation
uint32_t _ev_counter { 0 } ; ///< number of external vision samples read during initialisation
uint64_t _time_last_mag { 0 } ; ///< measurement time of last magnetomter sample (uSec)
2019-11-08 11:02:59 -04:00
AlphaFilterVector3f _mag_lpf ; ///< filtered magnetometer measurement (Gauss)
2017-07-19 05:26:19 -03:00
Vector3f _delVel_sum ; ///< summed delta velocity (m/sec)
float _hgt_sensor_offset { 0.0f } ; ///< set as necessary if desired to maintain the same height after a height reset (m)
float _baro_hgt_offset { 0.0f } ; ///< baro height reading at the local NED origin (m)
2016-06-06 08:59:46 -03:00
// Variables used to control activation of post takeoff functionality
2017-07-19 05:26:19 -03:00
float _last_on_ground_posD { 0.0f } ; ///< last vertical position when the in_air status was false (m)
2017-11-08 19:29:28 -04:00
bool _flt_mag_align_converging { false } ; ///< true when the in-flight mag field post alignment convergence is being performd
uint64_t _flt_mag_align_start_time { 0 } ; ///< time that inflight magnetic field alignment started (uSec)
2019-11-08 11:02:59 -04:00
uint64_t _time_last_mov_3d_mag_suitable { 0 } ; ///< last system time that sufficient movement to use 3-axis magnetometer fusion was detected (uSec)
2019-01-16 23:51:24 -04:00
float _saved_mag_bf_variance [ 4 ] { } ; ///< magnetic field state variances that have been saved for use at the next initialisation (Gauss**2)
float _saved_mag_ef_covmat [ 2 ] [ 2 ] { } ; ///< NE magnetic field state covariance sub-matrix saved for use at the next initialisation (Gauss**2)
2017-11-08 19:16:48 -04:00
bool _velpos_reset_request { false } ; ///< true when a large yaw error has been fixed and a velocity and position state reset is required
2016-01-30 16:44:19 -04:00
2017-02-05 14:05:10 -04:00
gps_check_fail_status_u _gps_check_fail_status { } ;
2016-01-28 06:52:39 -04:00
2017-03-01 20:54:10 -04:00
// variables used to inhibit accel bias learning
2017-07-19 05:26:19 -03:00
bool _accel_bias_inhibit { false } ; ///< true when the accel bias learning is being inhibited
2018-05-08 18:47:17 -03:00
Vector3f _accel_vec_filt { } ; ///< acceleration vector after application of a low pass filter (m/sec**2)
float _accel_mag_filt { 0.0f } ; ///< acceleration magnitude after application of a decaying envelope filter (rad/sec)
2017-07-19 05:26:19 -03:00
float _ang_rate_mag_filt { 0.0f } ; ///< angular rate magnitude after application of a decaying envelope filter (rad/sec)
Vector3f _prev_dvel_bias_var ; ///< saved delta velocity XYZ bias variances (m/sec)**2
2017-03-01 20:54:10 -04:00
2016-03-07 05:14:15 -04:00
// Terrain height state estimation
2017-07-19 05:26:19 -03:00
float _terrain_vpos { 0.0f } ; ///< estimated vertical position of the terrain underneath the vehicle in local NED frame (m)
float _terrain_var { 1e4 f } ; ///< variance of terrain position estimate (m**2)
2017-11-23 23:28:17 -04:00
uint64_t _time_last_hagl_fuse { 0 } ; ///< last system time that the hagl measurement failed it's checks (uSec)
2019-03-18 11:20:33 -03:00
bool _terrain_initialised { false } ; ///< true when the terrain estimator has been initialized
2017-07-19 05:26:19 -03:00
float _sin_tilt_rng { 0.0f } ; ///< sine of the range finder tilt rotation about the Y body axis
float _cos_tilt_rng { 0.0f } ; ///< cosine of the range finder tilt rotation about the Y body axis
float _R_rng_to_earth_2_2 { 0.0f } ; ///< 2,2 element of the rotation matrix from sensor frame to earth frame
float _dt_last_range_update_filt_us { 0.0f } ; ///< filtered value of the delta time elapsed since the last range measurement came into the filter (uSec)
2018-04-09 05:35:15 -03:00
bool _hagl_valid { false } ; ///< true when the height above ground estimate is valid
2016-03-07 05:14:15 -04:00
2019-05-29 19:53:29 -03:00
// height sensor status
2017-07-19 05:26:19 -03:00
bool _baro_hgt_faulty { false } ; ///< true if valid baro data is unavailable for use
2019-05-29 19:53:29 -03:00
bool _gps_hgt_intermittent { false } ; ///< true if gps height into the buffer is intermittent
2019-10-14 03:17:56 -03:00
bool _rng_hgt_valid { false } ; ///< true if range finder sample retrieved from buffer is valid
2017-07-19 05:26:19 -03:00
int _primary_hgt_source { VDIST_SENSOR_BARO } ; ///< specifies primary source of height data
2019-10-14 03:17:56 -03:00
uint64_t _time_bad_rng_signal_quality { 0 } ; ///< timestamp at which range finder signal quality was 0 (used for hysteresis)
2016-03-15 03:07:33 -03:00
2016-04-21 20:24:04 -03:00
// imu fault status
2017-07-19 05:26:19 -03:00
uint64_t _time_bad_vert_accel { 0 } ; ///< last time a bad vertical accel was detected (uSec)
uint64_t _time_good_vert_accel { 0 } ; ///< last time a good vertical accel was detected (uSec)
bool _bad_vert_accel_detected { false } ; ///< true when bad vertical accelerometer data has been detected
2016-04-21 20:24:04 -03:00
2017-07-19 05:26:19 -03:00
// variables used to control range aid functionality
2019-10-14 09:28:18 -03:00
bool _is_range_aid_suitable { false } ; ///< true when range finder can be used in flight as the height reference instead of the primary height sensor
2018-05-02 20:44:32 -03:00
bool _range_aid_mode_selected { false } ; ///< true when range finder is being used as the height reference instead of the primary height sensor
2017-04-06 05:07:55 -03:00
2018-07-11 19:50:26 -03:00
// variables used to check range finder validity data
float _rng_stuck_min_val { 0.0f } ; ///< minimum value for new rng measurement when being stuck
float _rng_stuck_max_val { 0.0f } ; ///< maximum value for new rng measurement when being stuck
2017-07-31 12:59:16 -03:00
2018-10-24 11:36:52 -03:00
float _height_rate_lpf { 0.0f } ;
2016-02-13 07:31:02 -04:00
// update the real time complementary filter states. This includes the prediction
// and the correction step
2016-01-31 04:01:44 -04:00
void calculateOutputStates ( ) ;
2015-12-10 11:36:10 -04:00
2016-02-23 22:49:27 -04:00
// initialise filter states of both the delayed ekf and the real time complementary filter
2015-11-19 13:08:04 -04:00
bool initialiseFilter ( void ) ;
2016-02-23 22:49:27 -04:00
// initialise ekf covariance matrix
2015-12-06 07:57:43 -04:00
void initialiseCovariance ( ) ;
2016-02-13 07:31:02 -04:00
// predict ekf state
2015-11-19 13:08:04 -04:00
void predictState ( ) ;
2016-02-13 07:31:02 -04:00
// predict ekf covariance
2015-11-19 13:08:04 -04:00
void predictCovariance ( ) ;
2016-02-13 07:31:02 -04:00
// ekf sequential fusion of magnetometer measurements
2016-01-31 04:01:44 -04:00
void fuseMag ( ) ;
2015-11-19 13:08:04 -04:00
2016-03-01 00:35:45 -04:00
// fuse the first euler angle from either a 321 or 312 rotation sequence as the observation (currently measures yaw using the magnetometer)
2015-12-07 04:26:30 -04:00
void fuseHeading ( ) ;
2015-11-19 13:08:04 -04:00
2018-08-27 18:22:48 -03:00
// fuse the yaw angle obtained from a dual antenna GPS unit
void fuseGpsAntYaw ( ) ;
// reset the quaternions states using the yaw angle obtained from a dual antenna GPS unit
// return true if the reset was successful
bool resetGpsAntYaw ( ) ;
2016-02-13 07:31:02 -04:00
// fuse magnetometer declination measurement
2019-01-16 22:51:54 -04:00
// argument passed in is the declination uncertainty in radians
void fuseDeclination ( float decl_sigma ) ;
2016-02-07 23:15:05 -04:00
2019-01-28 01:33:13 -04:00
// apply sensible limits to the declination and length of the NE mag field states estimates
void limitDeclination ( ) ;
2016-02-13 07:31:02 -04:00
// fuse airspeed measurement
2015-11-19 13:08:04 -04:00
void fuseAirspeed ( ) ;
2016-07-12 13:44:32 -03:00
// fuse synthetic zero sideslip measurement
2017-04-24 18:29:54 -03:00
void fuseSideslip ( ) ;
2016-07-12 13:44:32 -03:00
2017-04-09 20:21:29 -03:00
// fuse body frame drag specific forces for multi-rotor wind estimation
void fuseDrag ( ) ;
2019-10-15 09:49:05 -03:00
// fuse single velocity and position measurement
void fuseVelPosHeight ( const float innov , const float innov_var , const int obs_index ) ;
2015-12-07 04:26:30 -04:00
2016-02-13 07:31:02 -04:00
// reset velocity states of the ekf
2016-03-10 00:09:23 -04:00
bool resetVelocity ( ) ;
2015-12-06 07:57:43 -04:00
2016-03-07 05:14:15 -04:00
// fuse optical flow line of sight rate measurements
void fuseOptFlow ( ) ;
2019-10-29 06:58:01 -03:00
bool fuseHorizontalVelocity ( const Vector3f & innov , const Vector2f & innov_gate ,
const Vector3f & obs_var , Vector3f & innov_var , Vector2f & test_ratio ) ;
bool fuseVerticalVelocity ( const Vector3f & innov , const Vector2f & innov_gate ,
const Vector3f & obs_var , Vector3f & innov_var , Vector2f & test_ratio ) ;
bool fuseHorizontalPosition ( const Vector3f & innov , const Vector2f & innov_gate ,
const Vector3f & obs_var , Vector3f & innov_var , Vector2f & test_ratio ) ;
bool fuseVerticalPosition ( const Vector3f & innov , const Vector2f & innov_gate ,
const Vector3f & obs_var , Vector3f & innov_var , Vector2f & test_ratio ) ;
2018-06-12 02:52:34 -03:00
// calculate optical flow body angular rate compensation
// returns false if bias corrected body rate data is unavailable
bool calcOptFlowBodyRateComp ( ) ;
2016-03-07 05:14:15 -04:00
// initialise the terrain vertical position estimator
// return true if the initialisation is successful
bool initHagl ( ) ;
2016-12-02 02:13:11 -04:00
// run the terrain estimator
void runTerrainEstimator ( ) ;
2016-03-07 05:14:15 -04:00
// update the terrain vertical position estimate using a height above ground measurement from the range finder
void fuseHagl ( ) ;
2019-04-14 08:00:48 -03:00
// update the terrain vertical position estimate using an optical flow measurement
void fuseFlowForTerrain ( ) ;
2019-03-08 09:59:28 -04:00
// reset the heading and magnetic field states using the declination and magnetometer/external vision measurements
2016-02-11 23:02:50 -04:00
// return true if successful
2019-11-08 11:02:59 -04:00
bool resetMagHeading ( const Vector3f & mag_init , bool increase_yaw_var = true , bool update_buffer = true ) ;
2016-02-11 23:02:50 -04:00
2016-11-02 03:48:52 -03:00
// Do a forced re-alignment of the yaw angle to align with the horizontal velocity vector from the GPS.
// It is used to align the yaw angle after launch or takeoff for fixed wing vehicle.
bool realignYawGPS ( ) ;
2019-03-12 18:08:42 -03:00
// Return the magnetic declination in radians to be used by the alignment and fusion processing
2019-03-12 11:08:45 -03:00
float getMagDeclination ( ) ;
2016-02-11 23:09:23 -04:00
2017-10-17 06:41:55 -03:00
// reset position states of the ekf (only horizontal position)
2016-03-10 00:09:23 -04:00
bool resetPosition ( ) ;
2015-12-06 07:57:43 -04:00
2016-02-13 07:31:02 -04:00
// reset height state of the ekf
2016-02-09 21:53:24 -04:00
void resetHeight ( ) ;
2016-05-07 21:30:40 -03:00
// modify output filter to match the the EKF state at the fusion time horizon
void alignOutputFilter ( ) ;
2017-10-22 18:28:22 -03:00
// update the estimated angular misalignment vector between the EV naigration frame and the EKF navigation frame
// and update the rotation matrix which transforms EV navigation frame measurements into NED
void calcExtVisRotMat ( ) ;
// reset the estimated angular misalignment vector between the EV naigration frame and the EKF navigation frame
// and reset the rotation matrix which transforms EV navigation frame measurements into NED
void resetExtVisRotMat ( ) ;
2016-02-13 07:31:02 -04:00
// limit the diagonal of the covariance matrix
2016-05-07 07:29:50 -03:00
void fixCovarianceErrors ( ) ;
2015-12-07 04:26:30 -04:00
2016-05-07 07:29:50 -03:00
// make ekf covariance matrix symmetric between a nominated state indexe range
void makeSymmetrical ( float ( & cov_mat ) [ _k_num_states ] [ _k_num_states ] , uint8_t first , uint8_t last ) ;
2015-12-07 04:26:30 -04:00
2016-02-13 07:31:02 -04:00
// constrain the ekf states
2015-12-07 04:26:30 -04:00
void constrainStates ( ) ;
2016-02-13 07:31:02 -04:00
// generic function which will perform a fusion step given a kalman gain K
// and a scalar innovation value
2015-12-07 04:26:30 -04:00
void fuse ( float * K , float innovation ) ;
2016-02-13 07:31:02 -04:00
// calculate the earth rotation vector from a given latitude
2018-07-04 19:55:22 -03:00
void calcEarthRateNED ( Vector3f & omega , float lat_rad ) const ;
2015-11-19 13:08:04 -04:00
2016-01-31 04:01:44 -04:00
// return true id the GPS quality is good enough to set an origin and start aiding
2019-03-05 13:55:26 -04:00
bool gps_is_good ( const gps_message & gps ) ;
2016-01-28 06:52:39 -04:00
2016-01-31 04:01:44 -04:00
// Control the filter fusion modes
void controlFusionModes ( ) ;
2016-01-28 06:52:39 -04:00
2016-04-24 09:20:18 -03:00
// control fusion of external vision observations
2016-06-07 05:44:47 -03:00
void controlExternalVisionFusion ( ) ;
2016-04-24 09:20:18 -03:00
2019-03-18 11:20:33 -03:00
// control fusion of optical flow observations
2016-06-07 05:44:47 -03:00
void controlOpticalFlowFusion ( ) ;
2016-04-24 09:20:18 -03:00
// control fusion of GPS observations
2016-06-07 05:44:47 -03:00
void controlGpsFusion ( ) ;
2016-04-24 09:20:18 -03:00
// control fusion of magnetometer observations
2016-06-07 05:44:47 -03:00
void controlMagFusion ( ) ;
2019-11-08 11:02:59 -04:00
void updateMagFilter ( ) ;
bool canRunMagFusion ( ) const ;
void checkHaglYawResetReq ( ) ;
float getTerrainVPos ( ) const ;
void runOnGroundYawReset ( ) ;
bool isYawResetAuthorized ( ) const ;
bool canResetMagHeading ( ) const ;
void runInAirYawReset ( ) ;
bool canRealignYawUsingGps ( ) const ;
void runVelPosReset ( ) ;
void selectMagAuto ( ) ;
void check3DMagFusionSuitability ( ) ;
void checkYawAngleObservability ( ) ;
void checkMagBiasObservability ( ) ;
bool isYawAngleObservable ( ) const ;
bool isMagBiasObservable ( ) const ;
bool canUse3DMagFusion ( ) const ;
void checkMagDeclRequired ( ) ;
void checkMagInhibition ( ) ;
bool shouldInhibitMag ( ) const ;
void checkMagFieldStrength ( ) ;
bool isStrongMagneticDisturbance ( ) const ;
bool isMeasuredMatchingGpsMagStrength ( ) const ;
bool isMeasuredMatchingAverageMagStrength ( ) const ;
static bool isMeasuredMatchingExpected ( float measured , float expected , float gate ) ;
void runMagAndMagDeclFusions ( ) ;
void run3DMagAndDeclFusions ( ) ;
2016-06-07 03:54:12 -03:00
// control fusion of range finder observations
2016-06-07 05:44:47 -03:00
void controlRangeFinderFusion ( ) ;
2016-06-07 03:54:12 -03:00
// control fusion of air data observations
2016-06-07 05:44:47 -03:00
void controlAirDataFusion ( ) ;
2016-06-07 03:54:12 -03:00
2016-07-12 14:54:14 -03:00
// control fusion of synthetic sideslip observations
void controlBetaFusion ( ) ;
2017-04-09 20:21:29 -03:00
// control fusion of multi-rotor drag specific force observations
void controlDragFusion ( ) ;
2016-06-07 03:54:12 -03:00
// control fusion of pressure altitude observations
2016-06-07 05:44:47 -03:00
void controlBaroFusion ( ) ;
2016-06-07 03:54:12 -03:00
2019-10-15 09:49:05 -03:00
// control fusion of fake position observations to constrain drift
void controlFakePosFusion ( ) ;
2016-04-24 09:20:18 -03:00
2017-11-17 16:44:28 -04:00
// control fusion of auxiliary velocity observations
void controlAuxVelFusion ( ) ;
2016-04-24 09:20:18 -03:00
// control for height sensor timeouts, sensor changes and state resets
void controlHeightSensorTimeouts ( ) ;
2017-02-28 05:56:39 -04:00
// control for combined height fusion mode (implemented for switching between baro and range height)
void controlHeightFusion ( ) ;
2019-10-14 08:39:52 -03:00
// determine if flight condition is suitable to use range finder instead of the primary height sensor
2019-10-14 09:28:18 -03:00
void checkRangeAidSuitability ( ) ;
bool isRangeAidSuitable ( ) { return _is_range_aid_suitable ; }
2017-02-28 05:56:39 -04:00
2019-10-15 09:14:46 -03:00
// update _rng_hgt_valid, which indicates if the current range sample has passed validity checks
2019-10-14 03:17:56 -03:00
void updateRangeDataValidity ( ) ;
2017-02-28 05:56:39 -04:00
2019-10-15 09:14:46 -03:00
// check for "stuck" range finder measurements when rng was not valid for certain period
void updateRangeDataStuck ( ) ;
2016-02-18 06:21:04 -04:00
// return the square of two floating point numbers - used in auto coded sections
2018-07-04 19:55:22 -03:00
static constexpr float sq ( float var ) { return var * var ; }
2016-02-12 00:14:36 -04:00
2017-02-28 05:42:52 -04:00
// set control flags to use baro height
void setControlBaroHeight ( ) ;
// set control flags to use range height
void setControlRangeHeight ( ) ;
// set control flags to use GPS height
void setControlGPSHeight ( ) ;
// set control flags to use external vision height
void setControlEVHeight ( ) ;
2019-11-08 11:02:59 -04:00
void stopMagFusion ( ) ;
void stopMag3DFusion ( ) ;
void stopMagHdgFusion ( ) ;
void startMagHdgFusion ( ) ;
void startMag3DFusion ( ) ;
2016-02-18 06:21:04 -04:00
// zero the specified range of rows in the state covariance matrix
2016-02-12 00:14:36 -04:00
void zeroRows ( float ( & cov_mat ) [ _k_num_states ] [ _k_num_states ] , uint8_t first , uint8_t last ) ;
2016-02-18 06:21:04 -04:00
// zero the specified range of columns in the state covariance matrix
2016-02-12 00:14:36 -04:00
void zeroCols ( float ( & cov_mat ) [ _k_num_states ] [ _k_num_states ] , uint8_t first , uint8_t last ) ;
2016-04-09 16:46:27 -03:00
2017-11-09 02:49:32 -04:00
// zero the specified range of off diagonals in the state covariance matrix
2017-11-09 02:37:45 -04:00
void zeroOffDiag ( float ( & cov_mat ) [ _k_num_states ] [ _k_num_states ] , uint8_t first , uint8_t last ) ;
2017-11-09 02:49:32 -04:00
// zero the specified range of off diagonals in the state covariance matrix
// set the diagonals to the supplied value
void setDiag ( float ( & cov_mat ) [ _k_num_states ] [ _k_num_states ] , uint8_t first , uint8_t last , float variance ) ;
2016-05-08 02:40:06 -03:00
// calculate the measurement variance for the optical flow sensor
float calcOptFlowMeasVar ( ) ;
2016-05-16 21:42:37 -03:00
// rotate quaternion covariances into variances for an equivalent rotation vector
Vector3f calcRotVecVariances ( ) ;
2016-05-16 23:39:11 -03:00
// initialise the quaternion covariances using rotation vector variances
void initialiseQuatCovariances ( Vector3f & rot_vec_var ) ;
2016-06-07 08:09:17 -03:00
// perform a limited reset of the magnetic field state covariances
2019-11-08 11:02:59 -04:00
void resetMagRelatedCovariances ( ) ;
2016-06-07 08:09:17 -03:00
2016-07-24 08:27:53 -03:00
// perform a limited reset of the wind state covariances
void resetWindCovariance ( ) ;
2016-07-31 01:41:48 -03:00
// perform a reset of the wind states
void resetWindStates ( ) ;
2016-11-30 10:02:07 -04:00
// check that the range finder data is continuous
2019-10-14 03:17:56 -03:00
void updateRangeDataContinuity ( ) ;
2016-11-30 10:02:07 -04:00
2019-10-15 09:14:46 -03:00
bool isRangeDataContinuous ( ) { return _dt_last_range_update_filt_us < 2e6 f ; }
2018-12-20 20:34:57 -04:00
// Increase the yaw error variance of the quaternions
// Argument is additional yaw variance in rad**2
void increaseQuatYawErrVariance ( float yaw_variance ) ;
2019-11-08 11:02:59 -04:00
// load and save mag field state covariance data for re-use
void loadMagCovData ( ) ;
void saveMagCovData ( ) ;
void clearMagCov ( ) ;
void zeroMagCov ( ) ;
2019-01-17 00:51:37 -04:00
2018-12-20 23:18:25 -04:00
// uncorrelate quaternion states from other states
void uncorrelateQuatStates ( ) ;
2019-05-08 07:10:08 -03:00
// Use Kahan summation algorithm to get the sum of "sum_previous" and "input".
// This function relies on the caller to be responsible for keeping a copy of
// "accumulator" and passing this value at the next iteration.
// Ref: https://en.wikipedia.org/wiki/Kahan_summation_algorithm
float kahanSummation ( float sum_previous , float input , float & accumulator ) const ;
2019-09-04 14:51:39 -03:00
// calculate a synthetic value for the magnetometer Z component, given the 3D magnetomter
// sensor measurement
float calculate_synthetic_mag_z_measurement ( Vector3f mag_meas , Vector3f mag_earth_predicted ) ;
2019-10-15 09:52:13 -03:00
void stopGpsFusion ( ) ;
void stopGpsPosFusion ( ) ;
void stopGpsVelFusion ( ) ;
void stopGpsYawFusion ( ) ;
void stopEvFusion ( ) ;
void stopEvPosFusion ( ) ;
void stopEvVelFusion ( ) ;
void stopEvYawFusion ( ) ;
void stopAuxVelFusion ( ) ;
void stopFlowFusion ( ) ;
void setVelPosFaultStatus ( const int index , const bool status ) ;
2015-12-06 07:57:43 -04:00
} ;