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/AP_Compass_Calibration.cpp
Views: 1798
1
#include <AP_HAL/AP_HAL.h>
2
#include <AP_Notify/AP_Notify.h>
3
#include <AP_GPS/AP_GPS.h>
4
#include <GCS_MAVLink/GCS.h>
5
#include <AP_AHRS/AP_AHRS.h>
6
#include <AP_InternalError/AP_InternalError.h>
7
8
#include "AP_Compass.h"
9
10
const extern AP_HAL::HAL& hal;
11
12
#if COMPASS_CAL_ENABLED
13
14
void Compass::cal_update()
15
{
16
if (hal.util->get_soft_armed()) {
17
return;
18
}
19
20
bool running = false;
21
22
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
23
if (_calibrator[i] == nullptr) {
24
continue;
25
}
26
if (_calibrator[i]->failed()) {
27
AP_Notify::events.compass_cal_failed = 1;
28
}
29
30
if (_calibrator[i]->running()) {
31
running = true;
32
} else if (_cal_autosave && !_cal_saved[i] && _calibrator[i]->get_state().status == CompassCalibrator::Status::SUCCESS) {
33
_accept_calibration(uint8_t(i));
34
}
35
}
36
37
AP_Notify::flags.compass_cal_running = running;
38
39
if (is_calibrating()) {
40
_cal_has_run = true;
41
return;
42
} else if (_cal_has_run && _auto_reboot()) {
43
hal.scheduler->delay(1000);
44
hal.scheduler->reboot();
45
}
46
}
47
48
bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
49
{
50
if (!healthy(i)) {
51
return false;
52
}
53
if (!use_for_yaw(i)) {
54
return false;
55
}
56
Priority prio = Priority(i);
57
58
#if COMPASS_MAX_INSTANCES > 1
59
if (_priority_did_list[prio] != _priority_did_stored_list[prio]) {
60
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change");
61
return false;
62
}
63
#endif
64
65
if (_calibrator[prio] == nullptr) {
66
_calibrator[prio] = NEW_NOTHROW CompassCalibrator();
67
if (_calibrator[prio] == nullptr) {
68
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal object not initialised");
69
return false;
70
}
71
}
72
73
if (option_set(Option::CAL_REQUIRE_GPS)) {
74
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {
75
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock");
76
return false;
77
}
78
}
79
if (!is_calibrating()) {
80
AP_Notify::events.initiated_compass_cal = 1;
81
}
82
83
if (_rotate_auto) {
84
enum Rotation r = _get_state(prio).external?(enum Rotation)_get_state(prio).orientation.get():ROTATION_NONE;
85
if (r < ROTATION_MAX) {
86
_calibrator[prio]->set_orientation(r, _get_state(prio).external, _rotate_auto>=2, _rotate_auto>=3);
87
}
88
}
89
_cal_saved[prio] = false;
90
if (i == 0 && _get_state(prio).external != 0) {
91
_calibrator[prio]->start(retry, delay, get_offsets_max(), i, _calibration_threshold);
92
} else {
93
// internal compasses or secondary compasses get twice the
94
// threshold. This is because internal compasses tend to be a
95
// lot noisier
96
_calibrator[prio]->start(retry, delay, get_offsets_max(), i, _calibration_threshold*2);
97
}
98
if (!_cal_thread_started) {
99
_cal_requires_reboot = true;
100
if (!hal.scheduler->thread_create(FUNCTOR_BIND(this, &Compass::_update_calibration_trampoline, void), "compasscal", 2048, AP_HAL::Scheduler::PRIORITY_IO, 0)) {
101
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "CompassCalibrator: Cannot start compass thread.");
102
return false;
103
}
104
_cal_thread_started = true;
105
}
106
107
// disable compass learning both for calibration and after completion
108
_learn.set_and_save(0);
109
110
return true;
111
}
112
113
void Compass::_update_calibration_trampoline() {
114
while(true) {
115
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
116
if (_calibrator[i] == nullptr) {
117
continue;
118
}
119
_calibrator[i]->update();
120
}
121
hal.scheduler->delay(1);
122
}
123
}
124
125
bool Compass::_start_calibration_mask(uint8_t mask, bool retry, bool autosave, float delay, bool autoreboot)
126
{
127
_cal_autosave = autosave;
128
_compass_cal_autoreboot = autoreboot;
129
130
bool at_least_one_started = false;
131
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
132
if ((1<<i) & mask) {
133
if (!_start_calibration(i,retry,delay)) {
134
_cancel_calibration_mask(mask);
135
return false;
136
}
137
at_least_one_started = true;
138
}
139
}
140
return at_least_one_started;
141
}
142
143
bool Compass::start_calibration_all(bool retry, bool autosave, float delay, bool autoreboot)
144
{
145
_cal_autosave = autosave;
146
_compass_cal_autoreboot = autoreboot;
147
148
bool at_least_one_started = false;
149
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
150
// ignore any compasses that fail to start calibrating
151
// start all should only calibrate compasses that are being used
152
if (_start_calibration(i,retry,delay)) {
153
at_least_one_started = true;
154
}
155
}
156
return at_least_one_started;
157
}
158
159
void Compass::_cancel_calibration(uint8_t i)
160
{
161
AP_Notify::events.initiated_compass_cal = 0;
162
Priority prio = Priority(i);
163
if (_calibrator[prio] == nullptr) {
164
return;
165
}
166
if (_calibrator[prio]->running() || _calibrator[prio]->get_state().status == CompassCalibrator::Status::WAITING_TO_START) {
167
AP_Notify::events.compass_cal_canceled = 1;
168
}
169
_cal_saved[prio] = false;
170
_calibrator[prio]->stop();
171
}
172
173
void Compass::_cancel_calibration_mask(uint8_t mask)
174
{
175
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
176
if ((1<<i) & mask) {
177
_cancel_calibration(i);
178
}
179
}
180
}
181
182
void Compass::cancel_calibration_all()
183
{
184
_cancel_calibration_mask(0xFF);
185
}
186
187
bool Compass::_accept_calibration(uint8_t i)
188
{
189
Priority prio = Priority(i);
190
191
CompassCalibrator* cal = _calibrator[prio];
192
if (cal == nullptr) {
193
return false;
194
}
195
const CompassCalibrator::Report cal_report = cal->get_report();
196
197
if (_cal_saved[prio] || cal_report.status == CompassCalibrator::Status::NOT_STARTED) {
198
return true;
199
} else if (cal_report.status == CompassCalibrator::Status::SUCCESS) {
200
_cal_saved[prio] = true;
201
202
Vector3f ofs(cal_report.ofs), diag(cal_report.diag), offdiag(cal_report.offdiag);
203
float scale_factor = cal_report.scale_factor;
204
205
set_and_save_offsets(i, ofs);
206
#if AP_COMPASS_DIAGONALS_ENABLED
207
set_and_save_diagonals(i,diag);
208
set_and_save_offdiagonals(i,offdiag);
209
#endif
210
set_and_save_scale_factor(i,scale_factor);
211
212
if (cal_report.check_orientation && _get_state(prio).external && _rotate_auto >= 2) {
213
set_and_save_orientation(i, cal_report.orientation);
214
}
215
216
if (!is_calibrating()) {
217
AP_Notify::events.compass_cal_saved = 1;
218
}
219
return true;
220
} else {
221
return false;
222
}
223
}
224
225
bool Compass::_accept_calibration_mask(uint8_t mask)
226
{
227
bool success = true;
228
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
229
if (_calibrator[i] == nullptr) {
230
continue;
231
}
232
if ((1<<uint8_t(i)) & mask) {
233
if (!_accept_calibration(uint8_t(i))) {
234
success = false;
235
}
236
_calibrator[i]->stop();
237
}
238
}
239
240
return success;
241
}
242
243
#if HAL_GCS_ENABLED
244
bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link)
245
{
246
const mavlink_channel_t chan = link.get_chan();
247
248
for (uint8_t i = 0; i < COMPASS_MAX_INSTANCES; i++) {
249
const Priority compass_id = (next_cal_progress_idx[chan] + 1) % COMPASS_MAX_INSTANCES;
250
251
auto& calibrator = _calibrator[compass_id];
252
if (calibrator == nullptr) {
253
next_cal_progress_idx[chan] = compass_id;
254
continue;
255
}
256
const CompassCalibrator::State cal_state = calibrator->get_state();
257
258
if (cal_state.status == CompassCalibrator::Status::WAITING_TO_START ||
259
cal_state.status == CompassCalibrator::Status::RUNNING_STEP_ONE ||
260
cal_state.status == CompassCalibrator::Status::RUNNING_STEP_TWO) {
261
// ensure we don't try to send with no space available
262
if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_PROGRESS)) {
263
return false;
264
}
265
266
next_cal_progress_idx[chan] = compass_id;
267
268
mavlink_msg_mag_cal_progress_send(
269
link.get_chan(),
270
uint8_t(compass_id),
271
_get_cal_mask(),
272
(uint8_t)cal_state.status, cal_state.attempt, cal_state.completion_pct, cal_state.completion_mask,
273
0.0f, 0.0f, 0.0f
274
);
275
} else {
276
next_cal_progress_idx[chan] = compass_id;
277
}
278
}
279
280
return true;
281
}
282
283
bool Compass::send_mag_cal_report(const GCS_MAVLINK& link)
284
{
285
const mavlink_channel_t chan = link.get_chan();
286
287
for (uint8_t i = 0; i < COMPASS_MAX_INSTANCES; i++) {
288
const Priority compass_id = (next_cal_report_idx[chan] + 1) % COMPASS_MAX_INSTANCES;
289
290
if (_calibrator[compass_id] == nullptr) {
291
next_cal_report_idx[chan] = compass_id;
292
continue;
293
}
294
const CompassCalibrator::Report cal_report = _calibrator[compass_id]->get_report();
295
switch (cal_report.status) {
296
case CompassCalibrator::Status::NOT_STARTED:
297
case CompassCalibrator::Status::WAITING_TO_START:
298
case CompassCalibrator::Status::RUNNING_STEP_ONE:
299
case CompassCalibrator::Status::RUNNING_STEP_TWO:
300
// calibration has not finished ergo no report
301
next_cal_report_idx[chan] = compass_id;
302
continue;
303
case CompassCalibrator::Status::SUCCESS:
304
case CompassCalibrator::Status::FAILED:
305
case CompassCalibrator::Status::BAD_ORIENTATION:
306
case CompassCalibrator::Status::BAD_RADIUS:
307
// ensure we don't try to send with no space available
308
if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_REPORT)) {
309
return false;
310
}
311
312
next_cal_report_idx[chan] = compass_id;
313
314
mavlink_msg_mag_cal_report_send(
315
link.get_chan(),
316
uint8_t(compass_id),
317
_get_cal_mask(),
318
(uint8_t)cal_report.status,
319
_cal_saved[compass_id],
320
cal_report.fitness,
321
cal_report.ofs.x, cal_report.ofs.y, cal_report.ofs.z,
322
cal_report.diag.x, cal_report.diag.y, cal_report.diag.z,
323
cal_report.offdiag.x, cal_report.offdiag.y, cal_report.offdiag.z,
324
cal_report.orientation_confidence,
325
cal_report.original_orientation,
326
cal_report.orientation,
327
cal_report.scale_factor
328
);
329
}
330
}
331
return true;
332
}
333
#endif
334
335
bool Compass::is_calibrating() const
336
{
337
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
338
if (_calibrator[i] == nullptr) {
339
continue;
340
}
341
switch(_calibrator[i]->get_state().status) {
342
case CompassCalibrator::Status::NOT_STARTED:
343
case CompassCalibrator::Status::SUCCESS:
344
case CompassCalibrator::Status::FAILED:
345
case CompassCalibrator::Status::BAD_ORIENTATION:
346
case CompassCalibrator::Status::BAD_RADIUS:
347
// this backend isn't calibrating,
348
// but maybe the next one is:
349
continue;
350
case CompassCalibrator::Status::WAITING_TO_START:
351
case CompassCalibrator::Status::RUNNING_STEP_ONE:
352
case CompassCalibrator::Status::RUNNING_STEP_TWO:
353
return true;
354
}
355
}
356
return false;
357
}
358
359
uint8_t Compass::_get_cal_mask()
360
{
361
uint8_t cal_mask = 0;
362
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
363
if (_calibrator[i] == nullptr) {
364
continue;
365
}
366
if (_calibrator[i]->get_state().status != CompassCalibrator::Status::NOT_STARTED) {
367
cal_mask |= 1 << uint8_t(i);
368
}
369
}
370
return cal_mask;
371
}
372
373
/*
374
handle an incoming MAG_CAL command
375
*/
376
MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet)
377
{
378
MAV_RESULT result = MAV_RESULT_FAILED;
379
380
switch (packet.command) {
381
case MAV_CMD_DO_START_MAG_CAL: {
382
result = MAV_RESULT_ACCEPTED;
383
if (hal.util->get_soft_armed()) {
384
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration");
385
result = MAV_RESULT_FAILED;
386
break;
387
}
388
if (packet.param1 < 0 || packet.param1 > 255) {
389
result = MAV_RESULT_FAILED;
390
break;
391
}
392
393
uint8_t mag_mask = packet.param1;
394
bool retry = !is_zero(packet.param2);
395
bool autosave = !is_zero(packet.param3);
396
float delay = packet.param4;
397
bool autoreboot = packet.x != 0;
398
399
if (mag_mask == 0) { // 0 means all
400
_reset_compass_id();
401
if (!start_calibration_all(retry, autosave, delay, autoreboot)) {
402
result = MAV_RESULT_FAILED;
403
}
404
} else {
405
if (!_start_calibration_mask(mag_mask, retry, autosave, delay, autoreboot)) {
406
result = MAV_RESULT_FAILED;
407
}
408
}
409
410
break;
411
}
412
413
case MAV_CMD_DO_ACCEPT_MAG_CAL: {
414
result = MAV_RESULT_ACCEPTED;
415
if (packet.param1 < 0 || packet.param1 > 255) {
416
result = MAV_RESULT_FAILED;
417
break;
418
}
419
420
uint8_t mag_mask = packet.param1;
421
422
if (mag_mask == 0) { // 0 means all
423
mag_mask = 0xFF;
424
}
425
426
if (!_accept_calibration_mask(mag_mask)) {
427
result = MAV_RESULT_FAILED;
428
}
429
break;
430
}
431
432
case MAV_CMD_DO_CANCEL_MAG_CAL: {
433
result = MAV_RESULT_ACCEPTED;
434
if (packet.param1 < 0 || packet.param1 > 255) {
435
result = MAV_RESULT_FAILED;
436
break;
437
}
438
439
uint8_t mag_mask = packet.param1;
440
441
if (mag_mask == 0) { // 0 means all
442
cancel_calibration_all();
443
break;
444
}
445
446
_cancel_calibration_mask(mag_mask);
447
break;
448
}
449
}
450
451
return result;
452
}
453
454
#endif // COMPASS_CAL_ENABLED
455
456
#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
457
/*
458
get mag field with the effects of offsets, diagonals and
459
off-diagonals removed
460
*/
461
bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const
462
{
463
// get corrected field
464
field = get_field(instance);
465
466
#if AP_COMPASS_DIAGONALS_ENABLED
467
// form elliptical correction matrix and invert it. This is
468
// needed to remove the effects of the elliptical correction
469
// when calculating new offsets
470
const Vector3f &diagonals = get_diagonals(instance);
471
if (!diagonals.is_zero()) {
472
const Vector3f &offdiagonals = get_offdiagonals(instance);
473
Matrix3f mat {
474
diagonals.x, offdiagonals.x, offdiagonals.y,
475
offdiagonals.x, diagonals.y, offdiagonals.z,
476
offdiagonals.y, offdiagonals.z, diagonals.z
477
};
478
if (!mat.invert()) {
479
return false;
480
}
481
482
// remove impact of diagonals and off-diagonals
483
field = mat * field;
484
}
485
#endif
486
487
// remove impact of offsets
488
field -= get_offsets(instance);
489
490
return true;
491
}
492
493
/*
494
fast compass calibration given vehicle position and yaw. This
495
results in zero diagonal and off-diagonal elements, so is only
496
suitable for vehicles where the field is close to spherical. It is
497
useful for large vehicles where moving the vehicle to calibrate it
498
is difficult.
499
500
The offsets of the selected compasses are set to values to bring
501
them into consistency with the WMM tables at the given latitude and
502
longitude. If compass_mask is zero then all enabled compasses are
503
calibrated.
504
505
This assumes that the compass is correctly scaled in milliGauss
506
*/
507
bool Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
508
float lat_deg, float lon_deg, bool force_use)
509
{
510
_reset_compass_id();
511
if (is_zero(lat_deg) && is_zero(lon_deg)) {
512
Location loc;
513
// get AHRS position. If unavailable then try GPS location
514
if (!AP::ahrs().get_location(loc)) {
515
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
516
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: no position available");
517
return false;
518
}
519
loc = AP::gps().location();
520
}
521
lat_deg = loc.lat * 1.0e-7;
522
lon_deg = loc.lng * 1.0e-7;
523
}
524
525
// get the magnetic field intensity and orientation
526
float intensity;
527
float declination;
528
float inclination;
529
if (!AP_Declination::get_mag_field_ef(lat_deg, lon_deg, intensity, declination, inclination)) {
530
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: WMM table error");
531
return false;
532
}
533
534
// create a field vector and rotate to the required orientation
535
Vector3f field(1e3f * intensity, 0.0f, 0.0f);
536
Matrix3f R;
537
R.from_euler(0.0f, -ToRad(inclination), ToRad(declination));
538
field = R * field;
539
540
Matrix3f dcm;
541
dcm.from_euler(AP::ahrs().get_roll(), AP::ahrs().get_pitch(), radians(yaw_deg));
542
543
// Rotate into body frame using provided yaw
544
field = dcm.transposed() * field;
545
546
for (uint8_t i=0; i<get_count(); i++) {
547
if (compass_mask != 0 && ((1U<<i) & compass_mask) == 0) {
548
// skip this compass
549
continue;
550
}
551
if (_use_for_yaw[Priority(i)] == 0 || (!force_use && !use_for_yaw(i))) {
552
continue;
553
}
554
if (!healthy(i)) {
555
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: unhealthy\n", i);
556
return false;
557
}
558
559
Vector3f measurement;
560
if (!get_uncorrected_field(i, measurement)) {
561
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: bad uncorrected field", i);
562
return false;
563
}
564
565
Vector3f offsets = field - measurement;
566
set_and_save_offsets(i, offsets);
567
#if AP_COMPASS_DIAGONALS_ENABLED
568
Vector3f one{1,1,1};
569
set_and_save_diagonals(i, one);
570
Vector3f zero{0,0,0};
571
set_and_save_offdiagonals(i, zero);
572
#endif
573
}
574
575
return true;
576
}
577
578
#endif // AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
579
580