Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/CompassCalibrator.cpp
9352 views
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
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
/*
17
* The intention of a magnetometer in a compass application is to measure
18
* Earth's magnetic field. Measurements other than those of Earth's magnetic
19
* field are considered errors. This algorithm computes a set of correction
20
* parameters that null out errors from various sources:
21
*
22
* - Sensor bias error
23
* - "Hard iron" error caused by materials fixed to the vehicle body that
24
* produce static magnetic fields.
25
* - Sensor scale-factor error
26
* - Sensor cross-axis sensitivity
27
* - "Soft iron" error caused by materials fixed to the vehicle body that
28
* distort magnetic fields.
29
*
30
* This is done by taking a set of samples that are assumed to be the product
31
* of rotation in earth's magnetic field and fitting an offset ellipsoid to
32
* them, determining the correction to be applied to adjust the samples into an
33
* origin-centered sphere.
34
*
35
* The state machine of this library is described entirely by the
36
* CompassCalibrator::Status enum, and all state transitions are managed by the
37
* set_status function. Normally, the library is in the NOT_STARTED state. When
38
* the start function is called, the state transitions to WAITING_TO_START,
39
* until two conditions are met: the delay as elapsed, and the memory for the
40
* sample buffer has been successfully allocated.
41
* Once these conditions are met, the state transitions to RUNNING_STEP_ONE, and
42
* samples are collected via calls to the new_sample function. These samples are
43
* accepted or rejected based on distance to the nearest sample. The samples are
44
* assumed to cover the surface of a sphere, and the radius of that sphere is
45
* initialized to a conservative value. Based on a circle-packing pattern, the
46
* minimum distance is set such that some percentage of the surface of that
47
* sphere must be covered by samples.
48
*
49
* Once the sample buffer is full, a sphere fitting algorithm is run, which
50
* computes a new sphere radius. The sample buffer is thinned of samples which
51
* no longer meet the acceptance criteria, and the state transitions to
52
* RUNNING_STEP_TWO. Samples continue to be collected until the buffer is full
53
* again, the full ellipsoid fit is run, and the state transitions to either
54
* SUCCESS or FAILED.
55
*
56
* The fitting algorithm used is Levenberg-Marquardt. See also:
57
* http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm
58
*/
59
60
#include "AP_Compass_config.h"
61
62
#if COMPASS_CAL_ENABLED
63
64
#include "AP_Compass.h"
65
#include "CompassCalibrator.h"
66
#include <AP_HAL/AP_HAL.h>
67
#include <AP_Math/AP_GeodesicGrid.h>
68
#include <AP_AHRS/AP_AHRS.h>
69
#include <AP_GPS/AP_GPS.h>
70
#include <GCS_MAVLink/GCS.h>
71
#include <AP_InternalError/AP_InternalError.h>
72
73
#define FIELD_RADIUS_MIN 150
74
#define FIELD_RADIUS_MAX 950
75
76
////////////////////////////////////////////////////////////
77
///////////////////// PUBLIC INTERFACE /////////////////////
78
////////////////////////////////////////////////////////////
79
80
CompassCalibrator::CompassCalibrator()
81
{
82
set_status(Status::NOT_STARTED);
83
}
84
85
// Request to cancel calibration
86
void CompassCalibrator::stop()
87
{
88
WITH_SEMAPHORE(state_sem);
89
_requested_status = Status::NOT_STARTED;
90
_status_set_requested = true;
91
}
92
93
void CompassCalibrator::set_orientation(enum Rotation orientation, bool is_external, bool fix_orientation, bool always_45_deg)
94
{
95
WITH_SEMAPHORE(state_sem);
96
cal_settings.check_orientation = true;
97
cal_settings.orientation = orientation;
98
cal_settings.orig_orientation = orientation;
99
cal_settings.is_external = is_external;
100
cal_settings.fix_orientation = fix_orientation;
101
cal_settings.always_45_deg = always_45_deg;
102
}
103
104
void CompassCalibrator::start(bool retry, float delay, uint16_t offset_max, uint8_t compass_idx, float tolerance)
105
{
106
if (compass_idx > COMPASS_MAX_INSTANCES) {
107
return;
108
}
109
110
WITH_SEMAPHORE(state_sem);
111
// Don't do this while we are already started
112
if (_running()) {
113
return;
114
}
115
cal_settings.offset_max = offset_max;
116
cal_settings.attempt = 1;
117
cal_settings.retry = retry;
118
cal_settings.delay_start_sec = delay;
119
cal_settings.start_time_ms = AP_HAL::millis();
120
cal_settings.compass_idx = compass_idx;
121
cal_settings.tolerance = tolerance;
122
123
// Request status change to Waiting to start
124
_requested_status = Status::WAITING_TO_START;
125
_status_set_requested = true;
126
}
127
128
// Record point mag sample and associated attitude sample to intermediate struct
129
void CompassCalibrator::new_sample(const Vector3f& sample)
130
{
131
WITH_SEMAPHORE(sample_sem);
132
_last_sample.set(sample);
133
_last_sample.att.set_from_ahrs();
134
_new_sample = true;
135
}
136
137
bool CompassCalibrator::failed() {
138
WITH_SEMAPHORE(state_sem);
139
switch (cal_state.status) {
140
case Status::FAILED:
141
case Status::BAD_ORIENTATION:
142
case Status::BAD_RADIUS:
143
return true;
144
case Status::SUCCESS:
145
case Status::NOT_STARTED:
146
case Status::WAITING_TO_START:
147
case Status::RUNNING_STEP_ONE:
148
case Status::RUNNING_STEP_TWO:
149
return false;
150
}
151
152
// compiler guarantees we don't get here
153
return true;
154
}
155
156
157
bool CompassCalibrator::running() {
158
WITH_SEMAPHORE(state_sem);
159
return (cal_state.status == Status::RUNNING_STEP_ONE || cal_state.status == Status::RUNNING_STEP_TWO);
160
}
161
162
const CompassCalibrator::Report CompassCalibrator::get_report() {
163
WITH_SEMAPHORE(state_sem);
164
return cal_report;
165
}
166
167
const CompassCalibrator::State CompassCalibrator::get_state() {
168
WITH_SEMAPHORE(state_sem);
169
return cal_state;
170
}
171
/////////////////////////////////////////////////////////////
172
////////////////////// PRIVATE METHODS //////////////////////
173
/////////////////////////////////////////////////////////////
174
175
void CompassCalibrator::update()
176
{
177
178
//pickup samples from intermediate struct
179
pull_sample();
180
181
{
182
WITH_SEMAPHORE(state_sem);
183
//update_settings
184
if (!running()) {
185
update_cal_settings();
186
}
187
188
//update requested state
189
if (_status_set_requested) {
190
_status_set_requested = false;
191
set_status(_requested_status);
192
}
193
//update report and status
194
update_cal_status();
195
update_cal_report();
196
}
197
198
// collect the minimum number of samples
199
if (!_fitting()) {
200
return;
201
}
202
203
if (_status == Status::RUNNING_STEP_ONE) {
204
if (_fit_step >= 10) {
205
if (is_equal(_fitness, _initial_fitness) || isnan(_fitness)) { // if true, means that fitness is diverging instead of converging
206
set_status(Status::FAILED);
207
} else {
208
set_status(Status::RUNNING_STEP_TWO);
209
}
210
} else {
211
if (_fit_step == 0) {
212
calc_initial_offset();
213
}
214
run_sphere_fit();
215
_fit_step++;
216
}
217
} else if (_status == Status::RUNNING_STEP_TWO) {
218
if (_fit_step >= 35) {
219
if (fit_acceptable() && fix_radius() && calculate_orientation()) {
220
set_status(Status::SUCCESS);
221
} else {
222
set_status(Status::FAILED);
223
}
224
} else if (_fit_step < 15) {
225
run_sphere_fit();
226
_fit_step++;
227
} else {
228
run_ellipsoid_fit();
229
_fit_step++;
230
}
231
}
232
}
233
234
void CompassCalibrator::pull_sample()
235
{
236
CompassSample mag_sample;
237
{
238
WITH_SEMAPHORE(sample_sem);
239
if (!_new_sample) {
240
return;
241
}
242
if (_status == Status::WAITING_TO_START) {
243
set_status(Status::RUNNING_STEP_ONE);
244
}
245
_new_sample = false;
246
mag_sample = _last_sample;
247
}
248
if (_running() && _samples_collected < COMPASS_CAL_NUM_SAMPLES && accept_sample(mag_sample.get())) {
249
update_completion_mask(mag_sample.get());
250
_sample_buffer[_samples_collected] = mag_sample;
251
_samples_collected++;
252
}
253
}
254
255
256
void CompassCalibrator::update_cal_settings()
257
{
258
_tolerance = cal_settings.tolerance;
259
_check_orientation = cal_settings.check_orientation;
260
_orientation = cal_settings.orientation;
261
_orig_orientation = cal_settings.orig_orientation;
262
_is_external = cal_settings.is_external;
263
_fix_orientation = cal_settings.fix_orientation;
264
_offset_max = cal_settings.offset_max;
265
_attempt = cal_settings.attempt;
266
_retry = cal_settings.retry;
267
_delay_start_sec = cal_settings.delay_start_sec;
268
_start_time_ms = cal_settings.start_time_ms;
269
_compass_idx = cal_settings.compass_idx;
270
_always_45_deg = cal_settings.always_45_deg;
271
}
272
273
// update completion mask based on latest sample
274
// used to ensure we have collected samples in all directions
275
void CompassCalibrator::update_completion_mask(const Vector3f& v)
276
{
277
Matrix3f softiron {
278
_params.diag.x, _params.offdiag.x, _params.offdiag.y,
279
_params.offdiag.x, _params.diag.y, _params.offdiag.z,
280
_params.offdiag.y, _params.offdiag.z, _params.diag.z
281
};
282
Vector3f corrected = softiron * (v + _params.offset);
283
int section = AP_GeodesicGrid::section(corrected, true);
284
if (section < 0) {
285
return;
286
}
287
_completion_mask[section / 8] |= 1 << (section % 8);
288
}
289
290
// reset and update the completion mask using all samples in the sample buffer
291
void CompassCalibrator::update_completion_mask()
292
{
293
memset(_completion_mask, 0, sizeof(_completion_mask));
294
for (int i = 0; i < _samples_collected; i++) {
295
update_completion_mask(_sample_buffer[i].get());
296
}
297
}
298
299
void CompassCalibrator::update_cal_status()
300
{
301
cal_state.status = _status;
302
cal_state.attempt = _attempt;
303
memcpy(cal_state.completion_mask, _completion_mask, sizeof(completion_mask_t));
304
cal_state.completion_pct = 0.0f;
305
// first sampling step is 1/3rd of the progress bar
306
// never return more than 99% unless _status is Status::SUCCESS
307
switch (_status) {
308
case Status::NOT_STARTED:
309
case Status::WAITING_TO_START:
310
cal_state.completion_pct = 0.0f;
311
break;
312
case Status::RUNNING_STEP_ONE:
313
cal_state.completion_pct = 33.3f * _samples_collected/COMPASS_CAL_NUM_SAMPLES;
314
break;
315
case Status::RUNNING_STEP_TWO:
316
cal_state.completion_pct = 33.3f + 65.7f*((float)(_samples_collected-_samples_thinned)/(COMPASS_CAL_NUM_SAMPLES-_samples_thinned));
317
break;
318
case Status::SUCCESS:
319
cal_state.completion_pct = 100.0f;
320
break;
321
case Status::FAILED:
322
case Status::BAD_ORIENTATION:
323
case Status::BAD_RADIUS:
324
cal_state.completion_pct = 0.0f;
325
break;
326
};
327
}
328
329
330
void CompassCalibrator::update_cal_report()
331
{
332
cal_report.status = _status;
333
cal_report.fitness = sqrtf(_fitness);
334
cal_report.ofs = _params.offset;
335
cal_report.diag = _params.diag;
336
cal_report.offdiag = _params.offdiag;
337
cal_report.scale_factor = _params.scale_factor;
338
cal_report.orientation_confidence = _orientation_confidence;
339
cal_report.original_orientation = _orig_orientation;
340
cal_report.orientation = _orientation_solution;
341
cal_report.check_orientation = _check_orientation;
342
}
343
344
// running method for use in thread
345
bool CompassCalibrator::_running() const
346
{
347
return _status == Status::RUNNING_STEP_ONE || _status == Status::RUNNING_STEP_TWO;
348
}
349
350
// fitting method for use in thread
351
bool CompassCalibrator::_fitting() const
352
{
353
return _running() && (_samples_collected == COMPASS_CAL_NUM_SAMPLES);
354
}
355
356
// initialize fitness before starting a fit
357
void CompassCalibrator::initialize_fit()
358
{
359
if (_samples_collected != 0) {
360
_fitness = calc_mean_squared_residuals(_params);
361
} else {
362
_fitness = 1.0e30f;
363
}
364
_initial_fitness = _fitness;
365
_sphere_lambda = 1.0f;
366
_ellipsoid_lambda = 1.0f;
367
_fit_step = 0;
368
}
369
370
void CompassCalibrator::reset_state()
371
{
372
_samples_collected = 0;
373
_samples_thinned = 0;
374
_params.radius = 200;
375
_params.offset.zero();
376
_params.diag = Vector3f(1.0f,1.0f,1.0f);
377
_params.offdiag.zero();
378
_params.scale_factor = 0;
379
380
memset(_completion_mask, 0, sizeof(_completion_mask));
381
initialize_fit();
382
}
383
384
bool CompassCalibrator::set_status(CompassCalibrator::Status status)
385
{
386
if (status != Status::NOT_STARTED && _status == status) {
387
return true;
388
}
389
390
switch (status) {
391
case Status::NOT_STARTED:
392
reset_state();
393
_status = Status::NOT_STARTED;
394
if (_sample_buffer != nullptr) {
395
free(_sample_buffer);
396
_sample_buffer = nullptr;
397
}
398
return true;
399
400
case Status::WAITING_TO_START:
401
reset_state();
402
_status = Status::WAITING_TO_START;
403
set_status(Status::RUNNING_STEP_ONE);
404
return true;
405
406
case Status::RUNNING_STEP_ONE:
407
if (_status != Status::WAITING_TO_START) {
408
return false;
409
}
410
411
// on first attempt delay start if requested by caller
412
if (_attempt == 1 && (AP_HAL::millis()-_start_time_ms)*1.0e-3f < _delay_start_sec) {
413
return false;
414
}
415
416
if (_sample_buffer == nullptr) {
417
_sample_buffer = (CompassSample*)calloc(COMPASS_CAL_NUM_SAMPLES, sizeof(CompassSample));
418
}
419
if (_sample_buffer != nullptr) {
420
initialize_fit();
421
_status = Status::RUNNING_STEP_ONE;
422
return true;
423
}
424
return false;
425
426
case Status::RUNNING_STEP_TWO:
427
if (_status != Status::RUNNING_STEP_ONE) {
428
return false;
429
}
430
thin_samples();
431
initialize_fit();
432
_status = Status::RUNNING_STEP_TWO;
433
return true;
434
435
case Status::SUCCESS:
436
if (_status != Status::RUNNING_STEP_TWO) {
437
return false;
438
}
439
440
if (_sample_buffer != nullptr) {
441
free(_sample_buffer);
442
_sample_buffer = nullptr;
443
}
444
445
_status = Status::SUCCESS;
446
return true;
447
448
case Status::FAILED:
449
if (_status == Status::BAD_ORIENTATION ||
450
_status == Status::BAD_RADIUS) {
451
// don't overwrite bad orientation status
452
return false;
453
}
454
FALLTHROUGH;
455
456
case Status::BAD_ORIENTATION:
457
case Status::BAD_RADIUS:
458
if (_status == Status::NOT_STARTED) {
459
return false;
460
}
461
462
if (_retry && set_status(Status::WAITING_TO_START)) {
463
_attempt++;
464
return true;
465
}
466
467
if (_sample_buffer != nullptr) {
468
free(_sample_buffer);
469
_sample_buffer = nullptr;
470
}
471
472
_status = status;
473
return true;
474
};
475
476
// compiler guarantees we don't get here
477
return false;
478
}
479
480
bool CompassCalibrator::fit_acceptable() const
481
{
482
if (!isnan(_fitness) &&
483
_params.radius > FIELD_RADIUS_MIN && _params.radius < FIELD_RADIUS_MAX &&
484
fabsf(_params.offset.x) < _offset_max &&
485
fabsf(_params.offset.y) < _offset_max &&
486
fabsf(_params.offset.z) < _offset_max &&
487
_params.diag.x > 0.2f && _params.diag.x < 5.0f &&
488
_params.diag.y > 0.2f && _params.diag.y < 5.0f &&
489
_params.diag.z > 0.2f && _params.diag.z < 5.0f &&
490
fabsf(_params.offdiag.x) < 1.0f && //absolute of sine/cosine output cannot be greater than 1
491
fabsf(_params.offdiag.y) < 1.0f &&
492
fabsf(_params.offdiag.z) < 1.0f ) {
493
return _fitness <= sq(_tolerance);
494
}
495
return false;
496
}
497
498
void CompassCalibrator::thin_samples()
499
{
500
if (_sample_buffer == nullptr) {
501
return;
502
}
503
504
_samples_thinned = 0;
505
// shuffle the samples http://en.wikipedia.org/wiki/Fisher%E2%80%93Yates_shuffle
506
// this is so that adjacent samples don't get sequentially eliminated
507
for (uint16_t i=_samples_collected-1; i>=1; i--) {
508
uint16_t j = get_random16() % (i+1);
509
CompassSample temp = _sample_buffer[i];
510
_sample_buffer[i] = _sample_buffer[j];
511
_sample_buffer[j] = temp;
512
}
513
514
// remove any samples that are close together
515
for (uint16_t i=0; i < _samples_collected; i++) {
516
if (!accept_sample(_sample_buffer[i], i)) {
517
_sample_buffer[i] = _sample_buffer[_samples_collected-1];
518
_samples_collected--;
519
_samples_thinned++;
520
}
521
}
522
523
update_completion_mask();
524
}
525
526
/*
527
* The sample acceptance distance is determined as follows:
528
* For any regular polyhedron with triangular faces, the angle theta subtended
529
* by two closest points is defined as
530
*
531
* theta = arccos(cos(A)/(1-cos(A)))
532
*
533
* Where:
534
* A = (4pi/F + pi)/3
535
* and
536
* F = 2V - 4 is the number of faces for the polyhedron in consideration,
537
* which depends on the number of vertices V
538
*
539
* The above equation was proved after solving for spherical triangular excess
540
* and related equations.
541
*/
542
bool CompassCalibrator::accept_sample(const Vector3f& sample, uint16_t skip_index)
543
{
544
static const uint16_t faces = (2 * COMPASS_CAL_NUM_SAMPLES - 4);
545
static const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;
546
static const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));
547
548
if (_sample_buffer == nullptr) {
549
return false;
550
}
551
552
float min_distance = _params.radius * 2*sinf(theta/2);
553
554
for (uint16_t i = 0; i<_samples_collected; i++) {
555
if (i != skip_index) {
556
float distance = (sample - _sample_buffer[i].get()).length();
557
if (distance < min_distance) {
558
return false;
559
}
560
}
561
}
562
return true;
563
}
564
565
bool CompassCalibrator::accept_sample(const CompassSample& sample, uint16_t skip_index)
566
{
567
return accept_sample(sample.get(), skip_index);
568
}
569
570
float CompassCalibrator::calc_residual(const Vector3f& sample, const param_t& params) const
571
{
572
Matrix3f softiron(
573
params.diag.x , params.offdiag.x , params.offdiag.y,
574
params.offdiag.x , params.diag.y , params.offdiag.z,
575
params.offdiag.y , params.offdiag.z , params.diag.z
576
);
577
return params.radius - (softiron*(sample+params.offset)).length();
578
}
579
580
// calc the fitness given a set of parameters (offsets, diagonals, off diagonals)
581
float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const
582
{
583
if (_sample_buffer == nullptr || _samples_collected == 0) {
584
return 1.0e30f;
585
}
586
float sum = 0.0f;
587
for (uint16_t i=0; i < _samples_collected; i++) {
588
Vector3f sample = _sample_buffer[i].get();
589
float resid = calc_residual(sample, params);
590
sum += sq(resid);
591
}
592
sum /= _samples_collected;
593
return sum;
594
}
595
596
// calculate initial offsets by simply taking the average values of the samples
597
void CompassCalibrator::calc_initial_offset()
598
{
599
// Set initial offset to the average value of the samples
600
_params.offset.zero();
601
for (uint16_t k = 0; k < _samples_collected; k++) {
602
_params.offset -= _sample_buffer[k].get();
603
}
604
_params.offset /= _samples_collected;
605
}
606
607
void CompassCalibrator::calc_sphere_jacob(const Vector3f& sample, const param_t& params, float* ret) const
608
{
609
const Vector3f &offset = params.offset;
610
const Vector3f &diag = params.diag;
611
const Vector3f &offdiag = params.offdiag;
612
Matrix3f softiron(
613
diag.x , offdiag.x , offdiag.y,
614
offdiag.x , diag.y , offdiag.z,
615
offdiag.y , offdiag.z , diag.z
616
);
617
618
float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
619
float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
620
float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
621
float length = (softiron*(sample+offset)).length();
622
623
// 0: partial derivative (radius wrt fitness fn) fn operated on sample
624
ret[0] = 1.0f;
625
// 1-3: partial derivative (offsets wrt fitness fn) fn operated on sample
626
ret[1] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
627
ret[2] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
628
ret[3] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
629
}
630
631
// run sphere fit to calculate diagonals and offdiagonals
632
void CompassCalibrator::run_sphere_fit()
633
{
634
if (_sample_buffer == nullptr) {
635
return;
636
}
637
638
const float lma_damping = 10.0f;
639
640
// take backup of fitness and parameters so we can determine later if this fit has improved the calibration
641
float fitness = _fitness;
642
float fit1, fit2;
643
param_t fit1_params, fit2_params;
644
fit1_params = fit2_params = _params;
645
646
float JTJ[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
647
float JTJ2[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
648
float JTFI[COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
649
650
// Gauss Newton Part common for all kind of extensions including LM
651
for (uint16_t k = 0; k<_samples_collected; k++) {
652
Vector3f sample = _sample_buffer[k].get();
653
654
float sphere_jacob[COMPASS_CAL_NUM_SPHERE_PARAMS];
655
656
calc_sphere_jacob(sample, fit1_params, sphere_jacob);
657
658
for (uint8_t i = 0;i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {
659
// compute JTJ
660
for (uint8_t j = 0; j < COMPASS_CAL_NUM_SPHERE_PARAMS; j++) {
661
JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j];
662
JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j]; //a backup JTJ for LM
663
}
664
// compute JTFI
665
JTFI[i] += sphere_jacob[i] * calc_residual(sample, fit1_params);
666
}
667
}
668
669
//------------------------Levenberg-Marquardt-part-starts-here---------------------------------//
670
// refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter
671
for (uint8_t i = 0; i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {
672
JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda;
673
JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda/lma_damping;
674
}
675
676
if (!mat_inverse(JTJ, JTJ, 4)) {
677
return;
678
}
679
680
if (!mat_inverse(JTJ2, JTJ2, 4)) {
681
return;
682
}
683
684
// extract radius, offset, diagonals and offdiagonal parameters
685
for (uint8_t row=0; row < COMPASS_CAL_NUM_SPHERE_PARAMS; row++) {
686
for (uint8_t col=0; col < COMPASS_CAL_NUM_SPHERE_PARAMS; col++) {
687
fit1_params.get_sphere_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];
688
fit2_params.get_sphere_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];
689
}
690
}
691
692
// calculate fitness of two possible sets of parameters
693
fit1 = calc_mean_squared_residuals(fit1_params);
694
fit2 = calc_mean_squared_residuals(fit2_params);
695
696
// decide which of the two sets of parameters is best and store in fit1_params
697
if (fit1 > _fitness && fit2 > _fitness) {
698
// if neither set of parameters provided better results, increase lambda
699
_sphere_lambda *= lma_damping;
700
} else if (fit2 < _fitness && fit2 < fit1) {
701
// if fit2 was better we will use it. decrease lambda
702
_sphere_lambda /= lma_damping;
703
fit1_params = fit2_params;
704
fitness = fit2;
705
} else if (fit1 < _fitness) {
706
fitness = fit1;
707
}
708
//--------------------Levenberg-Marquardt-part-ends-here--------------------------------//
709
710
// store new parameters and update fitness
711
if (!isnan(fitness) && fitness < _fitness) {
712
_fitness = fitness;
713
_params = fit1_params;
714
update_completion_mask();
715
}
716
}
717
718
void CompassCalibrator::calc_ellipsoid_jacob(const Vector3f& sample, const param_t& params, float* ret) const
719
{
720
const Vector3f &offset = params.offset;
721
const Vector3f &diag = params.diag;
722
const Vector3f &offdiag = params.offdiag;
723
Matrix3f softiron(
724
diag.x , offdiag.x , offdiag.y,
725
offdiag.x , diag.y , offdiag.z,
726
offdiag.y , offdiag.z , diag.z
727
);
728
729
float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
730
float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
731
float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
732
float length = (softiron*(sample+offset)).length();
733
734
// 0-2: partial derivative (offset wrt fitness fn) fn operated on sample
735
ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
736
ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
737
ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
738
// 3-5: partial derivative (diag offset wrt fitness fn) fn operated on sample
739
ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;
740
ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;
741
ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;
742
// 6-8: partial derivative (off-diag offset wrt fitness fn) fn operated on sample
743
ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;
744
ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;
745
ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;
746
}
747
748
void CompassCalibrator::run_ellipsoid_fit()
749
{
750
if (_sample_buffer == nullptr) {
751
return;
752
}
753
754
const float lma_damping = 10.0f;
755
756
// take backup of fitness and parameters so we can determine later if this fit has improved the calibration
757
float fitness = _fitness;
758
float fit1, fit2;
759
param_t fit1_params, fit2_params;
760
fit1_params = fit2_params = _params;
761
762
float JTJ[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
763
float JTJ2[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
764
float JTFI[COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
765
766
// Gauss Newton Part common for all kind of extensions including LM
767
for (uint16_t k = 0; k<_samples_collected; k++) {
768
Vector3f sample = _sample_buffer[k].get();
769
770
float ellipsoid_jacob[COMPASS_CAL_NUM_ELLIPSOID_PARAMS];
771
772
calc_ellipsoid_jacob(sample, fit1_params, ellipsoid_jacob);
773
774
for (uint8_t i = 0;i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {
775
// compute JTJ
776
for (uint8_t j = 0; j < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; j++) {
777
JTJ [i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];
778
JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];
779
}
780
// compute JTFI
781
JTFI[i] += ellipsoid_jacob[i] * calc_residual(sample, fit1_params);
782
}
783
}
784
785
//------------------------Levenberg-Marquardt-part-starts-here---------------------------------//
786
//refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter
787
for (uint8_t i = 0; i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {
788
JTJ[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda;
789
JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda/lma_damping;
790
}
791
792
if (!mat_inverse(JTJ, JTJ, 9)) {
793
return;
794
}
795
796
if (!mat_inverse(JTJ2, JTJ2, 9)) {
797
return;
798
}
799
800
// extract radius, offset, diagonals and offdiagonal parameters
801
for (uint8_t row=0; row < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; row++) {
802
for (uint8_t col=0; col < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; col++) {
803
fit1_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];
804
fit2_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];
805
}
806
}
807
808
// calculate fitness of two possible sets of parameters
809
fit1 = calc_mean_squared_residuals(fit1_params);
810
fit2 = calc_mean_squared_residuals(fit2_params);
811
812
// decide which of the two sets of parameters is best and store in fit1_params
813
if (fit1 > _fitness && fit2 > _fitness) {
814
// if neither set of parameters provided better results, increase lambda
815
_ellipsoid_lambda *= lma_damping;
816
} else if (fit2 < _fitness && fit2 < fit1) {
817
// if fit2 was better we will use it. decrease lambda
818
_ellipsoid_lambda /= lma_damping;
819
fit1_params = fit2_params;
820
fitness = fit2;
821
} else if (fit1 < _fitness) {
822
fitness = fit1;
823
}
824
//--------------------Levenberg-part-ends-here--------------------------------//
825
826
// store new parameters and update fitness
827
if (fitness < _fitness) {
828
_fitness = fitness;
829
_params = fit1_params;
830
update_completion_mask();
831
}
832
}
833
834
835
//////////////////////////////////////////////////////////
836
//////////// CompassSample public interface //////////////
837
//////////////////////////////////////////////////////////
838
839
#define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X) ((int16_t)constrain_float(roundf(__X*8.0f), INT16_MIN, INT16_MAX))
840
#define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X) (__X/8.0f)
841
842
Vector3f CompassCalibrator::CompassSample::get() const
843
{
844
return Vector3f(COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(x),
845
COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(y),
846
COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(z));
847
}
848
849
void CompassCalibrator::CompassSample::set(const Vector3f &in)
850
{
851
x = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.x);
852
y = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.y);
853
z = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.z);
854
}
855
856
void CompassCalibrator::AttitudeSample::set_from_ahrs(void)
857
{
858
const Matrix3f &dcm = AP::ahrs().get_DCM_rotation_body_to_ned();
859
float roll_rad, pitch_rad, yaw_rad;
860
dcm.to_euler(&roll_rad, &pitch_rad, &yaw_rad);
861
roll = constrain_int16(127 * (roll_rad / M_PI), -INT8_MAX, INT8_MAX);
862
pitch = constrain_int16(127 * (pitch_rad / M_PI_2), -INT8_MAX, INT8_MAX);
863
yaw = constrain_int16(127 * (yaw_rad / M_PI), -INT8_MAX, INT8_MAX);
864
}
865
866
Matrix3f CompassCalibrator::AttitudeSample::get_rotmat(void) const
867
{
868
float roll_rad, pitch_rad, yaw_rad;
869
roll_rad = roll * (M_PI / 127);
870
pitch_rad = pitch * (M_PI_2 / 127);
871
yaw_rad = yaw * (M_PI / 127);
872
Matrix3f dcm;
873
dcm.from_euler(roll_rad, pitch_rad, yaw_rad);
874
return dcm;
875
}
876
877
/*
878
calculate the implied earth field for a compass sample and compass
879
rotation. This is used to check for consistency between
880
samples.
881
882
If the orientation is correct then when rotated the same (or
883
similar) earth field should be given for all samples.
884
885
Note that this earth field uses an arbitrary north reference, so it
886
may not match the true earth field.
887
*/
888
Vector3f CompassCalibrator::calculate_earth_field(CompassSample &sample, enum Rotation r)
889
{
890
Vector3f v = sample.get();
891
892
// convert the sample back to sensor frame
893
v.rotate_inverse(_orientation);
894
895
// rotate to body frame for this rotation
896
v.rotate(r);
897
898
// apply offsets, rotating them for the orientation we are testing
899
Vector3f rot_offsets = _params.offset;
900
rot_offsets.rotate_inverse(_orientation);
901
902
rot_offsets.rotate(r);
903
904
v += rot_offsets;
905
906
// rotate the sample from body frame back to earth frame
907
Matrix3f rot = sample.att.get_rotmat();
908
909
Vector3f efield = rot * v;
910
911
// earth field is the mag sample in earth frame
912
return efield;
913
}
914
915
/*
916
calculate compass orientation using the attitude estimate associated
917
with each sample, and fix orientation on external compasses if
918
the feature is enabled
919
*/
920
bool CompassCalibrator::calculate_orientation(void)
921
{
922
if (!_check_orientation) {
923
// we are not checking orientation
924
return true;
925
}
926
927
// this function is very slow
928
EXPECT_DELAY_MS(1000);
929
930
// Skip 4 rotations, see: auto_rotation_index()
931
float variance[ROTATION_MAX-4] {};
932
933
_orientation_solution = _orientation;
934
935
for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {
936
Rotation r = auto_rotation_index(n);
937
938
// calculate the average implied earth field across all samples
939
Vector3f total_ef {};
940
for (uint32_t i=0; i<_samples_collected; i++) {
941
Vector3f efield = calculate_earth_field(_sample_buffer[i], r);
942
total_ef += efield;
943
}
944
Vector3f avg_efield = total_ef / _samples_collected;
945
946
// now calculate the square error for this rotation against the average earth field
947
for (uint32_t i=0; i<_samples_collected; i++) {
948
Vector3f efield = calculate_earth_field(_sample_buffer[i], r);
949
float err = (efield - avg_efield).length_squared();
950
// divide by number of samples collected to get the variance
951
variance[n] += err / _samples_collected;
952
}
953
}
954
955
// find the rotation with the lowest variance
956
enum Rotation besti = ROTATION_NONE;
957
float bestv = variance[0];
958
enum Rotation besti_90 = ROTATION_NONE;
959
float bestv_90 = variance[0];
960
for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {
961
Rotation r = auto_rotation_index(n);
962
if (variance[n] < bestv) {
963
bestv = variance[n];
964
besti = r;
965
}
966
if (right_angle_rotation(r) && variance[n] < bestv_90) {
967
bestv_90 = variance[n];
968
besti_90 = r;
969
}
970
}
971
972
973
float second_best = besti==ROTATION_NONE?variance[1]:variance[0];
974
enum Rotation besti2 = besti==ROTATION_NONE?ROTATION_YAW_45:ROTATION_NONE;
975
float second_best_90 = besti_90==ROTATION_NONE?variance[2]:variance[0];
976
enum Rotation besti2_90 = besti_90==ROTATION_NONE?ROTATION_YAW_90:ROTATION_NONE;
977
for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {
978
Rotation r = auto_rotation_index(n);
979
if (besti != r) {
980
if (variance[n] < second_best) {
981
second_best = variance[n];
982
besti2 = r;
983
}
984
}
985
if (right_angle_rotation(r) && (besti_90 != r) && (variance[n] < second_best_90)) {
986
second_best_90 = variance[n];
987
besti2_90 = r;
988
}
989
}
990
991
_orientation_confidence = second_best/bestv;
992
993
bool pass;
994
if (besti == _orientation) {
995
// if the orientation matched then allow for a low threshold
996
pass = true;
997
} else {
998
if (_orientation_confidence > 4.0) {
999
// very confident, always pass
1000
pass = true;
1001
1002
} else if (_always_45_deg && (_orientation_confidence > 2.0)) {
1003
// use same tolerance for all rotations
1004
pass = true;
1005
1006
} else {
1007
// just consider 90's
1008
_orientation_confidence = second_best_90 / bestv_90;
1009
pass = _orientation_confidence > 2.0;
1010
besti = besti_90;
1011
besti2 = besti2_90;
1012
}
1013
}
1014
if (!pass) {
1015
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Mag(%u) bad orientation: %u/%u %.1f", _compass_idx,
1016
besti, besti2, (double)_orientation_confidence);
1017
(void)besti2;
1018
} else if (besti == _orientation) {
1019
// no orientation change
1020
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mag(%u) good orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);
1021
} else if (!_is_external || !_fix_orientation) {
1022
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Mag(%u) internal bad orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);
1023
} else {
1024
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mag(%u) new orientation: %u was %u %.1f", _compass_idx, besti, _orientation, (double)_orientation_confidence);
1025
}
1026
1027
if (!pass) {
1028
set_status(Status::BAD_ORIENTATION);
1029
return false;
1030
}
1031
1032
if (_orientation == besti) {
1033
// no orientation change
1034
return true;
1035
}
1036
1037
if (!_is_external || !_fix_orientation) {
1038
// we won't change the orientation, but we set _orientation
1039
// for reporting purposes
1040
_orientation = besti;
1041
_orientation_solution = besti;
1042
set_status(Status::BAD_ORIENTATION);
1043
return false;
1044
}
1045
1046
// correct the offsets for the new orientation
1047
Vector3f rot_offsets = _params.offset;
1048
rot_offsets.rotate_inverse(_orientation);
1049
rot_offsets.rotate(besti);
1050
_params.offset = rot_offsets;
1051
1052
// rotate the samples for the new orientation
1053
for (uint32_t i=0; i<_samples_collected; i++) {
1054
Vector3f s = _sample_buffer[i].get();
1055
s.rotate_inverse(_orientation);
1056
s.rotate(besti);
1057
_sample_buffer[i].set(s);
1058
}
1059
1060
_orientation = besti;
1061
_orientation_solution = besti;
1062
1063
// re-run the fit to get the diagonals and off-diagonals for the
1064
// new orientation
1065
initialize_fit();
1066
run_sphere_fit();
1067
run_ellipsoid_fit();
1068
1069
return fit_acceptable();
1070
}
1071
1072
/*
1073
fix radius of the fit to compensate for sensor scale factor errors
1074
return false if radius is outside acceptable range
1075
*/
1076
bool CompassCalibrator::fix_radius(void)
1077
{
1078
Location loc;
1079
if (!AP::ahrs().get_location(loc) && !AP::ahrs().get_origin(loc)) {
1080
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MagCal: No location, fix_radius skipped");
1081
// we don't have a position, leave scale factor as 0. This
1082
// will disable use of WMM in the EKF. Users can manually set
1083
// scale factor after calibration if it is known
1084
_params.scale_factor = 0;
1085
return true;
1086
}
1087
float intensity;
1088
float declination;
1089
float inclination;
1090
AP_Declination::get_mag_field_ef(loc.lat * 1e-7f, loc.lng * 1e-7f, intensity, declination, inclination);
1091
1092
float expected_radius = intensity * 1000; // mGauss
1093
float correction = expected_radius / _params.radius;
1094
1095
if (correction > COMPASS_MAX_SCALE_FACTOR || correction < COMPASS_MIN_SCALE_FACTOR) {
1096
// don't allow more than 30% scale factor correction
1097
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag(%u) bad radius %.0f expected %.0f",
1098
_compass_idx,
1099
_params.radius,
1100
expected_radius);
1101
set_status(Status::BAD_RADIUS);
1102
return false;
1103
}
1104
1105
_params.scale_factor = correction;
1106
1107
return true;
1108
}
1109
1110
// convert index to rotation, this allows to skip some rotations
1111
Rotation CompassCalibrator::auto_rotation_index(uint8_t n) const
1112
{
1113
if (n < ROTATION_PITCH_180_YAW_90) {
1114
return (Rotation)n;
1115
}
1116
// ROTATION_PITCH_180_YAW_90 (26) is the same as ROTATION_ROLL_180_YAW_90 (10)
1117
// ROTATION_PITCH_180_YAW_270 (27) is the same as ROTATION_ROLL_180_YAW_270 (14)
1118
n += 2;
1119
if (n < ROTATION_ROLL_90_PITCH_68_YAW_293) {
1120
return (Rotation)n;
1121
}
1122
// ROTATION_ROLL_90_PITCH_68_YAW_293 is for solo leg compass, not expecting to see this in other vehicles
1123
n += 1;
1124
if (n < ROTATION_PITCH_7) {
1125
return (Rotation)n;
1126
}
1127
// ROTATION_PITCH_7 is too close to ROTATION_NONE to tell the difference in compass cal
1128
n += 1;
1129
if (n < ROTATION_MAX) {
1130
return (Rotation)n;
1131
}
1132
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
1133
return ROTATION_NONE;
1134
};
1135
1136
bool CompassCalibrator::right_angle_rotation(Rotation r) const
1137
{
1138
switch (r) {
1139
case ROTATION_NONE:
1140
case ROTATION_YAW_90:
1141
case ROTATION_YAW_180:
1142
case ROTATION_YAW_270:
1143
case ROTATION_ROLL_180:
1144
case ROTATION_ROLL_180_YAW_90:
1145
case ROTATION_PITCH_180:
1146
case ROTATION_ROLL_180_YAW_270:
1147
case ROTATION_ROLL_90:
1148
case ROTATION_ROLL_90_YAW_90:
1149
case ROTATION_ROLL_270:
1150
case ROTATION_ROLL_270_YAW_90:
1151
case ROTATION_PITCH_90:
1152
case ROTATION_PITCH_270:
1153
case ROTATION_PITCH_180_YAW_90:
1154
case ROTATION_PITCH_180_YAW_270:
1155
case ROTATION_ROLL_90_PITCH_90:
1156
case ROTATION_ROLL_180_PITCH_90:
1157
case ROTATION_ROLL_270_PITCH_90:
1158
case ROTATION_ROLL_90_PITCH_180:
1159
case ROTATION_ROLL_270_PITCH_180:
1160
case ROTATION_ROLL_90_PITCH_270:
1161
case ROTATION_ROLL_180_PITCH_270:
1162
case ROTATION_ROLL_270_PITCH_270:
1163
case ROTATION_ROLL_90_PITCH_180_YAW_90:
1164
case ROTATION_ROLL_90_YAW_270:
1165
return true;
1166
1167
default:
1168
return false;
1169
}
1170
}
1171
1172
#endif // COMPASS_CAL_ENABLED
1173
1174