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 .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/**
2016-02-18 06:21:04 -04:00
* @ file estimator_interface . h
2015-11-19 13:08:04 -04:00
* Definition of base class for attitude estimators
*
2015-12-06 07:57:43 -04:00
* @ author Roman Bast < bapstroman @ gmail . com >
2015-11-19 13:08:04 -04:00
*
*/
2018-08-30 12:48:38 -03:00
# pragma once
2019-03-05 13:41:21 -04:00
# include <ecl.h>
2016-01-30 16:44:19 -04:00
# include "common.h"
2018-03-22 15:10:30 -03:00
# include "RingBuffer.h"
# include <geo/geo.h>
2018-05-03 14:07:56 -03:00
# include <matrix/math.hpp>
2018-03-22 15:10:30 -03:00
# include <mathlib/mathlib.h>
2015-12-26 02:14:57 -04:00
2016-01-30 00:04:21 -04:00
using namespace estimator ;
2017-04-24 18:29:54 -03:00
2016-01-31 03:37:34 -04:00
class EstimatorInterface
2015-11-19 13:08:04 -04:00
{
2016-01-30 00:04:21 -04:00
2015-11-19 13:08:04 -04:00
public :
2017-04-24 18:29:54 -03:00
EstimatorInterface ( ) = default ;
2017-08-11 12:22:12 -03:00
virtual ~ EstimatorInterface ( ) = default ;
2015-11-19 13:08:04 -04:00
2016-01-30 16:42:24 -04:00
virtual bool init ( uint64_t timestamp ) = 0 ;
2015-12-07 04:26:30 -04:00
virtual bool update ( ) = 0 ;
2015-12-06 07:57:43 -04:00
2016-01-12 02:30:53 -04:00
// gets the innovations of velocity and position measurements
// 0-2 vel, 3-5 pos
virtual void get_vel_pos_innov ( float vel_pos_innov [ 6 ] ) = 0 ;
2017-11-20 20:00:16 -04:00
// gets the innovations for of the NE auxiliary velocity measurement
virtual void get_aux_vel_innov ( float aux_vel_innov [ 2 ] ) = 0 ;
2016-01-12 02:30:53 -04:00
// gets the innovations of the earth magnetic field measurements
virtual void get_mag_innov ( float mag_innov [ 3 ] ) = 0 ;
2016-03-11 07:57:14 -04:00
// gets the innovation of airspeed measurement
2017-04-24 18:29:54 -03:00
virtual void get_airspeed_innov ( float * airspeed_innov ) = 0 ;
2016-03-11 07:57:14 -04:00
2016-07-12 13:48:42 -03:00
// gets the innovation of the synthetic sideslip measurement
virtual void get_beta_innov ( float * beta_innov ) = 0 ;
2016-01-12 02:30:53 -04:00
// gets the innovations of the heading measurement
virtual void get_heading_innov ( float * heading_innov ) = 0 ;
// gets the innovation variances of velocity and position measurements
// 0-2 vel, 3-5 pos
virtual void get_vel_pos_innov_var ( float vel_pos_innov_var [ 6 ] ) = 0 ;
// gets the innovation variances of the earth magnetic field measurements
virtual void get_mag_innov_var ( float mag_innov_var [ 3 ] ) = 0 ;
2016-03-11 07:57:14 -04:00
// gets the innovation variance of the airspeed measurement
2017-04-24 18:29:54 -03:00
virtual void get_airspeed_innov_var ( float * get_airspeed_innov_var ) = 0 ;
2016-03-11 07:57:14 -04:00
2016-07-12 13:48:42 -03:00
// gets the innovation variance of the synthetic sideslip measurement
virtual void get_beta_innov_var ( float * get_beta_innov_var ) = 0 ;
2016-01-12 02:30:53 -04:00
// gets the innovation variance of the heading measurement
virtual void get_heading_innov_var ( float * heading_innov_var ) = 0 ;
virtual void get_state_delayed ( float * state ) = 0 ;
2016-07-12 06:40:41 -03:00
virtual void get_wind_velocity ( float * wind ) = 0 ;
2017-08-06 20:19:48 -03:00
2017-10-02 09:47:56 -03:00
virtual void get_wind_velocity_var ( float * wind_var ) = 0 ;
2017-08-06 20:19:48 -03:00
virtual void get_true_airspeed ( float * tas ) = 0 ;
2016-07-12 06:40:41 -03:00
2016-08-13 20:08:44 -03:00
// gets the variances for the NED velocity states
2016-03-07 05:14:15 -04:00
virtual void get_vel_var ( Vector3f & vel_var ) = 0 ;
2016-08-13 20:08:44 -03:00
// gets the variances for the NED position states
2016-03-07 05:14:15 -04:00
virtual void get_pos_var ( Vector3f & pos_var ) = 0 ;
// gets the innovation variance of the flow measurement
virtual void get_flow_innov_var ( float flow_innov_var [ 2 ] ) = 0 ;
// gets the innovation of the flow measurement
virtual void get_flow_innov ( float flow_innov [ 2 ] ) = 0 ;
2017-04-09 20:21:29 -03:00
// gets the innovation variance of the drag specific force measurement
virtual void get_drag_innov_var ( float drag_innov_var [ 2 ] ) = 0 ;
// gets the innovation of the drag specific force measurement
virtual void get_drag_innov ( float drag_innov [ 2 ] ) = 0 ;
2016-03-07 05:14:15 -04:00
// gets the innovation variance of the HAGL measurement
2019-05-27 17:28:01 -03:00
virtual void get_hagl_innov_var ( float * hagl_innov_var ) = 0 ;
2016-03-07 05:14:15 -04:00
// gets the innovation of the HAGL measurement
2019-05-27 17:28:01 -03:00
virtual void get_hagl_innov ( float * hagl_innov ) = 0 ;
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
// error magnitudes (rad), (m/s), (m)
virtual void get_output_tracking_error ( float error [ 3 ] ) = 0 ;
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 )
*/
virtual void get_imu_vibe_metrics ( float vibe [ 3 ] ) = 0 ;
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
*/
virtual bool get_gps_drift_metrics ( float drift [ 3 ] , bool * blocked ) = 0 ;
2016-12-27 19:38:05 -04:00
// get the ekf WGS-84 origin position and height and the system time it was last set
// return true if the origin is valid
virtual bool get_ekf_origin ( uint64_t * origin_time , map_projection_reference_s * origin_pos , float * origin_alt ) = 0 ;
2016-01-29 21:15:18 -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
2018-04-23 08:15:29 -03:00
virtual void get_ekf_gpos_accuracy ( float * ekf_eph , float * ekf_epv ) = 0 ;
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
2018-04-23 08:15:29 -03:00
virtual void get_ekf_lpos_accuracy ( float * ekf_eph , float * ekf_epv ) = 0 ;
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
2018-04-23 08:15:29 -03:00
virtual void get_ekf_vel_accuracy ( float * ekf_evh , float * ekf_evv ) = 0 ;
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
virtual void get_ekf_ctrl_limits ( float * vxy_max , float * vz_max , float * hagl_min , float * hagl_max ) = 0 ;
2017-09-18 19:38:19 -03: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-03-05 13:55:26 -04:00
virtual bool collect_gps ( const gps_message & gps ) = 0 ;
2016-01-29 21:15:18 -04:00
2016-05-26 00:27:08 -03:00
// accumulate and downsample IMU data to the EKF prediction rate
2018-07-04 18:59:35 -03:00
virtual bool collect_imu ( const imuSample & imu ) = 0 ;
2016-01-29 21:15:18 -04:00
2015-11-19 13:08:04 -04:00
// set delta angle imu data
2018-10-17 16:30:25 -03:00
void setIMUData ( const imuSample & imu_sample ) ;
// legacy interface for compatibility (2018-09-14)
2017-01-15 05:17:41 -04:00
void setIMUData ( uint64_t time_usec , uint64_t delta_ang_dt , uint64_t delta_vel_dt , float ( & delta_ang ) [ 3 ] , float ( & delta_vel ) [ 3 ] ) ;
2015-11-19 13:08:04 -04:00
// set magnetometer data
2017-01-15 05:17:41 -04:00
void setMagData ( uint64_t time_usec , float ( & data ) [ 3 ] ) ;
2015-11-19 13:08:04 -04:00
// set gps data
2019-03-05 13:55:26 -04:00
void setGpsData ( uint64_t time_usec , const gps_message & gps ) ;
2015-11-19 13:08:04 -04:00
// set baro data
2017-01-15 05:17:41 -04:00
void setBaroData ( uint64_t time_usec , float data ) ;
2015-11-19 13:08:04 -04:00
// set airspeed data
2017-01-15 05:17:41 -04:00
void setAirspeedData ( uint64_t time_usec , float true_airspeed , float eas2tas ) ;
2015-11-19 13:08:04 -04:00
// set range data
2019-09-12 03:04:12 -03:00
void setRangeData ( uint64_t time_usec , float data , int8_t quality ) ;
2015-11-19 13:08:04 -04:00
// set optical flow data
2018-06-12 03:52:26 -03:00
// if optical flow sensor gyro delta angles are not available, set gyroXYZ vector fields to NaN and the EKF will use its internal delta angle data instead
2016-03-07 05:14:15 -04:00
void setOpticalFlowData ( uint64_t time_usec , flow_message * flow ) ;
2015-11-19 13:08:04 -04:00
2016-03-20 05:41:40 -03:00
// set external vision position and attitude data
void setExtVisionData ( uint64_t time_usec , ext_vision_message * evdata ) ;
2017-11-17 16:44:28 -04:00
// set auxiliary velocity data
void setAuxVelData ( uint64_t time_usec , float ( & data ) [ 2 ] , float ( & variance ) [ 2 ] ) ;
2015-12-26 02:14:57 -04:00
// return a address to the parameters struct
// in order to give access to the application
parameters * getParamHandle ( ) { return & _params ; }
2016-01-28 06:52:39 -04:00
2016-02-13 03:50:51 -04:00
// set vehicle landed status data
2016-05-09 21:21:45 -03:00
void set_in_air_status ( bool in_air ) { _control_status . flags . in_air = in_air ; }
2016-02-13 03:50:51 -04: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 .
*/
virtual bool reset_imu_bias ( ) = 0 ;
2018-07-04 18:59:35 -03:00
// return true if the attitude is usable
bool attitude_valid ( ) { return ISFINITE ( _output_new . quat_nominal ( 0 ) ) & & _control_status . flags . tilt_align ; }
2017-10-03 12:44:11 -03:00
// get vehicle landed status data
bool get_in_air_status ( ) { return _control_status . flags . in_air ; }
2018-03-14 17:41:09 -03:00
// get wind estimation status
bool get_wind_status ( ) { return _control_status . flags . wind ; }
2017-07-07 04:18:53 -03:00
// set vehicle is fixed wing status
void set_is_fixed_wing ( bool is_fixed_wing ) { _control_status . flags . fixed_wing = is_fixed_wing ; }
2016-07-12 13:48:42 -03:00
// set flag if synthetic sideslip measurement should be fused
2017-10-19 04:21:47 -03:00
void set_fuse_beta_flag ( bool fuse_beta ) { _control_status . flags . fuse_beta = ( fuse_beta & & _control_status . flags . in_air ) ; }
2016-07-12 13:48:42 -03:00
2017-11-02 22:11:32 -03:00
// set flag if static pressure rise due to ground effect is expected
// use _params.gnd_effect_deadzone to adjust for expected rise in static pressure
// flag will clear after GNDEFFECT_TIMEOUT uSec
void set_gnd_effect_flag ( bool gnd_effect )
{
_control_status . flags . gnd_effect = gnd_effect ;
_time_last_gnd_effect_on = _time_last_imu ;
}
2017-05-25 10:20:10 -03:00
// set flag if only only mag states should be updated by the magnetometer
void set_update_mag_states_only_flag ( bool update_mag_states_only ) { _control_status . flags . update_mag_states_only = update_mag_states_only ; }
2017-04-11 20:42:25 -03:00
// set air density used by the multi-rotor specific drag force fusion
void set_air_density ( float air_density ) { _air_density = air_density ; }
2018-05-19 15:16:08 -03:00
// set sensor limitations reported by the rangefinder
void set_rangefinder_limits ( float min_distance , float max_distance )
{
2018-07-11 19:50:26 -03:00
_rng_valid_min_val = min_distance ;
_rng_valid_max_val = max_distance ;
2018-05-19 15:16:08 -03:00
}
// set sensor limitations reported by the optical flow sensor
void set_optical_flow_limits ( float max_flow_rate , float min_distance , float max_distance )
{
_flow_max_rate = max_flow_rate ;
_flow_min_distance = min_distance ;
_flow_max_distance = max_distance ;
}
2016-03-07 05:14:15 -04:00
// return true if the global position estimate is valid
virtual bool global_position_is_valid ( ) = 0 ;
2017-02-23 06:24:28 -04:00
// return true if the EKF is dead reckoning the position using inertial data only
2018-03-21 19:31:52 -03:00
bool inertial_dead_reckoning ( ) { return _is_dead_reckoning ; }
2017-02-23 06:24:28 -04:00
2017-07-19 04:52:35 -03:00
// return true if the terrain estimate is valid
virtual bool get_terrain_valid ( ) = 0 ;
// get the estimated terrain vertical position relative to the NED origin
virtual void get_terrain_vert_pos ( float * ret ) = 0 ;
2016-03-07 05:14:15 -04:00
// return true if the local position estimate is valid
bool local_position_is_valid ( ) ;
2015-11-19 13:08:04 -04:00
2018-11-14 15:46:04 -04:00
const matrix : : Quatf & get_quaternion ( ) const { return _output_new . quat_nominal ; }
2017-10-22 18:28:22 -03:00
// return the quaternion defining the rotation from the EKF to the External Vision reference frame
2019-08-22 09:00:07 -03:00
virtual void get_ev2ekf_quaternion ( float * quat ) = 0 ;
2017-10-22 18:28:22 -03:00
2016-04-09 16:46:27 -03:00
// get the velocity of the body frame origin in local NED earth frame
void get_velocity ( float * vel )
2016-01-30 00:04:21 -04:00
{
2017-04-22 20:04:00 -03:00
Vector3f vel_earth = _output_new . vel - _vel_imu_rel_body_ned ;
2018-05-03 15:14:12 -03:00
2016-01-30 00:04:21 -04:00
for ( unsigned i = 0 ; i < 3 ; i + + ) {
2016-04-09 16:46:27 -03:00
vel [ i ] = vel_earth ( i ) ;
2016-01-30 00:04:21 -04:00
}
}
2017-04-22 20:04:00 -03:00
2017-09-05 03:58:59 -03:00
// get the NED velocity derivative in earth frame
void get_vel_deriv_ned ( float * vel_deriv )
{
for ( unsigned i = 0 ; i < 3 ; i + + ) {
vel_deriv [ i ] = _vel_deriv_ned ( i ) ;
}
}
2017-04-22 20:04:00 -03:00
// get the derivative of the vertical position of the body frame origin in local NED earth frame
void get_pos_d_deriv ( float * pos_d_deriv )
{
float var = _output_vert_new . vel_d - _vel_imu_rel_body_ned ( 2 ) ;
* pos_d_deriv = var ;
}
2016-04-09 16:46:27 -03:00
// get the position of the body frame origin in local NED earth frame
void get_position ( float * pos )
2016-01-30 00:04:21 -04:00
{
2016-04-09 16:46:27 -03:00
// rotate the position of the IMU relative to the boy origin into earth frame
Vector3f pos_offset_earth = _R_to_earth_now * _params . imu_pos_body ;
2017-04-24 18:29:54 -03:00
2016-04-09 16:46:27 -03:00
// subtract from the EKF position (which is at the IMU) to get position at the body origin
2016-01-30 00:04:21 -04:00
for ( unsigned i = 0 ; i < 3 ; i + + ) {
2016-04-09 16:46:27 -03:00
pos [ i ] = _output_new . pos ( i ) - pos_offset_earth ( i ) ;
2016-01-30 00:04:21 -04:00
}
}
void copy_timestamp ( uint64_t * time_us )
{
2016-02-13 07:31:02 -04:00
* time_us = _time_last_imu ;
2016-01-30 00:04:21 -04:00
}
2018-07-24 19:36:11 -03:00
// Get the value of magnetic declination in degrees to be saved for use at the next startup
2018-07-24 21:43:52 -03:00
// Returns true when the declination can be saved
2018-07-24 19:36:11 -03:00
// At the next startup, set param.mag_declination_deg to the value saved
2018-07-24 21:43:52 -03:00
bool get_mag_decl_deg ( float * val )
2016-02-11 23:17:14 -04:00
{
2019-03-12 11:38:30 -03:00
* val = 0.0f ;
if ( _NED_origin_initialised & & ( _params . mag_declination_source & MASK_SAVE_GEO_DECL ) ) {
* val = math : : degrees ( _mag_declination_gps ) ;
return true ;
} else {
return false ;
}
2016-02-11 23:17:14 -04:00
}
2016-04-27 23:05:54 -03:00
virtual void get_accel_bias ( float bias [ 3 ] ) = 0 ;
2016-06-21 08:51:04 -03:00
virtual void get_gyro_bias ( float bias [ 3 ] ) = 0 ;
2016-04-11 09:12:24 -03:00
2016-04-15 23:41:50 -03:00
// get EKF mode status
2017-06-01 06:02:56 -03:00
void get_control_mode ( uint32_t * val )
2016-04-15 23:41:50 -03:00
{
* val = _control_status . value ;
}
2016-05-07 08:18:00 -03:00
// get EKF internal fault status
void get_filter_fault_status ( uint16_t * val )
{
* val = _fault_status . value ;
}
2016-04-16 00:38:40 -03:00
// get GPS check status
virtual void get_gps_check_status ( uint16_t * val ) = 0 ;
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
virtual void get_posD_reset ( float * delta , uint8_t * counter ) = 0 ;
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
virtual void get_velD_reset ( float * delta , uint8_t * counter ) = 0 ;
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
2016-06-06 04:40:32 -03:00
virtual void get_posNE_reset ( float delta [ 2 ] , uint8_t * counter ) = 0 ;
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
2016-06-06 04:40:32 -03:00
virtual void get_velNE_reset ( float delta [ 2 ] , uint8_t * counter ) = 0 ;
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
2016-06-06 04:40:32 -03:00
virtual void get_quat_reset ( float delta_quat [ 4 ] , uint8_t * counter ) = 0 ;
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.
2017-12-18 10:36:28 -04:00
virtual void get_innovation_test_status ( uint16_t * status , float * mag , float * vel , float * pos , float * hgt , float * tas , float * hagl , float * beta ) = 0 ;
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
virtual void get_ekf_soln_status ( uint16_t * status ) = 0 ;
2016-05-23 18:44:43 -03:00
2017-08-11 12:25:05 -03:00
// Getter for the average imu update period in s
2018-07-04 18:59:35 -03:00
float get_dt_imu_avg ( ) const { return _dt_imu_avg ; }
2017-08-11 12:25:05 -03:00
// Getter for the imu sample on the delayed time horizon
imuSample get_imu_sample_delayed ( )
{
return _imu_sample_delayed ;
}
// Getter for the baro sample on the delayed time horizon
baroSample get_baro_sample_delayed ( )
{
return _baro_sample_delayed ;
}
2017-11-16 14:36:03 -04:00
void print_status ( ) ;
2018-07-04 19:55:22 -03:00
static constexpr unsigned FILTER_UPDATE_PERIOD_MS { 8 } ; // ekf prediction period in milliseconds - this should ideally be an integer multiple of the IMU time delta
static constexpr float FILTER_UPDATE_PERIOD_S { FILTER_UPDATE_PERIOD_MS * 0.001f } ;
2017-08-11 12:25:05 -03:00
2016-01-30 00:04:21 -04:00
protected :
2015-11-19 13:08:04 -04:00
2016-02-23 22:49:27 -04:00
parameters _params ; // filter parameters
2015-11-19 13:08:04 -04:00
2016-11-05 09:44:45 -03:00
/*
OBS_BUFFER_LENGTH defines how many observations ( non - IMU measurements ) we can buffer
which sets the maximum frequency at which we can process non - IMU measurements . Measurements that
arrive too soon after the previous measurement will not be processed .
2018-07-04 19:55:22 -03:00
max freq ( Hz ) = ( OBS_BUFFER_LENGTH - 1 ) / ( IMU_BUFFER_LENGTH * FILTER_UPDATE_PERIOD_S )
2016-11-05 09:44:45 -03:00
This can be adjusted to match the max sensor data rate plus some margin for jitter .
*/
2017-04-24 18:29:54 -03:00
uint8_t _obs_buffer_length { 0 } ;
2016-11-05 09:44:45 -03:00
/*
IMU_BUFFER_LENGTH defines how many IMU samples we buffer which sets the time delay from current time to the
EKF fusion time horizon and therefore the maximum sensor time offset relative to the IMU that we can compensate for .
max sensor time offet ( msec ) = IMU_BUFFER_LENGTH * FILTER_UPDATE_PERIOD_MS
This can be adjusted to a value that is FILTER_UPDATE_PERIOD_MS longer than the maximum observation time delay .
*/
2017-04-24 18:29:54 -03:00
uint8_t _imu_buffer_length { 0 } ;
2015-11-19 13:08:04 -04:00
2017-04-24 18:29:54 -03:00
unsigned _min_obs_interval_us { 0 } ; // minimum time interval between observations that will guarantee data is not lost (usec)
2016-05-26 00:27:08 -03:00
2017-04-24 18:29:54 -03:00
float _dt_imu_avg { 0.0f } ; // average imu update period in s
2015-11-19 13:08:04 -04:00
2017-04-24 18:29:54 -03:00
imuSample _imu_sample_delayed { } ; // captures the imu sample on the delayed time horizon
2015-11-19 13:08:04 -04:00
2016-02-13 07:31:02 -04:00
// measurement samples capturing measurements on the delayed time horizon
2017-04-24 18:29:54 -03:00
magSample _mag_sample_delayed { } ;
baroSample _baro_sample_delayed { } ;
gpsSample _gps_sample_delayed { } ;
rangeSample _range_sample_delayed { } ;
airspeedSample _airspeed_sample_delayed { } ;
flowSample _flow_sample_delayed { } ;
extVisionSample _ev_sample_delayed { } ;
dragSample _drag_sample_delayed { } ;
dragSample _drag_down_sampled { } ; // down sampled drag specific force data (filter prediction rate -> observation rate)
2017-11-17 16:44:28 -04:00
auxVelSample _auxvel_sample_delayed { } ;
2017-04-11 20:42:25 -03:00
// Used by the multi-rotor specific drag force fusion
2017-04-24 18:29:54 -03:00
uint8_t _drag_sample_count { 0 } ; // number of drag specific force samples assumulated at the filter prediction rate
float _drag_sample_time_dt { 0.0f } ; // time integral across all samples used to form _drag_down_sampled (sec)
2018-03-22 15:10:30 -03:00
float _air_density { CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C } ; // air density (kg/m**3)
2015-11-19 13:08:04 -04:00
2018-05-19 15:16:08 -03:00
// Sensor limitations
2018-07-11 19:50:26 -03:00
float _rng_valid_min_val { 0.0f } ; ///< minimum distance that the rangefinder can measure (m)
float _rng_valid_max_val { 0.0f } ; ///< maximum distance that the rangefinder can measure (m)
2018-05-19 15:16:08 -03:00
float _flow_max_rate { 0.0f } ; ///< maximum angular flow rate that the optical flow sensor can measure (rad/s)
float _flow_min_distance { 0.0f } ; ///< minimum distance that the optical flow sensor can operate at (m)
float _flow_max_distance { 0.0f } ; ///< maximum distance that the optical flow sensor can operate at (m)
2017-04-22 20:04:00 -03:00
// Output Predictor
2017-04-24 18:29:54 -03:00
outputSample _output_sample_delayed { } ; // filter output on the delayed time horizon
2017-04-22 20:04:00 -03:00
outputSample _output_new { } ; // filter output on the non-delayed time horizon
outputVert _output_vert_delayed { } ; // vertical filter output on the delayed time horizon
outputVert _output_vert_new { } ; // vertical filter output on the non-delayed time horizon
imuSample _imu_sample_new { } ; // imu sample capturing the newest imu data
Matrix3f _R_to_earth_now ; // rotation matrix from body to earth frame at current time
Vector3f _vel_imu_rel_body_ned ; // velocity of IMU relative to body origin in NED earth frame
2017-09-05 03:58:59 -03:00
Vector3f _vel_deriv_ned ; // velocity derivative at the IMU in NED earth frame (m/s/s)
2015-12-07 04:26:30 -04:00
2017-04-24 18:29:54 -03:00
bool _imu_updated { false } ; // true if the ekf should update (completed downsampling process)
bool _initialised { false } ; // true if the ekf interface instance (data buffering) is initialized
2016-01-29 21:15:18 -04:00
2017-04-24 18:29:54 -03:00
bool _NED_origin_initialised { false } ;
bool _gps_speed_valid { false } ;
float _gps_origin_eph { 0.0f } ; // horizontal position uncertainty of the GPS origin
float _gps_origin_epv { 0.0f } ; // vertical position uncertainty of the GPS origin
struct map_projection_reference_s _pos_ref { } ; // Contains WGS-84 position latitude and longitude (radians) of the EKF origin
struct map_projection_reference_s _gps_pos_prev { } ; // Contains WGS-84 position latitude and longitude (radians) of the previous GPS message
float _gps_alt_prev { 0.0f } ; // height from the previous GPS message (m)
2018-08-27 18:22:48 -03:00
float _gps_yaw_offset { 0.0f } ; // Yaw offset angle for dual GPS antennas used for yaw estimation (radians).
2015-11-19 13:08:04 -04:00
2016-05-23 04:33:48 -03:00
// innovation consistency check monitoring ratios
2017-04-24 18:29:54 -03:00
float _yaw_test_ratio { 0.0f } ; // yaw innovation consistency check ratio
float _mag_test_ratio [ 3 ] { } ; // magnetometer XYZ innovation consistency check ratios
float _vel_pos_test_ratio [ 6 ] { } ; // velocity and position innovation consistency check ratios
float _tas_test_ratio { 0.0f } ; // tas innovation consistency check ratio
float _terr_test_ratio { 0.0f } ; // height above terrain measurement innovation consistency check ratio
float _beta_test_ratio { 0.0f } ; // sideslip innovation consistency check ratio
2019-03-18 11:20:33 -03:00
float _drag_test_ratio [ 2 ] { } ; // drag innovation consistency check ratio
2017-02-05 14:05:10 -04:00
innovation_fault_status_u _innov_check_fail_status { } ;
2016-01-26 23:02:06 -04:00
2018-04-18 18:54:29 -03:00
bool _is_dead_reckoning { false } ; // true if we are no longer fusing measurements that constrain horizontal velocity drift
2019-06-28 05:46:53 -03:00
bool _deadreckon_time_exceeded { true } ; // true if the horizontal nav solution has been deadreckoning for too long and is invalid
2019-03-18 11:20:33 -03:00
bool _is_wind_dead_reckoning { false } ; // true if we are navigationg reliant on wind relative measurements
2017-03-14 18:41:11 -03:00
2018-05-15 21:31:22 -03:00
// IMU vibration and movement monitoring
2016-10-18 01:24:43 -03:00
Vector3f _delta_ang_prev ; // delta angle from the previous IMU measurement
Vector3f _delta_vel_prev ; // delta velocity from the previous IMU measurement
2017-04-24 18:29:54 -03:00
float _vibe_metrics [ 3 ] { } ; // IMU vibration metrics
2016-10-18 01:24:43 -03:00
// [0] Level of coning vibration in the IMU delta angles (rad^2)
2019-03-18 11:20:33 -03:00
// [1] high frequency vibration level in the IMU delta angle data (rad)
2016-10-18 01:24:43 -03:00
// [2] high frequency vibration level in the IMU delta velocity data (m/s)
2018-08-03 00:24:31 -03:00
float _gps_drift_metrics [ 3 ] { } ; // Array containing GPS drift metrics
// [0] Horizontal position drift rate (m/s)
// [1] Vertical position drift rate (m/s)
// [2] Filtered horizontal velocity (m/s)
2018-05-15 21:31:22 -03:00
bool _vehicle_at_rest { false } ; // true when the vehicle is at rest
uint64_t _time_last_move_detect_us { 0 } ; // timestamp of last movement detection event in microseconds
2018-08-03 00:24:31 -03:00
bool _gps_drift_updated { false } ; // true when _gps_drift_metrics has been updated and is ready for retrieval
2016-10-18 01:24:43 -03:00
2016-02-13 07:31:02 -04:00
// data buffer instances
2015-11-19 13:08:04 -04:00
RingBuffer < imuSample > _imu_buffer ;
RingBuffer < gpsSample > _gps_buffer ;
RingBuffer < magSample > _mag_buffer ;
RingBuffer < baroSample > _baro_buffer ;
RingBuffer < rangeSample > _range_buffer ;
RingBuffer < airspeedSample > _airspeed_buffer ;
RingBuffer < flowSample > _flow_buffer ;
2016-03-20 05:41:40 -03:00
RingBuffer < extVisionSample > _ext_vision_buffer ;
2015-11-19 13:08:04 -04:00
RingBuffer < outputSample > _output_buffer ;
2017-04-22 20:04:00 -03:00
RingBuffer < outputVert > _output_vert_buffer ;
2017-04-11 07:59:34 -03:00
RingBuffer < dragSample > _drag_buffer ;
2017-11-17 16:44:28 -04:00
RingBuffer < auxVelSample > _auxvel_buffer ;
2015-11-19 13:08:04 -04:00
2017-11-15 17:53:30 -04:00
// observation buffer final allocation failed
bool _gps_buffer_fail { false } ;
bool _mag_buffer_fail { false } ;
bool _baro_buffer_fail { false } ;
bool _range_buffer_fail { false } ;
bool _airspeed_buffer_fail { false } ;
bool _flow_buffer_fail { false } ;
bool _ev_buffer_fail { false } ;
bool _drag_buffer_fail { false } ;
2017-11-17 16:44:28 -04:00
bool _auxvel_buffer_fail { false } ;
2017-11-15 17:53:30 -04:00
2017-04-24 18:29:54 -03:00
uint64_t _time_last_imu { 0 } ; // timestamp of last imu sample in microseconds
uint64_t _time_last_gps { 0 } ; // timestamp of last gps measurement in microseconds
uint64_t _time_last_mag { 0 } ; // timestamp of last magnetometer measurement in microseconds
uint64_t _time_last_baro { 0 } ; // timestamp of last barometer measurement in microseconds
uint64_t _time_last_range { 0 } ; // timestamp of last range measurement in microseconds
uint64_t _time_last_airspeed { 0 } ; // timestamp of last airspeed measurement in microseconds
uint64_t _time_last_ext_vision { 0 } ; // timestamp of last external vision measurement in microseconds
uint64_t _time_last_optflow { 0 } ;
2017-11-02 22:11:32 -03:00
uint64_t _time_last_gnd_effect_on { 0 } ; //last time the baro ground effect compensation was turned on externally (uSec)
2017-11-17 16:44:28 -04:00
uint64_t _time_last_auxvel { 0 } ;
2015-11-19 13:08:04 -04:00
2017-02-05 14:05:10 -04:00
fault_status_u _fault_status { } ;
2016-02-13 07:31:02 -04:00
2019-03-18 11:20:33 -03:00
// allocate data buffers and initialize interface variables
2016-01-30 16:44:19 -04:00
bool initialise_interface ( uint64_t timestamp ) ;
2016-02-13 07:31:02 -04:00
// free buffer memory
2016-01-31 03:48:41 -04:00
void unallocate_buffers ( ) ;
2016-02-11 23:17:14 -04:00
2017-04-24 18:29:54 -03:00
float _mag_declination_gps { 0.0f } ; // magnetic declination returned by the geo library using the last valid GPS position (rad)
2019-01-28 01:33:13 -04:00
float _mag_inclination_gps { 0.0f } ; // magnetic inclination returned by the geo library using the last valid GPS position (rad)
float _mag_strength_gps { 0.0f } ; // magnetic strength returned by the geo library using the last valid GPS position (T)
2016-03-15 03:07:33 -03:00
// this is the current status of the filter control modes
2017-02-05 14:05:10 -04:00
filter_control_status_u _control_status { } ;
2016-03-15 03:07:33 -03:00
// this is the previous status of the filter control modes - used to detect mode transitions
2017-02-05 14:05:10 -04:00
filter_control_status_u _control_status_prev { } ;
2016-03-15 03:07:33 -03:00
2016-04-09 16:46:27 -03:00
// perform a vector cross product
Vector3f cross_product ( const Vector3f & vecIn1 , const Vector3f & vecIn2 ) ;
// calculate the inverse rotation matrix from a quaternion rotation
2017-06-19 12:10:01 -03:00
Matrix3f quat_to_invrotmat ( const Quatf & quat ) ;
2016-04-09 16:46:27 -03:00
2015-11-19 13:08:04 -04:00
} ;