AP_Baro_BMP085.h 1.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_HAL/I2CDevice.h>
  4. #include <AP_HAL/utility/OwnPtr.h>
  5. #include <Filter/Filter.h>
  6. #include "AP_Baro_Backend.h"
  7. #ifndef HAL_BARO_BMP085_I2C_ADDR
  8. #define HAL_BARO_BMP085_I2C_ADDR (0x77)
  9. #endif
  10. class AP_Baro_BMP085 : public AP_Baro_Backend {
  11. public:
  12. AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
  13. /* AP_Baro public interface: */
  14. void update() override;
  15. static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
  16. private:
  17. bool _init();
  18. void _cmd_read_pressure();
  19. void _cmd_read_temp();
  20. bool _read_pressure();
  21. void _read_temp();
  22. void _calculate();
  23. bool _data_ready();
  24. void _timer(void);
  25. uint16_t _read_prom_word(uint8_t word);
  26. bool _read_prom(uint16_t *prom);
  27. AP_HAL::OwnPtr<AP_HAL::Device> _dev;
  28. AP_HAL::DigitalSource *_eoc;
  29. uint8_t _instance;
  30. bool _has_sample;
  31. // Boards with no EOC pin: use times instead
  32. uint32_t _last_press_read_command_time;
  33. uint32_t _last_temp_read_command_time;
  34. // State machine
  35. uint8_t _state;
  36. // Internal calibration registers
  37. int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
  38. uint16_t ac4, ac5, ac6;
  39. int32_t _raw_pressure;
  40. int32_t _raw_temp;
  41. int32_t _temp;
  42. AverageIntegralFilter<int32_t, int32_t, 10> _pressure_filter;
  43. uint8_t _vers;
  44. uint8_t _type;
  45. };