2016-03-11 07:42:16 -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 airspeed_fusion.cpp
|
|
|
|
* airspeed fusion methods.
|
|
|
|
*
|
|
|
|
* @author Carl Olsson <carlolsson.co@gmail.com>
|
|
|
|
* @author Roman Bast <bapstroman@gmail.com>
|
|
|
|
* @author Paul Riseborough <p_riseborough@live.com.au>
|
|
|
|
*
|
|
|
|
*/
|
2016-06-07 07:32:55 -03:00
|
|
|
#include "../ecl.h"
|
2016-03-11 07:42:16 -04:00
|
|
|
#include "ekf.h"
|
|
|
|
#include "mathlib.h"
|
|
|
|
|
|
|
|
void Ekf::fuseAirspeed()
|
|
|
|
{
|
|
|
|
// Initialize variables
|
|
|
|
float vn; // Velocity in north direction
|
|
|
|
float ve; // Velocity in east direction
|
|
|
|
float vd; // Velocity in downwards direction
|
|
|
|
float vwn; // Wind speed in north direction
|
|
|
|
float vwe; // Wind speed in east direction
|
|
|
|
float v_tas_pred; // Predicted measurement
|
2016-04-05 10:14:04 -03:00
|
|
|
float R_TAS = sq(math::constrain(_params.eas_noise, 0.5f, 5.0f) * math::constrain(_airspeed_sample_delayed.eas2tas, 0.9f,
|
|
|
|
10.0f)); // Variance for true airspeed measurement - (m/sec)^2
|
2016-03-11 07:42:16 -04:00
|
|
|
float SH_TAS[3] = {}; // Varialbe used to optimise calculations of measurement jacobian
|
|
|
|
float H_TAS[24] = {}; // Observation Jacobian
|
|
|
|
float SK_TAS[2] = {}; // Varialbe used to optimise calculations of the Kalman gain vector
|
|
|
|
float Kfusion[24] = {}; // Kalman gain vector
|
|
|
|
|
|
|
|
// Copy required states to local variable names
|
|
|
|
vn = _state.vel(0);
|
|
|
|
ve = _state.vel(1);
|
|
|
|
vd = _state.vel(2);
|
|
|
|
vwn = _state.wind_vel(0);
|
|
|
|
vwe = _state.wind_vel(1);
|
|
|
|
|
|
|
|
// Calculate the predicted airspeed
|
|
|
|
v_tas_pred = sqrtf((ve - vwe) * (ve - vwe) + (vn - vwn) * (vn - vwn) + vd * vd);
|
|
|
|
|
|
|
|
// Perform fusion of True Airspeed measurement
|
2016-04-03 15:08:51 -03:00
|
|
|
if (v_tas_pred > 1.0f) {
|
2016-03-11 07:42:16 -04:00
|
|
|
// Calculate the observation jacobian
|
|
|
|
// intermediate variable from algebraic optimisation
|
2016-04-27 23:05:54 -03:00
|
|
|
SH_TAS[0] = 1.0f/v_tas_pred;
|
|
|
|
SH_TAS[1] = (SH_TAS[0]*(2.0f*ve - 2.0f*vwe))*0.5f;
|
|
|
|
SH_TAS[2] = (SH_TAS[0]*(2.0f*vn - 2.0f*vwn))*0.5f;
|
2016-03-11 07:42:16 -04:00
|
|
|
|
|
|
|
for (uint8_t i = 0; i < _k_num_states; i++) { H_TAS[i] = 0.0f; }
|
|
|
|
|
2016-04-27 23:05:54 -03:00
|
|
|
H_TAS[4] = SH_TAS[2];
|
|
|
|
H_TAS[5] = SH_TAS[1];
|
|
|
|
H_TAS[6] = vd*SH_TAS[0];
|
2016-03-11 07:42:16 -04:00
|
|
|
H_TAS[22] = -SH_TAS[2];
|
|
|
|
H_TAS[23] = -SH_TAS[1];
|
2016-04-05 10:14:04 -03:00
|
|
|
|
2016-03-11 07:42:16 -04:00
|
|
|
// We don't want to update the innovation variance if the calculation is ill conditioned
|
2016-04-27 23:05:54 -03:00
|
|
|
float _airspeed_innov_var_temp = (R_TAS + SH_TAS[2]*(P[4][4]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[22][4]*SH_TAS[2] - P[23][4]*SH_TAS[1] + P[6][4]*vd*SH_TAS[0]) + SH_TAS[1]*(P[4][5]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[22][5]*SH_TAS[2] - P[23][5]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]) - SH_TAS[2]*(P[4][22]*SH_TAS[2] + P[5][22]*SH_TAS[1] - P[22][22]*SH_TAS[2] - P[23][22]*SH_TAS[1] + P[6][22]*vd*SH_TAS[0]) - SH_TAS[1]*(P[4][23]*SH_TAS[2] + P[5][23]*SH_TAS[1] - P[22][23]*SH_TAS[2] - P[23][23]*SH_TAS[1] + P[6][23]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[4][6]*SH_TAS[2] + P[5][6]*SH_TAS[1] - P[22][6]*SH_TAS[2] - P[23][6]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]));
|
2016-04-05 10:14:04 -03:00
|
|
|
|
2016-03-11 07:42:16 -04:00
|
|
|
if (_airspeed_innov_var_temp >= R_TAS) { // Check for badly conditioned calculation
|
2016-04-05 10:14:04 -03:00
|
|
|
SK_TAS[0] = 1.0f / _airspeed_innov_var_temp;
|
2016-05-12 05:06:04 -03:00
|
|
|
_fault_status.flags.bad_airspeed = false;
|
2016-04-05 10:14:04 -03:00
|
|
|
|
2016-06-07 07:32:55 -03:00
|
|
|
} else { // Reset the estimator covarinace matrix
|
2016-05-12 05:06:04 -03:00
|
|
|
_fault_status.flags.bad_airspeed = true;
|
2016-04-05 10:14:04 -03:00
|
|
|
initialiseCovariance();
|
2016-06-07 07:32:55 -03:00
|
|
|
ECL_ERR("EKF airspeed fusion numerical error - covariance reset");
|
2016-04-05 10:14:04 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-03-11 07:42:16 -04:00
|
|
|
SK_TAS[1] = SH_TAS[1];
|
|
|
|
|
2016-04-27 23:05:54 -03:00
|
|
|
Kfusion[0] = SK_TAS[0]*(P[0][4]*SH_TAS[2] - P[0][22]*SH_TAS[2] + P[0][5]*SK_TAS[1] - P[0][23]*SK_TAS[1] + P[0][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[1] = SK_TAS[0]*(P[1][4]*SH_TAS[2] - P[1][22]*SH_TAS[2] + P[1][5]*SK_TAS[1] - P[1][23]*SK_TAS[1] + P[1][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[2] = SK_TAS[0]*(P[2][4]*SH_TAS[2] - P[2][22]*SH_TAS[2] + P[2][5]*SK_TAS[1] - P[2][23]*SK_TAS[1] + P[2][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[3] = SK_TAS[0]*(P[3][4]*SH_TAS[2] - P[3][22]*SH_TAS[2] + P[3][5]*SK_TAS[1] - P[3][23]*SK_TAS[1] + P[3][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[4] = SK_TAS[0]*(P[4][4]*SH_TAS[2] - P[4][22]*SH_TAS[2] + P[4][5]*SK_TAS[1] - P[4][23]*SK_TAS[1] + P[4][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[5] = SK_TAS[0]*(P[5][4]*SH_TAS[2] - P[5][22]*SH_TAS[2] + P[5][5]*SK_TAS[1] - P[5][23]*SK_TAS[1] + P[5][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[6] = SK_TAS[0]*(P[6][4]*SH_TAS[2] - P[6][22]*SH_TAS[2] + P[6][5]*SK_TAS[1] - P[6][23]*SK_TAS[1] + P[6][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[7] = SK_TAS[0]*(P[7][4]*SH_TAS[2] - P[7][22]*SH_TAS[2] + P[7][5]*SK_TAS[1] - P[7][23]*SK_TAS[1] + P[7][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[8] = SK_TAS[0]*(P[8][4]*SH_TAS[2] - P[8][22]*SH_TAS[2] + P[8][5]*SK_TAS[1] - P[8][23]*SK_TAS[1] + P[8][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[9] = SK_TAS[0]*(P[9][4]*SH_TAS[2] - P[9][22]*SH_TAS[2] + P[9][5]*SK_TAS[1] - P[9][23]*SK_TAS[1] + P[9][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[10] = SK_TAS[0]*(P[10][4]*SH_TAS[2] - P[10][22]*SH_TAS[2] + P[10][5]*SK_TAS[1] - P[10][23]*SK_TAS[1] + P[10][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[11] = SK_TAS[0]*(P[11][4]*SH_TAS[2] - P[11][22]*SH_TAS[2] + P[11][5]*SK_TAS[1] - P[11][23]*SK_TAS[1] + P[11][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[12] = SK_TAS[0]*(P[12][4]*SH_TAS[2] - P[12][22]*SH_TAS[2] + P[12][5]*SK_TAS[1] - P[12][23]*SK_TAS[1] + P[12][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[13] = SK_TAS[0]*(P[13][4]*SH_TAS[2] - P[13][22]*SH_TAS[2] + P[13][5]*SK_TAS[1] - P[13][23]*SK_TAS[1] + P[13][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[14] = SK_TAS[0]*(P[14][4]*SH_TAS[2] - P[14][22]*SH_TAS[2] + P[14][5]*SK_TAS[1] - P[14][23]*SK_TAS[1] + P[14][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[15] = SK_TAS[0]*(P[15][4]*SH_TAS[2] - P[15][22]*SH_TAS[2] + P[15][5]*SK_TAS[1] - P[15][23]*SK_TAS[1] + P[15][6]*vd*SH_TAS[0]);
|
2016-04-30 19:44:47 -03:00
|
|
|
Kfusion[16] = SK_TAS[0]*(P[16][4]*SH_TAS[2] - P[16][22]*SH_TAS[2] + P[16][5]*SK_TAS[1] - P[16][23]*SK_TAS[1] + P[16][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[17] = SK_TAS[0]*(P[17][4]*SH_TAS[2] - P[17][22]*SH_TAS[2] + P[17][5]*SK_TAS[1] - P[17][23]*SK_TAS[1] + P[17][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[18] = SK_TAS[0]*(P[18][4]*SH_TAS[2] - P[18][22]*SH_TAS[2] + P[18][5]*SK_TAS[1] - P[18][23]*SK_TAS[1] + P[18][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[19] = SK_TAS[0]*(P[19][4]*SH_TAS[2] - P[19][22]*SH_TAS[2] + P[19][5]*SK_TAS[1] - P[19][23]*SK_TAS[1] + P[19][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[20] = SK_TAS[0]*(P[20][4]*SH_TAS[2] - P[20][22]*SH_TAS[2] + P[20][5]*SK_TAS[1] - P[20][23]*SK_TAS[1] + P[20][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[21] = SK_TAS[0]*(P[21][4]*SH_TAS[2] - P[21][22]*SH_TAS[2] + P[21][5]*SK_TAS[1] - P[21][23]*SK_TAS[1] + P[21][6]*vd*SH_TAS[0]);
|
2016-04-27 23:05:54 -03:00
|
|
|
Kfusion[22] = SK_TAS[0]*(P[22][4]*SH_TAS[2] - P[22][22]*SH_TAS[2] + P[22][5]*SK_TAS[1] - P[22][23]*SK_TAS[1] + P[22][6]*vd*SH_TAS[0]);
|
|
|
|
Kfusion[23] = SK_TAS[0]*(P[23][4]*SH_TAS[2] - P[23][22]*SH_TAS[2] + P[23][5]*SK_TAS[1] - P[23][23]*SK_TAS[1] + P[23][6]*vd*SH_TAS[0]);
|
2016-03-11 07:42:16 -04:00
|
|
|
|
|
|
|
|
2016-05-08 13:21:48 -03:00
|
|
|
// Calculate measurement innovation
|
2016-04-05 10:14:04 -03:00
|
|
|
_airspeed_innov = v_tas_pred -
|
2016-05-08 13:21:48 -03:00
|
|
|
_airspeed_sample_delayed.true_airspeed;
|
2016-03-11 07:42:16 -04:00
|
|
|
|
|
|
|
// Calculate the innovation variance
|
|
|
|
_airspeed_innov_var = 1.0f / SK_TAS[0];
|
|
|
|
|
|
|
|
// Compute the ratio of innovation to gate size
|
|
|
|
_tas_test_ratio = sq(_airspeed_innov) / (sq(fmaxf(_params.tas_innov_gate, 1.0f)) * _airspeed_innov_var);
|
|
|
|
|
2016-05-08 13:21:48 -03:00
|
|
|
// If the innovation consistency check fails then don't fuse the sample and indicate bad airspeed health
|
2016-04-05 10:14:04 -03:00
|
|
|
if (_tas_test_ratio > 1.0f) {
|
2016-05-23 04:33:48 -03:00
|
|
|
_innov_check_fail_status.flags.reject_airspeed = true;
|
2016-04-05 10:14:04 -03:00
|
|
|
return;
|
|
|
|
}
|
2016-05-08 13:21:48 -03:00
|
|
|
else {
|
2016-05-23 04:33:48 -03:00
|
|
|
_innov_check_fail_status.flags.reject_airspeed = false;
|
2016-05-08 13:21:48 -03:00
|
|
|
}
|
2016-03-11 07:42:16 -04:00
|
|
|
|
2016-05-08 13:21:48 -03:00
|
|
|
// Airspeed measurement sample has passed check so record it
|
2016-04-05 10:14:04 -03:00
|
|
|
_time_last_arsp_fuse = _time_last_imu;
|
2016-03-11 07:42:16 -04:00
|
|
|
|
2016-04-05 10:14:04 -03:00
|
|
|
// update covariance matrix via Pnew = (I - KH)P = P - KHP
|
|
|
|
for (unsigned row = 0; row < _k_num_states; row++) {
|
|
|
|
for (unsigned column = 0; column < _k_num_states; column++) { // Here it will be a lot of zeros, should optimize that...
|
|
|
|
KH[row][column] = Kfusion[row] * H_TAS[column];
|
2016-03-11 07:42:16 -04:00
|
|
|
}
|
2016-04-05 10:14:04 -03:00
|
|
|
}
|
2016-03-11 07:42:16 -04:00
|
|
|
|
2016-04-05 10:14:04 -03:00
|
|
|
for (unsigned row = 0; row < _k_num_states; row++) {
|
|
|
|
for (unsigned column = 0; column < _k_num_states; column++) {
|
|
|
|
for (unsigned i = 0; i < _k_num_states; i++) { // Check if this is correct matrix multiplication!
|
|
|
|
KHP[row][column] += KH[row][i] * P[i][column];
|
2016-03-11 07:42:16 -04:00
|
|
|
}
|
|
|
|
}
|
2016-04-05 10:14:04 -03:00
|
|
|
}
|
2016-03-11 07:42:16 -04:00
|
|
|
|
2016-05-07 01:23:38 -03:00
|
|
|
// if the covariance correction will result in a negative variance, then
|
|
|
|
// the covariance marix is unhealthy and must be corrected
|
|
|
|
bool healthy = true;
|
2016-05-07 08:11:16 -03:00
|
|
|
_fault_status.flags.bad_airspeed = false;
|
2016-05-07 01:23:38 -03:00
|
|
|
for (int i = 0; i < _k_num_states; i++) {
|
|
|
|
if (P[i][i] < KHP[i][i]) {
|
|
|
|
// zero rows and columns
|
|
|
|
zeroRows(P,i,i);
|
|
|
|
zeroCols(P,i,i);
|
|
|
|
|
|
|
|
//flag as unhealthy
|
|
|
|
healthy = false;
|
|
|
|
|
|
|
|
// update individual measurement health status
|
2016-05-07 08:11:16 -03:00
|
|
|
_fault_status.flags.bad_airspeed = true;
|
2016-05-07 01:23:38 -03:00
|
|
|
|
2016-03-11 07:42:16 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-05-07 01:23:38 -03:00
|
|
|
// only apply covariance and state corrrections if healthy
|
|
|
|
if (healthy) {
|
|
|
|
// apply the covariance corrections
|
|
|
|
for (unsigned row = 0; row < _k_num_states; row++) {
|
|
|
|
for (unsigned column = 0; column < _k_num_states; column++) {
|
|
|
|
P[row][column] = P[row][column] - KHP[row][column];
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// correct the covariance marix for gross errors
|
2016-05-07 07:29:50 -03:00
|
|
|
fixCovarianceErrors();
|
2016-05-07 01:23:38 -03:00
|
|
|
|
|
|
|
// apply the state corrections
|
|
|
|
fuse(Kfusion, _airspeed_innov);
|
|
|
|
|
|
|
|
}
|
2016-03-11 07:42:16 -04:00
|
|
|
}
|
2016-05-04 20:34:01 -03:00
|
|
|
}
|
2016-07-12 06:40:41 -03:00
|
|
|
|
|
|
|
void Ekf::get_wind_velocity(float *wind)
|
|
|
|
{
|
|
|
|
wind[0] = _state.wind_vel(0);
|
|
|
|
wind[1] = _state.wind_vel(1);
|
|
|
|
}
|