AP_Compass_MMC3416.h 2.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. #pragma once
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_HAL/I2CDevice.h>
  19. #include <AP_Math/AP_Math.h>
  20. #include "AP_Compass.h"
  21. #include "AP_Compass_Backend.h"
  22. #ifndef HAL_COMPASS_MMC3416_I2C_ADDR
  23. # define HAL_COMPASS_MMC3416_I2C_ADDR 0x30
  24. #endif
  25. class AP_Compass_MMC3416 : public AP_Compass_Backend
  26. {
  27. public:
  28. static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
  29. bool force_external,
  30. enum Rotation rotation);
  31. void read() override;
  32. static constexpr const char *name = "MMC3416";
  33. private:
  34. AP_Compass_MMC3416(AP_HAL::OwnPtr<AP_HAL::Device> dev,
  35. bool force_external,
  36. enum Rotation rotation);
  37. AP_HAL::OwnPtr<AP_HAL::Device> dev;
  38. enum {
  39. STATE_REFILL1,
  40. STATE_REFILL1_WAIT,
  41. STATE_MEASURE_WAIT1,
  42. STATE_REFILL2_WAIT,
  43. STATE_MEASURE_WAIT2,
  44. STATE_MEASURE_WAIT3,
  45. } state;
  46. /**
  47. * Device periodic callback to read data from the sensor.
  48. */
  49. bool init();
  50. void timer();
  51. void accumulate_field(Vector3f &field);
  52. uint8_t compass_instance;
  53. bool force_external;
  54. Vector3f offset;
  55. uint16_t measure_count;
  56. bool have_initial_offset;
  57. uint32_t refill_start_ms;
  58. uint32_t last_sample_ms;
  59. uint16_t data0[3];
  60. enum Rotation rotation;
  61. };