42 #define CMD_READ_PT_MODE_1 0x401A 43 #define CMD_READ_PT_MODE_3 0x5059 44 #define CMD_READ_TP_MODE_1 0x609C 45 #define CMD_READ_TP_MODE_3 0x70DF 47 #define CONVERSION_INTERVAL_MODE_1 2000 48 #define CONVERSION_INTERVAL_MODE_3 20000 51 #define CMD_READ_PT CMD_READ_PT_MODE_3 52 #define CONVERSION_INTERVAL CONVERSION_INTERVAL_MODE_3 54 #define CMD_SOFT_RESET 0x805D 55 #define CMD_READ_ID 0xEFC8 57 #define BARO_ICM20789_DEBUG 0 59 #if BARO_ICM20789_DEBUG 60 #define debug(fmt, args...) hal.console->printf(fmt, ##args) 62 #define debug(fmt, args...) 71 , dev_imu(
std::move(_dev_imu))
79 debug(
"Probing for ICM20789 baro\n");
80 if (!dev || !dev_imu) {
84 if (!sensor || !sensor->
init()) {
98 AP_HAL::panic(
"PANIC: AP_Baro_ICM20789: failed to take serial semaphore ICM");
152 debug(
"ICM20789: whoami 0x%02x old_address=%02x\n", whoami, old_address);
173 debug(
"Looking for 20789 baro\n");
176 AP_HAL::panic(
"PANIC: AP_Baro_ICM20789: failed to take serial semaphore for init");
179 debug(
"Setting up IMU\n");
182 debug(
"ICM20789: failed to initialise IMU SPI device\n");
186 debug(
"ICM20789: failed to initialise IMU I2C device\n");
191 debug(
"ICM20789: reset failed\n");
199 debug(
"ICM20789: read_calibration_data failed\n");
205 debug(
"ICM20789: start read failed\n");
215 debug(
"ICM20789: startup OK\n");
229 uint8_t cmd_b[2] = { uint8_t(cmd >> 8), uint8_t(cmd & 0xFF) };
236 const uint8_t cmd[5] = { 0xC5, 0x95, 0x00, 0x66, 0x9C };
237 if (!
dev->
transfer(cmd,
sizeof(cmd),
nullptr, 0)) {
238 debug(
"ICM20789: read cal1 failed\n");
241 for (uint8_t i=0; i<4; i++) {
243 debug(
"ICM20789: read cal2[%u] failed\n", i);
248 debug(
"ICM20789: read cal3[%u] failed\n", i);
258 float &
A,
float &
B,
float &C)
260 C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +
261 p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +
262 p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /
263 (p_LUT[2] * (p_Pa[0] - p_Pa[1]) +
264 p_LUT[0] * (p_Pa[1] - p_Pa[2]) +
265 p_LUT[1] * (p_Pa[2] - p_Pa[0]));
266 A = (p_Pa[0] * p_LUT[0] - p_Pa[1] * p_LUT[1] - (p_Pa[1] - p_Pa[0]) * C) / (p_LUT[0] - p_LUT[1]);
267 B = (p_Pa[0] - A) * (p_LUT[0] + C);
278 float t = T_LSB - 32768.0;
285 return A + B / (C + p_LSB);
289 #if BARO_ICM20789_DEBUG 299 float T = -45 + (175.0 / (1U<<16)) * Traw;
309 #if BARO_ICM20789_DEBUG 328 uint32_t Praw = (uint32_t(d[0]) << 16) | (uint32_t(d[1]) << 8) | d[3];
329 uint32_t Traw = (uint32_t(d[6]) << 8) | d[7];
346 if (
accum.count > 0) {
352 #if BARO_ICM20789_DEBUG 356 dd.Traw, dd.Praw, dd.P, dd.T);
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define CONVERSION_INTERVAL
#define MPUREG_INT_PIN_CFG
AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::Device > dev_imu)
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
virtual AP_HAL::Semaphore * get_semaphore()=0
virtual void set_retries(uint8_t retries)
virtual Semaphore * get_semaphore() override=0
uint8_t get_bus_address(void) const
#define HAL_SEMAPHORE_BLOCK_FOREVER
AP_HAL::OwnPtr< AP_HAL::Device > dev_imu
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
bool read_calibration_data(void)
#define BIT_USER_CTRL_I2C_IF_DIS
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]
virtual void delay(uint16_t ms)=0
void Log_Write(const char *name, const char *labels, const char *fmt,...)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
virtual bool set_speed(Speed speed)=0
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
enum BusType bus_type(void) const
static DataFlash_Class * instance(void)
bool pressure_ok(float press)
#define debug(fmt, args...)
float get_pressure(uint32_t p_LSB, uint32_t T_LSB)
#define MPUREG_PWR_MGMT_1
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
Common definitions and utility routines for the ArduPilot libraries.
virtual void set_address(uint8_t address)
bool send_cmd16(uint16_t cmd)
void set_read_flag(uint8_t flag)
#define BIT_PWR_MGMT_1_CLK_XGYRO
void calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3], float &A, float &B, float &C)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
struct AP_Baro_ICM20789::@8 accum
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
#define BIT_PWR_MGMT_1_SLEEP
void panic(const char *errormsg,...) FMT_PRINTF(1
int16_t sensor_constants[4]
void convert_data(uint32_t Praw, uint32_t Traw)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
AP_HAL::Scheduler * scheduler