AP_Compass_LSM303D.h 1.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455
  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 AP_Compass_LSM303D : public AP_Compass_Backend
  9. {
  10. public:
  11. static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  12. enum Rotation rotation);
  13. static constexpr const char *name = "LSM303D";
  14. void read() override;
  15. virtual ~AP_Compass_LSM303D() { }
  16. private:
  17. AP_Compass_LSM303D(AP_HAL::OwnPtr<AP_HAL::Device> dev);
  18. bool init(enum Rotation rotation);
  19. uint8_t _register_read(uint8_t reg);
  20. void _register_write(uint8_t reg, uint8_t val);
  21. void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits);
  22. bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
  23. bool _read_sample();
  24. bool _data_ready();
  25. bool _hardware_init();
  26. void _update();
  27. void _disable_i2c();
  28. bool _mag_set_range(uint8_t max_ga);
  29. bool _mag_set_samplerate(uint16_t frequency);
  30. AP_HAL::DigitalSource *_drdy_pin_m;
  31. AP_HAL::OwnPtr<AP_HAL::Device> _dev;
  32. float _mag_range_scale;
  33. int16_t _mag_x;
  34. int16_t _mag_y;
  35. int16_t _mag_z;
  36. uint8_t _compass_instance;
  37. bool _initialised;
  38. uint8_t _mag_range_ga;
  39. uint8_t _mag_samplerate;
  40. uint8_t _reg7_expected;
  41. };