You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
229 lines
8.9 KiB
229 lines
8.9 KiB
/**************************************************************************** |
|
* |
|
* Copyright (c) 2015 Estimation and Control Library (ECL). All rights reserved. |
|
* |
|
* 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 |
|
* Class for core functions for ekf attitude and position estimator. |
|
* |
|
* @author Roman Bast <bapstroman@gmail.com> |
|
* @author Paul Riseborough <p_riseborough@live.com.au> |
|
* |
|
*/ |
|
|
|
#include "estimator_base.h" |
|
|
|
#define sq(_arg) powf(_arg, 2.0f) |
|
|
|
class Ekf : public EstimatorBase |
|
{ |
|
public: |
|
|
|
Ekf(); |
|
~Ekf(); |
|
|
|
bool init(uint64_t timestamp); |
|
bool update(); |
|
|
|
// 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]); |
|
|
|
// gets the innovation variance of the heading measurement |
|
void get_heading_innov_var(float *heading_innov_var); |
|
|
|
// get the state vector at the delayed time horizon |
|
void get_state_delayed(float *state); |
|
|
|
// get the diagonal elements of the covariance matrix |
|
void get_covariances(float *covariances); |
|
|
|
// 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); |
|
|
|
// bitmask containing filter control status |
|
union filter_control_status_u { |
|
struct { |
|
uint8_t angle_align : 1; // 0 - true if the filter angular alignment is complete |
|
uint8_t gps : 1; // 1 - true if GPS measurements are being fused |
|
uint8_t opt_flow : 1; // 2 - true if optical flow measurements are being fused |
|
uint8_t mag_hdg : 1; // 3 - true if a simple magnetic heading is being fused |
|
uint8_t mag_3D : 1; // 4 - true if 3-axis magnetometer measurement are being fused |
|
uint8_t mag_dec : 1; // 5 - true if synthetic magnetic declination measurements are being fused |
|
uint8_t in_air : 1; // 6 - true when the vehicle is airborne |
|
uint8_t armed : 1; // 7 - true when the vehicle motors are armed |
|
} flags; |
|
uint16_t value; |
|
}; |
|
filter_control_status_u _control_status={}; |
|
|
|
// get the ekf WGS-84 origin positoin and height and the system time it was last set |
|
void get_ekf_origin(uint64_t *origin_time, map_projection_reference_s *origin_pos, float *origin_alt); |
|
|
|
private: |
|
|
|
static const uint8_t _k_num_states = 24; |
|
static constexpr float _k_earth_rate = 0.000072921f; |
|
|
|
bool _filter_initialised; |
|
bool _earth_rate_initialised; |
|
|
|
bool _fuse_height; // baro height data should be fused |
|
bool _fuse_pos; // gps position data should be fused |
|
bool _fuse_hor_vel; // gps horizontal velocity measurement should be fused |
|
bool _fuse_vert_vel; // gps vertical velocity measurement should be fused |
|
|
|
uint64_t _time_last_fake_gps; |
|
|
|
uint64_t _time_last_pos_fuse; // time the last fusion of horizotal position measurements was performed (usec) |
|
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) |
|
Vector2f _last_known_posNE; // last known local NE position vector (m) |
|
float _last_disarmed_posD; // vertical position recorded at arming (m) |
|
|
|
Vector3f _earth_rate_NED; |
|
|
|
matrix::Dcm<float> _R_prev; |
|
|
|
float P[_k_num_states][_k_num_states]; // state covariance matrix |
|
|
|
float _vel_pos_innov[6]; // innovations: 0-2 vel, 3-5 pos |
|
float _mag_innov[3]; // earth magnetic field innovations |
|
float _heading_innov; // heading measurement innovation |
|
|
|
float _vel_pos_innov_var[6]; // innovation variances: 0-2 vel, 3-5 pos |
|
float _mag_innov_var[3]; // earth magnetic field innovation variance |
|
float _heading_innov_var; // heading measurement innovation variance |
|
|
|
// complementary filter states |
|
Vector3f _delta_angle_corr; |
|
Vector3f _delta_vel_corr; |
|
Vector3f _vel_corr; |
|
|
|
// variables used for the GPS quality checks |
|
float _gpsDriftVelN = 0.0f; // GPS north position derivative (m/s) |
|
float _gpsDriftVelE = 0.0f; // GPS east position derivative (m/s) |
|
float _gps_drift_velD = 0.0f; // GPS down position derivative (m/s) |
|
float _gps_velD_diff_filt = 0.0f; // GPS filtered Down velocity (m/s) |
|
float _gps_velN_filt = 0.0f; // GPS filtered North velocity (m/s) |
|
float _gps_velE_filt = 0.0f; // GPS filtered East velocity (m/s) |
|
uint64_t _last_gps_fail_us = 0; // last system time in usec that the GPS failed it's checks |
|
|
|
// Variables used to publish the WGS-84 location of the EKF local NED origin |
|
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) |
|
|
|
// publish the status of various GPS quality checks |
|
union gps_check_fail_status_u { |
|
struct { |
|
uint16_t fix : 1; // 0 - true if the fix type is insufficient (no 3D solution) |
|
uint16_t nsats : 1; // 1 - true if number of satellites used is insufficient |
|
uint16_t gdop : 1; // 2 - true if geometric dilution of precision is insufficient |
|
uint16_t hacc : 1; // 3 - true if reported horizontal accuracy is insufficient |
|
uint16_t vacc : 1; // 4 - true if reported vertical accuracy is insufficient |
|
uint16_t sacc : 1; // 5 - true if reported speed accuracy is insufficient |
|
uint16_t hdrift : 1; // 6 - true if horizontal drift is excessive (can only be used when stationary on ground) |
|
uint16_t vdrift : 1; // 7 - true if vertical drift is excessive (can only be used when stationary on ground) |
|
uint16_t hspeed : 1; // 8 - true if horizontal speed is excessive (can only be used when stationary on ground) |
|
uint16_t vspeed : 1; // 9 - true if vertical speed error is excessive |
|
} flags; |
|
uint16_t value; |
|
}_gps_check_fail_status; |
|
|
|
void calculateOutputStates(); |
|
|
|
bool initialiseFilter(void); |
|
|
|
void initialiseCovariance(); |
|
|
|
void predictState(); |
|
|
|
void predictCovariance(); |
|
|
|
void fuseMag(); |
|
|
|
void fuseHeading(); |
|
|
|
void fuseAirspeed(); |
|
|
|
void fuseRange(); |
|
|
|
void fuseVelPosHeight(); |
|
|
|
void resetVelocity(); |
|
|
|
void resetPosition(); |
|
|
|
void makeCovSymetrical(); |
|
|
|
void limitCov(); |
|
|
|
void printCovToFile(char const *filename); |
|
|
|
void assertCovNiceness(); |
|
|
|
void makeSymmetrical(); |
|
|
|
void constrainStates(); |
|
|
|
void fuse(float *K, float innovation); |
|
|
|
void printStates(); |
|
|
|
void printStatesFast(); |
|
|
|
void calcEarthRateNED(Vector3f &omega, double lat_rad) const; |
|
|
|
// return true id the GPS quality is good enough to set an origin and start aiding |
|
bool gps_is_good(struct gps_message *gps); |
|
|
|
// Control the filter fusion modes |
|
void controlFusionModes(); |
|
|
|
// Determine if we are airborne or motors are armed |
|
void calculateVehicleStatus(); |
|
};
|
|
|