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