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_MS4525.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 MS4525D0 sensor
18
*/
19
#include "AP_Airspeed_MS4525.h"
20
21
#if AP_AIRSPEED_MS4525_ENABLED
22
23
#include <AP_Common/AP_Common.h>
24
#include <AP_HAL/AP_HAL.h>
25
#include <AP_HAL/I2CDevice.h>
26
#include <AP_Math/AP_Math.h>
27
#include <GCS_MAVLink/GCS.h>
28
#include <stdio.h>
29
#include <utility>
30
31
extern const AP_HAL::HAL &hal;
32
33
#define MS4525D0_I2C_ADDR1 0x28
34
#define MS4525D0_I2C_ADDR2 0x36
35
#define MS4525D0_I2C_ADDR3 0x46
36
37
AP_Airspeed_MS4525::AP_Airspeed_MS4525(AP_Airspeed &_frontend, uint8_t _instance) :
38
AP_Airspeed_Backend(_frontend, _instance)
39
{
40
}
41
42
// probe for a sensor
43
bool AP_Airspeed_MS4525::probe(uint8_t bus, uint8_t address)
44
{
45
_dev = hal.i2c_mgr->get_device(bus, address);
46
if (!_dev) {
47
return false;
48
}
49
WITH_SEMAPHORE(_dev->get_semaphore());
50
51
// lots of retries during probe
52
_dev->set_retries(10);
53
54
_measure();
55
hal.scheduler->delay(10);
56
_collect();
57
58
return _last_sample_time_ms != 0;
59
}
60
61
// probe and initialise the sensor
62
bool AP_Airspeed_MS4525::init()
63
{
64
static const uint8_t addresses[] = { MS4525D0_I2C_ADDR1, MS4525D0_I2C_ADDR2, MS4525D0_I2C_ADDR3 };
65
if (bus_is_configured()) {
66
// the user has configured a specific bus
67
for (uint8_t addr : addresses) {
68
if (probe(get_bus(), addr)) {
69
goto found_sensor;
70
}
71
}
72
} else {
73
// if bus is not configured then fall back to the old
74
// behaviour of probing all buses, external first
75
FOREACH_I2C_EXTERNAL(bus) {
76
for (uint8_t addr : addresses) {
77
if (probe(bus, addr)) {
78
goto found_sensor;
79
}
80
}
81
}
82
FOREACH_I2C_INTERNAL(bus) {
83
for (uint8_t addr : addresses) {
84
if (probe(bus, addr)) {
85
goto found_sensor;
86
}
87
}
88
}
89
}
90
91
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MS4525[%u]: no sensor found", get_instance());
92
return false;
93
94
found_sensor:
95
_dev->set_device_type(uint8_t(DevType::MS4525));
96
set_bus_id(_dev->get_bus_id());
97
98
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS4525[%u]: Found bus %u addr 0x%02x", get_instance(), _dev->bus_num(), _dev->get_bus_address());
99
100
// drop to 2 retries for runtime
101
_dev->set_retries(2);
102
103
_dev->register_periodic_callback(20000,
104
FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS4525::_timer, void));
105
return true;
106
}
107
108
// start a measurement
109
void AP_Airspeed_MS4525::_measure()
110
{
111
_measurement_started_ms = 0;
112
uint8_t cmd = 0;
113
if (_dev->transfer(&cmd, 1, nullptr, 0)) {
114
_measurement_started_ms = AP_HAL::millis();
115
}
116
}
117
118
/*
119
this equation is an inversion of the equation in the
120
pressure transfer function figure on page 4 of the datasheet
121
122
We negate the result so that positive differential pressures
123
are generated when the bottom port is used as the static
124
port on the pitot and top port is used as the dynamic port
125
*/
126
float AP_Airspeed_MS4525::_get_pressure(int16_t dp_raw) const
127
{
128
const float P_max = get_psi_range();
129
const float P_min = - P_max;
130
const float PSI_to_Pa = 6894.757f;
131
132
float diff_press_PSI = -((dp_raw - 0.1f*16383) * (P_max-P_min)/(0.8f*16383) + P_min);
133
float press = diff_press_PSI * PSI_to_Pa;
134
return press;
135
}
136
137
/*
138
convert raw temperature to temperature in degrees C
139
*/
140
float AP_Airspeed_MS4525::_get_temperature(int16_t dT_raw) const
141
{
142
float temp = ((200.0f * dT_raw) / 2047) - 50;
143
return temp;
144
}
145
146
// read the values from the sensor
147
void AP_Airspeed_MS4525::_collect()
148
{
149
uint8_t data[4];
150
uint8_t data2[4];
151
152
_measurement_started_ms = 0;
153
154
if (!_dev->transfer(nullptr, 0, data, sizeof(data))) {
155
return;
156
}
157
// reread the data, so we can attempt to detect bad inputs
158
if (!_dev->transfer(nullptr, 0, data2, sizeof(data2))) {
159
return;
160
}
161
162
uint8_t status = (data[0] & 0xC0) >> 6;
163
// only check the status on the first read, the second read is expected to be stale
164
if (status == 2 || status == 3) {
165
return;
166
}
167
168
int16_t dp_raw, dT_raw;
169
dp_raw = (data[0] << 8) + data[1];
170
dp_raw = 0x3FFF & dp_raw;
171
dT_raw = (data[2] << 8) + data[3];
172
dT_raw = (0xFFE0 & dT_raw) >> 5;
173
174
int16_t dp_raw2, dT_raw2;
175
dp_raw2 = (data2[0] << 8) + data2[1];
176
dp_raw2 = 0x3FFF & dp_raw2;
177
dT_raw2 = (data2[2] << 8) + data2[3];
178
dT_raw2 = (0xFFE0 & dT_raw2) >> 5;
179
180
// reject any values that are the absolute minimum or maximums these
181
// can happen due to gnd lifts or communication errors on the bus
182
if (dp_raw == 0x3FFF || dp_raw == 0 || dT_raw == 0x7FF || dT_raw == 0 ||
183
dp_raw2 == 0x3FFF || dp_raw2 == 0 || dT_raw2 == 0x7FF || dT_raw2 == 0) {
184
return;
185
}
186
187
// reject any double reads where the value has shifted in the upper more than
188
// 0xFF
189
if (abs(dp_raw - dp_raw2) > 0xFF || abs(dT_raw - dT_raw2) > 0xFF) {
190
return;
191
}
192
193
float press = _get_pressure(dp_raw);
194
float press2 = _get_pressure(dp_raw2);
195
float temp = _get_temperature(dT_raw);
196
float temp2 = _get_temperature(dT_raw2);
197
198
if (!disable_voltage_correction()) {
199
_voltage_correction(press, temp);
200
_voltage_correction(press2, temp2);
201
}
202
203
WITH_SEMAPHORE(sem);
204
205
_press_sum += press + press2;
206
_temp_sum += temp + temp2;
207
_press_count += 2;
208
_temp_count += 2;
209
210
_last_sample_time_ms = AP_HAL::millis();
211
}
212
213
/**
214
correct for 5V rail voltage if the system_power ORB topic is
215
available
216
217
See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of
218
offset versus voltage for 3 sensors
219
*/
220
void AP_Airspeed_MS4525::_voltage_correction(float &diff_press_pa, float &temperature)
221
{
222
const float slope = 65.0f;
223
const float temp_slope = 0.887f;
224
225
/*
226
apply a piecewise linear correction within range given by above graph
227
*/
228
float voltage_diff = hal.analogin->board_voltage() - 5.0f;
229
230
voltage_diff = constrain_float(voltage_diff, -0.7f, 0.5f);
231
232
diff_press_pa -= voltage_diff * slope;
233
temperature -= voltage_diff * temp_slope;
234
}
235
236
// 50Hz timer
237
void AP_Airspeed_MS4525::_timer()
238
{
239
if (_measurement_started_ms == 0) {
240
_measure();
241
return;
242
}
243
if ((AP_HAL::millis() - _measurement_started_ms) > 10) {
244
_collect();
245
// start a new measurement
246
_measure();
247
}
248
}
249
250
// return the current differential_pressure in Pascal
251
bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)
252
{
253
WITH_SEMAPHORE(sem);
254
255
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
256
return false;
257
}
258
259
if (_press_count > 0) {
260
_pressure = _press_sum / _press_count;
261
_press_count = 0;
262
_press_sum = 0;
263
}
264
265
pressure = _pressure;
266
return true;
267
}
268
269
// return the current temperature in degrees C, if available
270
bool AP_Airspeed_MS4525::get_temperature(float &temperature)
271
{
272
WITH_SEMAPHORE(sem);
273
274
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
275
return false;
276
}
277
278
if (_temp_count > 0) {
279
_temperature = _temp_sum / _temp_count;
280
_temp_count = 0;
281
_temp_sum = 0;
282
}
283
284
temperature = _temperature;
285
return true;
286
}
287
288
#endif // AP_AIRSPEED_MS4525_ENABLED
289
290