APM:Libraries
Airspeed_Calibration.cpp
Go to the documentation of this file.
1 /*
2  * auto_calibration.cpp - airspeed auto calibration
3  *
4  * Algorithm by Paul Riseborough
5  *
6  */
7 
8 #include <AP_Common/AP_Common.h>
9 #include <AP_HAL/AP_HAL.h>
10 #include <AP_Math/AP_Math.h>
11 
12 #include "AP_Airspeed.h"
13 
14 extern const AP_HAL::HAL& hal;
15 
16 // constructor - fill in all the initial values
18  : P(100, 0, 0,
19  0, 100, 0,
20  0, 0, 0.000001f)
21  , Q0(0.01f)
22  , Q1(0.0000005f)
23  , state(0, 0, 0)
24  , DT(1)
25 {
26 }
27 
28 /*
29  initialise the ratio
30  */
31 void Airspeed_Calibration::init(float initial_ratio)
32 {
33  state.z = 1.0f / sqrtf(initial_ratio);
34 }
35 
36 /*
37  update the state of the airspeed calibration - needs to be called
38  once a second
39  */
40 float Airspeed_Calibration::update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
41 {
42  // Perform the covariance prediction
43  // Q is a diagonal matrix so only need to add three terms in
44  // C code implementation
45  // P = P + Q;
46  P.a.x += Q0;
47  P.b.y += Q0;
48  P.c.z += Q1;
49 
50  // Perform the predicted measurement using the current state estimates
51  // No state prediction required because states are assumed to be time
52  // invariant plus process noise
53  // Ignore vertical wind component
54  float TAS_pred = state.z * norm(vg.x - state.x, vg.y - state.y, vg.z);
55  float TAS_mea = airspeed;
56 
57  // Calculate the observation Jacobian H_TAS
58  float SH1 = sq(vg.y - state.y) + sq(vg.x - state.x);
59  if (SH1 < 0.000001f) {
60  // avoid division by a small number
61  return state.z;
62  }
63  float SH2 = 1/sqrtf(SH1);
64 
65  // observation Jacobian
66  Vector3f H_TAS(
67  -(state.z*SH2*(2*vg.x - 2*state.x))/2,
68  -(state.z*SH2*(2*vg.y - 2*state.y))/2,
69  1/SH2);
70 
71  // Calculate the fusion innovation covariance assuming a TAS measurement
72  // noise of 1.0 m/s
73  // S = H_TAS*P*H_TAS' + 1.0; % [1 x 3] * [3 x 3] * [3 x 1] + [1 x 1]
74  Vector3f PH = P * H_TAS;
75  float S = H_TAS * PH + 1.0f;
76 
77  // Calculate the Kalman gain
78  // [3 x 3] * [3 x 1] / [1 x 1]
79  Vector3f KG = PH / S;
80 
81  // Update the states
82  state += KG*(TAS_mea - TAS_pred); // [3 x 1] + [3 x 1] * [1 x 1]
83 
84  // Update the covariance matrix
85  Vector3f HP2 = H_TAS * P;
86  P -= KG.mul_rowcol(HP2);
87 
88  // force symmetry on the covariance matrix - necessary due to rounding
89  // errors
90  float P12 = 0.5f * (P.a.y + P.b.x);
91  float P13 = 0.5f * (P.a.z + P.c.x);
92  float P23 = 0.5f * (P.b.z + P.c.y);
93  P.a.y = P.b.x = P12;
94  P.a.z = P.c.x = P13;
95  P.b.z = P.c.y = P23;
96 
97  // Constrain diagonals to be non-negative - protects against rounding errors
98  P.a.x = MAX(P.a.x, 0.0f);
99  P.b.y = MAX(P.b.y, 0.0f);
100  P.c.z = MAX(P.c.z, 0.0f);
101 
102  state.x = constrain_float(state.x, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
103  state.y = constrain_float(state.y, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
104  state.z = constrain_float(state.z, 0.5f, 1.0f);
105 
106  return state.z;
107 }
108 
109 
110 /*
111  called once a second to do calibration update
112  */
113 void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
114 {
115  if (!param[i].autocal) {
116  // auto-calibration not enabled
117  return;
118  }
119 
120  // set state.z based on current ratio, this allows the operator to
121  // override the current ratio in flight with autocal, which is
122  // very useful both for testing and to force a reasonable value.
123  float ratio = constrain_float(param[i].ratio, 1.0f, 4.0f);
124 
125  state[i].calibration.state.z = 1.0f / sqrtf(ratio);
126 
127  // calculate true airspeed, assuming a airspeed ratio of 1.0
128  float dpress = MAX(get_differential_pressure(), 0);
129  float true_airspeed = sqrtf(dpress) * state[i].EAS2TAS;
130 
131  float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
132 
133  if (isnan(zratio) || isinf(zratio)) {
134  return;
135  }
136 
137  // this constrains the resulting ratio to between 1.0 and 4.0
138  zratio = constrain_float(zratio, 0.5f, 1.0f);
139  param[i].ratio.set(1/sq(zratio));
140  if (state[i].counter > 60) {
141  if (state[i].last_saved_ratio > 1.05f*param[i].ratio ||
142  state[i].last_saved_ratio < 0.95f*param[i].ratio) {
143  param[i].ratio.save();
144  state[i].last_saved_ratio = param[i].ratio;
145  state[i].counter = 0;
146  }
147  } else {
148  state[i].counter++;
149  }
150 }
151 
152 /*
153  called once a second to do calibration update
154  */
155 void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
156 {
157  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
158  update_calibration(i, vground, max_airspeed_allowed_during_cal);
159  }
160 }
161 
162 // log airspeed calibration data to MAVLink
163 void AP_Airspeed::log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground)
164 {
165  mavlink_msg_airspeed_autocal_send(chan,
166  vground.x,
167  vground.y,
168  vground.z,
169  get_differential_pressure(primary),
170  state[primary].EAS2TAS,
171  param[primary].ratio.get(),
172  state[primary].calibration.state.x,
173  state[primary].calibration.state.y,
174  state[primary].calibration.state.z,
175  state[primary].calibration.P.a.x,
176  state[primary].calibration.P.b.y,
177  state[primary].calibration.P.c.z);
178 }
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
static uint8_t counter
void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
float update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void init(float initial_ratio)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
#define f(i)
T y
Definition: vector3.h:67
Vector3< T > c
Definition: matrix3.h:48
T z
Definition: vector3.h:67
static int state
Definition: Util.cpp:20
#define AIRSPEED_MAX_SENSORS
Definition: AP_Airspeed.h:11
Common definitions and utility routines for the ArduPilot libraries.
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void log_mavlink_send(mavlink_channel_t chan, const Vector3f &vground)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
Matrix3< T > mul_rowcol(const Vector3< T > &v) const
Definition: vector3.cpp:400
float sq(const T val)
Definition: AP_Math.h:170
Vector3< T > b
Definition: matrix3.h:48
Vector3< T > a
Definition: matrix3.h:48
T x
Definition: vector3.h:67