AP_Compass_AK8963.h 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_HAL/I2CDevice.h>
  5. #include <AP_HAL/SPIDevice.h>
  6. #include <AP_Math/AP_Math.h>
  7. #include "AP_Compass.h"
  8. #include "AP_Compass_Backend.h"
  9. class AuxiliaryBus;
  10. class AuxiliaryBusSlave;
  11. class AP_InertialSensor;
  12. class AP_AK8963_BusDriver;
  13. class AP_Compass_AK8963 : public AP_Compass_Backend
  14. {
  15. public:
  16. /* Probe for AK8963 standalone on I2C bus */
  17. static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  18. enum Rotation rotation);
  19. /* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */
  20. static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  21. enum Rotation rotation);
  22. /* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */
  23. static AP_Compass_Backend *probe_mpu9250(uint8_t mpu9250_instance,
  24. enum Rotation rotation);
  25. static constexpr const char *name = "AK8963";
  26. virtual ~AP_Compass_AK8963();
  27. void read() override;
  28. private:
  29. AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
  30. enum Rotation rotation);
  31. bool init();
  32. void _make_factory_sensitivity_adjustment(Vector3f &field) const;
  33. void _make_adc_sensitivity_adjustment(Vector3f &field) const;
  34. bool _reset();
  35. bool _setup_mode();
  36. bool _check_id();
  37. bool _calibrate();
  38. void _update();
  39. AP_AK8963_BusDriver *_bus;
  40. float _magnetometer_ASA[3] {0, 0, 0};
  41. uint8_t _compass_instance;
  42. bool _initialized;
  43. enum Rotation _rotation;
  44. };
  45. class AP_AK8963_BusDriver
  46. {
  47. public:
  48. virtual ~AP_AK8963_BusDriver() { }
  49. virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
  50. virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
  51. virtual bool register_write(uint8_t reg, uint8_t val) = 0;
  52. virtual AP_HAL::Semaphore *get_semaphore() = 0;
  53. virtual bool configure() { return true; }
  54. virtual bool start_measurements() { return true; }
  55. virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
  56. // set device type within a device class
  57. virtual void set_device_type(uint8_t devtype) = 0;
  58. // return 24 bit bus identifier
  59. virtual uint32_t get_bus_id(void) const = 0;
  60. };
  61. class AP_AK8963_BusDriver_HALDevice: public AP_AK8963_BusDriver
  62. {
  63. public:
  64. AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  65. virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
  66. virtual bool register_read(uint8_t reg, uint8_t *val) override;
  67. virtual bool register_write(uint8_t reg, uint8_t val) override;
  68. virtual AP_HAL::Semaphore *get_semaphore() override;
  69. AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
  70. // set device type within a device class
  71. void set_device_type(uint8_t devtype) override {
  72. _dev->set_device_type(devtype);
  73. }
  74. // return 24 bit bus identifier
  75. uint32_t get_bus_id(void) const override {
  76. return _dev->get_bus_id();
  77. }
  78. private:
  79. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  80. };
  81. class AP_AK8963_BusDriver_Auxiliary : public AP_AK8963_BusDriver
  82. {
  83. public:
  84. AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
  85. uint8_t backend_instance, uint8_t addr);
  86. ~AP_AK8963_BusDriver_Auxiliary();
  87. bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
  88. bool register_read(uint8_t reg, uint8_t *val) override;
  89. bool register_write(uint8_t reg, uint8_t val) override;
  90. AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
  91. AP_HAL::Semaphore *get_semaphore() override;
  92. bool configure() override;
  93. bool start_measurements() override;
  94. // set device type within a device class
  95. void set_device_type(uint8_t devtype) override;
  96. // return 24 bit bus identifier
  97. uint32_t get_bus_id(void) const override;
  98. private:
  99. AuxiliaryBus *_bus;
  100. AuxiliaryBusSlave *_slave;
  101. bool _started;
  102. };