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_FBM320.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
FCM320 barometer driver
17
*/
18
19
#include "AP_Baro_FBM320.h"
20
21
#if AP_BARO_FBM320_ENABLED
22
23
#include <utility>
24
#include <stdio.h>
25
#include <AP_Math/definitions.h>
26
27
extern const AP_HAL::HAL &hal;
28
29
#define FBM320_REG_ID 0x6B
30
#define FBM320_REG_DATA 0xF6
31
#define FBM320_REG_CMD 0xF4
32
33
#define FBM320_CMD_READ_T 0x2E
34
#define FBM320_CMD_READ_P 0xF4
35
36
#define FBM320_WHOAMI 0x42
37
38
AP_Baro_FBM320::AP_Baro_FBM320(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> _dev)
39
: AP_Baro_Backend(baro)
40
, dev(std::move(_dev))
41
{
42
}
43
44
AP_Baro_Backend *AP_Baro_FBM320::probe(AP_Baro &baro,
45
AP_HAL::OwnPtr<AP_HAL::Device> _dev)
46
{
47
if (!_dev) {
48
return nullptr;
49
}
50
51
AP_Baro_FBM320 *sensor = NEW_NOTHROW AP_Baro_FBM320(baro, std::move(_dev));
52
if (!sensor || !sensor->init()) {
53
delete sensor;
54
return nullptr;
55
}
56
return sensor;
57
}
58
59
/*
60
read calibration data
61
*/
62
bool AP_Baro_FBM320::read_calibration(void)
63
{
64
uint8_t tmp[2];
65
uint16_t R[10];
66
67
for (uint8_t i=0; i<9; i++) {
68
if (!dev->read_registers(0xAA+(i*2),&tmp[0],1)) {
69
return false;
70
}
71
if (!dev->read_registers(0xAB+(i*2),&tmp[1],1)) {
72
return false;
73
}
74
R[i] = ((uint8_t)tmp[0] << 8 | tmp[1]);
75
}
76
77
if (!dev->read_registers(0xA4,&tmp[0],1)) {
78
return false;
79
}
80
if (!dev->read_registers(0xF1,&tmp[0],1)) {
81
return false;
82
}
83
R[9] = ((uint8_t)tmp[0] << 8) | tmp[1];
84
85
86
/* Use R0~R9 calculate C0~C12 of FBM320-02 */
87
calibration.C0 = R[0] >> 4;
88
calibration.C1 = ((R[1] & 0xFF00) >> 5) | (R[2] & 7);
89
calibration.C2 = ((R[1] & 0xFF) << 1) | (R[4] & 1);
90
calibration.C3 = R[2] >> 3;
91
calibration.C4 = ((uint32_t)R[3] << 2) | (R[0] & 3);
92
calibration.C5 = R[4] >> 1;
93
calibration.C6 = R[5] >> 3;
94
calibration.C7 = ((uint32_t)R[6] << 3) | (R[5] & 7);
95
calibration.C8 = R[7] >> 3;
96
calibration.C9 = R[8] >> 2;
97
calibration.C10 = ((R[9] & 0xFF00) >> 6) | (R[8] & 3);
98
calibration.C11 = R[9] & 0xFF;
99
calibration.C12 = ((R[0] & 0x0C) << 1) | (R[7] & 7);
100
101
return true;
102
}
103
104
bool AP_Baro_FBM320::init()
105
{
106
if (!dev) {
107
return false;
108
}
109
dev->get_semaphore()->take_blocking();
110
111
dev->set_speed(AP_HAL::Device::SPEED_HIGH);
112
113
uint8_t whoami;
114
if (!dev->read_registers(FBM320_REG_ID, &whoami, 1) ||
115
whoami != FBM320_WHOAMI) {
116
// not a FBM320
117
dev->get_semaphore()->give();
118
return false;
119
}
120
printf("FBM320 ID 0x%x\n", whoami);
121
122
if (!read_calibration()) {
123
dev->get_semaphore()->give();
124
return false;
125
}
126
127
dev->write_register(FBM320_REG_CMD, FBM320_CMD_READ_T);
128
129
instance = _frontend.register_sensor();
130
131
dev->set_device_type(DEVTYPE_BARO_FBM320);
132
set_bus_id(instance, dev->get_bus_id());
133
134
dev->get_semaphore()->give();
135
136
// request 50Hz update
137
dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_FBM320::timer, void));
138
139
return true;
140
}
141
142
/*
143
calculate corrected pressure and temperature
144
*/
145
void AP_Baro_FBM320::calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int32_t &temperature)
146
{
147
const struct fbm320_calibration &cal = calibration;
148
int32_t DT, DT2, X01, X02, X03, X11, X12, X13, X21, X22, X23, X24, X25, X26, X31, X32, CF, PP1, PP2, PP3, PP4;
149
150
DT = ((UT - 8388608) >> 4) + (cal.C0 << 4);
151
X01 = (cal.C1 + 4459) * DT >> 1;
152
X02 = ((((cal.C2 - 256) * DT) >> 14) * DT) >> 4;
153
X03 = (((((cal.C3 * DT) >> 18) * DT) >> 18) * DT);
154
155
temperature = ((2500 << 15) - X01 - X02 - X03) >> 15;
156
157
DT2 = (X01 + X02 + X03) >> 12;
158
X11 = ((cal.C5 - 4443) * DT2);
159
X12 = (((cal.C6 * DT2) >> 16) * DT2) >> 2;
160
X13 = ((X11 + X12) >> 10) + ((cal.C4 + 120586) << 4);
161
162
X21 = ((cal.C8 + 7180) * DT2) >> 10;
163
X22 = (((cal.C9 * DT2) >> 17) * DT2) >> 12;
164
X23 = (X22 >= X21) ? (X22 - X21) : (X21 - X22);
165
166
X24 = (X23 >> 11) * (cal.C7 + 166426);
167
X25 = ((X23 & 0x7FF) * (cal.C7 + 166426)) >> 11;
168
X26 = (X21 >= X22) ? (((0 - X24 - X25) >> 11) + cal.C7 + 166426) : (((X24 + X25) >> 11) + cal.C7 + 166426);
169
170
PP1 = ((UP - 8388608) - X13) >> 3;
171
PP2 = (X26 >> 11) * PP1;
172
PP3 = ((X26 & 0x7FF) * PP1) >> 11;
173
PP4 = (PP2 + PP3) >> 10;
174
175
CF = (2097152 + cal.C12 * DT2) >> 3;
176
X31 = (((CF * cal.C10) >> 17) * PP4) >> 2;
177
X32 = (((((CF * cal.C11) >> 15) * PP4) >> 18) * PP4);
178
179
pressure = ((X31 + X32) >> 15) + PP4 + 99880;
180
}
181
182
// accumulate a new sensor reading
183
void AP_Baro_FBM320::timer(void)
184
{
185
uint8_t buf[3];
186
187
if (!dev->read_registers(0xF6, buf, sizeof(buf))) {
188
return;
189
}
190
int32_t value = ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | (uint32_t)buf[2];
191
192
if (step == 0) {
193
value_T = value;
194
} else {
195
int32_t pressure, temperature;
196
calculate_PT(value_T, value, pressure, temperature);
197
if (pressure_ok(pressure)) {
198
WITH_SEMAPHORE(_sem);
199
pressure_sum += pressure;
200
// sum and convert to degrees
201
temperature_sum += temperature*0.01;
202
count++;
203
}
204
}
205
206
if (step++ >= 5) {
207
dev->write_register(FBM320_REG_CMD, FBM320_CMD_READ_T);
208
step = 0;
209
} else {
210
dev->write_register(FBM320_REG_CMD, FBM320_CMD_READ_P);
211
}
212
}
213
214
// transfer data to the frontend
215
void AP_Baro_FBM320::update(void)
216
{
217
if (count == 0) {
218
return;
219
}
220
WITH_SEMAPHORE(_sem);
221
222
_copy_to_frontend(instance, pressure_sum/count, temperature_sum/count);
223
pressure_sum = 0;
224
temperature_sum = 0;
225
count=0;
226
}
227
228
#endif // AP_BARO_FBM320_ENABLED
229
230