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_ICP101XX.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_ICP101XX.h"
17
18
#if AP_BARO_ICP101XX_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_HAL/AP_HAL.h>
26
#include <AP_Math/AP_Math.h>
27
#include <AP_BoardConfig/AP_BoardConfig.h>
28
29
#include <utility>
30
#include <stdio.h>
31
32
#include <AP_Math/AP_Math.h>
33
#include <AP_Logger/AP_Logger.h>
34
35
#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>
36
37
extern const AP_HAL::HAL &hal;
38
39
#define ICP101XX_ID 0x08
40
#define CMD_READ_ID 0xefc8
41
#define CMD_SET_ADDR 0xc595
42
#define CMD_READ_OTP 0xc7f7
43
#define CMD_MEAS_LP 0x609c
44
#define CMD_MEAS_N 0x6825
45
#define CMD_MEAS_LN 0x70df
46
#define CMD_MEAS_ULN 0x7866
47
#define CMD_SOFT_RESET 0x805d
48
49
/*
50
constructor
51
*/
52
AP_Baro_ICP101XX::AP_Baro_ICP101XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)
53
: AP_Baro_Backend(baro)
54
, dev(std::move(_dev))
55
{
56
}
57
58
AP_Baro_Backend *AP_Baro_ICP101XX::probe(AP_Baro &baro,
59
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
60
{
61
if (!dev) {
62
return nullptr;
63
}
64
AP_Baro_ICP101XX *sensor = NEW_NOTHROW AP_Baro_ICP101XX(baro, std::move(dev));
65
if (!sensor || !sensor->init()) {
66
delete sensor;
67
return nullptr;
68
}
69
return sensor;
70
}
71
72
bool AP_Baro_ICP101XX::init()
73
{
74
if (!dev) {
75
return false;
76
}
77
78
dev->get_semaphore()->take_blocking();
79
80
uint16_t id = 0;
81
read_response(CMD_READ_ID, (uint8_t *)&id, 2);
82
uint8_t whoami = (id >> 8) & 0x3f; // Product ID Bits 5:0
83
if (whoami != ICP101XX_ID) {
84
goto failed;
85
}
86
87
if (!send_command(CMD_SOFT_RESET)) {
88
goto failed;
89
}
90
91
// wait for sensor to settle
92
hal.scheduler->delay(10);
93
94
if (!read_calibration_data()) {
95
goto failed;
96
}
97
98
// start a reading
99
if (!start_measure(CMD_MEAS_ULN)) {
100
goto failed;
101
}
102
103
dev->set_retries(0);
104
105
instance = _frontend.register_sensor();
106
107
dev->set_device_type(DEVTYPE_BARO_ICP101XX);
108
set_bus_id(instance, dev->get_bus_id());
109
110
dev->get_semaphore()->give();
111
112
dev->register_periodic_callback(measure_interval, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP101XX::timer, void));
113
114
return true;
115
116
failed:
117
dev->get_semaphore()->give();
118
return false;
119
}
120
121
bool AP_Baro_ICP101XX::read_measure_results(uint8_t *buf, uint8_t len)
122
{
123
return dev->transfer(nullptr, 0, buf, len);
124
}
125
126
bool AP_Baro_ICP101XX::read_response(uint16_t cmd, uint8_t *buf, uint8_t len)
127
{
128
uint8_t buff[2];
129
buff[0] = (cmd >> 8) & 0xff;
130
buff[1] = cmd & 0xff;
131
return dev->transfer(&buff[0], 2, buf, len);
132
}
133
134
bool AP_Baro_ICP101XX::send_command(uint16_t cmd)
135
{
136
uint8_t buf[2];
137
buf[0] = (cmd >> 8) & 0xff;
138
buf[1] = cmd & 0xff;
139
return dev->transfer(buf, sizeof(buf), nullptr, 0);
140
}
141
142
bool AP_Baro_ICP101XX::send_command(uint16_t cmd, uint8_t *data, uint8_t len)
143
{
144
uint8_t buf[5];
145
buf[0] = (cmd >> 8) & 0xff;
146
buf[1] = cmd & 0xff;
147
memcpy(&buf[2], data, len);
148
return dev->transfer(&buf[0], len + 2, nullptr, 0);
149
}
150
151
int8_t AP_Baro_ICP101XX::cal_crc(uint8_t seed, uint8_t data)
152
{
153
int8_t poly = 0x31;
154
int8_t var2;
155
uint8_t i;
156
157
for (i = 0; i < 8; i++) {
158
if ((seed & 0x80) ^ (data & 0x80)) {
159
var2 = 1;
160
161
} else {
162
var2 = 0;
163
}
164
165
seed = (seed & 0x7F) << 1;
166
data = (data & 0x7F) << 1;
167
seed = seed ^ (uint8_t)(poly * var2);
168
}
169
170
return (int8_t)seed;
171
}
172
173
bool AP_Baro_ICP101XX::read_calibration_data(void)
174
{
175
// setup for OTP read
176
uint8_t cmd[3] = { 0x00, 0x66, 0x9c };
177
if (!send_command(CMD_SET_ADDR, cmd, 3)) {
178
return false;
179
}
180
for (uint8_t i = 0; i < 4; i++) {
181
uint8_t d[3];
182
uint8_t crc = 0xff;
183
read_response(CMD_READ_OTP, d, 3);
184
for (int j = 0; j < 2; j++) {
185
crc = (uint8_t)cal_crc(crc, d[j]);
186
}
187
if (crc != d[2]) {
188
return false;
189
}
190
sensor_constants[i] = (d[0] << 8) | d[1];
191
}
192
return true;
193
}
194
195
bool AP_Baro_ICP101XX::start_measure(uint16_t mode)
196
{
197
/*
198
From ds-000186-icp-101xx-v1.0.pdf, page 6, table 1
199
200
Sensor Measurement Max Time
201
Mode Time (Forced)
202
Low Power (LP) 1.6 ms 1.8 ms
203
Normal (N) 5.6 ms 6.3 ms
204
Low Noise (LN) 20.8 ms 23.8 ms
205
Ultra Low Noise(ULN) 83.2 ms 94.5 ms
206
*/
207
208
switch (mode) {
209
case CMD_MEAS_LP:
210
measure_interval = 2000;
211
break;
212
213
case CMD_MEAS_LN:
214
measure_interval = 24000;
215
break;
216
217
case CMD_MEAS_ULN:
218
measure_interval = 95000;
219
break;
220
221
case CMD_MEAS_N:
222
default:
223
measure_interval = 7000;
224
break;
225
}
226
227
if (!send_command(mode)) {
228
return false;
229
}
230
231
return true;
232
}
233
234
void AP_Baro_ICP101XX::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],
235
float &A, float &B, float &C)
236
{
237
C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) +
238
p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) +
239
p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) /
240
(p_LUT[2] * (p_Pa[0] - p_Pa[1]) +
241
p_LUT[0] * (p_Pa[1] - p_Pa[2]) +
242
p_LUT[1] * (p_Pa[2] - p_Pa[0]));
243
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]);
244
B = (p_Pa[0] - A) * (p_LUT[0] + C);
245
}
246
247
/*
248
Convert an output from a calibrated sensor to a pressure in Pa.
249
Arguments:
250
p_LSB -- Raw pressure data from sensor
251
T_LSB -- Raw temperature data from sensor
252
*/
253
float AP_Baro_ICP101XX::get_pressure(uint32_t p_LSB, uint32_t T_LSB)
254
{
255
float t = T_LSB - 32768.0;
256
float s[3];
257
s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor;
258
s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor;
259
s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor;
260
float A, B, C;
261
calculate_conversion_constants(p_Pa_calib, s, A, B, C);
262
return A + B / (C + p_LSB);
263
}
264
265
void AP_Baro_ICP101XX::convert_data(uint32_t Praw, uint32_t Traw)
266
{
267
// temperature is easy
268
float T = -45 + (175.0f / (1U<<16)) * Traw;
269
270
// pressure involves a few more calculations
271
float P = get_pressure(Praw, Traw);
272
273
if (!pressure_ok(P)) {
274
return;
275
}
276
277
WITH_SEMAPHORE(_sem);
278
279
accum.psum += P;
280
accum.tsum += T;
281
accum.count++;
282
}
283
284
void AP_Baro_ICP101XX::timer(void)
285
{
286
uint8_t d[9] {};
287
if (read_measure_results(d, 9)) {
288
// ignore CRC bytes for now
289
uint32_t Traw = (uint32_t(d[0]) << 8) | d[1];
290
uint32_t Praw = (uint32_t(d[3]) << 16) | (uint32_t(d[4]) << 8) | d[6];
291
292
convert_data(Praw, Traw);
293
start_measure(CMD_MEAS_ULN);
294
last_measure_us = AP_HAL::micros();
295
} else {
296
if (AP_HAL::micros() - last_measure_us > measure_interval*3) {
297
// lost a sample
298
start_measure(CMD_MEAS_ULN);
299
last_measure_us = AP_HAL::micros();
300
}
301
}
302
}
303
304
void AP_Baro_ICP101XX::update()
305
{
306
WITH_SEMAPHORE(_sem);
307
308
if (accum.count > 0) {
309
_copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count);
310
accum.psum = accum.tsum = 0;
311
accum.count = 0;
312
}
313
}
314
315
#endif // AP_BARO_ICP101XX_ENABLED
316
317