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