9 #ifndef HAL_BARO_ICM20789_I2C_ADDR    12 #define HAL_BARO_ICM20789_I2C_ADDR 0x63    33                                         float &
A, 
float &
B, 
float &C);
    61     const float p_Pa_calib[3] = {45000.0, 80000.0, 105000.0};
 
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]
 
float get_pressure(uint32_t p_LSB, uint32_t T_LSB)
 
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
 
bool send_cmd16(uint16_t cmd)
 
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)