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
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
2016-01-31 03:37:34 -04:00
|
|
|
#include "estimator_interface.h"
|
2016-02-17 21:33:18 -04:00
|
|
|
#include "geo.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:
|
|
|
|
|
|
|
|
Ekf();
|
|
|
|
~Ekf();
|
|
|
|
|
2016-02-13 07:31:02 -04:00
|
|
|
// initialise variables to sane values (also interface class)
|
2016-01-31 04:01:44 -04:00
|
|
|
bool init(uint64_t timestamp);
|
2016-02-13 07:31:02 -04:00
|
|
|
|
|
|
|
// should be called every time new data is pushed into the filter
|
2015-12-07 04:26:30 -04:00
|
|
|
bool update();
|
2015-11-19 13:08:04 -04:00
|
|
|
|
2016-01-12 02:30:53 -04:00
|
|
|
// gets the innovations of velocity and position measurements
|
|
|
|
// 0-2 vel, 3-5 pos
|
|
|
|
void get_vel_pos_innov(float vel_pos_innov[6]);
|
|
|
|
|
|
|
|
// gets the innovations of the earth magnetic field measurements
|
|
|
|
void get_mag_innov(float mag_innov[3]);
|
|
|
|
|
|
|
|
// gets the innovations of the heading measurement
|
|
|
|
void get_heading_innov(float *heading_innov);
|
|
|
|
|
|
|
|
// gets the innovation variances of velocity and position measurements
|
|
|
|
// 0-2 vel, 3-5 pos
|
|
|
|
void get_vel_pos_innov_var(float vel_pos_innov_var[6]);
|
|
|
|
|
|
|
|
// gets the innovation variances of the earth magnetic field measurements
|
|
|
|
void get_mag_innov_var(float mag_innov_var[3]);
|
|
|
|
|
2016-03-11 07:52:38 -04:00
|
|
|
// gets the innovations of airspeed measurement
|
|
|
|
void get_airspeed_innov(float *airspeed_innov);
|
|
|
|
|
|
|
|
// gets the innovation variance of the airspeed measurement
|
|
|
|
void get_airspeed_innov_var(float *airspeed_innov_var);
|
|
|
|
|
2016-01-12 02:30:53 -04:00
|
|
|
// gets the innovation variance of the heading measurement
|
|
|
|
void get_heading_innov_var(float *heading_innov_var);
|
|
|
|
|
2016-03-07 05:14:15 -04:00
|
|
|
// gets the innovation variance of the flow measurement
|
|
|
|
void get_flow_innov_var(float flow_innov_var[2]);
|
|
|
|
|
|
|
|
// gets the innovation of the flow measurement
|
|
|
|
void get_flow_innov(float flow_innov[2]);
|
|
|
|
|
|
|
|
// gets the innovation variance of the HAGL measurement
|
|
|
|
void get_hagl_innov_var(float *hagl_innov_var);
|
|
|
|
|
|
|
|
// gets the innovation of the HAGL measurement
|
|
|
|
void get_hagl_innov(float *hagl_innov);
|
|
|
|
|
2016-01-12 02:30:53 -04:00
|
|
|
// get the state vector at the delayed time horizon
|
|
|
|
void get_state_delayed(float *state);
|
|
|
|
|
2016-07-12 06:40:41 -03:00
|
|
|
// get the wind velocity in m/s
|
|
|
|
void get_wind_velocity(float *wind);
|
|
|
|
|
2016-01-12 02:30:53 -04:00
|
|
|
// get the diagonal elements of the covariance matrix
|
|
|
|
void get_covariances(float *covariances);
|
|
|
|
|
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
|
|
|
|
bool collect_gps(uint64_t time_usec, struct gps_message *gps);
|
|
|
|
bool collect_imu(imuSample &imu);
|
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-01-31 04:01:44 -04:00
|
|
|
void get_ekf_origin(uint64_t *origin_time, map_projection_reference_s *origin_pos, float *origin_alt);
|
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
|
|
|
|
void get_ekf_accuracy(float *ekf_eph, float *ekf_epv, bool *dead_reckoning);
|
|
|
|
|
2016-03-07 05:14:15 -04:00
|
|
|
void get_vel_var(Vector3f &vel_var);
|
|
|
|
|
|
|
|
void get_pos_var(Vector3f &pos_var);
|
|
|
|
|
|
|
|
// return true if the global position estimate is valid
|
|
|
|
bool global_position_is_valid();
|
|
|
|
|
|
|
|
// return true if the etimate is valid
|
|
|
|
// return the estimated terrain vertical position relative to the NED origin
|
|
|
|
bool get_terrain_vert_pos(float *ret);
|
|
|
|
|
2016-04-27 23:05:54 -03:00
|
|
|
// get the accerometer bias in m/s/s
|
|
|
|
void get_accel_bias(float bias[3]);
|
2016-04-11 09:12:24 -03:00
|
|
|
|
2016-06-21 08:51:04 -03:00
|
|
|
// get the gyroscope bias in rad/s
|
|
|
|
void get_gyro_bias(float bias[3]);
|
|
|
|
|
2016-04-16 00:38:40 -03:00
|
|
|
// get GPS check status
|
|
|
|
void get_gps_check_status(uint16_t *_gps_check_fail_status);
|
|
|
|
|
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
|
|
|
|
void get_posD_reset(float *delta, uint8_t *counter) {*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
|
|
|
|
void get_velD_reset(float *delta, uint8_t *counter) {*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
|
2016-06-06 04:40:32 -03:00
|
|
|
void get_posNE_reset(float delta[2], uint8_t *counter){
|
|
|
|
memcpy(delta, &_state_reset_status.posNE_change._data[0], sizeof(_state_reset_status.posNE_change._data));
|
|
|
|
*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
|
2016-06-06 04:40:32 -03:00
|
|
|
void get_velNE_reset(float delta[2], uint8_t *counter) {
|
|
|
|
memcpy(delta, &_state_reset_status.velNE_change._data[0], sizeof(_state_reset_status.velNE_change._data));
|
|
|
|
*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
|
2016-06-06 04:40:32 -03:00
|
|
|
void get_quat_reset(float delta_quat[4], uint8_t *counter)
|
2016-05-23 08:07:35 -03:00
|
|
|
{
|
2016-06-06 04:40:32 -03:00
|
|
|
memcpy(delta_quat, &_state_reset_status.quat_change._data[0], sizeof(_state_reset_status.quat_change._data));
|
2016-05-25 05:24:31 -03:00
|
|
|
*counter = _state_reset_status.quat_counter;
|
2016-05-23 08:07:35 -03:00
|
|
|
}
|
|
|
|
|
2015-11-19 13:08:04 -04:00
|
|
|
private:
|
|
|
|
|
2015-12-07 04:26:30 -04:00
|
|
|
static const uint8_t _k_num_states = 24;
|
2016-05-19 12:58:18 -03:00
|
|
|
static const float _k_earth_rate;
|
|
|
|
static const float _gravity_mss;
|
2015-12-07 04:26:30 -04:00
|
|
|
|
2016-05-23 06:56:25 -03:00
|
|
|
// reset event monitoring
|
|
|
|
// structure containing velocity, position, height and yaw reset information
|
|
|
|
struct {
|
2016-05-25 05:24:31 -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)
|
2016-05-23 06:56:25 -03:00
|
|
|
Vector2f velNE_change; // North East velocity change due to last reset (m)
|
|
|
|
float velD_change; // Down velocity change due to last reset (m/s)
|
|
|
|
Vector2f posNE_change; // North, East position change due to last reset (m)
|
|
|
|
float posD_change; // Down position change due to last reset (m)
|
2016-05-23 07:38:49 -03:00
|
|
|
Quaternion quat_change; // quaternion delta due to last reset - multiply pre-reset quaternion by this to get post-reset quaternion
|
2016-05-23 06:56:25 -03:00
|
|
|
} _state_reset_status;
|
|
|
|
|
2016-04-27 23:05:54 -03:00
|
|
|
float _dt_ekf_avg; // average update rate of the ekf
|
|
|
|
|
2016-02-23 22:49:27 -04:00
|
|
|
stateSample _state; // state struct of the ekf running at the delayed time horizon
|
2016-01-30 16:45:23 -04:00
|
|
|
|
2016-03-07 05:14:15 -04:00
|
|
|
bool _filter_initialised; // true when the EKF sttes and covariances been initialised
|
|
|
|
bool _earth_rate_initialised; // true when we know the earth rotatin rate (requires GPS)
|
2015-11-19 13:08:04 -04:00
|
|
|
|
2016-03-07 05:14:15 -04:00
|
|
|
bool _fuse_height; // baro height data should be fused
|
|
|
|
bool _fuse_pos; // gps position data should be fused
|
2016-02-23 22:49:27 -04:00
|
|
|
bool _fuse_hor_vel; // gps horizontal velocity measurement should be fused
|
2016-03-07 05:14:15 -04:00
|
|
|
bool _fuse_vert_vel; // gps vertical velocity measurement should be fused
|
2016-06-07 03:54:12 -03:00
|
|
|
|
|
|
|
// booleans true when fresh sensor data is available at the fusion time horizon
|
|
|
|
bool _gps_data_ready;
|
|
|
|
bool _mag_data_ready;
|
|
|
|
bool _baro_data_ready;
|
|
|
|
bool _range_data_ready;
|
|
|
|
bool _flow_data_ready;
|
|
|
|
bool _ev_data_ready;
|
|
|
|
bool _tas_data_ready;
|
2015-11-19 13:08:04 -04:00
|
|
|
|
2016-02-23 22:49:27 -04:00
|
|
|
uint64_t _time_last_fake_gps; // last time in us at which we have faked gps measurement for static mode
|
2016-01-28 06:52:39 -04:00
|
|
|
|
2016-02-18 06:21:04 -04:00
|
|
|
uint64_t _time_last_pos_fuse; // time the last fusion of horizontal position measurements was performed (usec)
|
2016-01-31 04:01:44 -04:00
|
|
|
uint64_t _time_last_vel_fuse; // time the last fusion of velocity measurements was performed (usec)
|
|
|
|
uint64_t _time_last_hgt_fuse; // time the last fusion of height measurements was performed (usec)
|
|
|
|
uint64_t _time_last_of_fuse; // time the last fusion of optical flow measurements were performed (usec)
|
2016-04-05 10:14:04 -03:00
|
|
|
uint64_t _time_last_arsp_fuse; // time the last fusion of airspeed measurements were performed (usec)
|
2016-01-31 04:01:44 -04:00
|
|
|
Vector2f _last_known_posNE; // last known local NE position vector (m)
|
|
|
|
float _last_disarmed_posD; // vertical position recorded at arming (m)
|
2016-05-22 12:40:43 -03:00
|
|
|
float _last_dt_overrun; // the amount of time the last IMU collection over-ran the target set by FILTER_UPDATE_PERIOD_MS (sec)
|
2015-12-22 06:22:17 -04:00
|
|
|
|
2016-02-23 22:49:27 -04:00
|
|
|
Vector3f _earth_rate_NED; // earth rotation vector (NED) in rad/s
|
2015-12-07 04:26:30 -04:00
|
|
|
|
2016-04-11 17:34:50 -03:00
|
|
|
matrix::Dcm<float> _R_to_earth; // transformation matrix from body frame to earth frame from last EKF predition
|
2015-12-07 04:26:30 -04:00
|
|
|
|
|
|
|
float P[_k_num_states][_k_num_states]; // state covariance matrix
|
2016-03-04 02:58:11 -04:00
|
|
|
float KH[_k_num_states][_k_num_states]; // intermediate variable for the covariance update
|
|
|
|
float KHP[_k_num_states][_k_num_states]; // intermediate variable for the covariance update
|
2015-12-06 07:57:43 -04:00
|
|
|
|
2016-02-23 22:49:27 -04:00
|
|
|
float _vel_pos_innov[6]; // innovations: 0-2 vel, 3-5 pos
|
2016-03-07 05:14:15 -04:00
|
|
|
float _vel_pos_innov_var[6]; // innovation variances: 0-2 vel, 3-5 pos
|
|
|
|
|
2016-02-23 22:49:27 -04:00
|
|
|
float _mag_innov[3]; // earth magnetic field innovations
|
2016-03-07 05:14:15 -04:00
|
|
|
float _mag_innov_var[3]; // earth magnetic field innovation variance
|
|
|
|
|
2016-03-11 07:52:38 -04:00
|
|
|
float _airspeed_innov; // airspeed measurement innovation
|
2016-04-21 19:38:41 -03:00
|
|
|
float _airspeed_innov_var; // airspeed measurement innovation variance
|
2016-03-11 07:52:38 -04:00
|
|
|
|
2016-02-23 22:49:27 -04:00
|
|
|
float _heading_innov; // heading measurement innovation
|
2016-03-07 05:14:15 -04:00
|
|
|
float _heading_innov_var; // heading measurement innovation variance
|
|
|
|
|
|
|
|
// optical flow processing
|
|
|
|
float _flow_innov[2]; // flow measurement innovation
|
|
|
|
float _flow_innov_var[2]; // flow innovation variance
|
2016-04-09 13:22:49 -03:00
|
|
|
Vector3f _flow_gyro_bias; // bias errors in optical flow sensor rate gyro outputs
|
|
|
|
Vector3f _imu_del_ang_of; // bias corrected delta angle measurements accumulated across the same time frame as the optical flow rates
|
2016-03-07 05:14:15 -04:00
|
|
|
float _delta_time_of; // time in sec that _imu_del_ang_of was accumulated over
|
2016-01-12 02:30:53 -04:00
|
|
|
|
2016-03-07 05:14:15 -04:00
|
|
|
float _mag_declination; // magnetic declination used by reset and fusion functions (rad)
|
2016-02-11 23:02:50 -04:00
|
|
|
|
2015-12-10 11:36:10 -04:00
|
|
|
// complementary filter states
|
2016-02-23 22:49:27 -04:00
|
|
|
Vector3f _delta_angle_corr; // delta angle correction vector
|
|
|
|
imuSample _imu_down_sampled; // down sampled imu data (sensor rate -> filter update rate)
|
2016-03-07 05:14:15 -04:00
|
|
|
Quaternion _q_down_sampled; // down sampled quaternion (tracking delta angles between ekf update steps)
|
2015-12-10 11:36:10 -04:00
|
|
|
|
2016-01-31 04:01:44 -04:00
|
|
|
// variables used for the GPS quality checks
|
2016-03-07 05:14:15 -04:00
|
|
|
float _gpsDriftVelN; // GPS north position derivative (m/s)
|
|
|
|
float _gpsDriftVelE; // GPS east position derivative (m/s)
|
|
|
|
float _gps_drift_velD; // GPS down position derivative (m/s)
|
|
|
|
float _gps_velD_diff_filt; // GPS filtered Down velocity (m/s)
|
|
|
|
float _gps_velN_filt; // GPS filtered North velocity (m/s)
|
|
|
|
float _gps_velE_filt; // GPS filtered East velocity (m/s)
|
|
|
|
uint64_t _last_gps_fail_us; // last system time in usec that the GPS failed it's checks
|
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
|
2016-02-18 06:21:04 -04:00
|
|
|
uint64_t _last_gps_origin_time_us; // time the origin was last set (uSec)
|
2016-03-07 05:14:15 -04:00
|
|
|
float _gps_alt_ref; // 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
|
2016-05-18 06:18:07 -03:00
|
|
|
uint32_t _hgt_counter; // number of height samples read during initialisation
|
2016-04-21 19:38:41 -03:00
|
|
|
float _rng_filt_state; // filtered height measurement
|
2016-05-18 06:18:07 -03:00
|
|
|
uint32_t _mag_counter; // number of magnetometer samples read during initialisation
|
|
|
|
uint32_t _ev_counter; // number of exgernal vision samples read during initialisation
|
2016-03-13 04:44:34 -03:00
|
|
|
uint64_t _time_last_mag; // measurement time of last magnetomter sample
|
2016-03-15 03:07:33 -03:00
|
|
|
Vector3f _mag_filt_state; // filtered magnetometer measurement
|
2016-03-07 05:14:15 -04:00
|
|
|
Vector3f _delVel_sum; // summed delta velocity
|
2016-04-22 18:55:25 -03:00
|
|
|
float _hgt_sensor_offset; // set as necessary if desired to maintain the same height after a height reset (m)
|
2016-06-06 08:59:46 -03:00
|
|
|
float _baro_hgt_offset; // baro height reading at the local NED origin (m)
|
|
|
|
|
|
|
|
// Variables used to control activation of post takeoff functionality
|
|
|
|
float _last_on_ground_posD; // last vertical position when the in_air status was false (m)
|
2016-01-30 16:44:19 -04:00
|
|
|
|
2016-01-31 04:01:44 -04:00
|
|
|
gps_check_fail_status_u _gps_check_fail_status;
|
2016-01-28 06:52:39 -04:00
|
|
|
|
2016-03-07 05:14:15 -04:00
|
|
|
// Terrain height state estimation
|
|
|
|
float _terrain_vpos; // estimated vertical position of the terrain underneath the vehicle in local NED frame (m)
|
|
|
|
float _terrain_var; // variance of terrain position estimate (m^2)
|
|
|
|
float _hagl_innov; // innovation of the last height above terrain measurement (m)
|
|
|
|
float _hagl_innov_var; // innovation variance for the last height above terrain measurement (m^2)
|
|
|
|
uint64_t _time_last_hagl_fuse; // last system time in usec that the hagl measurement failed it's checks
|
|
|
|
bool _terrain_initialised; // true when the terrain estimator has been intialised
|
|
|
|
|
2016-03-15 03:07:33 -03:00
|
|
|
// height sensor fault status
|
|
|
|
bool _baro_hgt_faulty; // true if valid baro data is unavailable for use
|
|
|
|
bool _gps_hgt_faulty; // true if valid gps height data is unavailable for use
|
|
|
|
bool _rng_hgt_faulty; // true if valid rnage finder height data is unavailable for use
|
|
|
|
int _primary_hgt_source; // priary source of height data set at initialisation
|
|
|
|
|
2016-04-21 20:24:04 -03:00
|
|
|
// imu fault status
|
|
|
|
uint64_t _time_bad_vert_accel; // last time a bad vertical accel was detected (usec)
|
|
|
|
|
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
|
|
|
|
2016-02-13 07:31:02 -04:00
|
|
|
// fuse magnetometer declination measurement
|
2016-02-08 00:12:38 -04:00
|
|
|
void fuseDeclination();
|
2016-02-07 23:15:05 -04:00
|
|
|
|
2016-02-13 07:31:02 -04:00
|
|
|
// fuse airspeed measurement
|
2015-11-19 13:08:04 -04:00
|
|
|
void fuseAirspeed();
|
|
|
|
|
2016-02-13 07:31:02 -04:00
|
|
|
// fuse velocity and position measurements (also barometer height)
|
2015-12-07 04:26:30 -04:00
|
|
|
void fuseVelPosHeight();
|
|
|
|
|
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();
|
|
|
|
|
|
|
|
// calculate optical flow bias errors
|
|
|
|
void calcOptFlowBias();
|
|
|
|
|
|
|
|
// initialise the terrain vertical position estimator
|
|
|
|
// return true if the initialisation is successful
|
|
|
|
bool initHagl();
|
|
|
|
|
|
|
|
// predict the terrain vertical position state and variance
|
|
|
|
void predictHagl();
|
|
|
|
|
|
|
|
// update the terrain vertical position estimate using a height above ground measurement from the range finder
|
|
|
|
void fuseHagl();
|
|
|
|
|
2016-02-11 23:02:50 -04:00
|
|
|
// reset the heading and magnetic field states using the declination and magnetometer measurements
|
|
|
|
// return true if successful
|
|
|
|
bool resetMagHeading(Vector3f &mag_init);
|
|
|
|
|
2016-02-11 23:09:23 -04:00
|
|
|
// calculate the magnetic declination to be used by the alignment and fusion processing
|
|
|
|
void calcMagDeclination();
|
|
|
|
|
2016-02-13 07:31:02 -04:00
|
|
|
// reset position states of the ekf (only vertical 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();
|
|
|
|
|
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
|
2015-12-10 11:36:10 -04:00
|
|
|
void calcEarthRateNED(Vector3f &omega, double 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
|
|
|
|
bool gps_is_good(struct 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
|
|
|
|
|
|
|
// control fusion of optical flow observtions
|
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();
|
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
|
|
|
|
|
|
|
// control fusion of pressure altitude observations
|
2016-06-07 05:44:47 -03:00
|
|
|
void controlBaroFusion();
|
2016-06-07 03:54:12 -03:00
|
|
|
|
|
|
|
// control fusion of velocity and position observations
|
|
|
|
void controlVelPosFusion();
|
2016-04-24 09:20:18 -03:00
|
|
|
|
|
|
|
// control for height sensor timeouts, sensor changes and state resets
|
|
|
|
void controlHeightSensorTimeouts();
|
|
|
|
|
2016-02-18 06:21:04 -04:00
|
|
|
// return the square of two floating point numbers - used in auto coded sections
|
2016-02-07 19:58:25 -04:00
|
|
|
inline float sq(float var)
|
|
|
|
{
|
|
|
|
return var * var;
|
|
|
|
}
|
2016-02-12 00:14:36 -04:00
|
|
|
|
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
|
|
|
|
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
|
|
|
|
void resetMagCovariance();
|
|
|
|
|
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();
|
|
|
|
|
2015-12-06 07:57:43 -04:00
|
|
|
};
|