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