AP_Compass_HMC5843.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_HAL/Device.h>
  5. #include <AP_Math/AP_Math.h>
  6. #include "AP_Compass.h"
  7. #include "AP_Compass_Backend.h"
  8. class AuxiliaryBus;
  9. class AuxiliaryBusSlave;
  10. class AP_InertialSensor;
  11. class AP_HMC5843_BusDriver;
  12. class AP_Compass_HMC5843 : public AP_Compass_Backend
  13. {
  14. public:
  15. static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  16. bool force_external,
  17. enum Rotation rotation);
  18. static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation);
  19. static constexpr const char *name = "HMC5843";
  20. virtual ~AP_Compass_HMC5843();
  21. void read() override;
  22. private:
  23. AP_Compass_HMC5843(AP_HMC5843_BusDriver *bus,
  24. bool force_external, enum Rotation rotation);
  25. bool init();
  26. bool _check_whoami();
  27. bool _calibrate();
  28. bool _setup_sampling_mode();
  29. void _timer();
  30. /* Read a single sample */
  31. bool _read_sample();
  32. // ask for a new sample
  33. void _take_sample();
  34. AP_HMC5843_BusDriver *_bus;
  35. Vector3f _scaling;
  36. float _gain_scale;
  37. int16_t _mag_x;
  38. int16_t _mag_y;
  39. int16_t _mag_z;
  40. uint8_t _compass_instance;
  41. enum Rotation _rotation;
  42. bool _initialised:1;
  43. bool _force_external:1;
  44. };
  45. class AP_HMC5843_BusDriver
  46. {
  47. public:
  48. virtual ~AP_HMC5843_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. virtual void set_retries(uint8_t retries) {}
  61. };
  62. class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver
  63. {
  64. public:
  65. AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);
  66. bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
  67. bool register_read(uint8_t reg, uint8_t *val) override;
  68. bool register_write(uint8_t reg, uint8_t val) override;
  69. AP_HAL::Semaphore *get_semaphore() override;
  70. AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
  71. // set device type within a device class
  72. void set_device_type(uint8_t devtype) override {
  73. _dev->set_device_type(devtype);
  74. }
  75. // return 24 bit bus identifier
  76. uint32_t get_bus_id(void) const override {
  77. return _dev->get_bus_id();
  78. }
  79. void set_retries(uint8_t retries) override {
  80. return _dev->set_retries(retries);
  81. }
  82. private:
  83. AP_HAL::OwnPtr<AP_HAL::Device> _dev;
  84. };
  85. class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver
  86. {
  87. public:
  88. AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
  89. uint8_t addr);
  90. virtual ~AP_HMC5843_BusDriver_Auxiliary();
  91. bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
  92. bool register_read(uint8_t reg, uint8_t *val) override;
  93. bool register_write(uint8_t reg, uint8_t val) override;
  94. AP_HAL::Semaphore *get_semaphore() override;
  95. bool configure() override;
  96. bool start_measurements() override;
  97. AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
  98. // set device type within a device class
  99. void set_device_type(uint8_t devtype) override;
  100. // return 24 bit bus identifier
  101. uint32_t get_bus_id(void) const override;
  102. private:
  103. AuxiliaryBus *_bus;
  104. AuxiliaryBusSlave *_slave;
  105. bool _started;
  106. };