APM:Libraries
AP_Compass.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <inttypes.h>
4 
5 #include <AP_Common/AP_Common.h>
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_Math/AP_Math.h>
9 #include <AP_Param/AP_Param.h>
12 
13 #include "CompassCalibrator.h"
14 #include "AP_Compass_Backend.h"
15 #include "Compass_PerMotor.h"
16 
17 // motor compensation types (for use with motor_comp_enabled)
18 #define AP_COMPASS_MOT_COMP_DISABLED 0x00
19 #define AP_COMPASS_MOT_COMP_THROTTLE 0x01
20 #define AP_COMPASS_MOT_COMP_CURRENT 0x02
21 #define AP_COMPASS_MOT_COMP_PER_MOTOR 0x03
22 
23 // setup default mag orientation for some board types
24 #ifndef MAG_BOARD_ORIENTATION
25 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
26 # define MAG_BOARD_ORIENTATION ROTATION_YAW_90
27 #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
28  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI)
29 # define MAG_BOARD_ORIENTATION ROTATION_YAW_270
30 #else
31 # define MAG_BOARD_ORIENTATION ROTATION_NONE
32 #endif
33 #endif
34 
35 
36 // define default compass calibration fitness and consistency checks
37 #define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT 16.0f
38 #define AP_COMPASS_MAX_XYZ_ANG_DIFF radians(90.0f)
39 #define AP_COMPASS_MAX_XY_ANG_DIFF radians(60.0f)
40 #define AP_COMPASS_MAX_XY_LENGTH_DIFF 200.0f
41 
46 #define COMPASS_MAX_INSTANCES 3
47 #define COMPASS_MAX_BACKEND 3
48 
49 class Compass
50 {
51 friend class AP_Compass_Backend;
52 public:
53  Compass();
54 
55  /* Do not allow copies */
56  Compass(const Compass &other) = delete;
57  Compass &operator=(const Compass&) = delete;
58 
59  // get singleton instance
60  static Compass *get_singleton() {
61  return _singleton;
62  }
63 
64  friend class CompassLearn;
65 
71  bool init();
72 
75  bool read();
76 
79  void accumulate();
80 
87  float calculate_heading(const Matrix3f &dcm_matrix) const {
88  return calculate_heading(dcm_matrix, get_primary());
89  }
90  float calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const;
91 
97  void set_offsets(uint8_t i, const Vector3f &offsets);
98 
104  void set_and_save_offsets(uint8_t i, const Vector3f &offsets);
105  void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals);
106  void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals);
107 
115  void save_offsets(uint8_t i);
116  void save_offsets(void);
117 
118  // return the number of compass instances
119  uint8_t get_count(void) const { return _compass_count; }
120 
122  const Vector3f &get_field(uint8_t i) const { return _state[i].field; }
123  const Vector3f &get_field(void) const { return get_field(get_primary()); }
124 
125  // compass calibrator interface
126  void compass_cal_update();
127 
128  // per-motor calibration access
131  }
134  }
137  }
138 
139  void start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot = false);
140 
141  void cancel_calibration_all();
142 
144  bool is_calibrating() const;
145 
146  /*
147  handle an incoming MAG_CAL command
148  */
149  MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet);
150 
151  void send_mag_cal_progress(mavlink_channel_t chan);
152  void send_mag_cal_report(mavlink_channel_t chan);
153 
154  // check if the compasses are pointing in the same direction
155  bool consistent() const;
156 
158  bool healthy(uint8_t i) const { return _state[i].healthy; }
159  bool healthy(void) const { return healthy(get_primary()); }
160  uint8_t get_healthy_mask() const;
161 
166  const Vector3f &get_offsets(uint8_t i) const { return _state[i].offset; }
167  const Vector3f &get_offsets(void) const { return get_offsets(get_primary()); }
168 
169  const Vector3f &get_diagonals(uint8_t i) const { return _state[i].diagonals; }
170  const Vector3f &get_diagonals(void) const { return get_diagonals(get_primary()); }
171 
172  const Vector3f &get_offdiagonals(uint8_t i) const { return _state[i].offdiagonals; }
173  const Vector3f &get_offdiagonals(void) const { return get_offdiagonals(get_primary()); }
174 
180  void set_initial_location(int32_t latitude, int32_t longitude);
181 
189  void set_and_save_offsets(uint8_t i, int x, int y, int z) {
190  set_and_save_offsets(i, Vector3f(x, y, z));
191  }
192 
193  // learn offsets accessor
194  bool learn_offsets_enabled() const { return _learn; }
195 
197  bool use_for_yaw(uint8_t i) const;
198  bool use_for_yaw(void) const;
199 
200  void set_use_for_yaw(uint8_t i, bool use) {
201  _state[i].use_for_yaw.set(use);
202  }
203 
209  void set_declination(float radians, bool save_to_eeprom = true);
210  float get_declination() const;
211 
212  // set overall board orientation
213  void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
214  _board_orientation = orientation;
215  _custom_rotation = custom_rotation;
216  }
217 
222  void motor_compensation_type(const uint8_t comp_type);
223 
225  uint8_t get_motor_compensation_type() const {
226  return _motor_comp_type;
227  }
228 
234  void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor);
235 
237  const Vector3f& get_motor_compensation(uint8_t i) const { return _state[i].motor_compensation; }
239 
245 
250  const Vector3f &get_motor_offsets(uint8_t i) const { return _state[i].motor_offset; }
251  const Vector3f &get_motor_offsets(void) const { return get_motor_offsets(get_primary()); }
252 
255  void set_throttle(float thr_pct) {
257  _thr = thr_pct;
258  }
259  }
260 
262  void set_voltage(float voltage) {
263  _per_motor.set_voltage(voltage);
264  }
265 
270  bool configured(uint8_t i);
271  bool configured(void);
272 
277  uint8_t get_primary(void) const { return _primary; }
278 
279  // HIL methods
280  void setHIL(uint8_t instance, float roll, float pitch, float yaw);
281  void setHIL(uint8_t instance, const Vector3f &mag, uint32_t last_update_usec);
282  const Vector3f& getHIL(uint8_t instance) const;
283  void _setup_earth_field();
284 
285  // enable HIL mode
286  void set_hil_mode(void) { _hil_mode = true; }
287 
288  // return last update time in microseconds
289  uint32_t last_update_usec(void) const { return _state[get_primary()].last_update_usec; }
290  uint32_t last_update_usec(uint8_t i) const { return _state[i].last_update_usec; }
291 
292  uint32_t last_update_ms(void) const { return _state[get_primary()].last_update_ms; }
293  uint32_t last_update_ms(uint8_t i) const { return _state[i].last_update_ms; }
294 
295  static const struct AP_Param::GroupInfo var_info[];
296 
297  // HIL variables
298  struct {
303  } _hil;
304 
305  enum LearnType {
310  };
311 
312  // return the chosen learning type
313  enum LearnType get_learn_type(void) const {
314  return (enum LearnType)_learn.get();
315  }
316 
317  // set the learning type
318  void set_learn_type(enum LearnType type, bool save) {
319  if (save) {
320  _learn.set_and_save((int8_t)type);
321  } else {
322  _learn.set((int8_t)type);
323  }
324  }
325 
326  // return maximum allowed compass offsets
327  uint16_t get_offsets_max(void) const {
328  return (uint16_t)_offset_max.get();
329  }
330 
331  uint8_t get_filter_range() const { return uint8_t(_filter_range.get()); }
332 
333 private:
338  uint8_t register_compass(void);
339 
340  // load backend drivers
341  bool _add_backend(AP_Compass_Backend *backend, const char *name, bool external);
342  void _detect_backends(void);
343 
344  // compass cal
345  bool _accept_calibration(uint8_t i);
346  bool _accept_calibration_mask(uint8_t mask);
347  void _cancel_calibration(uint8_t i);
348  void _cancel_calibration_mask(uint8_t mask);
349  uint8_t _get_cal_mask() const;
350  bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f);
351  bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false);
353 
354  // see if we already have probed a driver by bus type
355  bool _have_driver(AP_HAL::Device::BusType bus_type, uint8_t bus_num, uint8_t address, uint8_t devtype) const;
356 
357 
358  //keep track of which calibrators have been saved
361 
362  //autoreboot after compass calibration
366 
367  // enum of drivers for COMPASS_TYPEMASK
368  enum DriverType {
383  };
384 
385  bool _driver_enabled(enum DriverType driver_type);
386 
387  // backend objects
389  uint8_t _backend_count;
390 
391  // number of registered compasses.
392  uint8_t _compass_count;
393 
394  // settable parameters
395  AP_Int8 _learn;
396 
397  // board orientation from AHRS
400 
401  // primary instance
402  AP_Int8 _primary;
403 
404  // declination in radians
405  AP_Float _declination;
406 
407  // enable automatic declination code
409 
410  // first-time-around flag used by offset nulling
412 
413  // used by offset correction
414  static const uint8_t _mag_history_size = 20;
415 
416  // motor compensation type
417  // 0 = disabled, 1 = enabled for throttle, 2 = enabled for current
419 
420  // throttle expressed as a percentage from 0 ~ 1.0, used for motor compensation
421  float _thr;
422 
423  struct mag_state {
424  AP_Int8 external;
425  bool healthy;
426  AP_Int8 orientation;
427  AP_Vector3f offset;
428  AP_Vector3f diagonals;
429  AP_Vector3f offdiagonals;
430 
431  // device id detected at init.
432  // saved to eeprom when offsets are saved allowing ram &
433  // eeprom values to be compared as consistency check
434  AP_Int32 dev_id;
435 
436  AP_Int8 use_for_yaw;
437 
440 
441  // factors multiplied by throttle and added to compass outputs
442  AP_Vector3f motor_compensation;
443 
444  // latest compensation added to compass
446 
447  // corrected magnetic field strength
449 
450  // when we last got data
451  uint32_t last_update_ms;
453 
454  // board specific orientation
455  enum Rotation rotation;
457 
458  AP_Int16 _offset_max;
459 
461 
462  // per-motor compass compensation
464 
465  // if we want HIL only
466  bool _hil_mode:1;
467 
469 
470  // mask of driver types to not load. Bit positions match DEVTYPE_ in backend
472 
473  AP_Int8 _filter_range;
474 };
475 
476 namespace AP {
477  Compass &compass();
478 };
uint8_t register_compass(void)
Definition: AP_Compass.cpp:503
bool _cal_has_run
Definition: AP_Compass.h:365
AP_Int8 _auto_declination
Definition: AP_Compass.h:408
void per_motor_calibration_end(void)
Definition: AP_Compass.h:135
bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f)
void calibration_end(void)
bool _have_driver(AP_HAL::Device::BusType bus_type, uint8_t bus_num, uint8_t address, uint8_t devtype) const
Definition: AP_Compass.cpp:538
Vector3< float > Vector3f
Definition: vector3.h:246
void set_board_orientation(enum Rotation orientation, Matrix3f *custom_rotation=nullptr)
Definition: AP_Compass.h:213
void set_learn_type(enum LearnType type, bool save)
Definition: AP_Compass.h:318
bool _cal_complete_requires_reboot
Definition: AP_Compass.h:364
float get_declination() const
uint32_t last_update_usec
Definition: AP_Compass.h:452
AP_Int32 _driver_type_mask
Definition: AP_Compass.h:471
static Compass * get_singleton()
Definition: AP_Compass.h:60
AP_Int8 _learn
Definition: AP_Compass.h:395
bool _driver_enabled(enum DriverType driver_type)
Definition: AP_Compass.cpp:529
const Vector3f & get_motor_offsets(uint8_t i) const
Definition: AP_Compass.h:250
bool _compass_cal_autoreboot
Definition: AP_Compass.h:363
void set_hil_mode(void)
Definition: AP_Compass.h:286
void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals)
const Vector3f & get_offsets(void) const
Definition: AP_Compass.h:167
bool _cal_saved[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:359
void setHIL(uint8_t instance, float roll, float pitch, float yaw)
float _thr
Definition: AP_Compass.h:421
void start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false)
bool _cal_autosave
Definition: AP_Compass.h:360
void calibration_update(void)
bool _add_backend(AP_Compass_Backend *backend, const char *name, bool external)
Definition: AP_Compass.cpp:511
bool init()
Definition: AP_Compass.cpp:487
void set_and_save_offsets(uint8_t i, const Vector3f &offsets)
uint8_t mag_history_index
Definition: AP_Compass.h:438
void cancel_calibration_all()
void per_motor_calibration_update(void)
Definition: AP_Compass.h:132
void accumulate()
Definition: AP_Compass.cpp:970
bool read()
Definition: AP_Compass.cpp:979
#define AP_COMPASS_MOT_COMP_THROTTLE
Definition: AP_Compass.h:19
uint8_t _get_cal_mask() const
AP_Float _declination
Definition: AP_Compass.h:405
void set_offsets(uint8_t i, const Vector3f &offsets)
const char * name
Definition: BusTest.cpp:11
const Vector3f & get_offdiagonals(void) const
Definition: AP_Compass.h:173
AP_Vector3f diagonals
Definition: AP_Compass.h:428
Rotation
Definition: rotations.h:27
void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
void set_throttle(float thr_pct)
Definition: AP_Compass.h:255
uint8_t get_healthy_mask() const
Definition: AP_Compass.cpp:993
void _setup_earth_field()
AP_Vector3f offdiagonals
Definition: AP_Compass.h:429
uint32_t last_update_usec(uint8_t i) const
Definition: AP_Compass.h:290
uint8_t get_primary(void) const
Definition: AP_Compass.h:277
float calculate_heading(const Matrix3f &dcm_matrix) const
Definition: AP_Compass.h:87
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
Definition: AP_Compass.h:122
CompassCalibrator _calibrator[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:460
MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet)
A system for managing and storing variables that are of general interest to the system.
bool _accept_calibration(uint8_t i)
void send_mag_cal_report(mavlink_channel_t chan)
void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
const Vector3f & get_diagonals(uint8_t i) const
Definition: AP_Compass.h:169
AP_Int8 _primary
Definition: AP_Compass.h:402
const Vector3f & get_motor_compensation(uint8_t i) const
get motor compensation factors as a vector
Definition: AP_Compass.h:237
#define x(i)
uint8_t get_filter_range() const
Definition: AP_Compass.h:331
Definition: AP_AHRS.cpp:486
float last_declination
Definition: AP_Compass.h:300
const Vector3f & get_diagonals(void) const
Definition: AP_Compass.h:170
#define f(i)
void set_use_for_yaw(uint8_t i, bool use)
Definition: AP_Compass.h:200
const Vector3f & get_offsets(uint8_t i) const
Definition: AP_Compass.h:166
AP_Vector3f offset
Definition: AP_Compass.h:427
bool _accept_calibration_mask(uint8_t mask)
Compass & operator=(const Compass &)=delete
bool _auto_reboot()
Definition: AP_Compass.h:352
bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false)
bool _null_init_done
Definition: AP_Compass.h:411
AP_Compass_Backend * _backends[COMPASS_MAX_BACKEND]
Definition: AP_Compass.h:388
Vector3f field[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:302
AP_Int16 _offset_max
Definition: AP_Compass.h:458
uint16_t get_offsets_max(void) const
Definition: AP_Compass.h:327
bool healthy(void) const
Definition: AP_Compass.h:159
bool consistent() const
AP_Int8 _motor_comp_type
Definition: AP_Compass.h:418
static Compass compass
Definition: AHRS_Test.cpp:20
const Vector3f & getHIL(uint8_t instance) const
const Vector3f & get_motor_offsets(void) const
Definition: AP_Compass.h:251
uint32_t last_update_ms(uint8_t i) const
Definition: AP_Compass.h:293
void _detect_backends(void)
Definition: AP_Compass.cpp:552
bool learn_offsets_enabled() const
Definition: AP_Compass.h:194
struct Compass::@17 _hil
void calibration_start(void)
AP_Float _calibration_threshold
Definition: AP_Compass.h:468
Compass_PerMotor _per_motor
Definition: AP_Compass.h:463
uint8_t get_count(void) const
Definition: AP_Compass.h:119
Common definitions and utility routines for the ArduPilot libraries.
void set_voltage(float _voltage)
void set_voltage(float voltage)
Set the battery voltage for per-motor compensation.
Definition: AP_Compass.h:262
Vector3f motor_offset
Definition: AP_Compass.h:445
enum LearnType get_learn_type(void) const
Definition: AP_Compass.h:313
void set_declination(float radians, bool save_to_eeprom=true)
#define COMPASS_MAX_INSTANCES
Definition: AP_Compass.h:46
bool _hil_mode
Definition: AP_Compass.h:466
void motor_compensation_type(const uint8_t comp_type)
uint32_t last_update_usec(void) const
Definition: AP_Compass.h:289
Matrix3f * _custom_rotation
Definition: AP_Compass.h:399
AP_Int8 _filter_range
Definition: AP_Compass.h:473
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void per_motor_calibration_start(void)
Definition: AP_Compass.h:129
const Vector3f & get_field(void) const
Definition: AP_Compass.h:123
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
static Compass * _singleton
Definition: AP_Compass.h:334
uint8_t get_motor_compensation_type() const
get the motor compensation value.
Definition: AP_Compass.h:225
uint32_t last_update_ms(void) const
Definition: AP_Compass.h:292
bool healthy(uint8_t i) const
Return the health of a compass.
Definition: AP_Compass.h:158
void _cancel_calibration(uint8_t i)
float voltage
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Compass.h:295
void _cancel_calibration_mask(uint8_t mask)
uint32_t last_update_ms
Definition: AP_Compass.h:451
uint8_t _compass_count
Definition: AP_Compass.h:392
bool is_calibrating() const
void send_mag_cal_progress(mavlink_channel_t chan)
Vector3f Bearth
Definition: AP_Compass.h:299
void save_offsets(void)
uint8_t _backend_count
Definition: AP_Compass.h:389
void set_and_save_offsets(uint8_t i, int x, int y, int z)
Definition: AP_Compass.h:189
#define COMPASS_MAX_BACKEND
Definition: AP_Compass.h:47
bool use_for_yaw(void) const
return true if the compass should be used for yaw calculations
bool configured(void)
bool compass_cal_requires_reboot()
Definition: AP_Compass.h:143
struct Compass::mag_state _state[COMPASS_MAX_INSTANCES]
void set_initial_location(int32_t latitude, int32_t longitude)
const Vector3f & get_motor_compensation(void) const
Definition: AP_Compass.h:238
enum Rotation _board_orientation
Definition: AP_Compass.h:398
AP_Vector3f motor_compensation
Definition: AP_Compass.h:442
static const uint8_t _mag_history_size
Definition: AP_Compass.h:414
void save_motor_compensation()
const Vector3f & get_offdiagonals(uint8_t i) const
Definition: AP_Compass.h:172