Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass.h
9532 views
1
#pragma once
2
3
#include "AP_Compass_config.h"
4
5
#include <inttypes.h>
6
7
#include <AP_Common/AP_Common.h>
8
#include <AP_Declination/AP_Declination.h>
9
#include <AP_HAL/AP_HAL.h>
10
#include <AP_Math/AP_Math.h>
11
#include <AP_Param/AP_Param.h>
12
#include <GCS_MAVLink/GCS_MAVLink.h>
13
#include <AP_MSP/msp.h>
14
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
15
16
#include "AP_Compass_Backend.h"
17
#include "Compass_PerMotor.h"
18
#include <AP_Common/TSIndex.h>
19
20
// motor compensation types (for use with motor_comp_enabled)
21
#define AP_COMPASS_MOT_COMP_DISABLED 0x00
22
#define AP_COMPASS_MOT_COMP_THROTTLE 0x01
23
#define AP_COMPASS_MOT_COMP_CURRENT 0x02
24
#define AP_COMPASS_MOT_COMP_PER_MOTOR 0x03
25
26
#ifndef MAG_BOARD_ORIENTATION
27
#define MAG_BOARD_ORIENTATION ROTATION_NONE
28
#endif
29
30
#ifndef COMPASS_MOT_ENABLED
31
#define COMPASS_MOT_ENABLED 1
32
#endif
33
#ifndef COMPASS_LEARN_ENABLED
34
#define COMPASS_LEARN_ENABLED AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
35
#endif
36
37
// define default compass calibration fitness and consistency checks
38
#define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT 16.0f
39
#define AP_COMPASS_MAX_XYZ_ANG_DIFF radians(90.0f)
40
#define AP_COMPASS_MAX_XY_ANG_DIFF radians(60.0f)
41
#define AP_COMPASS_MAX_XY_LENGTH_DIFF 200.0f
42
43
/**
44
maximum number of compass instances available on this platform. If more
45
than 1 then redundant sensors may be available
46
*/
47
#ifndef HAL_BUILD_AP_PERIPH
48
#ifndef HAL_COMPASS_MAX_SENSORS
49
#define HAL_COMPASS_MAX_SENSORS 3
50
#endif
51
#if HAL_COMPASS_MAX_SENSORS > 1
52
#define COMPASS_MAX_UNREG_DEV 5
53
#else
54
#define COMPASS_MAX_UNREG_DEV 0
55
#endif
56
#else
57
#ifndef HAL_COMPASS_MAX_SENSORS
58
#define HAL_COMPASS_MAX_SENSORS 1
59
#endif
60
#define COMPASS_MAX_UNREG_DEV 0
61
#endif
62
63
#define COMPASS_MAX_INSTANCES HAL_COMPASS_MAX_SENSORS
64
#define COMPASS_MAX_BACKEND HAL_COMPASS_MAX_SENSORS
65
66
#define MAX_CONNECTED_MAGS (COMPASS_MAX_UNREG_DEV+COMPASS_MAX_INSTANCES)
67
68
#include "CompassCalibrator.h"
69
70
class CompassLearn;
71
72
class Compass
73
{
74
friend class AP_Compass_Backend;
75
friend class AP_Compass_DroneCAN;
76
public:
77
Compass();
78
79
/* Do not allow copies */
80
CLASS_NO_COPY(Compass);
81
82
// get singleton instance
83
static Compass *get_singleton() {
84
return _singleton;
85
}
86
87
friend class CompassLearn;
88
89
/// Initialize the compass device.
90
///
91
/// @returns True if the compass was initialized OK, false if it was not
92
/// found or is not functioning.
93
///
94
__INITFUNC__ void init();
95
96
/// Read the compass and update the mag_ variables.
97
///
98
bool read();
99
100
// available returns true if the compass is both enabled and has
101
// been initialised
102
bool available() const { return _enabled && init_done; }
103
104
/// Calculate the tilt-compensated heading_ variables.
105
///
106
/// @param dcm_matrix The current orientation rotation matrix
107
///
108
/// @returns heading in radians
109
///
110
float calculate_heading(const Matrix3f &dcm_matrix) const {
111
return calculate_heading(dcm_matrix, _first_usable);
112
}
113
float calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const;
114
115
/// Sets offset x/y/z values.
116
///
117
/// @param i compass instance
118
/// @param offsets Offsets to the raw mag_ values in milligauss.
119
///
120
void set_offsets(uint8_t i, const Vector3f &offsets);
121
122
/// Sets and saves the compass offset x/y/z values.
123
///
124
/// @param i compass instance
125
/// @param offsets Offsets to the raw mag_ values in milligauss.
126
///
127
void set_and_save_offsets(uint8_t i, const Vector3f &offsets);
128
#if AP_COMPASS_DIAGONALS_ENABLED
129
void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals);
130
void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals);
131
#endif
132
void set_and_save_scale_factor(uint8_t i, float scale_factor);
133
void set_and_save_orientation(uint8_t i, Rotation orientation);
134
135
/// Saves the current offset x/y/z values for one or all compasses
136
///
137
/// @param i compass instance
138
///
139
/// This should be invoked periodically to save the offset values maintained by
140
/// ::learn_offsets.
141
///
142
void save_offsets(uint8_t i);
143
void save_offsets(void);
144
145
// return the number of compass instances
146
uint8_t get_count(void) const { return _compass_count; }
147
148
// return the number of enabled sensors
149
uint8_t get_num_enabled(void) const;
150
151
/// Return the current field as a Vector3f in milligauss
152
const Vector3f &get_field(uint8_t i) const { return _get_state(Priority(i)).field; }
153
const Vector3f &get_field(void) const { return get_field(_first_usable); }
154
155
/// Return true if we have set a scale factor for a compass
156
bool have_scale_factor(uint8_t i) const;
157
158
#if COMPASS_MOT_ENABLED
159
// per-motor calibration access
160
void per_motor_calibration_start(void) {
161
_per_motor.calibration_start();
162
}
163
void per_motor_calibration_update(void) {
164
_per_motor.calibration_update();
165
}
166
void per_motor_calibration_end(void) {
167
_per_motor.calibration_end();
168
}
169
#endif
170
171
#if COMPASS_CAL_ENABLED
172
// compass calibrator interface
173
void cal_update();
174
175
// start_calibration_all will only return false if there are no
176
// compasses to calibrate.
177
bool start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot = false);
178
179
void cancel_calibration_all();
180
181
bool compass_cal_requires_reboot() const { return _cal_requires_reboot; }
182
bool is_calibrating() const;
183
184
#if HAL_MAVLINK_BINDINGS_ENABLED
185
/*
186
handle an incoming MAG_CAL command
187
*/
188
MAV_RESULT handle_mag_cal_command(const mavlink_command_int_t &packet);
189
190
bool send_mag_cal_progress(const class GCS_MAVLINK& link);
191
bool send_mag_cal_report(const class GCS_MAVLINK& link);
192
#endif // HAL_MAVLINK_BINDINGS_ENABLED
193
#endif // COMPASS_CAL_ENABLED
194
195
// indicate which bit in LOG_BITMASK indicates we should log compass readings
196
void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }
197
198
// check if the compasses are pointing in the same direction
199
bool consistent() const;
200
201
/// Return the health of a compass
202
bool healthy(uint8_t i) const;
203
bool healthy(void) const { return healthy(_first_usable); }
204
uint8_t get_healthy_mask() const;
205
206
/// Returns the current offset values
207
///
208
/// @returns The current compass offsets in milligauss.
209
///
210
const Vector3f &get_offsets(uint8_t i) const { return _get_state(Priority(i)).offset; }
211
const Vector3f &get_offsets(void) const { return get_offsets(_first_usable); }
212
213
#if AP_COMPASS_DIAGONALS_ENABLED
214
const Vector3f &get_diagonals(uint8_t i) const { return _get_state(Priority(i)).diagonals; }
215
const Vector3f &get_diagonals(void) const { return get_diagonals(_first_usable); }
216
217
const Vector3f &get_offdiagonals(uint8_t i) const { return _get_state(Priority(i)).offdiagonals; }
218
const Vector3f &get_offdiagonals(void) const { return get_offdiagonals(_first_usable); }
219
#endif // AP_COMPASS_DIAGONALS_ENABLED
220
221
// learn offsets accessor
222
bool learn_offsets_enabled() const { return _learn == LearnType::INFLIGHT; }
223
224
/// return true if the compass should be used for yaw calculations
225
bool use_for_yaw(uint8_t i) const;
226
bool use_for_yaw(void) const;
227
228
/// Sets the local magnetic field declination.
229
///
230
/// @param radians Local field declination.
231
/// @param save_to_eeprom true to save to eeprom (false saves only to memory)
232
///
233
void set_declination(float radians, bool save_to_eeprom = true);
234
float get_declination() const;
235
236
bool auto_declination_enabled() const { return _auto_declination != 0; }
237
238
// set overall board orientation
239
void set_board_orientation(enum Rotation orientation) {
240
_board_orientation = orientation;
241
}
242
243
// get overall board orientation
244
enum Rotation get_board_orientation(void) const {
245
return _board_orientation;
246
}
247
248
/// Set the motor compensation type
249
///
250
/// @param comp_type 0 = disabled, 1 = enabled use throttle, 2 = enabled use current
251
///
252
void motor_compensation_type(const uint8_t comp_type);
253
254
/// get the motor compensation value.
255
uint8_t get_motor_compensation_type() const {
256
return _motor_comp_type;
257
}
258
259
/// Set the motor compensation factor x/y/z values.
260
///
261
/// @param i instance of compass
262
/// @param offsets Offsets multiplied by the throttle value and added to the raw mag_ values.
263
///
264
void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor);
265
266
/// get motor compensation factors as a vector
267
const Vector3f& get_motor_compensation(uint8_t i) const { return _get_state(Priority(i)).motor_compensation; }
268
const Vector3f& get_motor_compensation(void) const { return get_motor_compensation(_first_usable); }
269
270
/// Saves the current motor compensation x/y/z values.
271
///
272
/// This should be invoked periodically to save the offset values calculated by the motor compensation auto learning
273
///
274
void save_motor_compensation();
275
276
/// Returns the current motor compensation offset values
277
///
278
/// @returns The current compass offsets in milligauss.
279
///
280
const Vector3f &get_motor_offsets(uint8_t i) const { return _get_state(Priority(i)).motor_offset; }
281
const Vector3f &get_motor_offsets(void) const { return get_motor_offsets(_first_usable); }
282
283
/// Set the throttle as a percentage from 0.0 to 1.0
284
/// @param thr_pct throttle expressed as a percentage from 0 to 1.0
285
void set_throttle(float thr_pct) {
286
if (_motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
287
_thr = thr_pct;
288
}
289
}
290
291
#if COMPASS_MOT_ENABLED
292
/// Set the battery voltage for per-motor compensation
293
void set_voltage(float voltage) {
294
_per_motor.set_voltage(voltage);
295
}
296
#endif
297
298
/// Returns True if the compasses have been configured (i.e. offsets saved)
299
///
300
/// @returns True if compass has been configured
301
///
302
bool configured(uint8_t i);
303
bool configured(char *failure_msg, uint8_t failure_msg_len);
304
305
// return last update time in microseconds
306
uint32_t last_update_usec(void) const { return last_update_usec(_first_usable); }
307
uint32_t last_update_usec(uint8_t i) const { return _get_state(Priority(i)).last_update_usec; }
308
309
uint32_t last_update_ms(void) const { return last_update_ms(_first_usable); }
310
uint32_t last_update_ms(uint8_t i) const { return _get_state(Priority(i)).last_update_ms; }
311
312
static const struct AP_Param::GroupInfo var_info[];
313
314
enum class LearnType {
315
NONE = 0,
316
// INTERNAL = 1,
317
COPY_FROM_EKF = 2,
318
INFLIGHT = 3,
319
};
320
321
// return the chosen learning type
322
LearnType get_learn_type(void) const {
323
return (LearnType)_learn.get();
324
}
325
326
// set the learning type
327
void set_learn_type(LearnType type, bool save) {
328
if (save) {
329
_learn.set_and_save(type);
330
} else {
331
_learn.set(type);
332
}
333
}
334
335
// return maximum allowed compass offsets
336
uint16_t get_offsets_max(void) const {
337
return (uint16_t)_offset_max.get();
338
}
339
340
uint8_t get_filter_range() const { return uint8_t(_filter_range.get()); }
341
342
#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
343
/*
344
fast compass calibration given vehicle position and yaw
345
*/
346
bool mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
347
float lat_deg, float lon_deg,
348
bool force_use=false);
349
#endif
350
351
#if AP_COMPASS_MSP_ENABLED
352
void handle_msp(const MSP::msp_compass_data_message_t &pkt);
353
#endif
354
355
#if AP_COMPASS_EXTERNALAHRS_ENABLED
356
void handle_external(const AP_ExternalAHRS::mag_data_message_t &pkt);
357
#endif
358
359
// force save of current calibration as valid
360
void force_save_calibration(void);
361
362
// get the first compass marked for use by COMPASSx_USE
363
uint8_t get_first_usable(void) const { return _first_usable; }
364
365
private:
366
static Compass *_singleton;
367
368
// Use Priority and StateIndex typesafe index types
369
// to distinguish between two different type of indexing
370
// We use StateIndex for access by Backend
371
// and Priority for access by Frontend
372
DECLARE_TYPESAFE_INDEX(Priority, uint8_t);
373
DECLARE_TYPESAFE_INDEX(StateIndex, uint8_t);
374
375
/// Register a new compas driver, allocating an instance number
376
///
377
/// @param dev_id Dev ID of compass to register against
378
///
379
/// @return instance number saved against the dev id or first available empty instance number
380
bool register_compass(int32_t dev_id, uint8_t& instance) WARN_IF_UNUSED;
381
382
// load backend drivers
383
__INITFUNC__ void _probe_external_i2c_compasses(void);
384
__INITFUNC__ void _detect_backends(void);
385
__INITFUNC__ void probe_i2c_spi_compasses(void);
386
#if AP_COMPASS_DRONECAN_ENABLED
387
void probe_dronecan_compasses(void);
388
#endif
389
390
#if COMPASS_CAL_ENABLED
391
// compass cal
392
void _update_calibration_trampoline();
393
bool _accept_calibration(uint8_t i);
394
bool _accept_calibration_mask(uint8_t mask);
395
void _cancel_calibration(uint8_t i);
396
void _cancel_calibration_mask(uint8_t mask);
397
uint8_t _get_cal_mask();
398
bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f);
399
bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false);
400
bool _auto_reboot() const { return _compass_cal_autoreboot; }
401
#if HAL_MAVLINK_BINDINGS_ENABLED
402
Priority next_cal_progress_idx[MAVLINK_COMM_NUM_BUFFERS];
403
Priority next_cal_report_idx[MAVLINK_COMM_NUM_BUFFERS];
404
#endif
405
#endif // COMPASS_CAL_ENABLED
406
407
// see if we already have probed a i2c sensor by bus number and address
408
bool _i2c_sensor_is_registered(uint8_t bus_num, uint8_t address) const;
409
410
#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED
411
/*
412
get mag field with the effects of offsets, diagonals and
413
off-diagonals removed
414
*/
415
bool get_uncorrected_field(uint8_t instance, Vector3f &field) const;
416
#endif
417
418
#if COMPASS_CAL_ENABLED
419
//keep track of which calibrators have been saved
420
RestrictIDTypeArray<bool, COMPASS_MAX_INSTANCES, Priority> _cal_saved;
421
bool _cal_autosave;
422
423
//autoreboot after compass calibration
424
bool _compass_cal_autoreboot;
425
bool _cal_requires_reboot;
426
bool _cal_has_run;
427
#endif // COMPASS_CAL_ENABLED
428
429
// enum of drivers for COMPASS_DISBLMSK
430
enum DriverType {
431
#if AP_COMPASS_HMC5843_ENABLED
432
DRIVER_HMC5843 =0,
433
#endif
434
#if AP_COMPASS_LSM303D_ENABLED
435
DRIVER_LSM303D =1,
436
#endif
437
#if AP_COMPASS_AK8963_ENABLED
438
DRIVER_AK8963 =2,
439
#endif
440
#if AP_COMPASS_BMM150_ENABLED
441
DRIVER_BMM150 =3,
442
#endif
443
#if AP_COMPASS_LSM9DS1_ENABLED
444
DRIVER_LSM9DS1 =4,
445
#endif
446
#if AP_COMPASS_LIS3MDL_ENABLED
447
DRIVER_LIS3MDL =5,
448
#endif
449
#if AP_COMPASS_AK09916_ENABLED
450
DRIVER_AK09916 =6,
451
#endif
452
#if AP_COMPASS_IST8310_ENABLED
453
DRIVER_IST8310 =7,
454
#endif
455
#if AP_COMPASS_ICM20948_ENABLED
456
DRIVER_ICM20948 =8,
457
#endif
458
#if AP_COMPASS_MMC3416_ENABLED
459
DRIVER_MMC3416 =9,
460
#endif
461
#if AP_COMPASS_DRONECAN_ENABLED
462
DRIVER_UAVCAN =11,
463
#endif
464
#if AP_COMPASS_QMC5883L_ENABLED
465
DRIVER_QMC5883L =12,
466
#endif
467
#if AP_COMPASS_SITL_ENABLED
468
DRIVER_SITL =13,
469
#endif
470
#if AP_COMPASS_MAG3110_ENABLED
471
DRIVER_MAG3110 =14,
472
#endif
473
#if AP_COMPASS_IST8308_ENABLED
474
DRIVER_IST8308 =15,
475
#endif
476
#if AP_COMPASS_RM3100_ENABLED
477
DRIVER_RM3100 =16,
478
#endif
479
#if AP_COMPASS_MSP_ENABLED
480
DRIVER_MSP =17,
481
#endif
482
#if AP_COMPASS_EXTERNALAHRS_ENABLED
483
DRIVER_EXTERNALAHRS =18,
484
#endif
485
#if AP_COMPASS_MMC5XX3_ENABLED
486
DRIVER_MMC5XX3 =19,
487
#endif
488
#if AP_COMPASS_QMC5883P_ENABLED
489
DRIVER_QMC5883P =20,
490
#endif
491
#if AP_COMPASS_BMM350_ENABLED
492
DRIVER_BMM350 =21,
493
#endif
494
#if AP_COMPASS_IIS2MDC_ENABLED
495
DRIVER_IIS2MDC =22,
496
#endif
497
#if AP_COMPASS_LIS2MDL_ENABLED
498
DRIVER_LIS2MDL =23,
499
#endif
500
501
};
502
503
bool _driver_enabled(enum DriverType driver_type);
504
void add_backend(DriverType driver_type, AP_Compass_Backend *backend);
505
506
// helper probe functions
507
void probe_ak09916_via_icm20948(uint8_t i2c_bus, uint8_t ak09916_addr, uint8_t icm20948_addr, bool external, Rotation rotation);
508
void probe_ak09916_via_icm20948(uint8_t ins_instance, Rotation rotation);
509
void probe_ak8963_via_mpu9250(uint8_t imu_instance, Rotation rotation);
510
511
using probe_i2c_dev_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation);
512
void probe_i2c_dev(DriverType driver_type, probe_i2c_dev_probefn_t probefn, uint8_t i2c_bus, uint8_t i2c_addr, bool external, Rotation rotation);
513
514
using probe_spi_dev_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation);
515
void probe_spi_dev(DriverType driver_type, probe_spi_dev_probefn_t probefn, const char *name, bool external, Rotation rotation);
516
// short-lived method which expects a probe function that doesn't
517
// offer the ability to specify an external rotation
518
using probe_spi_dev_noexternal_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, Rotation);
519
void probe_spi_dev(DriverType driver_type, probe_spi_dev_noexternal_probefn_t probefn, const char *name, Rotation rotation);
520
521
// backend objects
522
AP_Compass_Backend *_backends[COMPASS_MAX_BACKEND];
523
uint8_t _backend_count;
524
525
// whether to enable the compass drivers at all
526
AP_Int8 _enabled;
527
528
// number of registered compasses.
529
uint8_t _compass_count;
530
531
// number of unregistered compasses.
532
uint8_t _unreg_compass_count;
533
534
// settable parameters
535
AP_Enum<LearnType> _learn;
536
537
// board orientation from AHRS
538
enum Rotation _board_orientation = ROTATION_NONE;
539
540
// declination in radians
541
AP_Float _declination;
542
543
// enable automatic declination code
544
AP_Int8 _auto_declination;
545
546
// stores which bit is used to indicate we should log compass readings
547
uint32_t _log_bit = -1;
548
549
// motor compensation type
550
// 0 = disabled, 1 = enabled for throttle, 2 = enabled for current
551
AP_Int8 _motor_comp_type;
552
553
// automatic compass orientation on calibration
554
AP_Int8 _rotate_auto;
555
556
// throttle expressed as a percentage from 0 ~ 1.0, used for motor compensation
557
float _thr;
558
559
struct mag_state {
560
AP_Int8 external;
561
bool healthy;
562
bool registered;
563
Compass::Priority priority;
564
AP_Int8 orientation;
565
AP_Vector3f offset;
566
#if AP_COMPASS_DIAGONALS_ENABLED
567
AP_Vector3f diagonals;
568
AP_Vector3f offdiagonals;
569
#endif
570
AP_Float scale_factor;
571
572
// device id detected at init.
573
// saved to eeprom when offsets are saved allowing ram &
574
// eeprom values to be compared as consistency check
575
AP_Int32 dev_id;
576
// Initialised when compass is detected
577
int32_t detected_dev_id;
578
// Initialised at boot from saved devid
579
int32_t expected_dev_id;
580
581
// factors multiplied by throttle and added to compass outputs
582
AP_Vector3f motor_compensation;
583
584
// latest compensation added to compass
585
Vector3f motor_offset;
586
587
// corrected magnetic field strength
588
Vector3f field;
589
590
// when we last got data
591
uint32_t last_update_ms;
592
uint32_t last_update_usec;
593
594
// board specific orientation
595
enum Rotation rotation;
596
597
// accumulated samples, protected by _sem, used by AP_Compass_Backend
598
Vector3f accum;
599
uint32_t accum_count;
600
// We only copy persistent params
601
void copy_from(const mag_state& state);
602
};
603
604
//Create an Array of mag_state to be accessible by StateIndex only
605
RestrictIDTypeArray<mag_state, COMPASS_MAX_INSTANCES+1, StateIndex> _state;
606
607
//Convert Priority to StateIndex
608
StateIndex _get_state_id(Priority priority) const;
609
//Get State Struct by Priority
610
const struct mag_state& _get_state(Priority priority) const { return _state[_get_state_id(priority)]; }
611
//Convert StateIndex to Priority
612
Priority _get_priority(StateIndex state_id) { return _state[state_id].priority; }
613
//Method to detect compass beyond initialisation stage
614
void _detect_runtime(void);
615
// This method reorganises devid list to match
616
// priority list, only call before detection at boot
617
#if COMPASS_MAX_INSTANCES > 1
618
void _reorder_compass_params();
619
#endif
620
// Update Priority List for Mags, by default, we just
621
// load them as they come up the first time
622
Priority _update_priority_list(int32_t dev_id);
623
624
// method to check if the mag with the devid
625
// is a replacement mag
626
bool is_replacement_mag(uint32_t dev_id);
627
628
//remove the devid from unreg compass list
629
void remove_unreg_dev_id(uint32_t devid);
630
631
void _reset_compass_id();
632
//Create Arrays to be accessible by Priority only
633
RestrictIDTypeArray<AP_Int8, COMPASS_MAX_INSTANCES, Priority> _use_for_yaw;
634
#if COMPASS_MAX_INSTANCES > 1
635
RestrictIDTypeArray<AP_Int32, COMPASS_MAX_INSTANCES, Priority> _priority_did_stored_list;
636
RestrictIDTypeArray<int32_t, COMPASS_MAX_INSTANCES, Priority> _priority_did_list;
637
#endif
638
639
AP_Int16 _offset_max;
640
641
// bitmask of options
642
enum class Option : uint16_t {
643
CAL_REQUIRE_GPS = (1U<<0),
644
ALLOW_DRONECAN_AUTO_REPLACEMENT = (1U<<1),
645
};
646
bool option_set(Option opt) const { return (_options.get() & uint16_t(opt)) != 0; }
647
AP_Int16 _options;
648
649
#if COMPASS_CAL_ENABLED
650
RestrictIDTypeArray<CompassCalibrator*, COMPASS_MAX_INSTANCES, Priority> _calibrator;
651
#endif
652
653
#if COMPASS_MOT_ENABLED
654
// per-motor compass compensation
655
Compass_PerMotor _per_motor{*this};
656
#endif
657
658
AP_Float _calibration_threshold;
659
660
// mask of driver types to not load. Bit positions match DEVTYPE_ in backend
661
AP_Int32 _driver_type_mask;
662
663
#if COMPASS_MAX_UNREG_DEV
664
// Put extra dev ids detected
665
AP_Int32 extra_dev_id[COMPASS_MAX_UNREG_DEV];
666
uint32_t _previously_unreg_mag[COMPASS_MAX_UNREG_DEV];
667
#endif
668
669
AP_Int8 _filter_range;
670
671
CompassLearn *learn;
672
bool learn_allocated;
673
674
/// Sets the initial location used to get declination
675
///
676
/// @param latitude GPS Latitude.
677
/// @param longitude GPS Longitude.
678
///
679
void try_set_initial_location();
680
bool _initial_location_set;
681
682
bool _cal_thread_started;
683
684
#if AP_COMPASS_MSP_ENABLED
685
uint8_t msp_instance_mask;
686
#endif
687
bool init_done;
688
689
bool suppress_devid_save;
690
691
uint8_t _first_usable; // first compass usable based on COMPASSx_USE param
692
};
693
694
namespace AP {
695
Compass &compass();
696
};
697
698