AP_Compass.h 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503
  1. #pragma once
  2. #include <inttypes.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <AP_Declination/AP_Declination.h>
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AP_Math/AP_Math.h>
  7. #include <AP_Param/AP_Param.h>
  8. #include <GCS_MAVLink/GCS_MAVLink.h>
  9. #include "CompassCalibrator.h"
  10. #include "AP_Compass_Backend.h"
  11. #include "Compass_PerMotor.h"
  12. // motor compensation types (for use with motor_comp_enabled)
  13. #define AP_COMPASS_MOT_COMP_DISABLED 0x00
  14. #define AP_COMPASS_MOT_COMP_THROTTLE 0x01
  15. #define AP_COMPASS_MOT_COMP_CURRENT 0x02
  16. #define AP_COMPASS_MOT_COMP_PER_MOTOR 0x03
  17. // setup default mag orientation for some board types
  18. #ifndef MAG_BOARD_ORIENTATION
  19. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  20. # define MAG_BOARD_ORIENTATION ROTATION_YAW_90
  21. #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
  22. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI)
  23. # define MAG_BOARD_ORIENTATION ROTATION_YAW_270
  24. #else
  25. # define MAG_BOARD_ORIENTATION ROTATION_NONE
  26. #endif
  27. #endif
  28. #define COMPASS_CAL_ENABLED !defined(HAL_BUILD_AP_PERIPH)
  29. #define COMPASS_MOT_ENABLED !defined(HAL_BUILD_AP_PERIPH)
  30. #define COMPASS_LEARN_ENABLED !defined(HAL_BUILD_AP_PERIPH)
  31. // define default compass calibration fitness and consistency checks
  32. #define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT 16.0f
  33. #define AP_COMPASS_MAX_XYZ_ANG_DIFF radians(90.0f)
  34. #define AP_COMPASS_MAX_XY_ANG_DIFF radians(60.0f)
  35. #define AP_COMPASS_MAX_XY_LENGTH_DIFF 200.0f
  36. /**
  37. maximum number of compass instances available on this platform. If more
  38. than 1 then redundant sensors may be available
  39. */
  40. #define COMPASS_MAX_INSTANCES 3
  41. #define COMPASS_MAX_BACKEND 3
  42. class CompassLearn;
  43. class Compass
  44. {
  45. friend class AP_Compass_Backend;
  46. public:
  47. Compass();
  48. /* Do not allow copies */
  49. Compass(const Compass &other) = delete;
  50. Compass &operator=(const Compass&) = delete;
  51. // get singleton instance
  52. static Compass *get_singleton() {
  53. return _singleton;
  54. }
  55. friend class CompassLearn;
  56. /// Initialize the compass device.
  57. ///
  58. /// @returns True if the compass was initialized OK, false if it was not
  59. /// found or is not functioning.
  60. ///
  61. void init();
  62. /// Read the compass and update the mag_ variables.
  63. ///
  64. bool read();
  65. bool enabled() const { return _enabled; }
  66. /// Calculate the tilt-compensated heading_ variables.
  67. ///
  68. /// @param dcm_matrix The current orientation rotation matrix
  69. ///
  70. /// @returns heading in radians
  71. ///
  72. float calculate_heading(const Matrix3f &dcm_matrix) const {
  73. return calculate_heading(dcm_matrix, get_primary());
  74. }
  75. float calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const;
  76. /// Sets offset x/y/z values.
  77. ///
  78. /// @param i compass instance
  79. /// @param offsets Offsets to the raw mag_ values in milligauss.
  80. ///
  81. void set_offsets(uint8_t i, const Vector3f &offsets);
  82. /// Sets and saves the compass offset x/y/z values.
  83. ///
  84. /// @param i compass instance
  85. /// @param offsets Offsets to the raw mag_ values in milligauss.
  86. ///
  87. void set_and_save_offsets(uint8_t i, const Vector3f &offsets);
  88. void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals);
  89. void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals);
  90. /// Saves the current offset x/y/z values for one or all compasses
  91. ///
  92. /// @param i compass instance
  93. ///
  94. /// This should be invoked periodically to save the offset values maintained by
  95. /// ::learn_offsets.
  96. ///
  97. void save_offsets(uint8_t i);
  98. void save_offsets(void);
  99. // return the number of compass instances
  100. uint8_t get_count(void) const { return _compass_count; }
  101. /// Return the current field as a Vector3f in milligauss
  102. const Vector3f &get_field(uint8_t i) const { return _state[i].field; }
  103. const Vector3f &get_field(void) const { return get_field(get_primary()); }
  104. // compass calibrator interface
  105. void cal_update();
  106. #if COMPASS_MOT_ENABLED
  107. // per-motor calibration access
  108. void per_motor_calibration_start(void) {
  109. _per_motor.calibration_start();
  110. }
  111. void per_motor_calibration_update(void) {
  112. _per_motor.calibration_update();
  113. }
  114. void per_motor_calibration_end(void) {
  115. _per_motor.calibration_end();
  116. }
  117. #endif
  118. void start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot = false);
  119. void cancel_calibration_all();
  120. bool compass_cal_requires_reboot() const { return _cal_complete_requires_reboot; }
  121. bool is_calibrating() const;
  122. // indicate which bit in LOG_BITMASK indicates we should log compass readings
  123. void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }
  124. /*
  125. handle an incoming MAG_CAL command
  126. */
  127. MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet);
  128. bool send_mag_cal_progress(const class GCS_MAVLINK& link);
  129. bool send_mag_cal_report(const class GCS_MAVLINK& link);
  130. // check if the compasses are pointing in the same direction
  131. bool consistent() const;
  132. /// Return the health of a compass
  133. bool healthy(uint8_t i) const { return _state[i].healthy; }
  134. bool healthy(void) const { return healthy(get_primary()); }
  135. uint8_t get_healthy_mask() const;
  136. /// Returns the current offset values
  137. ///
  138. /// @returns The current compass offsets in milligauss.
  139. ///
  140. const Vector3f &get_offsets(uint8_t i) const { return _state[i].offset; }
  141. const Vector3f &get_offsets(void) const { return get_offsets(get_primary()); }
  142. const Vector3f &get_diagonals(uint8_t i) const { return _state[i].diagonals; }
  143. const Vector3f &get_diagonals(void) const { return get_diagonals(get_primary()); }
  144. const Vector3f &get_offdiagonals(uint8_t i) const { return _state[i].offdiagonals; }
  145. const Vector3f &get_offdiagonals(void) const { return get_offdiagonals(get_primary()); }
  146. // learn offsets accessor
  147. bool learn_offsets_enabled() const { return _learn == LEARN_INFLIGHT; }
  148. /// return true if the compass should be used for yaw calculations
  149. bool use_for_yaw(uint8_t i) const;
  150. bool use_for_yaw(void) const;
  151. void set_use_for_yaw(uint8_t i, bool use) {
  152. _state[i].use_for_yaw.set(use);
  153. }
  154. /// Sets the local magnetic field declination.
  155. ///
  156. /// @param radians Local field declination.
  157. /// @param save_to_eeprom true to save to eeprom (false saves only to memory)
  158. ///
  159. void set_declination(float radians, bool save_to_eeprom = true);
  160. float get_declination() const;
  161. // set overall board orientation
  162. void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
  163. _board_orientation = orientation;
  164. _custom_rotation = custom_rotation;
  165. }
  166. /// Set the motor compensation type
  167. ///
  168. /// @param comp_type 0 = disabled, 1 = enabled use throttle, 2 = enabled use current
  169. ///
  170. void motor_compensation_type(const uint8_t comp_type);
  171. /// get the motor compensation value.
  172. uint8_t get_motor_compensation_type() const {
  173. return _motor_comp_type;
  174. }
  175. /// Set the motor compensation factor x/y/z values.
  176. ///
  177. /// @param i instance of compass
  178. /// @param offsets Offsets multiplied by the throttle value and added to the raw mag_ values.
  179. ///
  180. void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor);
  181. /// get motor compensation factors as a vector
  182. const Vector3f& get_motor_compensation(uint8_t i) const { return _state[i].motor_compensation; }
  183. const Vector3f& get_motor_compensation(void) const { return get_motor_compensation(get_primary()); }
  184. /// Saves the current motor compensation x/y/z values.
  185. ///
  186. /// This should be invoked periodically to save the offset values calculated by the motor compensation auto learning
  187. ///
  188. void save_motor_compensation();
  189. /// Returns the current motor compensation offset values
  190. ///
  191. /// @returns The current compass offsets in milligauss.
  192. ///
  193. const Vector3f &get_motor_offsets(uint8_t i) const { return _state[i].motor_offset; }
  194. const Vector3f &get_motor_offsets(void) const { return get_motor_offsets(get_primary()); }
  195. /// Set the throttle as a percentage from 0.0 to 1.0
  196. /// @param thr_pct throttle expressed as a percentage from 0 to 1.0
  197. void set_throttle(float thr_pct) {
  198. if (_motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
  199. _thr = thr_pct;
  200. }
  201. }
  202. #if COMPASS_MOT_ENABLED
  203. /// Set the battery voltage for per-motor compensation
  204. void set_voltage(float voltage) {
  205. _per_motor.set_voltage(voltage);
  206. }
  207. #endif
  208. /// Returns True if the compasses have been configured (i.e. offsets saved)
  209. ///
  210. /// @returns True if compass has been configured
  211. ///
  212. bool configured(uint8_t i);
  213. bool configured(void);
  214. /// Returns the instance of the primary compass
  215. ///
  216. /// @returns the instance number of the primary compass
  217. ///
  218. uint8_t get_primary(void) const { return _primary; }
  219. // HIL methods
  220. void setHIL(uint8_t instance, float roll, float pitch, float yaw);
  221. void setHIL(uint8_t instance, const Vector3f &mag, uint32_t last_update_usec);
  222. const Vector3f& getHIL(uint8_t instance) const;
  223. void _setup_earth_field();
  224. // enable HIL mode
  225. void set_hil_mode(void) { _hil_mode = true; }
  226. // return last update time in microseconds
  227. uint32_t last_update_usec(void) const { return _state[get_primary()].last_update_usec; }
  228. uint32_t last_update_usec(uint8_t i) const { return _state[i].last_update_usec; }
  229. uint32_t last_update_ms(void) const { return _state[get_primary()].last_update_ms; }
  230. uint32_t last_update_ms(uint8_t i) const { return _state[i].last_update_ms; }
  231. static const struct AP_Param::GroupInfo var_info[];
  232. // HIL variables
  233. struct {
  234. Vector3f Bearth;
  235. float last_declination;
  236. bool healthy[COMPASS_MAX_INSTANCES];
  237. Vector3f field[COMPASS_MAX_INSTANCES];
  238. } _hil;
  239. enum LearnType {
  240. LEARN_NONE=0,
  241. LEARN_INTERNAL=1,
  242. LEARN_EKF=2,
  243. LEARN_INFLIGHT=3
  244. };
  245. // return the chosen learning type
  246. enum LearnType get_learn_type(void) const {
  247. return (enum LearnType)_learn.get();
  248. }
  249. // set the learning type
  250. void set_learn_type(enum LearnType type, bool save) {
  251. if (save) {
  252. _learn.set_and_save((int8_t)type);
  253. } else {
  254. _learn.set((int8_t)type);
  255. }
  256. }
  257. // return maximum allowed compass offsets
  258. uint16_t get_offsets_max(void) const {
  259. return (uint16_t)_offset_max.get();
  260. }
  261. uint8_t get_filter_range() const { return uint8_t(_filter_range.get()); }
  262. private:
  263. static Compass *_singleton;
  264. /// Register a new compas driver, allocating an instance number
  265. ///
  266. /// @return number of compass instances
  267. uint8_t register_compass(void);
  268. // load backend drivers
  269. bool _add_backend(AP_Compass_Backend *backend);
  270. void _probe_external_i2c_compasses(void);
  271. void _detect_backends(void);
  272. // compass cal
  273. bool _accept_calibration(uint8_t i);
  274. bool _accept_calibration_mask(uint8_t mask);
  275. void _cancel_calibration(uint8_t i);
  276. void _cancel_calibration_mask(uint8_t mask);
  277. uint8_t _get_cal_mask() const;
  278. bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f);
  279. bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false);
  280. bool _auto_reboot() { return _compass_cal_autoreboot; }
  281. // see if we already have probed a i2c driver by bus number and address
  282. bool _have_i2c_driver(uint8_t bus_num, uint8_t address) const;
  283. #if COMPASS_CAL_ENABLED
  284. //keep track of which calibrators have been saved
  285. bool _cal_saved[COMPASS_MAX_INSTANCES];
  286. bool _cal_autosave;
  287. #endif
  288. //autoreboot after compass calibration
  289. bool _compass_cal_autoreboot;
  290. bool _cal_complete_requires_reboot;
  291. bool _cal_has_run;
  292. // enum of drivers for COMPASS_TYPEMASK
  293. enum DriverType {
  294. DRIVER_HMC5843 =0,
  295. DRIVER_LSM303D =1,
  296. DRIVER_AK8963 =2,
  297. DRIVER_BMM150 =3,
  298. DRIVER_LSM9DS1 =4,
  299. DRIVER_LIS3MDL =5,
  300. DRIVER_AK09916 =6,
  301. DRIVER_IST8310 =7,
  302. DRIVER_ICM20948 =8,
  303. DRIVER_MMC3416 =9,
  304. DRIVER_UAVCAN =11,
  305. DRIVER_QMC5883L =12,
  306. DRIVER_SITL =13,
  307. DRIVER_MAG3110 =14,
  308. DRIVER_IST8308 = 15,
  309. DRIVER_RM3100 =16,
  310. };
  311. bool _driver_enabled(enum DriverType driver_type);
  312. // backend objects
  313. AP_Compass_Backend *_backends[COMPASS_MAX_BACKEND];
  314. uint8_t _backend_count;
  315. // whether to enable the compass drivers at all
  316. AP_Int8 _enabled;
  317. // number of registered compasses.
  318. uint8_t _compass_count;
  319. // settable parameters
  320. AP_Int8 _learn;
  321. // board orientation from AHRS
  322. enum Rotation _board_orientation = ROTATION_NONE;
  323. Matrix3f* _custom_rotation;
  324. // primary instance
  325. AP_Int8 _primary;
  326. // declination in radians
  327. AP_Float _declination;
  328. // enable automatic declination code
  329. AP_Int8 _auto_declination;
  330. // first-time-around flag used by offset nulling
  331. bool _null_init_done;
  332. // stores which bit is used to indicate we should log compass readings
  333. uint32_t _log_bit = -1;
  334. // used by offset correction
  335. static const uint8_t _mag_history_size = 20;
  336. // motor compensation type
  337. // 0 = disabled, 1 = enabled for throttle, 2 = enabled for current
  338. AP_Int8 _motor_comp_type;
  339. // automatic compass orientation on calibration
  340. AP_Int8 _rotate_auto;
  341. // throttle expressed as a percentage from 0 ~ 1.0, used for motor compensation
  342. float _thr;
  343. struct mag_state {
  344. AP_Int8 external;
  345. bool healthy;
  346. AP_Int8 orientation;
  347. AP_Vector3f offset;
  348. AP_Vector3f diagonals;
  349. AP_Vector3f offdiagonals;
  350. // device id detected at init.
  351. // saved to eeprom when offsets are saved allowing ram &
  352. // eeprom values to be compared as consistency check
  353. AP_Int32 dev_id;
  354. AP_Int32 expected_dev_id;
  355. int32_t detected_dev_id;
  356. AP_Int8 use_for_yaw;
  357. uint8_t mag_history_index;
  358. Vector3i mag_history[_mag_history_size];
  359. // factors multiplied by throttle and added to compass outputs
  360. AP_Vector3f motor_compensation;
  361. // latest compensation added to compass
  362. Vector3f motor_offset;
  363. // corrected magnetic field strength
  364. Vector3f field;
  365. // when we last got data
  366. uint32_t last_update_ms;
  367. uint32_t last_update_usec;
  368. // board specific orientation
  369. enum Rotation rotation;
  370. // accumulated samples, protected by _sem, used by AP_Compass_Backend
  371. Vector3f accum;
  372. uint32_t accum_count;
  373. } _state[COMPASS_MAX_INSTANCES];
  374. AP_Int16 _offset_max;
  375. #if COMPASS_CAL_ENABLED
  376. CompassCalibrator _calibrator[COMPASS_MAX_INSTANCES];
  377. #endif
  378. #if COMPASS_MOT_ENABLED
  379. // per-motor compass compensation
  380. Compass_PerMotor _per_motor{*this};
  381. #endif
  382. // if we want HIL only
  383. bool _hil_mode:1;
  384. AP_Float _calibration_threshold;
  385. // mask of driver types to not load. Bit positions match DEVTYPE_ in backend
  386. AP_Int32 _driver_type_mask;
  387. AP_Int8 _filter_range;
  388. CompassLearn *learn;
  389. bool learn_allocated;
  390. /// Sets the initial location used to get declination
  391. ///
  392. /// @param latitude GPS Latitude.
  393. /// @param longitude GPS Longitude.
  394. ///
  395. void try_set_initial_location();
  396. bool _initial_location_set;
  397. };
  398. namespace AP {
  399. Compass &compass();
  400. };