2013-07-19 19:14:58 -03:00
|
|
|
/*
|
|
|
|
* auto_calibration.cpp - airspeed auto calibration
|
2016-01-29 07:38:33 -04:00
|
|
|
*
|
|
|
|
* Algorithm by Paul Riseborough
|
2013-07-19 19:14:58 -03:00
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
2023-06-09 02:58:29 -03:00
|
|
|
#include "AP_Airspeed_config.h"
|
|
|
|
|
|
|
|
#if AP_AIRSPEED_ENABLED
|
|
|
|
|
2016-01-29 07:38:33 -04:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2018-11-22 19:43:22 -04:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2019-06-26 23:38:33 -03:00
|
|
|
#include <AP_Baro/AP_Baro.h>
|
2016-01-29 07:38:33 -04:00
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include "AP_Airspeed.h"
|
2013-07-19 19:14:58 -03:00
|
|
|
|
|
|
|
|
|
|
|
// constructor - fill in all the initial values
|
2016-08-08 00:29:50 -03:00
|
|
|
Airspeed_Calibration::Airspeed_Calibration()
|
2016-01-29 07:38:33 -04:00
|
|
|
: P(100, 0, 0,
|
|
|
|
0, 100, 0,
|
|
|
|
0, 0, 0.000001f)
|
|
|
|
, Q0(0.01f)
|
|
|
|
, Q1(0.0000005f)
|
|
|
|
, state(0, 0, 0)
|
|
|
|
, DT(1)
|
2013-07-19 19:14:58 -03:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
initialise the ratio
|
|
|
|
*/
|
|
|
|
void Airspeed_Calibration::init(float initial_ratio)
|
|
|
|
{
|
2014-07-08 07:26:44 -03:00
|
|
|
state.z = 1.0f / sqrtf(initial_ratio);
|
2013-07-19 19:14:58 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
update the state of the airspeed calibration - needs to be called
|
|
|
|
once a second
|
|
|
|
*/
|
2016-08-08 00:28:24 -03:00
|
|
|
float Airspeed_Calibration::update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
|
2013-07-19 19:14:58 -03:00
|
|
|
{
|
|
|
|
// Perform the covariance prediction
|
|
|
|
// Q is a diagonal matrix so only need to add three terms in
|
|
|
|
// C code implementation
|
|
|
|
// P = P + Q;
|
|
|
|
P.a.x += Q0;
|
|
|
|
P.b.y += Q0;
|
|
|
|
P.c.z += Q1;
|
2016-01-29 07:38:33 -04:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// Perform the predicted measurement using the current state estimates
|
|
|
|
// No state prediction required because states are assumed to be time
|
|
|
|
// invariant plus process noise
|
|
|
|
// Ignore vertical wind component
|
2016-04-16 06:58:46 -03:00
|
|
|
float TAS_pred = state.z * norm(vg.x - state.x, vg.y - state.y, vg.z);
|
2016-08-07 21:48:54 -03:00
|
|
|
float TAS_mea = airspeed;
|
2016-01-29 07:38:33 -04:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// Calculate the observation Jacobian H_TAS
|
|
|
|
float SH1 = sq(vg.y - state.y) + sq(vg.x - state.x);
|
|
|
|
if (SH1 < 0.000001f) {
|
|
|
|
// avoid division by a small number
|
|
|
|
return state.z;
|
|
|
|
}
|
2014-04-01 08:09:21 -03:00
|
|
|
float SH2 = 1/sqrtf(SH1);
|
2013-07-19 19:14:58 -03:00
|
|
|
|
|
|
|
// observation Jacobian
|
|
|
|
Vector3f H_TAS(
|
|
|
|
-(state.z*SH2*(2*vg.x - 2*state.x))/2,
|
|
|
|
-(state.z*SH2*(2*vg.y - 2*state.y))/2,
|
|
|
|
1/SH2);
|
2016-01-29 07:38:33 -04:00
|
|
|
|
2016-08-08 00:29:50 -03:00
|
|
|
// Calculate the fusion innovation covariance assuming a TAS measurement
|
2013-07-19 19:14:58 -03:00
|
|
|
// noise of 1.0 m/s
|
|
|
|
// S = H_TAS*P*H_TAS' + 1.0; % [1 x 3] * [3 x 3] * [3 x 1] + [1 x 1]
|
|
|
|
Vector3f PH = P * H_TAS;
|
|
|
|
float S = H_TAS * PH + 1.0f;
|
2016-01-29 07:38:33 -04:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// Calculate the Kalman gain
|
|
|
|
// [3 x 3] * [3 x 1] / [1 x 1]
|
2016-01-29 07:38:33 -04:00
|
|
|
Vector3f KG = PH / S;
|
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// Update the states
|
|
|
|
state += KG*(TAS_mea - TAS_pred); // [3 x 1] + [3 x 1] * [1 x 1]
|
2016-01-29 07:38:33 -04:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// Update the covariance matrix
|
2022-07-23 05:33:20 -03:00
|
|
|
Vector3f HP2 = H_TAS.row_times_mat(P);
|
2013-07-19 19:14:58 -03:00
|
|
|
P -= KG.mul_rowcol(HP2);
|
2016-01-29 07:38:33 -04:00
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
// force symmetry on the covariance matrix - necessary due to rounding
|
|
|
|
// errors
|
2016-01-29 07:38:33 -04:00
|
|
|
float P12 = 0.5f * (P.a.y + P.b.x);
|
|
|
|
float P13 = 0.5f * (P.a.z + P.c.x);
|
|
|
|
float P23 = 0.5f * (P.b.z + P.c.y);
|
|
|
|
P.a.y = P.b.x = P12;
|
|
|
|
P.a.z = P.c.x = P13;
|
|
|
|
P.b.z = P.c.y = P23;
|
2013-07-19 19:14:58 -03:00
|
|
|
|
2013-07-20 04:16:07 -03:00
|
|
|
// Constrain diagonals to be non-negative - protects against rounding errors
|
2015-11-27 13:11:58 -04:00
|
|
|
P.a.x = MAX(P.a.x, 0.0f);
|
|
|
|
P.b.y = MAX(P.b.y, 0.0f);
|
|
|
|
P.c.z = MAX(P.c.z, 0.0f);
|
2013-07-20 04:16:07 -03:00
|
|
|
|
2016-08-08 00:28:24 -03:00
|
|
|
state.x = constrain_float(state.x, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
|
|
|
|
state.y = constrain_float(state.y, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
|
2013-08-28 09:36:05 -03:00
|
|
|
state.z = constrain_float(state.z, 0.5f, 1.0f);
|
|
|
|
|
2013-07-19 19:14:58 -03:00
|
|
|
return state.z;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
called once a second to do calibration update
|
|
|
|
*/
|
2017-11-03 03:17:34 -03:00
|
|
|
void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
|
2013-07-19 19:14:58 -03:00
|
|
|
{
|
2019-10-03 08:02:07 -03:00
|
|
|
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
2020-11-24 10:13:10 -04:00
|
|
|
if (!param[i].autocal && !calibration_enabled) {
|
2013-07-19 19:14:58 -03:00
|
|
|
// auto-calibration not enabled
|
|
|
|
return;
|
|
|
|
}
|
2013-09-12 22:45:57 -03:00
|
|
|
|
|
|
|
// set state.z based on current ratio, this allows the operator to
|
|
|
|
// override the current ratio in flight with autocal, which is
|
2016-01-29 07:38:33 -04:00
|
|
|
// very useful both for testing and to force a reasonable value.
|
2017-11-03 03:17:34 -03:00
|
|
|
float ratio = constrain_float(param[i].ratio, 1.0f, 4.0f);
|
2013-09-12 22:45:57 -03:00
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
state[i].calibration.state.z = 1.0f / sqrtf(ratio);
|
2013-09-12 22:45:57 -03:00
|
|
|
|
2013-07-19 22:11:04 -03:00
|
|
|
// calculate true airspeed, assuming a airspeed ratio of 1.0
|
2022-05-16 02:25:21 -03:00
|
|
|
float dpress = MAX(get_differential_pressure(i), 0);
|
2019-06-01 02:07:03 -03:00
|
|
|
float true_airspeed = sqrtf(dpress) * AP::baro().get_EAS2TAS();
|
2013-08-28 09:35:50 -03:00
|
|
|
|
2017-11-03 03:17:34 -03:00
|
|
|
float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
|
2013-09-12 22:45:57 -03:00
|
|
|
|
|
|
|
if (isnan(zratio) || isinf(zratio)) {
|
2013-07-19 19:14:58 -03:00
|
|
|
return;
|
|
|
|
}
|
2013-07-20 22:17:50 -03:00
|
|
|
|
|
|
|
// this constrains the resulting ratio to between 1.0 and 4.0
|
2013-09-12 22:45:57 -03:00
|
|
|
zratio = constrain_float(zratio, 0.5f, 1.0f);
|
2017-11-03 03:17:34 -03:00
|
|
|
param[i].ratio.set(1/sq(zratio));
|
|
|
|
if (state[i].counter > 60) {
|
|
|
|
if (state[i].last_saved_ratio > 1.05f*param[i].ratio ||
|
|
|
|
state[i].last_saved_ratio < 0.95f*param[i].ratio) {
|
|
|
|
param[i].ratio.save();
|
|
|
|
state[i].last_saved_ratio = param[i].ratio;
|
|
|
|
state[i].counter = 0;
|
2020-11-24 10:13:10 -04:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u ratio reset: %f", i , static_cast<double> (param[i].ratio));
|
2013-07-19 19:14:58 -03:00
|
|
|
}
|
|
|
|
} else {
|
2017-11-03 03:17:34 -03:00
|
|
|
state[i].counter++;
|
|
|
|
}
|
2019-10-03 08:02:07 -03:00
|
|
|
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
|
2017-11-03 03:17:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
called once a second to do calibration update
|
|
|
|
*/
|
|
|
|
void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
|
|
|
update_calibration(i, vground, max_airspeed_allowed_during_cal);
|
2013-07-19 19:14:58 -03:00
|
|
|
}
|
2018-11-22 19:43:22 -04:00
|
|
|
send_airspeed_calibration(vground);
|
2013-07-19 19:14:58 -03:00
|
|
|
}
|
2013-08-28 09:35:50 -03:00
|
|
|
|
2018-11-22 19:43:22 -04:00
|
|
|
|
|
|
|
void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground)
|
2013-08-28 09:35:50 -03:00
|
|
|
{
|
2019-10-03 08:02:07 -03:00
|
|
|
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
2019-06-26 20:47:38 -03:00
|
|
|
const mavlink_airspeed_autocal_t packet{
|
2019-07-09 07:44:09 -03:00
|
|
|
vx: vground.x,
|
|
|
|
vy: vground.y,
|
|
|
|
vz: vground.z,
|
|
|
|
diff_pressure: get_differential_pressure(primary),
|
|
|
|
EAS2TAS: AP::baro().get_EAS2TAS(),
|
|
|
|
ratio: param[primary].ratio.get(),
|
|
|
|
state_x: state[primary].calibration.state.x,
|
|
|
|
state_y: state[primary].calibration.state.y,
|
|
|
|
state_z: state[primary].calibration.state.z,
|
|
|
|
Pax: state[primary].calibration.P.a.x,
|
|
|
|
Pby: state[primary].calibration.P.b.y,
|
|
|
|
Pcz: state[primary].calibration.P.c.z
|
2019-06-26 20:47:38 -03:00
|
|
|
};
|
|
|
|
gcs().send_to_active_channels(MAVLINK_MSG_ID_AIRSPEED_AUTOCAL,
|
|
|
|
(const char *)&packet);
|
2019-10-03 08:02:07 -03:00
|
|
|
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
|
2013-08-28 09:35:50 -03:00
|
|
|
}
|
2023-06-09 02:58:29 -03:00
|
|
|
|
|
|
|
#endif // AP_AIRSPEED_ENABLED
|