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_ICP201XX.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
This program is distributed in the hope that it will be useful,
7
but WITHOUT ANY WARRANTY; without even the implied warranty of
8
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
9
GNU General Public License for more details.
10
You should have received a copy of the GNU General Public License
11
along with this program. If not, see <http://www.gnu.org/licenses/>.
12
*/
13
14
#include "AP_Baro_ICP201XX.h"
15
16
#if AP_BARO_ICP201XX_ENABLED
17
18
#include <AP_HAL/AP_HAL.h>
19
#include <AP_HAL/I2CDevice.h>
20
#include <utility>
21
22
#include <AP_Common/AP_Common.h>
23
#include <AP_HAL/AP_HAL.h>
24
#include <AP_Math/AP_Math.h>
25
#include <AP_BoardConfig/AP_BoardConfig.h>
26
27
#include <utility>
28
#include <stdio.h>
29
30
#include <AP_Math/AP_Math.h>
31
#include <AP_Logger/AP_Logger.h>
32
33
#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>
34
35
extern const AP_HAL::HAL &hal;
36
37
#define ICP201XX_ID 0x63
38
39
#define CONVERSION_INTERVAL 25000
40
41
#define REG_EMPTY 0x00
42
#define REG_TRIM1_MSB 0x05
43
#define REG_TRIM2_LSB 0x06
44
#define REG_TRIM2_MSB 0x07
45
#define REG_DEVICE_ID 0x0C
46
#define REG_OTP_MTP_OTP_CFG1 0xAC
47
#define REG_OTP_MTP_MR_LSB 0xAD
48
#define REG_OTP_MTP_MR_MSB 0xAE
49
#define REG_OTP_MTP_MRA_LSB 0xAF
50
#define REG_OTP_MTP_MRA_MSB 0xB0
51
#define REG_OTP_MTP_MRB_LSB 0xB1
52
#define REG_OTP_MTP_MRB_MSB 0xB2
53
#define REG_OTP_MTP_OTP_ADDR 0xB5
54
#define REG_OTP_MTP_OTP_CMD 0xB6
55
#define REG_OTP_MTP_RD_DATA 0xB8
56
#define REG_OTP_MTP_OTP_STATUS 0xB9
57
#define REG_OTP_DEBUG2 0xBC
58
#define REG_MASTER_LOCK 0xBE
59
#define REG_OTP_MTP_OTP_STATUS2 0xBF
60
#define REG_MODE_SELECT 0xC0
61
#define REG_INTERRUPT_STATUS 0xC1
62
#define REG_INTERRUPT_MASK 0xC2
63
#define REG_FIFO_CONFIG 0xC3
64
#define REG_FIFO_FILL 0xC4
65
#define REG_SPI_MODE 0xC5
66
#define REG_PRESS_ABS_LSB 0xC7
67
#define REG_PRESS_ABS_MSB 0xC8
68
#define REG_PRESS_DELTA_LSB 0xC9
69
#define REG_PRESS_DELTA_MSB 0xCA
70
#define REG_DEVICE_STATUS 0xCD
71
#define REG_I3C_INFO 0xCE
72
#define REG_VERSION 0xD3
73
#define REG_FIFO_BASE 0xFA
74
75
/*
76
constructor
77
*/
78
AP_Baro_ICP201XX::AP_Baro_ICP201XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)
79
: AP_Baro_Backend(baro)
80
, dev(std::move(_dev))
81
{
82
}
83
84
AP_Baro_Backend *AP_Baro_ICP201XX::probe(AP_Baro &baro,
85
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
86
{
87
if (!dev) {
88
return nullptr;
89
}
90
AP_Baro_ICP201XX *sensor = NEW_NOTHROW AP_Baro_ICP201XX(baro, std::move(dev));
91
if (!sensor || !sensor->init()) {
92
delete sensor;
93
return nullptr;
94
}
95
return sensor;
96
}
97
98
bool AP_Baro_ICP201XX::init()
99
{
100
if (!dev) {
101
return false;
102
}
103
104
dev->get_semaphore()->take_blocking();
105
106
uint8_t id = 0xFF;
107
uint8_t ver = 0xFF;
108
read_reg(REG_DEVICE_ID, &id);
109
read_reg(REG_DEVICE_ID, &id);
110
read_reg(REG_VERSION, &ver);
111
112
if (id != ICP201XX_ID) {
113
goto failed;
114
}
115
116
if (ver != 0x00 && ver != 0xB2) {
117
goto failed;
118
}
119
120
hal.scheduler->delay(10);
121
122
soft_reset();
123
124
if (!boot_sequence()) {
125
goto failed;
126
}
127
128
if (!configure()) {
129
goto failed;
130
}
131
132
wait_read();
133
134
dev->set_retries(0);
135
136
instance = _frontend.register_sensor();
137
138
dev->set_device_type(DEVTYPE_BARO_ICP201XX);
139
set_bus_id(instance, dev->get_bus_id());
140
141
dev->get_semaphore()->give();
142
143
dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP201XX::timer, void));
144
return true;
145
146
failed:
147
dev->get_semaphore()->give();
148
return false;
149
}
150
151
152
void AP_Baro_ICP201XX::dummy_reg()
153
{
154
do {
155
uint8_t reg = REG_EMPTY;
156
uint8_t val = 0;
157
dev->transfer(&reg, 1, &val, 1);
158
} while (0);
159
}
160
161
bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *buf, uint8_t len)
162
{
163
bool ret;
164
ret = dev->transfer(&reg, 1, buf, len);
165
dummy_reg();
166
return ret;
167
}
168
169
bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *val)
170
{
171
return read_reg(reg, val, 1);
172
}
173
174
bool AP_Baro_ICP201XX::write_reg(uint8_t reg, uint8_t val)
175
{
176
bool ret;
177
uint8_t data[2] = { reg, val };
178
ret = dev->transfer(data, sizeof(data), nullptr, 0);
179
dummy_reg();
180
return ret;
181
}
182
183
void AP_Baro_ICP201XX::soft_reset()
184
{
185
/* Stop the measurement */
186
mode_select(0x00);
187
188
hal.scheduler->delay(2);
189
190
/* Flush FIFO */
191
flush_fifo();
192
193
/* Mask all interrupts */
194
write_reg(REG_FIFO_CONFIG, 0x00);
195
write_reg(REG_INTERRUPT_MASK, 0xFF);
196
}
197
198
bool AP_Baro_ICP201XX::mode_select(uint8_t mode)
199
{
200
uint8_t mode_sync_status = 0;
201
202
do {
203
read_reg(REG_DEVICE_STATUS, &mode_sync_status, 1);
204
205
if (mode_sync_status & 0x01) {
206
break;
207
}
208
209
hal.scheduler->delay(1);
210
} while (1);
211
212
return write_reg(REG_MODE_SELECT, mode);
213
}
214
215
bool AP_Baro_ICP201XX::read_otp_data(uint8_t addr, uint8_t cmd, uint8_t *val)
216
{
217
uint8_t otp_status = 0xFF;
218
219
/* Write the address content and read command */
220
if (!write_reg(REG_OTP_MTP_OTP_ADDR, addr)) {
221
return false;
222
}
223
224
if (!write_reg(REG_OTP_MTP_OTP_CMD, cmd)) {
225
return false;
226
}
227
228
/* Wait for the OTP read to finish Monitor otp_status */
229
do {
230
read_reg(REG_OTP_MTP_OTP_STATUS, &otp_status);
231
232
if (otp_status == 0) {
233
break;
234
}
235
236
hal.scheduler->delay_microseconds(1);
237
} while (1);
238
239
/* Read the data from register */
240
if (!read_reg(REG_OTP_MTP_RD_DATA, val)) {
241
return false;
242
}
243
244
return true;
245
}
246
247
bool AP_Baro_ICP201XX::get_sensor_data(float *pressure, float *temperature)
248
{
249
uint8_t fifo_data[96] {0};
250
uint8_t fifo_packets = 0;
251
int32_t data_temp = 0;
252
int32_t data_press = 0;
253
*pressure = 0;
254
*temperature = 0;
255
256
if (read_reg(REG_FIFO_FILL, &fifo_packets)) {
257
fifo_packets = (uint8_t)(fifo_packets & 0x1F);
258
if (fifo_packets > 16) {
259
flush_fifo();
260
return false;
261
}
262
if (fifo_packets > 0 && fifo_packets <= 16 && read_reg(REG_FIFO_BASE, fifo_data, fifo_packets * 2 * 3)) {
263
uint8_t offset = 0;
264
265
for (uint8_t i = 0; i < fifo_packets; i++) {
266
data_press = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]);
267
if (data_press & 0x080000) {
268
data_press |= 0xFFF00000;
269
}
270
/* P = (POUT/2^17)*40kPa + 70kPa */
271
*pressure += ((float)(data_press) * 40 / 131072) + 70;
272
offset += 3;
273
274
data_temp = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]);
275
if (data_temp & 0x080000) {
276
data_temp |= 0xFFF00000;
277
}
278
/* T = (TOUT/2^18)*65C + 25C */
279
*temperature += ((float)(data_temp) * 65 / 262144) + 25;
280
offset += 3;
281
}
282
283
*pressure = *pressure * 1000 / fifo_packets;
284
*temperature = *temperature / fifo_packets;
285
return true;
286
}
287
}
288
289
return false;
290
}
291
292
bool AP_Baro_ICP201XX::boot_sequence()
293
{
294
uint8_t reg_value = 0;
295
uint8_t offset = 0, gain = 0, Hfosc = 0;
296
uint8_t version = 0;
297
uint8_t bootup_status = 0;
298
int ret = 1;
299
300
/* read version register */
301
if (!read_reg(REG_VERSION, &version)) {
302
return false;
303
}
304
305
if (version == 0xB2) {
306
/* B2 version Asic is detected. Boot up sequence is not required for B2 Asic, so returning */
307
return true;
308
}
309
310
/* Read boot up status and avoid re running boot up sequence if it is already done */
311
if (!read_reg(REG_OTP_MTP_OTP_STATUS2, &bootup_status)) {
312
return false;
313
}
314
315
if (bootup_status & 0x01) {
316
/* Boot up sequence is already done, not required to repeat boot up sequence */
317
return true;
318
}
319
320
/* Bring the ASIC in power mode to activate the OTP power domain and get access to the main registers */
321
mode_select(0x04);
322
hal.scheduler->delay(4);
323
324
/* Unlock the main registers */
325
write_reg(REG_MASTER_LOCK, 0x1F);
326
327
/* Enable the OTP and the write switch */
328
read_reg(REG_OTP_MTP_OTP_CFG1, &reg_value);
329
reg_value |= 0x03;
330
write_reg(REG_OTP_MTP_OTP_CFG1, reg_value);
331
hal.scheduler->delay_microseconds(10);
332
333
/* Toggle the OTP reset pin */
334
read_reg(REG_OTP_DEBUG2, &reg_value);
335
reg_value |= 1 << 7;
336
write_reg(REG_OTP_DEBUG2, reg_value);
337
hal.scheduler->delay_microseconds(10);
338
339
read_reg(REG_OTP_DEBUG2, &reg_value);
340
reg_value &= ~(1 << 7);
341
write_reg(REG_OTP_DEBUG2, reg_value);
342
hal.scheduler->delay_microseconds(10);
343
344
/* Program redundant read */
345
write_reg(REG_OTP_MTP_MRA_LSB, 0x04);
346
write_reg(REG_OTP_MTP_MRA_MSB, 0x04);
347
write_reg(REG_OTP_MTP_MRB_LSB, 0x21);
348
write_reg(REG_OTP_MTP_MRB_MSB, 0x20);
349
write_reg(REG_OTP_MTP_MR_LSB, 0x10);
350
write_reg(REG_OTP_MTP_MR_MSB, 0x80);
351
352
/* Read the data from register */
353
ret &= read_otp_data(0xF8, 0x10, &offset);
354
ret &= read_otp_data(0xF9, 0x10, &gain);
355
ret &= read_otp_data(0xFA, 0x10, &Hfosc);
356
hal.scheduler->delay_microseconds(10);
357
358
/* Write OTP values to main registers */
359
ret &= read_reg(REG_TRIM1_MSB, &reg_value);
360
if (ret) {
361
reg_value = (reg_value & (~0x3F)) | (offset & 0x3F);
362
ret &= write_reg(REG_TRIM1_MSB, reg_value);
363
}
364
365
ret &= read_reg(REG_TRIM2_MSB, &reg_value);
366
if (ret) {
367
reg_value = (reg_value & (~0x70)) | ((gain & 0x07) << 4);
368
ret &= write_reg(REG_TRIM2_MSB, reg_value);
369
}
370
371
ret &= read_reg(REG_TRIM2_LSB, &reg_value);
372
if (ret) {
373
reg_value = (reg_value & (~0x7F)) | (Hfosc & 0x7F);
374
ret &= write_reg(REG_TRIM2_LSB, reg_value);
375
}
376
377
hal.scheduler->delay_microseconds(10);
378
379
/* Update boot up status to 1 */
380
if (ret) {
381
ret &= read_reg(REG_OTP_MTP_OTP_STATUS2, &reg_value);
382
if (!ret) {
383
reg_value |= 0x01;
384
ret &= write_reg(REG_OTP_MTP_OTP_STATUS2, reg_value);
385
}
386
}
387
388
/* Disable OTP and write switch */
389
read_reg(REG_OTP_MTP_OTP_CFG1, &reg_value);
390
reg_value &= ~0x03;
391
write_reg(REG_OTP_MTP_OTP_CFG1, reg_value);
392
393
/* Lock the main register */
394
write_reg(REG_MASTER_LOCK, 0x00);
395
396
/* Move to standby */
397
mode_select(0x00);
398
399
return ret;
400
}
401
402
bool AP_Baro_ICP201XX::configure()
403
{
404
uint8_t reg_value = 0;
405
406
/* Initiate Triggered Operation: Stay in Standby mode */
407
reg_value |= (reg_value & (~0x10)) | ((uint8_t)_forced_meas_trigger << 4);
408
409
/* Power Mode Selection: Normal Mode */
410
reg_value |= (reg_value & (~0x04)) | ((uint8_t)_power_mode << 2);
411
412
/* FIFO Readout Mode Selection: Pressure first. */
413
reg_value |= (reg_value & (~0x03)) | ((uint8_t)(_fifo_readout_mode));
414
415
/* Measurement Configuration: Mode2*/
416
reg_value |= (reg_value & (~0xE0)) | (((uint8_t)_op_mode) << 5);
417
418
/* Measurement Mode Selection: Continuous Measurements (duty cycled) */
419
reg_value |= (reg_value & (~0x08)) | ((uint8_t)_meas_mode << 3);
420
421
return mode_select(reg_value);
422
}
423
424
void AP_Baro_ICP201XX::wait_read()
425
{
426
/*
427
* If FIR filter is enabled, it will cause a settling effect on the first 14 pressure values.
428
* Therefore the first 14 pressure output values are discarded.
429
**/
430
uint8_t fifo_packets = 0;
431
uint8_t fifo_packets_to_skip = 14;
432
433
do {
434
hal.scheduler->delay(10);
435
read_reg(REG_FIFO_FILL, &fifo_packets);
436
fifo_packets = (uint8_t)(fifo_packets & 0x1F);
437
} while (fifo_packets >= fifo_packets_to_skip);
438
439
flush_fifo();
440
fifo_packets = 0;
441
442
do {
443
hal.scheduler->delay(10);
444
read_reg(REG_FIFO_FILL, &fifo_packets);
445
fifo_packets = (uint8_t)(fifo_packets & 0x1F);
446
} while (fifo_packets == 0);
447
}
448
449
bool AP_Baro_ICP201XX::flush_fifo()
450
{
451
uint8_t reg_value;
452
453
if (!read_reg(REG_FIFO_FILL, &reg_value)) {
454
return false;
455
}
456
457
reg_value |= 0x80;
458
459
if (!write_reg(REG_FIFO_FILL, reg_value)) {
460
return false;
461
}
462
463
return true;
464
}
465
466
void AP_Baro_ICP201XX::timer()
467
{
468
float p = 0;
469
float t = 0;
470
471
if (get_sensor_data(&p, &t)) {
472
WITH_SEMAPHORE(_sem);
473
474
accum.psum += p;
475
accum.tsum += t;
476
accum.count++;
477
last_measure_us = AP_HAL::micros();
478
} else {
479
if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) {
480
flush_fifo();
481
last_measure_us = AP_HAL::micros();
482
}
483
}
484
}
485
486
void AP_Baro_ICP201XX::update()
487
{
488
WITH_SEMAPHORE(_sem);
489
490
if (accum.count > 0) {
491
_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);
492
accum.psum = accum.tsum = 0;
493
accum.count = 0;
494
}
495
}
496
497
#endif // AP_BARO_ICP201XX_ENABLED
498
499