AP_Baro_ICM20789.h 1.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566
  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_ICM20789_I2C_ADDR
  7. // the baro is on a separate I2C address from the IMU, even though in
  8. // the same package
  9. #define HAL_BARO_ICM20789_I2C_ADDR 0x63
  10. #endif
  11. class AP_Baro_ICM20789 : public AP_Baro_Backend
  12. {
  13. public:
  14. void update() override;
  15. static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, AP_HAL::OwnPtr<AP_HAL::Device> dev_imu);
  16. private:
  17. AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, AP_HAL::OwnPtr<AP_HAL::Device> dev_imu);
  18. bool init();
  19. bool send_cmd16(uint16_t cmd);
  20. bool read_calibration_data(void);
  21. void convert_data(uint32_t Praw, uint32_t Traw);
  22. void calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],
  23. float &A, float &B, float &C);
  24. float get_pressure(uint32_t p_LSB, uint32_t T_LSB);
  25. bool imu_spi_init(void);
  26. bool imu_i2c_init(void);
  27. void timer(void);
  28. // calibration data
  29. int16_t sensor_constants[4];
  30. uint8_t instance;
  31. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
  32. AP_HAL::OwnPtr<AP_HAL::Device> dev_imu;
  33. // time last read command was sent
  34. uint32_t last_measure_us;
  35. // accumulation structure, protected by _sem
  36. struct {
  37. float tsum;
  38. float psum;
  39. uint32_t count;
  40. } accum;
  41. // conversion constants. Thanks to invensense for including python
  42. // sample code in the datasheet!
  43. const float p_Pa_calib[3] = {45000.0, 80000.0, 105000.0};
  44. const float LUT_lower = 3.5 * (1U<<20);
  45. const float LUT_upper = 11.5 * (1U<<20);
  46. const float quadr_factor = 1 / 16777216.0;
  47. const float offst_factor = 2048.0;
  48. };