Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Airspeed/Airspeed_Calibration.cpp
Views: 1798
/*1* auto_calibration.cpp - airspeed auto calibration2*3* Algorithm by Paul Riseborough4*5*/67#include "AP_Airspeed_config.h"89#if AP_AIRSPEED_ENABLED1011#include <AP_Common/AP_Common.h>12#include <AP_Math/AP_Math.h>13#include <GCS_MAVLink/GCS.h>14#include <AP_AHRS/AP_AHRS.h>1516#include "AP_Airspeed.h"171819// constructor - fill in all the initial values20Airspeed_Calibration::Airspeed_Calibration()21: P(100, 0, 0,220, 100, 0,230, 0, 0.000001f)24, Q0(0.01f)25, Q1(0.0000005f)26, state(0, 0, 0)27, DT(1)28{29}3031/*32initialise the ratio33*/34void Airspeed_Calibration::init(float initial_ratio)35{36state.z = 1.0f / sqrtf(initial_ratio);37}3839/*40update the state of the airspeed calibration - needs to be called41once a second42*/43float Airspeed_Calibration::update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)44{45// Perform the covariance prediction46// Q is a diagonal matrix so only need to add three terms in47// C code implementation48// P = P + Q;49P.a.x += Q0;50P.b.y += Q0;51P.c.z += Q1;5253// Perform the predicted measurement using the current state estimates54// No state prediction required because states are assumed to be time55// invariant plus process noise56// Ignore vertical wind component57float TAS_pred = state.z * norm(vg.x - state.x, vg.y - state.y, vg.z);58float TAS_mea = airspeed;5960// Calculate the observation Jacobian H_TAS61float SH1 = sq(vg.y - state.y) + sq(vg.x - state.x);62if (SH1 < 0.000001f) {63// avoid division by a small number64return state.z;65}66float SH2 = 1/sqrtf(SH1);6768// observation Jacobian69Vector3f H_TAS(70-(state.z*SH2*(2*vg.x - 2*state.x))/2,71-(state.z*SH2*(2*vg.y - 2*state.y))/2,721/SH2);7374// Calculate the fusion innovation covariance assuming a TAS measurement75// noise of 1.0 m/s76// S = H_TAS*P*H_TAS' + 1.0; % [1 x 3] * [3 x 3] * [3 x 1] + [1 x 1]77Vector3f PH = P * H_TAS;78float S = H_TAS * PH + 1.0f;7980// Calculate the Kalman gain81// [3 x 3] * [3 x 1] / [1 x 1]82Vector3f KG = PH / S;8384// Update the states85state += KG*(TAS_mea - TAS_pred); // [3 x 1] + [3 x 1] * [1 x 1]8687// Update the covariance matrix88Vector3f HP2 = H_TAS.row_times_mat(P);89P -= KG.mul_rowcol(HP2);9091// force symmetry on the covariance matrix - necessary due to rounding92// errors93float P12 = 0.5f * (P.a.y + P.b.x);94float P13 = 0.5f * (P.a.z + P.c.x);95float P23 = 0.5f * (P.b.z + P.c.y);96P.a.y = P.b.x = P12;97P.a.z = P.c.x = P13;98P.b.z = P.c.y = P23;99100// Constrain diagonals to be non-negative - protects against rounding errors101P.a.x = MAX(P.a.x, 0.0f);102P.b.y = MAX(P.b.y, 0.0f);103P.c.z = MAX(P.c.z, 0.0f);104105state.x = constrain_float(state.x, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);106state.y = constrain_float(state.y, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);107state.z = constrain_float(state.z, 0.5f, 1.0f);108109return state.z;110}111112113/*114called once a second to do calibration update115*/116void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)117{118#if AP_AIRSPEED_AUTOCAL_ENABLE119if (!param[i].autocal && !calibration_enabled) {120// auto-calibration not enabled121return;122}123124// set state.z based on current ratio, this allows the operator to125// override the current ratio in flight with autocal, which is126// very useful both for testing and to force a reasonable value.127float ratio = constrain_float(param[i].ratio, 1.0f, 4.0f);128129state[i].calibration.state.z = 1.0f / sqrtf(ratio);130131// calculate true airspeed, assuming a airspeed ratio of 1.0132float dpress = MAX(get_differential_pressure(i), 0);133float true_airspeed = sqrtf(dpress) * AP::ahrs().get_EAS2TAS();134135float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);136137if (isnan(zratio) || isinf(zratio)) {138return;139}140141// this constrains the resulting ratio to between 1.0 and 4.0142zratio = constrain_float(zratio, 0.5f, 1.0f);143param[i].ratio.set(1/sq(zratio));144if (state[i].counter > 60) {145if (state[i].last_saved_ratio > 1.05f*param[i].ratio ||146state[i].last_saved_ratio < 0.95f*param[i].ratio) {147param[i].ratio.save();148state[i].last_saved_ratio = param[i].ratio;149state[i].counter = 0;150GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u ratio reset: %f", i , static_cast<double> (param[i].ratio));151}152} else {153state[i].counter++;154}155#endif // AP_AIRSPEED_AUTOCAL_ENABLE156}157158/*159called once a second to do calibration update160*/161void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)162{163for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {164update_calibration(i, vground, max_airspeed_allowed_during_cal);165}166#if HAL_GCS_ENABLED && AP_AIRSPEED_AUTOCAL_ENABLE167send_airspeed_calibration(vground);168#endif169}170171172#if HAL_GCS_ENABLED && AP_AIRSPEED_AUTOCAL_ENABLE173void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground)174{175/*176the AIRSPEED_AUTOCAL message doesn't have an instance number177so we can only send it for one sensor at a time178*/179for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {180if (!param[i].autocal && !calibration_enabled) {181// auto-calibration not enabled on this sensor182continue;183}184const mavlink_airspeed_autocal_t packet{185vx: vground.x,186vy: vground.y,187vz: vground.z,188diff_pressure: get_differential_pressure(i),189EAS2TAS: AP::ahrs().get_EAS2TAS(),190ratio: param[i].ratio.get(),191state_x: state[i].calibration.state.x,192state_y: state[i].calibration.state.y,193state_z: state[i].calibration.state.z,194Pax: state[i].calibration.P.a.x,195Pby: state[i].calibration.P.b.y,196Pcz: state[i].calibration.P.c.z197};198gcs().send_to_active_channels(MAVLINK_MSG_ID_AIRSPEED_AUTOCAL,199(const char *)&packet);200break; // we can only send for one sensor201}202}203#endif // HAL_GCS_ENABLED && AP_AIRSPEED_AUTOCAL_ENABLE204205#endif // AP_AIRSPEED_ENABLED206207208