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_AccelCal/AccelCalibrator.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
This program is distributed in the hope that it will be useful,
7
but WITHOUT ANY WARRANTY; without even the implied warranty of
8
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
9
GNU General Public License for more details.
10
You should have received a copy of the GNU General Public License
11
along with this program. If not, see <http://www.gnu.org/licenses/>.
12
*/
13
14
// Authored by Jonathan Challinger, 3D Robotics Inc.
15
16
#include "AccelCalibrator.h"
17
#include <stdio.h>
18
#include <AP_HAL/AP_HAL.h>
19
20
const extern AP_HAL::HAL& hal;
21
/*
22
* TODO
23
* - time out when not receiving samples
24
*/
25
26
////////////////////////////////////////////////////////////
27
///////////////////// PUBLIC INTERFACE /////////////////////
28
////////////////////////////////////////////////////////////
29
30
AccelCalibrator::AccelCalibrator() :
31
_conf_tolerance(ACCEL_CAL_TOLERANCE),
32
_sample_buffer(nullptr)
33
{
34
clear();
35
}
36
/*
37
Select options, initialise variables and initiate accel calibration
38
Options:
39
Fit Type: Will assume that if accelerometer static samples around all possible orientation
40
are spread in space will cover a surface of AXIS_ALIGNED_ELLIPSOID or any general
41
ELLIPSOID as chosen
42
43
Num Samples: Number of samples user should will be gathering, please note that with type of surface
44
chosen the minimum number of samples required will vary, for instance in the case of AXIS
45
ALIGNED ELLIPSOID atleast 6 distinct samples are required while for generic ELLIPSOIDAL fit
46
which will include calculation of offdiagonal parameters too requires atleast 8 parameters
47
to form a distinct ELLIPSOID
48
49
Sample Time: Time over which the samples will be gathered and averaged to add to a single sample for least
50
square regression
51
52
offset,diag,offdiag: initial parameter values for LSQ calculation
53
*/
54
void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time) {
55
start(fit_type, num_samples, sample_time, Vector3f(0,0,0), Vector3f(1,1,1), Vector3f(0,0,0));
56
}
57
58
void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time, Vector3f offset, Vector3f diag, Vector3f offdiag) {
59
if (_status == ACCEL_CAL_FAILED || _status == ACCEL_CAL_SUCCESS) {
60
clear();
61
}
62
if (_status != ACCEL_CAL_NOT_STARTED) {
63
return;
64
}
65
66
_conf_num_samples = num_samples;
67
_conf_sample_time = sample_time;
68
_conf_fit_type = fit_type;
69
70
const uint16_t faces = 2*_conf_num_samples-4;
71
const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;
72
const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));
73
_min_sample_dist = GRAVITY_MSS * 2*sinf(theta/2);
74
75
_param.s.offset = offset;
76
_param.s.diag = diag;
77
_param.s.offdiag = offdiag;
78
79
switch (_conf_fit_type) {
80
case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
81
if (_conf_num_samples < 6) {
82
set_status(ACCEL_CAL_FAILED);
83
return;
84
}
85
break;
86
case ACCEL_CAL_ELLIPSOID:
87
if (_conf_num_samples < 8) {
88
set_status(ACCEL_CAL_FAILED);
89
return;
90
}
91
break;
92
}
93
94
set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);
95
}
96
97
98
// set Accel calibrator status to make itself ready for future accel cals
99
void AccelCalibrator::clear() {
100
set_status(ACCEL_CAL_NOT_STARTED);
101
}
102
103
// returns true if accel calibrator is running
104
bool AccelCalibrator::running() {
105
return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;
106
}
107
108
// set Accel calibrator to start collecting samples in the next cycle
109
void AccelCalibrator::collect_sample() {
110
set_status(ACCEL_CAL_COLLECTING_SAMPLE);
111
}
112
113
// collect and avg sample to be passed onto LSQ estimator after all requisite orientations are done
114
void AccelCalibrator::new_sample(const Vector3f& delta_velocity, float dt) {
115
if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {
116
return;
117
}
118
119
if (_samples_collected >= _conf_num_samples) {
120
set_status(ACCEL_CAL_FAILED);
121
return;
122
}
123
124
_sample_buffer[_samples_collected].delta_velocity += delta_velocity;
125
_sample_buffer[_samples_collected].delta_time += dt;
126
127
_last_samp_frag_collected_ms = AP_HAL::millis();
128
129
if (_sample_buffer[_samples_collected].delta_time > _conf_sample_time) {
130
Vector3f sample = _sample_buffer[_samples_collected].delta_velocity/_sample_buffer[_samples_collected].delta_time;
131
if (!accept_sample(sample)) {
132
set_status(ACCEL_CAL_FAILED);
133
return;
134
}
135
136
_samples_collected++;
137
138
if (_samples_collected >= _conf_num_samples) {
139
run_fit(MAX_ITERATIONS, _fitness);
140
141
if (_fitness < _conf_tolerance && accept_result()) {
142
set_status(ACCEL_CAL_SUCCESS);
143
} else {
144
set_status(ACCEL_CAL_FAILED);
145
}
146
} else {
147
set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);
148
}
149
}
150
}
151
152
// determines if the result is acceptable
153
bool AccelCalibrator::accept_result() const {
154
if (fabsf(_param.s.offset.x) > GRAVITY_MSS ||
155
fabsf(_param.s.offset.y) > GRAVITY_MSS ||
156
fabsf(_param.s.offset.z) > GRAVITY_MSS ||
157
_param.s.diag.x < 0.8f || _param.s.diag.x > 1.2f ||
158
_param.s.diag.y < 0.8f || _param.s.diag.y > 1.2f ||
159
_param.s.diag.z < 0.8f || _param.s.diag.z > 1.2f) {
160
return false;
161
} else {
162
return true;
163
}
164
}
165
166
// interface for LSq estimator to read sample buffer sent after conversion from delta velocity
167
// to averaged acc over time
168
bool AccelCalibrator::get_sample(uint8_t i, Vector3f& s) const {
169
if (i >= _samples_collected) {
170
return false;
171
}
172
s = _sample_buffer[i].delta_velocity / _sample_buffer[i].delta_time;
173
return true;
174
}
175
176
// returns true and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure
177
// returns false if no correct parameter exists to be applied along with existing sample without corrections
178
bool AccelCalibrator::get_sample_corrected(uint8_t i, Vector3f& s) const {
179
if (_status != ACCEL_CAL_SUCCESS || !get_sample(i,s)) {
180
return false;
181
}
182
183
Matrix3f M (
184
_param.s.diag.x , _param.s.offdiag.x , _param.s.offdiag.y,
185
_param.s.offdiag.x , _param.s.diag.y , _param.s.offdiag.z,
186
_param.s.offdiag.y , _param.s.offdiag.z , _param.s.diag.z
187
);
188
189
s = M*(s+_param.s.offset);
190
191
return true;
192
}
193
194
// checks if no new sample has been received for considerable amount of time
195
void AccelCalibrator::check_for_timeout() {
196
const uint32_t timeout = _conf_sample_time*2*1000 + 500;
197
if (_status == ACCEL_CAL_COLLECTING_SAMPLE && AP_HAL::millis() - _last_samp_frag_collected_ms > timeout) {
198
set_status(ACCEL_CAL_FAILED);
199
}
200
}
201
202
// returns spherical fit parameters
203
void AccelCalibrator::get_calibration(Vector3f& offset) const {
204
offset = -_param.s.offset;
205
}
206
207
// returns axis aligned ellipsoidal fit parameters
208
void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag) const {
209
offset = -_param.s.offset;
210
diag = _param.s.diag;
211
}
212
213
// returns generic ellipsoidal fit parameters
214
void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag, Vector3f& offdiag) const {
215
offset = -_param.s.offset;
216
diag = _param.s.diag;
217
offdiag = _param.s.offdiag;
218
}
219
220
/////////////////////////////////////////////////////////////
221
////////////////////// PRIVATE METHODS //////////////////////
222
/////////////////////////////////////////////////////////////
223
224
/*
225
The sample acceptance distance is determined as follows:
226
For any regular polyhedron with triangular faces, the angle theta subtended
227
by two closest points is defined as
228
229
theta = arccos(cos(A)/(1-cos(A)))
230
231
Where:
232
A = (4pi/F + pi)/3
233
and
234
F = 2V - 4 is the number of faces for the polyhedron in consideration,
235
which depends on the number of vertices V
236
237
The above equation was proved after solving for spherical triangular excess
238
and related equations.
239
*/
240
bool AccelCalibrator::accept_sample(const Vector3f& sample)
241
{
242
if (_sample_buffer == nullptr) {
243
return false;
244
}
245
246
for(uint8_t i=0; i < _samples_collected; i++) {
247
Vector3f other_sample;
248
get_sample(i, other_sample);
249
250
if ((other_sample - sample).length() < _min_sample_dist){
251
return false;
252
}
253
}
254
return true;
255
}
256
257
// sets status of calibrator and takes appropriate actions
258
void AccelCalibrator::set_status(enum accel_cal_status_t status) {
259
switch (status) {
260
case ACCEL_CAL_NOT_STARTED:
261
//Calibrator not started
262
_status = ACCEL_CAL_NOT_STARTED;
263
264
_samples_collected = 0;
265
if (_sample_buffer != nullptr) {
266
free(_sample_buffer);
267
_sample_buffer = nullptr;
268
}
269
270
break;
271
272
case ACCEL_CAL_WAITING_FOR_ORIENTATION:
273
//Callibrator has been started and is waiting for user to ack after orientation setting
274
if (!running()) {
275
_samples_collected = 0;
276
if (_sample_buffer == nullptr) {
277
_sample_buffer = (struct AccelSample*)calloc(_conf_num_samples,sizeof(struct AccelSample));
278
if (_sample_buffer == nullptr) {
279
set_status(ACCEL_CAL_FAILED);
280
break;
281
}
282
}
283
}
284
if (_samples_collected >= _conf_num_samples) {
285
break;
286
}
287
_status = ACCEL_CAL_WAITING_FOR_ORIENTATION;
288
break;
289
290
case ACCEL_CAL_COLLECTING_SAMPLE:
291
// Calibrator is waiting on collecting samples from accelerometer for amount of
292
// time as requested by user/GCS
293
if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {
294
break;
295
}
296
_last_samp_frag_collected_ms = AP_HAL::millis();
297
_status = ACCEL_CAL_COLLECTING_SAMPLE;
298
break;
299
300
case ACCEL_CAL_SUCCESS:
301
// Calibrator has successfully fitted the samples to user requested surface model
302
// and has passed tolerance test
303
if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {
304
break;
305
}
306
307
_status = ACCEL_CAL_SUCCESS;
308
break;
309
310
case ACCEL_CAL_FAILED:
311
// Calibration has failed with reasons that can range from
312
// bad sample data leading to failure in tolerance test to lack of distinct samples
313
if (_status == ACCEL_CAL_NOT_STARTED) {
314
break;
315
}
316
317
_status = ACCEL_CAL_FAILED;
318
break;
319
};
320
}
321
322
/*
323
Run Gauss Newton fitting algorithm over the sample space and come up with offsets, diagonal/scale factors
324
and crosstalk/offdiagonal parameters
325
*/
326
void AccelCalibrator::run_fit(uint8_t max_iterations, float& fitness)
327
{
328
if (_sample_buffer == nullptr) {
329
return;
330
}
331
fitness = calc_mean_squared_residuals(_param.s);
332
float min_fitness = fitness;
333
union param_u fit_param = _param;
334
uint8_t num_iterations = 0;
335
336
while(num_iterations < max_iterations) {
337
float JTJ[ACCEL_CAL_MAX_NUM_PARAMS*ACCEL_CAL_MAX_NUM_PARAMS] {};
338
VectorP JTFI;
339
340
for(uint16_t k = 0; k<_samples_collected; k++) {
341
Vector3f sample;
342
get_sample(k, sample);
343
344
VectorN<float,ACCEL_CAL_MAX_NUM_PARAMS> jacob;
345
346
calc_jacob(sample, fit_param.s, jacob);
347
348
for(uint8_t i = 0; i < get_num_params(); i++) {
349
// compute JTJ
350
for(uint8_t j = 0; j < get_num_params(); j++) {
351
JTJ[i*get_num_params()+j] += jacob[i] * jacob[j];
352
}
353
// compute JTFI
354
JTFI[i] += jacob[i] * calc_residual(sample, fit_param.s);
355
}
356
}
357
358
if (!mat_inverse(JTJ, JTJ, get_num_params())) {
359
return;
360
}
361
362
for(uint8_t row=0; row < get_num_params(); row++) {
363
for(uint8_t col=0; col < get_num_params(); col++) {
364
fit_param.a[row] -= JTFI[col] * JTJ[row*get_num_params()+col];
365
}
366
}
367
368
fitness = calc_mean_squared_residuals(fit_param.s);
369
370
if (isnan(fitness) || isinf(fitness)) {
371
return;
372
}
373
374
if (fitness < min_fitness) {
375
min_fitness = fitness;
376
_param = fit_param;
377
}
378
379
num_iterations++;
380
}
381
}
382
383
// calculates residual from samples(corrected using supplied parameter) to gravity
384
// used to create Fitness column matrix
385
float AccelCalibrator::calc_residual(const Vector3f& sample, const struct param_t& params) const {
386
Matrix3f M (
387
params.diag.x , params.offdiag.x , params.offdiag.y,
388
params.offdiag.x , params.diag.y , params.offdiag.z,
389
params.offdiag.y , params.offdiag.z , params.diag.z
390
);
391
return GRAVITY_MSS - (M*(sample+params.offset)).length();
392
}
393
394
// calculated the total mean squared fitness of all the collected samples using parameters
395
// supplied
396
float AccelCalibrator::calc_mean_squared_residuals(const struct param_t& params) const
397
{
398
if (_sample_buffer == nullptr || _samples_collected == 0) {
399
return 1.0e30f;
400
}
401
float sum = 0.0f;
402
for(uint16_t i=0; i < _samples_collected; i++){
403
Vector3f sample;
404
get_sample(i, sample);
405
float resid = calc_residual(sample, params);
406
sum += sq(resid);
407
}
408
sum /= _samples_collected;
409
return sum;
410
}
411
412
// calculate jacobian, a matrix that defines relation to variation in fitness with variation in each of the parameters
413
// this is used in LSq estimator to adjust variation in parameter to be used for next iteration of LSq
414
void AccelCalibrator::calc_jacob(const Vector3f& sample, const struct param_t& params, VectorP &ret) const {
415
switch (_conf_fit_type) {
416
case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
417
case ACCEL_CAL_ELLIPSOID: {
418
const Vector3f &offset = params.offset;
419
const Vector3f &diag = params.diag;
420
const Vector3f &offdiag = params.offdiag;
421
Matrix3f M(
422
diag.x , offdiag.x , offdiag.y,
423
offdiag.x , diag.y , offdiag.z,
424
offdiag.y , offdiag.z , diag.z
425
);
426
427
float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
428
float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
429
float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
430
float length = (M*(sample+offset)).length();
431
432
// 0-2: offsets
433
ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
434
ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
435
ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
436
// 3-5: diagonals
437
ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;
438
ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;
439
ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;
440
// 6-8: off-diagonals
441
ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;
442
ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;
443
ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;
444
return;
445
}
446
}
447
}
448
449
// returns number of parameters are required for selected Fit type
450
uint8_t AccelCalibrator::get_num_params() const {
451
switch (_conf_fit_type) {
452
case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
453
return 6;
454
case ACCEL_CAL_ELLIPSOID:
455
return 9;
456
default:
457
return 6;
458
}
459
}
460
461