APM:Libraries
AP_Baro_ICM20789.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_Baro_Backend.h"
4 
5 #include <AP_HAL/AP_HAL.h>
6 #include <AP_HAL/Semaphores.h>
7 #include <AP_HAL/Device.h>
8 
9 #ifndef HAL_BARO_ICM20789_I2C_ADDR
10 // the baro is on a separate I2C address from the IMU, even though in
11 // the same package
12 #define HAL_BARO_ICM20789_I2C_ADDR 0x63
13 #endif
14 
16 {
17 public:
18  void update();
19 
21 
22 private:
24 
25  bool init();
26  bool send_cmd16(uint16_t cmd);
27 
28  bool read_calibration_data(void);
29 
30  void convert_data(uint32_t Praw, uint32_t Traw);
31 
32  void calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],
33  float &A, float &B, float &C);
34  float get_pressure(uint32_t p_LSB, uint32_t T_LSB);
35 
36  bool imu_spi_init(void);
37  bool imu_i2c_init(void);
38 
39  void timer(void);
40 
41  // calibration data
42  int16_t sensor_constants[4];
43 
44  uint8_t instance;
45 
48 
49  // time last read command was sent
50  uint32_t last_measure_us;
51 
52  // accumulation structure, protected by _sem
53  struct {
54  float tsum;
55  float psum;
56  uint32_t count;
57  } accum;
58 
59  // conversion constants. Thanks to invensense for including python
60  // sample code in the datasheet!
61  const float p_Pa_calib[3] = {45000.0, 80000.0, 105000.0};
62  const float LUT_lower = 3.5 * (1U<<20);
63  const float LUT_upper = 11.5 * (1U<<20);
64  const float quadr_factor = 1 / 16777216.0;
65  const float offst_factor = 2048.0;
66 };
const float offst_factor
AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::Device > dev_imu)
AP_HAL::OwnPtr< AP_HAL::Device > dev_imu
bool read_calibration_data(void)
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::Device > dev_imu)
const float p_Pa_calib[3]
static AP_Baro baro
Definition: ModuleTest.cpp:18
float get_pressure(uint32_t p_LSB, uint32_t T_LSB)
const float quadr_factor
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
bool send_cmd16(uint16_t cmd)
uint32_t last_measure_us
const float LUT_upper
void calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3], float &A, float &B, float &C)
struct AP_Baro_ICM20789::@8 accum
int16_t sensor_constants[4]
void convert_data(uint32_t Praw, uint32_t Traw)
const float LUT_lower