Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_BMP388.cpp
9592 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
#include "AP_Baro_BMP388.h"
16
17
#if AP_BARO_BMP388_ENABLED
18
19
#include <AP_Math/AP_Math.h>
20
21
extern const AP_HAL::HAL &hal;
22
23
#define BMP388_MODE_SLEEP 0
24
#define BMP388_MODE_FORCED 1
25
#define BMP388_MODE_NORMAL 3
26
#define BMP388_MODE BMP388_MODE_NORMAL
27
28
#define BMP388_ID 0x50
29
#define BMP390_ID 0x60
30
31
#define BMP388_REG_ID 0x00
32
#define BMP388_REV_ID_ADDR 0x01
33
#define BMP388_REG_ERR 0x02
34
#define BMP388_REG_STATUS 0x03
35
#define BMP388_REG_PRESS 0x04 // 24 bit
36
#define BMP388_REG_TEMP 0x07 // 24 bit
37
#define BMP388_REG_TIME 0x0C // 24 bit
38
#define BMP388_REG_EVENT 0x10
39
#define BMP388_REG_INT_STS 0x11
40
#define BMP388_REG_FIFO_LEN 0x12 // 9 bit
41
#define BMP388_REG_FIFO_DATA 0x14
42
#define BMP388_REG_FIFO_WTMK 0x15 // 9 bit
43
#define BMP388_REG_FIFO_CNF1 0x17
44
#define BMP388_REG_FIFO_CNF2 0x18
45
#define BMP388_REG_INT_CTRL 0x19
46
#define BMP388_REG_PWR_CTRL 0x1B
47
#define BMP388_REG_OSR 0x1C
48
#define BMP388_REG_ODR 0x1D
49
#define BMP388_REG_CONFIG 0x1F
50
#define BMP388_REG_CMD 0x7E
51
52
#define BMP388_REG_CAL_P 0x36
53
#define BMP388_REG_CAL_T 0x31
54
55
AP_Baro_BMP388::AP_Baro_BMP388(AP_Baro &baro, AP_HAL::Device &_dev)
56
: AP_Baro_Backend(baro)
57
, dev(&_dev)
58
{
59
}
60
61
AP_Baro_Backend *AP_Baro_BMP388::probe(AP_Baro &baro, AP_HAL::Device &_dev)
62
{
63
AP_Baro_BMP388 *sensor = NEW_NOTHROW AP_Baro_BMP388(baro, _dev);
64
if (!sensor || !sensor->init()) {
65
delete sensor;
66
return nullptr;
67
}
68
return sensor;
69
}
70
71
bool AP_Baro_BMP388::init()
72
{
73
if (!dev) {
74
return false;
75
}
76
WITH_SEMAPHORE(dev->get_semaphore());
77
78
dev->set_speed(AP_HAL::Device::SPEED_HIGH);
79
80
// setup to allow reads on SPI
81
if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
82
dev->set_read_flag(0x80);
83
}
84
85
// normal mode, temp and pressure
86
dev->write_register(BMP388_REG_PWR_CTRL, 0x33, true);
87
88
uint8_t whoami;
89
if (!read_registers(BMP388_REG_ID, &whoami, 1)) {
90
return false;
91
}
92
93
switch (whoami) {
94
case BMP388_ID:
95
dev->set_device_type(DEVTYPE_BARO_BMP388);
96
break;
97
case BMP390_ID:
98
dev->set_device_type(DEVTYPE_BARO_BMP390);
99
break;
100
default:
101
return false;
102
}
103
104
// read the calibration data
105
read_registers(BMP388_REG_CAL_P, (uint8_t *)&calib_p, sizeof(calib_p));
106
read_registers(BMP388_REG_CAL_T, (uint8_t *)&calib_t, sizeof(calib_t));
107
108
scale_calibration_data();
109
110
dev->setup_checked_registers(4);
111
112
// normal mode, temp and pressure
113
dev->write_register(BMP388_REG_PWR_CTRL, 0x33, true);
114
115
instance = _frontend.register_sensor();
116
117
set_bus_id(instance, dev->get_bus_id());
118
119
// request 50Hz update
120
dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP388::timer, void));
121
122
return true;
123
}
124
125
126
127
// accumulate a new sensor reading
128
void AP_Baro_BMP388::timer(void)
129
{
130
uint8_t buf[7];
131
132
if (!read_registers(BMP388_REG_STATUS, buf, sizeof(buf))) {
133
return;
134
}
135
const uint8_t status = buf[0];
136
if ((status & 0x20) != 0) {
137
// we have pressure data
138
update_pressure((buf[3] << 16) | (buf[2] << 8) | buf[1]);
139
}
140
if ((status & 0x40) != 0) {
141
// we have temperature data
142
update_temperature((buf[6] << 16) | (buf[5] << 8) | buf[4]);
143
}
144
145
dev->check_next_register();
146
}
147
148
// transfer data to the frontend
149
void AP_Baro_BMP388::update(void)
150
{
151
WITH_SEMAPHORE(_sem);
152
153
if (pressure_count == 0) {
154
return;
155
}
156
157
_copy_to_frontend(instance,
158
pressure_sum/pressure_count,
159
temperature);
160
161
pressure_sum = 0;
162
pressure_count = 0;
163
}
164
165
/*
166
convert calibration data from NVM values to values ready for
167
compensation calculations
168
*/
169
void AP_Baro_BMP388::scale_calibration_data(void)
170
{
171
// note that this assumes little-endian MCU
172
calib.par_t1 = calib_t.nvm_par_t1 * 256.0;
173
calib.par_t2 = calib_t.nvm_par_t2 / 1073741824.0f;
174
calib.par_t3 = calib_t.nvm_par_t3 / 281474976710656.0f;
175
176
calib.par_p1 = (calib_p.nvm_par_p1 - 16384) / 1048576.0f;
177
calib.par_p2 = (calib_p.nvm_par_p2 - 16384) / 536870912.0f;
178
calib.par_p3 = calib_p.nvm_par_p3 / 4294967296.0f;
179
calib.par_p4 = calib_p.nvm_par_p4 / 137438953472.0;
180
calib.par_p5 = calib_p.nvm_par_p5 * 8.0f;
181
calib.par_p6 = calib_p.nvm_par_p6 / 64.0;
182
calib.par_p7 = calib_p.nvm_par_p7 / 256.0f;
183
calib.par_p8 = calib_p.nvm_par_p8 / 32768.0f;
184
calib.par_p9 = calib_p.nvm_par_p9 / 281474976710656.0f;
185
calib.par_p10 = calib_p.nvm_par_p10 / 281474976710656.0f;
186
calib.par_p11 = calib_p.nvm_par_p11 / 36893488147419103232.0f;
187
}
188
189
/*
190
update temperature from raw sample
191
*/
192
void AP_Baro_BMP388::update_temperature(uint32_t data)
193
{
194
float partial1 = data - calib.par_t1;
195
float partial2 = partial1 * calib.par_t2;
196
197
WITH_SEMAPHORE(_sem);
198
temperature = partial2 + sq(partial1) * calib.par_t3;
199
}
200
201
/*
202
update pressure from raw pressure data
203
*/
204
void AP_Baro_BMP388::update_pressure(uint32_t data)
205
{
206
float partial1 = calib.par_p6 * temperature;
207
float partial2 = calib.par_p7 * powf(temperature, 2);
208
float partial3 = calib.par_p8 * powf(temperature, 3);
209
float partial_out1 = calib.par_p5 + partial1 + partial2 + partial3;
210
211
partial1 = calib.par_p2 * temperature;
212
partial2 = calib.par_p3 * powf(temperature, 2);
213
partial3 = calib.par_p4 * powf(temperature, 3);
214
float partial_out2 = data * (calib.par_p1 + partial1 + partial2 + partial3);
215
216
partial1 = powf(data, 2);
217
partial2 = calib.par_p9 + calib.par_p10 * temperature;
218
partial3 = partial1 * partial2;
219
float partial4 = partial3 + powf(data, 3) * calib.par_p11;
220
float press = partial_out1 + partial_out2 + partial4;
221
222
WITH_SEMAPHORE(_sem);
223
224
pressure_sum += press;
225
pressure_count++;
226
}
227
228
/*
229
read registers, special SPI handling needed
230
*/
231
bool AP_Baro_BMP388::read_registers(uint8_t reg, uint8_t *data, uint8_t len)
232
{
233
// when on I2C we just read normally
234
if (dev->bus_type() != AP_HAL::Device::BUS_TYPE_SPI) {
235
return dev->read_registers(reg, data, len);
236
}
237
// for SPI we need to discard the first returned byte. See
238
// datasheet for explanation
239
uint8_t b[len+2];
240
b[0] = reg | 0x80;
241
memset(&b[1], 0, len+1);
242
if (!dev->transfer_fullduplex(b, len+2)) {
243
return false;
244
}
245
memcpy(data, &b[2], len);
246
return true;
247
}
248
249
#endif // AP_BARO_BMP388_ENABLED
250
251