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_Airspeed/AP_Airspeed_MS5525.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
/*
17
backend driver for airspeed from a I2C MS5525D0 sensor
18
*/
19
#include "AP_Airspeed_MS5525.h"
20
21
#if AP_AIRSPEED_MS5525_ENABLED
22
23
#include <stdio.h>
24
#include <utility>
25
26
#include <AP_Common/AP_Common.h>
27
#include <AP_HAL/AP_HAL.h>
28
#include <AP_HAL/I2CDevice.h>
29
#include <AP_HAL/utility/sparse-endian.h>
30
#include <AP_Math/AP_Math.h>
31
#include <AP_Math/crc.h>
32
#include <GCS_MAVLink/GCS.h>
33
34
extern const AP_HAL::HAL &hal;
35
36
#define MS5525D0_I2C_ADDR_1 0x76
37
#define MS5525D0_I2C_ADDR_2 0x77
38
39
#define REG_RESET 0x1E
40
#define REG_CONVERT_D1_OSR_256 0x40
41
#define REG_CONVERT_D1_OSR_512 0x42
42
#define REG_CONVERT_D1_OSR_1024 0x44
43
#define REG_CONVERT_D1_OSR_2048 0x46
44
#define REG_CONVERT_D1_OSR_4096 0x48
45
#define REG_CONVERT_D2_OSR_256 0x50
46
#define REG_CONVERT_D2_OSR_512 0x52
47
#define REG_CONVERT_D2_OSR_1024 0x54
48
#define REG_CONVERT_D2_OSR_2048 0x56
49
#define REG_CONVERT_D2_OSR_4096 0x58
50
#define REG_ADC_READ 0x00
51
#define REG_PROM_BASE 0xA0
52
53
// go for 1024 oversampling. This should be fast enough to reduce
54
// noise but low enough to keep self-heating small
55
#define REG_CONVERT_PRESSURE REG_CONVERT_D1_OSR_1024
56
#define REG_CONVERT_TEMPERATURE REG_CONVERT_D2_OSR_1024
57
58
AP_Airspeed_MS5525::AP_Airspeed_MS5525(AP_Airspeed &_frontend, uint8_t _instance, MS5525_ADDR address) :
59
AP_Airspeed_Backend(_frontend, _instance)
60
{
61
_address = address;
62
}
63
64
// probe and initialise the sensor
65
bool AP_Airspeed_MS5525::init()
66
{
67
const uint8_t addresses[] = { MS5525D0_I2C_ADDR_1, MS5525D0_I2C_ADDR_2 };
68
bool found = false;
69
for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {
70
if (_address != MS5525_ADDR_AUTO && i != (uint8_t)_address) {
71
continue;
72
}
73
dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);
74
if (!dev) {
75
continue;
76
}
77
WITH_SEMAPHORE(dev->get_semaphore());
78
79
// lots of retries during probe
80
dev->set_retries(5);
81
82
found = read_prom();
83
84
if (found) {
85
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS5525[%u]: Found on bus %u addr 0x%02x", get_instance(), get_bus(), addresses[i]);
86
break;
87
}
88
}
89
if (!found) {
90
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MS5525[%u]: no sensor found", get_instance());
91
return false;
92
}
93
94
// Send a command to read temperature first
95
WITH_SEMAPHORE(dev->get_semaphore());
96
uint8_t reg = REG_CONVERT_TEMPERATURE;
97
dev->transfer(&reg, 1, nullptr, 0);
98
state = 0;
99
command_send_us = AP_HAL::micros();
100
101
dev->set_device_type(uint8_t(DevType::MS5525));
102
set_bus_id(dev->get_bus_id());
103
104
// drop to 2 retries for runtime
105
dev->set_retries(2);
106
107
// read at 80Hz
108
dev->register_periodic_callback(1000000UL/80U,
109
FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS5525::timer, void));
110
return true;
111
}
112
113
114
/**
115
* CRC used by MS pressure devices
116
*/
117
uint16_t AP_Airspeed_MS5525::crc4_prom(void)
118
{
119
return crc_crc4(prom);
120
}
121
122
bool AP_Airspeed_MS5525::read_prom(void)
123
{
124
// reset the chip to ensure it has correct prom values loaded
125
uint8_t reg = REG_RESET;
126
if (!dev->transfer(&reg, 1, nullptr, 0)) {
127
return false;
128
}
129
hal.scheduler->delay(5);
130
131
bool all_zero = true;
132
for (uint8_t i = 0; i < 8; i++) {
133
be16_t val;
134
if (!dev->read_registers(REG_PROM_BASE+i*2, (uint8_t *) &val,
135
sizeof(uint16_t))) {
136
return false;
137
}
138
prom[i] = be16toh(val);
139
if (prom[i] != 0) {
140
all_zero = false;
141
}
142
}
143
144
if (all_zero) {
145
return false;
146
}
147
148
/* save the read crc */
149
const uint16_t crc_read = prom[7] & 0xf;
150
151
/* remove CRC byte */
152
prom[7] &= 0xff00;
153
154
uint16_t crc_calc = crc4_prom();
155
if (crc_read != crc_calc) {
156
printf("MS5525: CRC mismatch 0x%04x 0x%04x\n", crc_read, crc_calc);
157
}
158
return crc_read == crc_calc;
159
}
160
161
162
/*
163
read from the ADC
164
*/
165
int32_t AP_Airspeed_MS5525::read_adc()
166
{
167
uint8_t val[3];
168
if (!dev->read_registers(REG_ADC_READ, val, 3)) {
169
return 0;
170
}
171
return (val[0] << 16) | (val[1] << 8) | val[2];
172
}
173
174
/*
175
calculate pressure and temperature
176
*/
177
void AP_Airspeed_MS5525::calculate(void)
178
{
179
// table for the 001DS part, 1PSI range
180
const uint8_t Q1 = 15;
181
const uint8_t Q2 = 17;
182
const uint8_t Q3 = 7;
183
const uint8_t Q4 = 5;
184
const uint8_t Q5 = 7;
185
const uint8_t Q6 = 21;
186
187
float dT = float(D2) - int64_t(prom[5]) * (1L<<Q5);
188
float TEMP = 2000 + (dT*int64_t(prom[6]))/(1L<<Q6);
189
float OFF = int64_t(prom[2])*(1L<<Q2) + (int64_t(prom[4])*dT)/(1L<<Q4);
190
float SENS = int64_t(prom[1])*(1L<<Q1) + (int64_t(prom[3])*dT)/(1L<<Q3);
191
float P = (float(D1)*SENS/(1L<<21)-OFF)/(1L<<15);
192
const float PSI_to_Pa = 6894.757f;
193
float P_Pa = PSI_to_Pa * 1.0e-4 * P;
194
float Temp_C = TEMP * 0.01;
195
196
#if 0
197
static uint16_t counter;
198
if (counter++ == 100) {
199
printf("P=%.6f T=%.2f D1=%d D2=%d\n", P_Pa, Temp_C, D1, D2);
200
counter=0;
201
}
202
#endif
203
204
WITH_SEMAPHORE(sem);
205
206
pressure_sum += P_Pa;
207
temperature_sum += Temp_C;
208
press_count++;
209
temp_count++;
210
last_sample_time_ms = AP_HAL::millis();
211
}
212
213
// 80Hz timer
214
void AP_Airspeed_MS5525::timer()
215
{
216
if (AP_HAL::micros() - command_send_us < 10000) {
217
// we should avoid trying to read the ADC too soon after
218
// sending the command
219
return;
220
}
221
222
uint32_t adc_val = read_adc();
223
224
if (adc_val == 0) {
225
// we have either done a read too soon after sending the
226
// request or we have tried to read the same sample twice. We
227
// re-send the command now as we don't know what state the
228
// sensor is in, and we do want to trigger it sending a value,
229
// which we will discard
230
if (dev->transfer(&cmd_sent, 1, nullptr, 0)) {
231
command_send_us = AP_HAL::micros();
232
}
233
// when we get adc_val == 0 then then both the current value and
234
// the next value we read from the sensor are invalid
235
ignore_next = true;
236
return;
237
}
238
239
/*
240
* If read fails, re-initiate a read command for current state or we are
241
* stuck
242
*/
243
if (!ignore_next) {
244
if (cmd_sent == REG_CONVERT_TEMPERATURE) {
245
D2 = adc_val;
246
} else if (cmd_sent == REG_CONVERT_PRESSURE) {
247
D1 = adc_val;
248
calculate();
249
}
250
}
251
252
ignore_next = false;
253
254
cmd_sent = (state == 0) ? REG_CONVERT_TEMPERATURE : REG_CONVERT_PRESSURE;
255
if (!dev->transfer(&cmd_sent, 1, nullptr, 0)) {
256
// we don't know for sure what state the sensor is in when we
257
// fail to send the command, so ignore the next response
258
ignore_next = true;
259
return;
260
}
261
command_send_us = AP_HAL::micros();
262
263
state = (state + 1) % 5;
264
}
265
266
// return the current differential_pressure in Pascal
267
bool AP_Airspeed_MS5525::get_differential_pressure(float &_pressure)
268
{
269
WITH_SEMAPHORE(sem);
270
271
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
272
return false;
273
}
274
275
if (press_count > 0) {
276
pressure = pressure_sum / press_count;
277
press_count = 0;
278
pressure_sum = 0;
279
}
280
_pressure = pressure;
281
282
return true;
283
}
284
285
// return the current temperature in degrees C, if available
286
bool AP_Airspeed_MS5525::get_temperature(float &_temperature)
287
{
288
WITH_SEMAPHORE(sem);
289
290
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
291
return false;
292
}
293
294
if (temp_count > 0) {
295
temperature = temperature_sum / temp_count;
296
temp_count = 0;
297
temperature_sum = 0;
298
}
299
300
_temperature = temperature;
301
return true;
302
}
303
304
#endif // AP_AIRSPEED_MS5525_ENABLED
305
306