CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Airspeed/Airspeed_Calibration.cpp
Views: 1798
1
/*
2
* auto_calibration.cpp - airspeed auto calibration
3
*
4
* Algorithm by Paul Riseborough
5
*
6
*/
7
8
#include "AP_Airspeed_config.h"
9
10
#if AP_AIRSPEED_ENABLED
11
12
#include <AP_Common/AP_Common.h>
13
#include <AP_Math/AP_Math.h>
14
#include <GCS_MAVLink/GCS.h>
15
#include <AP_AHRS/AP_AHRS.h>
16
17
#include "AP_Airspeed.h"
18
19
20
// constructor - fill in all the initial values
21
Airspeed_Calibration::Airspeed_Calibration()
22
: P(100, 0, 0,
23
0, 100, 0,
24
0, 0, 0.000001f)
25
, Q0(0.01f)
26
, Q1(0.0000005f)
27
, state(0, 0, 0)
28
, DT(1)
29
{
30
}
31
32
/*
33
initialise the ratio
34
*/
35
void Airspeed_Calibration::init(float initial_ratio)
36
{
37
state.z = 1.0f / sqrtf(initial_ratio);
38
}
39
40
/*
41
update the state of the airspeed calibration - needs to be called
42
once a second
43
*/
44
float Airspeed_Calibration::update(float airspeed, const Vector3f &vg, int16_t max_airspeed_allowed_during_cal)
45
{
46
// Perform the covariance prediction
47
// Q is a diagonal matrix so only need to add three terms in
48
// C code implementation
49
// P = P + Q;
50
P.a.x += Q0;
51
P.b.y += Q0;
52
P.c.z += Q1;
53
54
// Perform the predicted measurement using the current state estimates
55
// No state prediction required because states are assumed to be time
56
// invariant plus process noise
57
// Ignore vertical wind component
58
float TAS_pred = state.z * norm(vg.x - state.x, vg.y - state.y, vg.z);
59
float TAS_mea = airspeed;
60
61
// Calculate the observation Jacobian H_TAS
62
float SH1 = sq(vg.y - state.y) + sq(vg.x - state.x);
63
if (SH1 < 0.000001f) {
64
// avoid division by a small number
65
return state.z;
66
}
67
float SH2 = 1/sqrtf(SH1);
68
69
// observation Jacobian
70
Vector3f H_TAS(
71
-(state.z*SH2*(2*vg.x - 2*state.x))/2,
72
-(state.z*SH2*(2*vg.y - 2*state.y))/2,
73
1/SH2);
74
75
// Calculate the fusion innovation covariance assuming a TAS measurement
76
// noise of 1.0 m/s
77
// S = H_TAS*P*H_TAS' + 1.0; % [1 x 3] * [3 x 3] * [3 x 1] + [1 x 1]
78
Vector3f PH = P * H_TAS;
79
float S = H_TAS * PH + 1.0f;
80
81
// Calculate the Kalman gain
82
// [3 x 3] * [3 x 1] / [1 x 1]
83
Vector3f KG = PH / S;
84
85
// Update the states
86
state += KG*(TAS_mea - TAS_pred); // [3 x 1] + [3 x 1] * [1 x 1]
87
88
// Update the covariance matrix
89
Vector3f HP2 = H_TAS.row_times_mat(P);
90
P -= KG.mul_rowcol(HP2);
91
92
// force symmetry on the covariance matrix - necessary due to rounding
93
// errors
94
float P12 = 0.5f * (P.a.y + P.b.x);
95
float P13 = 0.5f * (P.a.z + P.c.x);
96
float P23 = 0.5f * (P.b.z + P.c.y);
97
P.a.y = P.b.x = P12;
98
P.a.z = P.c.x = P13;
99
P.b.z = P.c.y = P23;
100
101
// Constrain diagonals to be non-negative - protects against rounding errors
102
P.a.x = MAX(P.a.x, 0.0f);
103
P.b.y = MAX(P.b.y, 0.0f);
104
P.c.z = MAX(P.c.z, 0.0f);
105
106
state.x = constrain_float(state.x, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
107
state.y = constrain_float(state.y, -max_airspeed_allowed_during_cal, max_airspeed_allowed_during_cal);
108
state.z = constrain_float(state.z, 0.5f, 1.0f);
109
110
return state.z;
111
}
112
113
114
/*
115
called once a second to do calibration update
116
*/
117
void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
118
{
119
#if AP_AIRSPEED_AUTOCAL_ENABLE
120
if (!param[i].autocal && !calibration_enabled) {
121
// auto-calibration not enabled
122
return;
123
}
124
125
// set state.z based on current ratio, this allows the operator to
126
// override the current ratio in flight with autocal, which is
127
// very useful both for testing and to force a reasonable value.
128
float ratio = constrain_float(param[i].ratio, 1.0f, 4.0f);
129
130
state[i].calibration.state.z = 1.0f / sqrtf(ratio);
131
132
// calculate true airspeed, assuming a airspeed ratio of 1.0
133
float dpress = MAX(get_differential_pressure(i), 0);
134
float true_airspeed = sqrtf(dpress) * AP::ahrs().get_EAS2TAS();
135
136
float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
137
138
if (isnan(zratio) || isinf(zratio)) {
139
return;
140
}
141
142
// this constrains the resulting ratio to between 1.0 and 4.0
143
zratio = constrain_float(zratio, 0.5f, 1.0f);
144
param[i].ratio.set(1/sq(zratio));
145
if (state[i].counter > 60) {
146
if (state[i].last_saved_ratio > 1.05f*param[i].ratio ||
147
state[i].last_saved_ratio < 0.95f*param[i].ratio) {
148
param[i].ratio.save();
149
state[i].last_saved_ratio = param[i].ratio;
150
state[i].counter = 0;
151
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u ratio reset: %f", i , static_cast<double> (param[i].ratio));
152
}
153
} else {
154
state[i].counter++;
155
}
156
#endif // AP_AIRSPEED_AUTOCAL_ENABLE
157
}
158
159
/*
160
called once a second to do calibration update
161
*/
162
void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal)
163
{
164
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
165
update_calibration(i, vground, max_airspeed_allowed_during_cal);
166
}
167
#if HAL_GCS_ENABLED && AP_AIRSPEED_AUTOCAL_ENABLE
168
send_airspeed_calibration(vground);
169
#endif
170
}
171
172
173
#if HAL_GCS_ENABLED && AP_AIRSPEED_AUTOCAL_ENABLE
174
void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground)
175
{
176
/*
177
the AIRSPEED_AUTOCAL message doesn't have an instance number
178
so we can only send it for one sensor at a time
179
*/
180
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
181
if (!param[i].autocal && !calibration_enabled) {
182
// auto-calibration not enabled on this sensor
183
continue;
184
}
185
const mavlink_airspeed_autocal_t packet{
186
vx: vground.x,
187
vy: vground.y,
188
vz: vground.z,
189
diff_pressure: get_differential_pressure(i),
190
EAS2TAS: AP::ahrs().get_EAS2TAS(),
191
ratio: param[i].ratio.get(),
192
state_x: state[i].calibration.state.x,
193
state_y: state[i].calibration.state.y,
194
state_z: state[i].calibration.state.z,
195
Pax: state[i].calibration.P.a.x,
196
Pby: state[i].calibration.P.b.y,
197
Pcz: state[i].calibration.P.c.z
198
};
199
gcs().send_to_active_channels(MAVLINK_MSG_ID_AIRSPEED_AUTOCAL,
200
(const char *)&packet);
201
break; // we can only send for one sensor
202
}
203
}
204
#endif // HAL_GCS_ENABLED && AP_AIRSPEED_AUTOCAL_ENABLE
205
206
#endif // AP_AIRSPEED_ENABLED
207
208