AP_Baro_MS5611.h 2.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192
  1. #pragma once
  2. #include "AP_Baro_Backend.h"
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_HAL/Semaphores.h>
  5. #include <AP_HAL/Device.h>
  6. #ifndef HAL_BARO_MS5611_I2C_ADDR
  7. #define HAL_BARO_MS5611_I2C_ADDR 0x77
  8. #endif
  9. #ifndef HAL_BARO_MS5611_I2C_ADDR2
  10. #define HAL_BARO_MS5611_I2C_ADDR2 0x76
  11. #endif
  12. #ifndef HAL_BARO_MS5607_I2C_ADDR
  13. #define HAL_BARO_MS5607_I2C_ADDR 0x77
  14. #endif
  15. #ifndef HAL_BARO_MS5837_I2C_ADDR
  16. #define HAL_BARO_MS5837_I2C_ADDR 0x76
  17. #endif
  18. #ifndef HAL_BARO_MS5637_I2C_ADDR
  19. #define HAL_BARO_MS5637_I2C_ADDR 0x76
  20. #endif
  21. class AP_Baro_MS56XX : public AP_Baro_Backend
  22. {
  23. public:
  24. void update() override;
  25. enum MS56XX_TYPE {
  26. BARO_MS5611 = 0,
  27. BARO_MS5607 = 1,
  28. BARO_MS5637 = 2,
  29. BARO_MS5837 = 3
  30. };
  31. static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, enum MS56XX_TYPE ms56xx_type = BARO_MS5611);
  32. private:
  33. /*
  34. * Update @accum and @count with the new sample in @val, taking into
  35. * account a maximum number of samples given by @max_count; in case
  36. * maximum number is reached, @accum and @count are updated appropriately
  37. */
  38. static void _update_and_wrap_accumulator(uint32_t *accum, uint32_t val,
  39. uint8_t *count, uint8_t max_count);
  40. AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, enum MS56XX_TYPE ms56xx_type);
  41. bool _init();
  42. void _calculate_5611();
  43. void _calculate_5607();
  44. void _calculate_5637();
  45. void _calculate_5837();
  46. bool _read_prom_5611(uint16_t prom[8]);
  47. bool _read_prom_5637(uint16_t prom[8]);
  48. uint16_t _read_prom_word(uint8_t word);
  49. uint32_t _read_adc();
  50. void _timer();
  51. AP_HAL::OwnPtr<AP_HAL::Device> _dev;
  52. /* Shared values between thread sampling the HW and main thread */
  53. struct {
  54. uint32_t s_D1;
  55. uint32_t s_D2;
  56. uint8_t d1_count;
  57. uint8_t d2_count;
  58. } _accum;
  59. uint8_t _state;
  60. uint8_t _instance;
  61. /* Last compensated values from accumulated sample */
  62. float _D1, _D2;
  63. // Internal calibration registers
  64. struct {
  65. uint16_t c1, c2, c3, c4, c5, c6;
  66. } _cal_reg;
  67. bool _discard_next;
  68. enum MS56XX_TYPE _ms56xx_type;
  69. };