APM:Libraries
AP_Baro_ICM20789.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_HAL/AP_HAL.h>
17 #include <AP_HAL/I2CDevice.h>
18 #include <utility>
19 
20 #include <AP_Common/AP_Common.h>
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Math/AP_Math.h>
24 #include "AP_Baro_ICM20789.h"
25 
26 #include <utility>
27 #include <stdio.h>
28 
29 #include <AP_Math/AP_Math.h>
30 #include <DataFlash/DataFlash.h>
31 
33 
34 extern const AP_HAL::HAL &hal;
35 
36 /*
37  CMD_READ options. The draft datasheet doesn't specify, but it seems
38  Mode_1 has a conversion interval of 2ms. Mode_3 has a conversion
39  interval of 20ms. Both seem to produce equally as smooth results, so
40  presumably Mode_3 is doing internal averaging
41  */
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
46 
47 #define CONVERSION_INTERVAL_MODE_1 2000
48 #define CONVERSION_INTERVAL_MODE_3 20000
49 
50 // setup for Mode_3
51 #define CMD_READ_PT CMD_READ_PT_MODE_3
52 #define CONVERSION_INTERVAL CONVERSION_INTERVAL_MODE_3
53 
54 #define CMD_SOFT_RESET 0x805D
55 #define CMD_READ_ID 0xEFC8
56 
57 #define BARO_ICM20789_DEBUG 0
58 
59 #if BARO_ICM20789_DEBUG
60 #define debug(fmt, args...) hal.console->printf(fmt, ##args)
61 #else
62 #define debug(fmt, args...)
63 #endif
64 
65 /*
66  constructor
67  */
69  : AP_Baro_Backend(baro)
70  , dev(std::move(_dev))
71  , dev_imu(std::move(_dev_imu))
72 {
73 }
74 
78 {
79  debug("Probing for ICM20789 baro\n");
80  if (!dev || !dev_imu) {
81  return nullptr;
82  }
83  AP_Baro_ICM20789 *sensor = new AP_Baro_ICM20789(baro, std::move(dev), std::move(dev_imu));
84  if (!sensor || !sensor->init()) {
85  delete sensor;
86  return nullptr;
87  }
88  return sensor;
89 }
90 
91 
92 /*
93  setup ICM20789 to enable barometer, assuming IMU is on SPI and baro is on I2C
94 */
96 {
98  AP_HAL::panic("PANIC: AP_Baro_ICM20789: failed to take serial semaphore ICM");
99  }
100 
101  dev_imu->set_read_flag(0x80);
102 
104  uint8_t whoami = 0;
105  uint8_t v;
106 
109 
110  hal.scheduler->delay(1);
114 
115  hal.scheduler->delay(1);
117 
118  hal.scheduler->delay(1);
122 
123  dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);
124 
125  // wait for sensor to settle
126  hal.scheduler->delay(100);
127 
128  dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);
129 
132 
133  dev_imu->get_semaphore()->give();
134 
135  return true;
136 }
137 
138 /*
139  setup ICM20789 to enable barometer, assuming both IMU and baro on the same i2c bus
140 */
142 {
143  // as the baro device is already locked we need to re-use it,
144  // changing its address to match the IMU address
145  uint8_t old_address = dev->get_bus_address();
147 
148  dev->set_retries(4);
149 
150  uint8_t whoami=0;
151  dev->read_registers(MPUREG_WHOAMI, &whoami, 1);
152  debug("ICM20789: whoami 0x%02x old_address=%02x\n", whoami, old_address);
153 
156 
157  // wait for sensor to settle
158  hal.scheduler->delay(10);
159 
161 
162  dev->set_address(old_address);
163 
164  return true;
165 }
166 
168 {
169  if (!dev) {
170  return false;
171  }
172 
173  debug("Looking for 20789 baro\n");
174 
176  AP_HAL::panic("PANIC: AP_Baro_ICM20789: failed to take serial semaphore for init");
177  }
178 
179  debug("Setting up IMU\n");
181  if (!imu_spi_init()) {
182  debug("ICM20789: failed to initialise IMU SPI device\n");
183  return false;
184  }
185  } else if (!imu_i2c_init()) {
186  debug("ICM20789: failed to initialise IMU I2C device\n");
187  return false;
188  }
189 
190  if (!send_cmd16(CMD_SOFT_RESET)) {
191  debug("ICM20789: reset failed\n");
192  goto failed;
193  }
194 
195  // wait for sensor to settle
196  hal.scheduler->delay(10);
197 
198  if (!read_calibration_data()) {
199  debug("ICM20789: read_calibration_data failed\n");
200  goto failed;
201  }
202 
203  // start a reading
204  if (!send_cmd16(CMD_READ_PT)) {
205  debug("ICM20789: start read failed\n");
206  goto failed;
207  }
208 
209  dev->set_retries(0);
210 
212 
213  dev->get_semaphore()->give();
214 
215  debug("ICM20789: startup OK\n");
216 
217  // use 10ms to ensure we don't lose samples, with max lag of 10ms
219 
220  return true;
221 
222  failed:
223  dev->get_semaphore()->give();
224  return false;
225 }
226 
228 {
229  uint8_t cmd_b[2] = { uint8_t(cmd >> 8), uint8_t(cmd & 0xFF) };
230  return dev->transfer(cmd_b, 2, nullptr, 0);
231 }
232 
234 {
235  // setup for OTP read
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");
239  return false;
240  }
241  for (uint8_t i=0; i<4; i++) {
242  if (!send_cmd16(0xC7F7)) {
243  debug("ICM20789: read cal2[%u] failed\n", i);
244  return false;
245  }
246  uint8_t d[3];
247  if (!dev->transfer(nullptr, 0, d, sizeof(d))) {
248  debug("ICM20789: read cal3[%u] failed\n", i);
249  return false;
250  }
251  sensor_constants[i] = int16_t((d[0]<<8) | d[1]);
252  debug("sensor_constants[%u]=%d\n", i, sensor_constants[i]);
253  }
254  return true;
255 }
256 
257 void AP_Baro_ICM20789::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],
258  float &A, float &B, float &C)
259 {
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);
268 }
269 
270 /*
271  Convert an output from a calibrated sensor to a pressure in Pa.
272  Arguments:
273  p_LSB -- Raw pressure data from sensor
274  T_LSB -- Raw temperature data from sensor
275 */
276 float AP_Baro_ICM20789::get_pressure(uint32_t p_LSB, uint32_t T_LSB)
277 {
278  float t = T_LSB - 32768.0;
279  float s[3];
280  s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;
281  s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;
282  s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;
283  float A, B, C;
285  return A + B / (C + p_LSB);
286 }
287 
288 
289 #if BARO_ICM20789_DEBUG
290 static struct {
291  uint32_t Praw, Traw;
292  float T, P;
293 } dd;
294 #endif
295 
296 void AP_Baro_ICM20789::convert_data(uint32_t Praw, uint32_t Traw)
297 {
298  // temperature is easy
299  float T = -45 + (175.0 / (1U<<16)) * Traw;
300 
301  // pressure involves a few more calculations
302  float P = get_pressure(Praw, Traw);
303 
304  if (!pressure_ok(P)) {
305  return;
306  }
307 
309 #if BARO_ICM20789_DEBUG
310  dd.Praw = Praw;
311  dd.Traw = Traw;
312  dd.P = P;
313  dd.T = T;
314 #endif
315 
316  accum.psum += P;
317  accum.tsum += T;
318  accum.count++;
319  _sem->give();
320  }
321 }
322 
324 {
325  uint8_t d[9] {};
326  if (dev->transfer(nullptr, 0, d, sizeof(d))) {
327  // ignore CRC bytes for now
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];
330 
331  convert_data(Praw, Traw);
334  } else {
336  // lost a sample
339  }
340  }
341 }
342 
344 {
346  if (accum.count > 0) {
347  _copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);
348  accum.psum = accum.tsum = 0;
349  accum.count = 0;
350  }
351  _sem->give();
352 #if BARO_ICM20789_DEBUG
353  // useful for debugging
354  DataFlash_Class::instance()->Log_Write("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff",
356  dd.Traw, dd.Praw, dd.P, dd.T);
357 #endif
358  }
359 }
360 
#define BIT_BYPASS_EN
Definition: ICM20789.cpp:24
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define CONVERSION_INTERVAL
#define MPUREG_INT_PIN_CFG
Definition: ICM20789.cpp:23
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)
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
AP_HAL::Semaphore * _sem
virtual AP_HAL::Semaphore * get_semaphore()=0
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
virtual Semaphore * get_semaphore() override=0
uint8_t get_bus_address(void) const
Definition: Device.h:65
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
AP_HAL::OwnPtr< AP_HAL::Device > dev_imu
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define CMD_READ_PT
bool read_calibration_data(void)
#define MPUREG_WHOAMI
Definition: ICM20789.cpp:19
#define BIT_USER_CTRL_I2C_IF_DIS
Definition: ICM20789.cpp:30
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
AP_Baro & _frontend
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
virtual bool set_speed(Speed speed)=0
static AP_Baro baro
Definition: ModuleTest.cpp:18
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
Definition: Device.h:50
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
bool pressure_ok(float press)
uint64_t micros64()
Definition: system.cpp:162
#define debug(fmt, args...)
virtual bool give()=0
float get_pressure(uint32_t p_LSB, uint32_t T_LSB)
float v
Definition: Printf.cpp:15
const float quadr_factor
#define MPUREG_PWR_MGMT_1
Definition: ICM20789.cpp:21
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
Common definitions and utility routines for the ArduPilot libraries.
virtual void set_address(uint8_t address)
Definition: Device.h:85
bool send_cmd16(uint16_t cmd)
void set_read_flag(uint8_t flag)
Definition: Device.h:221
uint32_t last_measure_us
const float LUT_upper
#define BIT_PWR_MGMT_1_CLK_XGYRO
Definition: ICM20789.cpp:31
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)
Definition: Device.h:113
struct AP_Baro_ICM20789::@8 accum
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
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)
Definition: Device.h:125
uint32_t micros()
Definition: system.cpp:152
const float LUT_lower
#define CMD_SOFT_RESET
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define MPUREG_USER_CTRL
Definition: ICM20789.cpp:20