APM:Libraries
AP_Airspeed_SDP3X.cpp
Go to the documentation of this file.
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 SDP3X sensor
18 
19  with thanks to https://github.com/PX4/Firmware/blob/master/src/drivers/sdp3x_airspeed
20  */
21 #include "AP_Airspeed_SDP3X.h"
22 #include <GCS_MAVLink/GCS.h>
23 
24 #include <stdio.h>
25 
26 #define SDP3X_SCALE_TEMPERATURE 200.0f
27 
28 #define SDP3XD0_I2C_ADDR 0x21
29 #define SDP3XD1_I2C_ADDR 0x22
30 #define SDP3XD2_I2C_ADDR 0x23
31 
32 #define SDP3X_CONT_MEAS_AVG_MODE 0x3615
33 #define SDP3X_CONT_MEAS_STOP 0x3FF9
34 
35 #define SDP3X_SCALE_PRESSURE_SDP31 60
36 #define SDP3X_SCALE_PRESSURE_SDP32 240
37 #define SDP3X_SCALE_PRESSURE_SDP33 20
38 
39 extern const AP_HAL::HAL &hal;
40 
41 AP_Airspeed_SDP3X::AP_Airspeed_SDP3X(AP_Airspeed &_frontend, uint8_t _instance) :
42  AP_Airspeed_Backend(_frontend, _instance)
43 {
44 }
45 
46 /*
47  send a 16 bit command code
48  */
50 {
51  uint8_t b[2] {uint8_t(cmd >> 8), uint8_t(cmd & 0xFF)};
52  return _dev->transfer(b, 2, nullptr, 0);
53 }
54 
55 // probe and initialise the sensor
57 {
58  const uint8_t addresses[3] = { SDP3XD0_I2C_ADDR,
61  };
62  bool found = false;
63  bool ret = false;
64 
65  for (uint8_t i=0; i<ARRAY_SIZE(addresses) && !found; i++) {
66  _dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);
67  if (!_dev) {
68  continue;
69  }
71  continue;
72  }
73 
74  // lots of retries during probe
75  _dev->set_retries(10);
76 
77  // stop continuous average mode
79  _dev->get_semaphore()->give();
80  continue;
81  }
82 
83  // these delays are needed for reliable operation
84  _dev->get_semaphore()->give();
85  hal.scheduler->delay_microseconds(20000);
87  continue;
88  }
89 
90  // start continuous average mode
92  _dev->get_semaphore()->give();
93  continue;
94  }
95 
96  // these delays are needed for reliable operation
97  _dev->get_semaphore()->give();
98  hal.scheduler->delay_microseconds(20000);
100  continue;
101  }
102 
103  // step 3 - get scale
104  uint8_t val[9];
105  ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));
106  if (!ret) {
107  _dev->get_semaphore()->give();
108  continue;
109  }
110 
111  // Check the CRC
112  if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5]) || !_crc(&val[6], 2, val[8])) {
113  _dev->get_semaphore()->give();
114  continue;
115  }
116 
117  _scale = (((uint16_t)val[6]) << 8) | val[7];
118 
119  _dev->get_semaphore()->give();
120 
121  found = true;
122 
123  char c = 'X';
124  switch (_scale) {
126  c = '1';
127  break;
129  c = '2';
130  break;
132  c = '3';
133  break;
134  }
135  hal.console->printf("SDP3%c: Found on bus %u address 0x%02x scale=%u\n",
136  c, get_bus(), addresses[i], _scale);
137  }
138 
139  if (!found) {
140  return false;
141  }
142 
143  /*
144  this sensor uses zero offset and skips cal
145  */
147  set_skip_cal();
148  set_offset(0);
149 
150  // drop to 2 retries for runtime
151  _dev->set_retries(2);
152 
155  return true;
156 }
157 
158 // read the values from the sensor. Called at 50Hz
160 {
161  // read 6 bytes from the sensor
162  uint8_t val[6];
163  int ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));
164  uint32_t now = AP_HAL::millis();
165  if (!ret) {
166  if (now - _last_sample_time_ms > 200) {
167  // try and re-connect
169  }
170  return;
171  }
172  // Check the CRC
173  if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5])) {
174  return;
175  }
176 
177  int16_t P = (((int16_t)val[0]) << 8) | val[1];
178  int16_t temp = (((int16_t)val[3]) << 8) | val[4];
179 
180  float diff_press_pa = float(P) / float(_scale);
181  float temperature = float(temp) / SDP3X_SCALE_TEMPERATURE;
182 
184  _press_sum += diff_press_pa;
186  _press_count++;
187  _temp_count++;
188  _last_sample_time_ms = now;
189  sem->give();
190  }
191 }
192 
193 /*
194  correct pressure for barometric height
195  With thanks to:
196  https://github.com/PX4/Firmware/blob/master/Tools/models/sdp3x_pitot_model.py
197  */
199 {
200  float temperature;
202 
203  if (baro == nullptr) {
204  return press;
205  }
206 
207  float sign = 1;
208 
209  // fix for tube order
211  switch (tube_order) {
213  press = -press;
214  sign = -1;
215  //FALLTHROUGH;
217  break;
219  default:
220  if (press < 0) {
221  sign = -1;
222  press = -press;
223  }
224  break;
225  }
226 
227  if (press <= 0) {
228  return 0;
229  }
230 
231  get_temperature(temperature);
232  float rho_air = baro->get_pressure() / (ISA_GAS_CONSTANT * (temperature + C_TO_KELVIN));
233 
234  /*
235  the constants in the code below come from a calibrated test of
236  the drotek pitot tube by Sensiron. They are specific to the droktek pitot tube
237 
238  At 25m/s, the rough proportions of each pressure correction are:
239 
240  - dp_pitot: 5%
241  - press_correction: 14%
242  - press: 81%
243 
244  dp_tube has been removed from the Sensiron model as it is
245  insignificant (less than 0.02% over the supported speed ranges)
246  */
247 
248  // flow through sensor
249  float flow_SDP3X = (300.805f - 300.878f / (0.00344205f * (float)powf(press, 0.68698f) + 1)) * 1.29f / rho_air;
250  if (flow_SDP3X < 0.0f) {
251  flow_SDP3X = 0.0f;
252  }
253 
254  // diffential pressure through pitot tube
255  float dp_pitot = 28557670.0f - 28557670.0f / (1 + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f));
256 
257  // uncorrected pressure
258  float press_uncorrected = (press + dp_pitot) / SSL_AIR_DENSITY;
259 
260  // correction for speed at pitot-tube tip due to flow through sensor
261  float dv = 0.0331582 * flow_SDP3X;
262 
263  // airspeed ratio
264  float ratio = get_airspeed_ratio();
265 
266  // calculate equivalent pressure correction. This formula comes
267  // from turning the dv correction above into an equivalent
268  // pressure correction. We need to do this so the airspeed ratio
269  // calibrator can work, as it operates on pressure values
270  float press_correction = sq(sqrtf(press_uncorrected*ratio)+dv)/ratio - press_uncorrected;
271 
272  return (press_uncorrected + press_correction) * sign;
273 }
274 
275 // return the current differential_pressure in Pascal
277 {
278  uint32_t now = AP_HAL::millis();
279  if (now - _last_sample_time_ms > 100) {
280  return false;
281  }
283  if (_press_count > 0) {
285  _press_count = 0;
286  _press_sum = 0;
287  }
288  sem->give();
289  }
290  pressure = _correct_pressure(_press);
291  return true;
292 }
293 
294 // return the current temperature in degrees C, if available
296 {
297  if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
298  return false;
299  }
301  if (_temp_count > 0) {
303  _temp_count = 0;
304  _temp_sum = 0;
305  }
306  sem->give();
307  }
308  temperature = _temp;
309  return true;
310 }
311 
312 /*
313  check CRC for a set of bytes
314  */
315 bool AP_Airspeed_SDP3X::_crc(const uint8_t data[], unsigned size, uint8_t checksum)
316 {
317  uint8_t crc_value = 0xff;
318 
319  // calculate 8-bit checksum with polynomial 0x31 (x^8 + x^5 + x^4 + 1)
320  for (uint8_t i = 0; i < size; i++) {
321  crc_value ^= data[i];
322  for (uint8_t bit = 8; bit > 0; --bit) {
323  if (crc_value & 0x80) {
324  crc_value = (crc_value << 1) ^ 0x31;
325  } else {
326  crc_value = (crc_value << 1);
327  }
328  }
329  }
330  // verify checksum
331  return (crc_value == checksum);
332 }
#define SDP3XD1_I2C_ADDR
uint32_t _last_sample_time_ms
AP_Airspeed_SDP3X(AP_Airspeed &frontend, uint8_t _instance)
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define SDP3X_SCALE_PRESSURE_SDP33
#define SDP3XD0_I2C_ADDR
#define C_TO_KELVIN
Definition: definitions.h:74
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool _send_command(uint16_t cmd)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
float get_airspeed_ratio(void) const
#define SSL_AIR_DENSITY
Definition: definitions.h:82
Interface definition for the various Ground Control System.
float _correct_pressure(float press)
#define ISA_GAS_CONSTANT
Definition: definitions.h:77
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
virtual Semaphore * get_semaphore() override=0
static AP_Baro * get_instance(void)
Definition: AP_Baro.h:34
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define SDP3X_SCALE_PRESSURE_SDP32
bool get_differential_pressure(float &pressure) override
AP_HAL::Semaphore * sem
float temperature
Definition: Airspeed.cpp:32
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void set_offset(float ofs)
#define f(i)
#define SDP3XD2_I2C_ADDR
bool _crc(const uint8_t data[], unsigned size, uint8_t checksum)
static AP_Baro baro
Definition: ModuleTest.cpp:18
uint32_t millis()
Definition: system.cpp:157
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
virtual bool give()=0
float get_pressure(void) const
Definition: AP_Baro.h:59
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
#define SDP3X_SCALE_TEMPERATURE
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
#define SDP3X_CONT_MEAS_STOP
bool init() override
uint8_t get_bus(void) const
#define SDP3X_SCALE_PRESSURE_SDP31
virtual void delay_microseconds(uint16_t us)=0
float sq(const T val)
Definition: AP_Math.h:170
#define SDP3X_CONT_MEAS_AVG_MODE
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool get_temperature(float &temperature) override
AP_Airspeed::pitot_tube_order get_tube_order(void) const
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114