2015-12-07 04:26:30 -04:00
|
|
|
/****************************************************************************
|
|
|
|
*
|
|
|
|
* 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 vel_pos_fusion.cpp
|
|
|
|
* Function for fusing gps and baro measurements/
|
|
|
|
*
|
|
|
|
* @author Roman Bast <bapstroman@gmail.com>
|
2016-03-07 05:27:40 -04:00
|
|
|
* @author Siddharth Bharat Purohit <siddharthbharatpurohit@gmail.com>
|
|
|
|
* @author Paul Riseborough <p_riseborough@live.com.au>
|
2015-12-07 04:26:30 -04:00
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "ekf.h"
|
2018-03-22 15:10:30 -03:00
|
|
|
#include <ecl.h>
|
|
|
|
#include <mathlib/mathlib.h>
|
2015-12-07 04:26:30 -04:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
bool Ekf::fuseHorizontalVelocity(const Vector3f &innov, const Vector2f &innov_gate,
|
|
|
|
const Vector3f &obs_var, Vector3f &innov_var, Vector2f &test_ratio)
|
|
|
|
{
|
2019-12-06 08:18:27 -04:00
|
|
|
innov_var(0) = P(4,4) + obs_var(0);
|
|
|
|
innov_var(1) = P(5,5) + obs_var(1);
|
2019-10-29 06:58:01 -03:00
|
|
|
test_ratio(0) = fmaxf( sq(innov(0)) / (sq(innov_gate(0)) * innov_var(0)),
|
|
|
|
sq(innov(1)) / (sq(innov_gate(0)) * innov_var(1)));
|
|
|
|
|
|
|
|
bool innov_check_pass = (test_ratio(0) <= 1.0f);
|
|
|
|
if (innov_check_pass)
|
|
|
|
{
|
|
|
|
_time_last_hor_vel_fuse = _time_last_imu;
|
|
|
|
_innov_check_fail_status.flags.reject_hor_vel = false;
|
|
|
|
|
|
|
|
fuseVelPosHeight(innov(0),innov_var(0),0);
|
|
|
|
fuseVelPosHeight(innov(1),innov_var(1),1);
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}else{
|
|
|
|
_innov_check_fail_status.flags.reject_hor_vel = true;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
2019-10-15 09:49:05 -03:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
bool Ekf::fuseVerticalVelocity(const Vector3f &innov, const Vector2f &innov_gate,
|
|
|
|
const Vector3f &obs_var, Vector3f &innov_var, Vector2f &test_ratio)
|
|
|
|
{
|
2019-12-06 08:18:27 -04:00
|
|
|
innov_var(2) = P(6,6) + obs_var(2);
|
2019-10-29 06:58:01 -03:00
|
|
|
test_ratio(1) = sq(innov(2)) / (sq(innov_gate(1)) * innov_var(2));
|
2019-10-15 09:49:05 -03:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
bool innov_check_pass = (test_ratio(1) <= 1.0f);
|
|
|
|
if (innov_check_pass) {
|
|
|
|
_time_last_ver_vel_fuse = _time_last_imu;
|
|
|
|
_innov_check_fail_status.flags.reject_ver_vel = false;
|
2019-10-15 09:49:05 -03:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
fuseVelPosHeight(innov(2),innov_var(2),2);
|
2016-01-06 14:51:27 -04:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
return true;
|
|
|
|
}else{
|
|
|
|
_innov_check_fail_status.flags.reject_ver_vel = true;
|
|
|
|
return false;
|
2016-02-24 17:17:50 -04:00
|
|
|
}
|
2019-10-29 06:58:01 -03:00
|
|
|
}
|
2016-01-06 14:51:27 -04:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
bool Ekf::fuseHorizontalPosition(const Vector3f &innov, const Vector2f &innov_gate,
|
|
|
|
const Vector3f &obs_var, Vector3f &innov_var, Vector2f &test_ratio)
|
|
|
|
{
|
2019-12-06 08:18:27 -04:00
|
|
|
innov_var(0) = P(7,7) + obs_var(0);
|
|
|
|
innov_var(1) = P(8,8) + obs_var(1);
|
2019-10-29 06:58:01 -03:00
|
|
|
test_ratio(0) = fmaxf( sq(innov(0)) / (sq(innov_gate(0)) * innov_var(0)),
|
|
|
|
sq(innov(1)) / (sq(innov_gate(0)) * innov_var(1)));
|
2016-02-24 17:17:50 -04:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
bool innov_check_pass = (test_ratio(0) <= 1.0f) || !_control_status.flags.tilt_align;
|
2019-10-15 09:49:05 -03:00
|
|
|
if (innov_check_pass) {
|
|
|
|
if (!_fuse_hpos_as_odom) {
|
2019-10-29 06:58:01 -03:00
|
|
|
_time_last_hor_pos_fuse = _time_last_imu;
|
2016-05-26 22:29:10 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
} else {
|
|
|
|
_time_last_delpos_fuse = _time_last_imu;
|
2017-11-02 22:11:32 -03:00
|
|
|
}
|
2019-10-29 06:58:01 -03:00
|
|
|
_innov_check_fail_status.flags.reject_hor_pos = false;
|
2017-11-02 22:11:32 -03:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
fuseVelPosHeight(innov(0),innov_var(0),3);
|
|
|
|
fuseVelPosHeight(innov(1),innov_var(1),4);
|
2016-02-24 17:17:50 -04:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
return true;
|
2019-09-17 04:17:29 -03:00
|
|
|
}else{
|
2019-10-29 06:58:01 -03:00
|
|
|
_innov_check_fail_status.flags.reject_hor_pos = true;
|
|
|
|
return false;
|
2016-02-24 17:17:50 -04:00
|
|
|
}
|
2019-10-29 06:58:01 -03:00
|
|
|
}
|
2016-02-24 17:17:50 -04:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
bool Ekf::fuseVerticalPosition(const Vector3f &innov, const Vector2f &innov_gate,
|
|
|
|
const Vector3f &obs_var, Vector3f &innov_var, Vector2f &test_ratio)
|
|
|
|
{
|
2019-12-06 08:18:27 -04:00
|
|
|
innov_var(2) = P(9,9) + obs_var(2);
|
2019-10-29 06:58:01 -03:00
|
|
|
test_ratio(1) = sq(innov(2)) / (sq(innov_gate(1)) * innov_var(2));
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
bool innov_check_pass = (test_ratio(1) <= 1.0f) || !_control_status.flags.tilt_align;
|
|
|
|
if (innov_check_pass) {
|
|
|
|
_time_last_hgt_fuse = _time_last_imu;
|
|
|
|
_innov_check_fail_status.flags.reject_ver_pos = false;
|
2016-02-24 17:17:50 -04:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
fuseVelPosHeight(innov(2),innov_var(2),5);
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
return true;
|
|
|
|
}else{
|
|
|
|
_innov_check_fail_status.flags.reject_ver_pos = true;
|
|
|
|
return false;
|
2016-02-24 17:17:50 -04:00
|
|
|
}
|
2019-10-15 09:49:05 -03:00
|
|
|
}
|
2016-02-24 17:17:50 -04:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
// Helper function that fuses a single velocity or position measurement
|
|
|
|
void Ekf::fuseVelPosHeight(const float innov, const float innov_var, const int obs_index)
|
|
|
|
{
|
|
|
|
float Kfusion[24] = {}; // Kalman gain vector for any single observation - sequential fusion is used.
|
|
|
|
unsigned state_index = obs_index + 4; // we start with vx and this is the 4. state
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
// calculate kalman gain K = PHS, where S = 1/innovation variance
|
|
|
|
for (int row = 0; row < _k_num_states; row++) {
|
2019-12-06 08:18:27 -04:00
|
|
|
Kfusion[row] = P(row,state_index) / innov_var;
|
2016-02-24 17:17:50 -04:00
|
|
|
}
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-12-06 08:18:27 -04:00
|
|
|
matrix::SquareMatrix<float, _k_num_states> KHP {};
|
2016-02-24 17:17:50 -04:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
for (unsigned row = 0; row < _k_num_states; row++) {
|
|
|
|
for (unsigned column = 0; column < _k_num_states; column++) {
|
2019-12-06 08:18:27 -04:00
|
|
|
KHP(row,column) = Kfusion[row] * P(state_index,column);
|
2016-01-06 14:51:27 -04:00
|
|
|
}
|
2019-10-15 09:49:05 -03:00
|
|
|
}
|
2016-01-06 14:51:27 -04:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
// if the covariance correction will result in a negative variance, then
|
|
|
|
// the covariance matrix is unhealthy and must be corrected
|
|
|
|
bool healthy = true;
|
2016-01-06 14:51:27 -04:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
for (int i = 0; i < _k_num_states; i++) {
|
2019-12-06 08:18:27 -04:00
|
|
|
if (P(i,i) < KHP(i,i)) {
|
2019-10-15 09:49:05 -03:00
|
|
|
// zero rows and columns
|
2019-12-06 08:18:27 -04:00
|
|
|
P.uncorrelateCovarianceSetVariance<1>(i, 0.0f);
|
2019-10-15 09:49:05 -03:00
|
|
|
|
|
|
|
healthy = false;
|
|
|
|
|
2019-10-29 06:58:01 -03:00
|
|
|
setVelPosFaultStatus(obs_index, true);
|
2019-10-15 09:49:05 -03:00
|
|
|
|
|
|
|
} else {
|
2019-10-29 06:58:01 -03:00
|
|
|
setVelPosFaultStatus(obs_index, false);
|
2016-02-24 17:17:50 -04:00
|
|
|
}
|
2019-10-15 09:49:05 -03:00
|
|
|
}
|
2016-02-24 17:17:50 -04:00
|
|
|
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
// only apply covariance and state corrections if healthy
|
|
|
|
if (healthy) {
|
|
|
|
// apply the covariance corrections
|
2015-12-07 04:26:30 -04:00
|
|
|
for (unsigned row = 0; row < _k_num_states; row++) {
|
|
|
|
for (unsigned column = 0; column < _k_num_states; column++) {
|
2019-12-06 08:18:27 -04:00
|
|
|
P(row,column) = P(row,column) - KHP(row,column);
|
2015-12-07 04:26:30 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
// correct the covariance matrix for gross errors
|
|
|
|
fixCovarianceErrors();
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
// apply the state corrections
|
|
|
|
fuse(Kfusion, innov);
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
}
|
|
|
|
}
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
void Ekf::setVelPosFaultStatus(const int index, const bool status)
|
|
|
|
{
|
|
|
|
if (index == 0) {
|
|
|
|
_fault_status.flags.bad_vel_N = status;
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
} else if (index == 1) {
|
|
|
|
_fault_status.flags.bad_vel_E = status;
|
2018-05-03 15:14:12 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
} else if (index == 2) {
|
|
|
|
_fault_status.flags.bad_vel_D = status;
|
2015-12-07 04:26:30 -04:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
} else if (index == 3) {
|
|
|
|
_fault_status.flags.bad_pos_N = status;
|
2016-05-07 01:22:59 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
} else if (index == 4) {
|
|
|
|
_fault_status.flags.bad_pos_E = status;
|
2016-05-07 01:22:59 -03:00
|
|
|
|
2019-10-15 09:49:05 -03:00
|
|
|
} else if (index == 5) {
|
|
|
|
_fault_status.flags.bad_pos_D = status;
|
2016-01-06 14:51:27 -04:00
|
|
|
}
|
|
|
|
}
|