CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_ICM20789.cpp
Views: 1798
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_Baro_ICM20789.h"
17
18
#if AP_BARO_ICM20789_ENABLED
19
20
#include <AP_HAL/AP_HAL.h>
21
#include <AP_HAL/I2CDevice.h>
22
#include <utility>
23
24
#include <AP_Common/AP_Common.h>
25
#include <AP_BoardConfig/AP_BoardConfig.h>
26
27
#include <stdio.h>
28
29
#include <AP_Math/AP_Math.h>
30
#include <AP_Logger/AP_Logger.h>
31
32
#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>
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
*/
68
AP_Baro_ICM20789::AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev, AP_HAL::OwnPtr<AP_HAL::Device> _dev_imu)
69
: AP_Baro_Backend(baro)
70
, dev(std::move(_dev))
71
, dev_imu(std::move(_dev_imu))
72
{
73
}
74
75
AP_Baro_Backend *AP_Baro_ICM20789::probe(AP_Baro &baro,
76
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
77
AP_HAL::OwnPtr<AP_HAL::Device> dev_imu)
78
{
79
debug("Probing for ICM20789 baro\n");
80
if (!dev || !dev_imu) {
81
return nullptr;
82
}
83
AP_Baro_ICM20789 *sensor = NEW_NOTHROW 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
*/
95
bool AP_Baro_ICM20789::imu_spi_init(void)
96
{
97
dev_imu->get_semaphore()->take_blocking();
98
99
dev_imu->set_read_flag(0x80);
100
101
dev_imu->set_speed(AP_HAL::Device::SPEED_LOW);
102
uint8_t whoami = 0;
103
uint8_t v;
104
105
dev_imu->read_registers(MPUREG_USER_CTRL, &v, 1);
106
dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
107
108
hal.scheduler->delay(1);
109
dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
110
dev_imu->write_register(MPUREG_PWR_MGMT_1,
111
BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);
112
113
hal.scheduler->delay(1);
114
dev_imu->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
115
116
hal.scheduler->delay(1);
117
dev_imu->write_register(MPUREG_FIFO_EN, 0x00);
118
dev_imu->write_register(MPUREG_PWR_MGMT_1,
119
BIT_PWR_MGMT_1_SLEEP | BIT_PWR_MGMT_1_CLK_XGYRO);
120
121
dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);
122
123
// wait for sensor to settle
124
hal.scheduler->delay(100);
125
126
dev_imu->read_registers(MPUREG_WHOAMI, &whoami, 1);
127
128
dev_imu->write_register(MPUREG_INT_PIN_CFG, 0x00);
129
dev_imu->write_register(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
130
131
dev_imu->get_semaphore()->give();
132
133
return true;
134
}
135
136
/*
137
setup ICM20789 to enable barometer, assuming both IMU and baro on the same i2c bus
138
*/
139
bool AP_Baro_ICM20789::imu_i2c_init(void)
140
{
141
// as the baro device is already locked we need to re-use it,
142
// changing its address to match the IMU address
143
uint8_t old_address = dev->get_bus_address();
144
dev->set_address(dev_imu->get_bus_address());
145
146
dev->set_retries(4);
147
148
uint8_t whoami=0;
149
dev->read_registers(MPUREG_WHOAMI, &whoami, 1);
150
debug("ICM20789: whoami 0x%02x old_address=%02x\n", whoami, old_address);
151
152
dev->write_register(MPUREG_FIFO_EN, 0x00);
153
dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
154
155
// wait for sensor to settle
156
hal.scheduler->delay(10);
157
158
dev->write_register(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);
159
160
dev->set_address(old_address);
161
162
return true;
163
}
164
165
bool AP_Baro_ICM20789::init()
166
{
167
if (!dev) {
168
return false;
169
}
170
171
debug("Looking for 20789 baro\n");
172
173
dev->get_semaphore()->take_blocking();
174
175
debug("Setting up IMU\n");
176
if (dev_imu->bus_type() != AP_HAL::Device::BUS_TYPE_I2C) {
177
if (!imu_spi_init()) {
178
debug("ICM20789: failed to initialise IMU SPI device\n");
179
return false;
180
}
181
} else if (!imu_i2c_init()) {
182
debug("ICM20789: failed to initialise IMU I2C device\n");
183
return false;
184
}
185
186
if (!send_cmd16(CMD_SOFT_RESET)) {
187
debug("ICM20789: reset failed\n");
188
goto failed;
189
}
190
191
// wait for sensor to settle
192
hal.scheduler->delay(10);
193
194
if (!read_calibration_data()) {
195
debug("ICM20789: read_calibration_data failed\n");
196
goto failed;
197
}
198
199
// start a reading
200
if (!send_cmd16(CMD_READ_PT)) {
201
debug("ICM20789: start read failed\n");
202
goto failed;
203
}
204
205
dev->set_retries(0);
206
207
instance = _frontend.register_sensor();
208
209
dev->set_device_type(DEVTYPE_BARO_ICM20789);
210
set_bus_id(instance, dev->get_bus_id());
211
212
dev->get_semaphore()->give();
213
214
debug("ICM20789: startup OK\n");
215
216
// use 10ms to ensure we don't lose samples, with max lag of 10ms
217
dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICM20789::timer, void));
218
219
return true;
220
221
failed:
222
dev->get_semaphore()->give();
223
return false;
224
}
225
226
bool AP_Baro_ICM20789::send_cmd16(uint16_t cmd)
227
{
228
uint8_t cmd_b[2] = { uint8_t(cmd >> 8), uint8_t(cmd & 0xFF) };
229
return dev->transfer(cmd_b, 2, nullptr, 0);
230
}
231
232
bool AP_Baro_ICM20789::read_calibration_data(void)
233
{
234
// setup for OTP read
235
const uint8_t cmd[5] = { 0xC5, 0x95, 0x00, 0x66, 0x9C };
236
if (!dev->transfer(cmd, sizeof(cmd), nullptr, 0)) {
237
debug("ICM20789: read cal1 failed\n");
238
return false;
239
}
240
for (uint8_t i=0; i<4; i++) {
241
if (!send_cmd16(0xC7F7)) {
242
debug("ICM20789: read cal2[%u] failed\n", i);
243
return false;
244
}
245
uint8_t d[3];
246
if (!dev->transfer(nullptr, 0, d, sizeof(d))) {
247
debug("ICM20789: read cal3[%u] failed\n", i);
248
return false;
249
}
250
sensor_constants[i] = int16_t((d[0]<<8) | d[1]);
251
debug("sensor_constants[%u]=%d\n", i, sensor_constants[i]);
252
}
253
return true;
254
}
255
256
void AP_Baro_ICM20789::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],
257
float &A, float &B, float &C)
258
{
259
C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +
260
p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +
261
p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /
262
(p_LUT[2] * (p_Pa[0] - p_Pa[1]) +
263
p_LUT[0] * (p_Pa[1] - p_Pa[2]) +
264
p_LUT[1] * (p_Pa[2] - p_Pa[0]));
265
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]);
266
B = (p_Pa[0] - A) * (p_LUT[0] + C);
267
}
268
269
/*
270
Convert an output from a calibrated sensor to a pressure in Pa.
271
Arguments:
272
p_LSB -- Raw pressure data from sensor
273
T_LSB -- Raw temperature data from sensor
274
*/
275
float AP_Baro_ICM20789::get_pressure(uint32_t p_LSB, uint32_t T_LSB)
276
{
277
float t = T_LSB - 32768.0;
278
float s[3];
279
s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;
280
s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;
281
s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;
282
float A, B, C;
283
calculate_conversion_constants(p_Pa_calib, s, A, B, C);
284
return A + B / (C + p_LSB);
285
}
286
287
288
#if BARO_ICM20789_DEBUG
289
static struct {
290
uint32_t Praw, Traw;
291
float T, P;
292
} dd;
293
#endif
294
295
void AP_Baro_ICM20789::convert_data(uint32_t Praw, uint32_t Traw)
296
{
297
// temperature is easy
298
float T = -45 + (175.0f / (1U<<16)) * Traw;
299
300
// pressure involves a few more calculations
301
float P = get_pressure(Praw, Traw);
302
303
if (!pressure_ok(P)) {
304
return;
305
}
306
307
WITH_SEMAPHORE(_sem);
308
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
}
320
321
void AP_Baro_ICM20789::timer(void)
322
{
323
uint8_t d[9] {};
324
if (dev->transfer(nullptr, 0, d, sizeof(d))) {
325
// ignore CRC bytes for now
326
uint32_t Praw = (uint32_t(d[0]) << 16) | (uint32_t(d[1]) << 8) | d[3];
327
uint32_t Traw = (uint32_t(d[6]) << 8) | d[7];
328
329
convert_data(Praw, Traw);
330
send_cmd16(CMD_READ_PT);
331
last_measure_us = AP_HAL::micros();
332
} else {
333
if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) {
334
// lost a sample
335
send_cmd16(CMD_READ_PT);
336
last_measure_us = AP_HAL::micros();
337
}
338
}
339
}
340
341
void AP_Baro_ICM20789::update()
342
{
343
#if BARO_ICM20789_DEBUG
344
// useful for debugging
345
// @LoggerMessage: ICMB
346
// @Description: ICM20789 diagnostics
347
// @Field: TimeUS: Time since system startup
348
// @Field: Traw: raw temperature from sensor
349
// @Field: Praw: raw pressure from sensor
350
// @Field: P: pressure
351
// @Field: T: temperature
352
AP::logger().WriteStreaming("ICMB", "TimeUS,Traw,Praw,P,T", "QIIff",
353
AP_HAL::micros64(),
354
dd.Traw, dd.Praw, dd.P, dd.T);
355
#endif
356
357
WITH_SEMAPHORE(_sem);
358
359
if (accum.count > 0) {
360
_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);
361
accum.psum = accum.tsum = 0;
362
accum.count = 0;
363
}
364
}
365
366
#endif // AP_BARO_ICM20789_ENABLED
367
368