AP_Baro_BMP388.h 1.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_HAL/Device.h>
  4. #include <AP_HAL/utility/OwnPtr.h>
  5. #include "AP_Baro_Backend.h"
  6. #ifndef HAL_BARO_BMP388_I2C_ADDR
  7. #define HAL_BARO_BMP388_I2C_ADDR (0x76)
  8. #endif
  9. #ifndef HAL_BARO_BMP388_I2C_ADDR2
  10. #define HAL_BARO_BMP388_I2C_ADDR2 (0x77)
  11. #endif
  12. class AP_Baro_BMP388 : public AP_Baro_Backend
  13. {
  14. public:
  15. AP_Baro_BMP388(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> _dev);
  16. /* AP_Baro public interface: */
  17. void update() override;
  18. static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> _dev);
  19. private:
  20. bool init(void);
  21. void timer(void);
  22. void update_temperature(uint32_t);
  23. void update_pressure(uint32_t);
  24. AP_HAL::OwnPtr<AP_HAL::Device> dev;
  25. bool has_sample;
  26. uint8_t instance;
  27. float pressure;
  28. float temperature;
  29. // Internal calibration registers
  30. struct PACKED {
  31. int16_t nvm_par_p1; // at 0x36
  32. int16_t nvm_par_p2;
  33. int8_t nvm_par_p3;
  34. int8_t nvm_par_p4;
  35. int16_t nvm_par_p5;
  36. int16_t nvm_par_p6;
  37. int8_t nvm_par_p7;
  38. int8_t nvm_par_p8;
  39. int16_t nvm_par_p9;
  40. int8_t nvm_par_p10;
  41. int8_t nvm_par_p11;
  42. } calib_p;
  43. struct PACKED {
  44. uint16_t nvm_par_t1; // at 0x31
  45. uint16_t nvm_par_t2;
  46. int8_t nvm_par_t3;
  47. } calib_t;
  48. // scaled calibration data
  49. struct {
  50. float par_t1;
  51. float par_t2;
  52. float par_t3;
  53. float par_p1;
  54. float par_p2;
  55. float par_p3;
  56. float par_p4;
  57. float par_p5;
  58. float par_p6;
  59. float par_p7;
  60. float par_p8;
  61. float par_p9;
  62. float par_p10;
  63. float par_p11;
  64. float t_lin;
  65. } calib;
  66. void scale_calibration_data(void);
  67. };