AP_Airspeed_SDP3X.cpp 9.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. backend driver for airspeed from a I2C SDP3X sensor
  15. with thanks to https://github.com/PX4/Firmware/blob/master/src/drivers/sdp3x_airspeed
  16. */
  17. #include "AP_Airspeed_SDP3X.h"
  18. #include <GCS_MAVLink/GCS.h>
  19. #include <AP_Baro/AP_Baro.h>
  20. #include <stdio.h>
  21. #define SDP3X_SCALE_TEMPERATURE 200.0f
  22. #define SDP3XD0_I2C_ADDR 0x21
  23. #define SDP3XD1_I2C_ADDR 0x22
  24. #define SDP3XD2_I2C_ADDR 0x23
  25. #define SDP3X_CONT_MEAS_AVG_MODE 0x3615
  26. #define SDP3X_CONT_MEAS_STOP 0x3FF9
  27. #define SDP3X_SCALE_PRESSURE_SDP31 60
  28. #define SDP3X_SCALE_PRESSURE_SDP32 240
  29. #define SDP3X_SCALE_PRESSURE_SDP33 20
  30. extern const AP_HAL::HAL &hal;
  31. AP_Airspeed_SDP3X::AP_Airspeed_SDP3X(AP_Airspeed &_frontend, uint8_t _instance) :
  32. AP_Airspeed_Backend(_frontend, _instance)
  33. {
  34. }
  35. /*
  36. send a 16 bit command code
  37. */
  38. bool AP_Airspeed_SDP3X::_send_command(uint16_t cmd)
  39. {
  40. uint8_t b[2] {uint8_t(cmd >> 8), uint8_t(cmd & 0xFF)};
  41. return _dev->transfer(b, 2, nullptr, 0);
  42. }
  43. // probe and initialise the sensor
  44. bool AP_Airspeed_SDP3X::init()
  45. {
  46. const uint8_t addresses[3] = { SDP3XD0_I2C_ADDR,
  47. SDP3XD1_I2C_ADDR,
  48. SDP3XD2_I2C_ADDR
  49. };
  50. bool found = false;
  51. bool ret = false;
  52. for (uint8_t i=0; i<ARRAY_SIZE(addresses) && !found; i++) {
  53. _dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);
  54. if (!_dev) {
  55. continue;
  56. }
  57. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  58. continue;
  59. }
  60. // lots of retries during probe
  61. _dev->set_retries(10);
  62. // stop continuous average mode
  63. if (!_send_command(SDP3X_CONT_MEAS_STOP)) {
  64. _dev->get_semaphore()->give();
  65. continue;
  66. }
  67. // these delays are needed for reliable operation
  68. _dev->get_semaphore()->give();
  69. hal.scheduler->delay_microseconds(20000);
  70. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  71. continue;
  72. }
  73. // start continuous average mode
  74. if (!_send_command(SDP3X_CONT_MEAS_AVG_MODE)) {
  75. _dev->get_semaphore()->give();
  76. continue;
  77. }
  78. // these delays are needed for reliable operation
  79. _dev->get_semaphore()->give();
  80. hal.scheduler->delay_microseconds(20000);
  81. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  82. continue;
  83. }
  84. // step 3 - get scale
  85. uint8_t val[9];
  86. ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));
  87. if (!ret) {
  88. _dev->get_semaphore()->give();
  89. continue;
  90. }
  91. // Check the CRC
  92. if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5]) || !_crc(&val[6], 2, val[8])) {
  93. _dev->get_semaphore()->give();
  94. continue;
  95. }
  96. _scale = (((uint16_t)val[6]) << 8) | val[7];
  97. _dev->get_semaphore()->give();
  98. found = true;
  99. char c = 'X';
  100. switch (_scale) {
  101. case SDP3X_SCALE_PRESSURE_SDP31:
  102. c = '1';
  103. break;
  104. case SDP3X_SCALE_PRESSURE_SDP32:
  105. c = '2';
  106. break;
  107. case SDP3X_SCALE_PRESSURE_SDP33:
  108. c = '3';
  109. break;
  110. }
  111. hal.console->printf("SDP3%c: Found on bus %u address 0x%02x scale=%u\n",
  112. c, get_bus(), addresses[i], _scale);
  113. }
  114. if (!found) {
  115. return false;
  116. }
  117. /*
  118. this sensor uses zero offset and skips cal
  119. */
  120. set_use_zero_offset();
  121. set_skip_cal();
  122. set_offset(0);
  123. // drop to 2 retries for runtime
  124. _dev->set_retries(2);
  125. _dev->register_periodic_callback(20000,
  126. FUNCTOR_BIND_MEMBER(&AP_Airspeed_SDP3X::_timer, void));
  127. return true;
  128. }
  129. // read the values from the sensor. Called at 50Hz
  130. void AP_Airspeed_SDP3X::_timer()
  131. {
  132. // read 6 bytes from the sensor
  133. uint8_t val[6];
  134. int ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));
  135. uint32_t now = AP_HAL::millis();
  136. if (!ret) {
  137. if (now - _last_sample_time_ms > 200) {
  138. // try and re-connect
  139. _send_command(SDP3X_CONT_MEAS_AVG_MODE);
  140. }
  141. return;
  142. }
  143. // Check the CRC
  144. if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5])) {
  145. return;
  146. }
  147. int16_t P = (((int16_t)val[0]) << 8) | val[1];
  148. int16_t temp = (((int16_t)val[3]) << 8) | val[4];
  149. float diff_press_pa = float(P) / float(_scale);
  150. float temperature = float(temp) / SDP3X_SCALE_TEMPERATURE;
  151. WITH_SEMAPHORE(sem);
  152. _press_sum += diff_press_pa;
  153. _temp_sum += temperature;
  154. _press_count++;
  155. _temp_count++;
  156. _last_sample_time_ms = now;
  157. }
  158. /*
  159. correct pressure for barometric height
  160. With thanks to:
  161. https://github.com/PX4/Firmware/blob/master/Tools/models/sdp3x_pitot_model.py
  162. */
  163. float AP_Airspeed_SDP3X::_correct_pressure(float press)
  164. {
  165. float sign = 1.0f;
  166. // fix for tube order
  167. AP_Airspeed::pitot_tube_order tube_order = get_tube_order();
  168. switch (tube_order) {
  169. case AP_Airspeed::PITOT_TUBE_ORDER_NEGATIVE:
  170. press = -press;
  171. sign = -1.0f;
  172. //FALLTHROUGH;
  173. case AP_Airspeed::PITOT_TUBE_ORDER_POSITIVE:
  174. break;
  175. case AP_Airspeed::PITOT_TUBE_ORDER_AUTO:
  176. default:
  177. if (press < 0.0f) {
  178. sign = -1.0f;
  179. press = -press;
  180. }
  181. break;
  182. }
  183. if (press <= 0.0f) {
  184. return 0.0f;
  185. }
  186. AP_Baro *baro = AP_Baro::get_singleton();
  187. if (baro == nullptr) {
  188. return press;
  189. }
  190. float temperature;
  191. if (!get_temperature(temperature)) {
  192. return press;
  193. }
  194. float rho_air = baro->get_pressure() / (ISA_GAS_CONSTANT * (temperature + C_TO_KELVIN));
  195. /*
  196. the constants in the code below come from a calibrated test of
  197. the drotek pitot tube by Sensiron. They are specific to the droktek pitot tube
  198. At 25m/s, the rough proportions of each pressure correction are:
  199. - dp_pitot: 5%
  200. - press_correction: 14%
  201. - press: 81%
  202. dp_tube has been removed from the Sensiron model as it is
  203. insignificant (less than 0.02% over the supported speed ranges)
  204. */
  205. // flow through sensor
  206. float flow_SDP3X = (300.805f - 300.878f / (0.00344205f * (float)powf(press, 0.68698f) + 1.0f)) * 1.29f / rho_air;
  207. if (flow_SDP3X < 0.0f) {
  208. flow_SDP3X = 0.0f;
  209. }
  210. // diffential pressure through pitot tube
  211. float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f)));
  212. // uncorrected pressure
  213. float press_uncorrected = (press + dp_pitot) / SSL_AIR_DENSITY;
  214. // correction for speed at pitot-tube tip due to flow through sensor
  215. float dv = 0.0331582f * flow_SDP3X;
  216. // airspeed ratio
  217. float ratio = get_airspeed_ratio();
  218. // calculate equivalent pressure correction. This formula comes
  219. // from turning the dv correction above into an equivalent
  220. // pressure correction. We need to do this so the airspeed ratio
  221. // calibrator can work, as it operates on pressure values
  222. float press_correction = sq(sqrtf(press_uncorrected*ratio)+dv)/ratio - press_uncorrected;
  223. return (press_uncorrected + press_correction) * sign;
  224. }
  225. // return the current differential_pressure in Pascal
  226. bool AP_Airspeed_SDP3X::get_differential_pressure(float &pressure)
  227. {
  228. uint32_t now = AP_HAL::millis();
  229. if (now - _last_sample_time_ms > 100) {
  230. return false;
  231. }
  232. {
  233. WITH_SEMAPHORE(sem);
  234. if (_press_count > 0) {
  235. _press = _press_sum / _press_count;
  236. _press_count = 0;
  237. _press_sum = 0;
  238. }
  239. }
  240. pressure = _correct_pressure(_press);
  241. return true;
  242. }
  243. // return the current temperature in degrees C, if available
  244. bool AP_Airspeed_SDP3X::get_temperature(float &temperature)
  245. {
  246. if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
  247. return false;
  248. }
  249. WITH_SEMAPHORE(sem);
  250. if (_temp_count > 0) {
  251. _temp = _temp_sum / _temp_count;
  252. _temp_count = 0;
  253. _temp_sum = 0;
  254. }
  255. temperature = _temp;
  256. return true;
  257. }
  258. /*
  259. check CRC for a set of bytes
  260. */
  261. bool AP_Airspeed_SDP3X::_crc(const uint8_t data[], unsigned size, uint8_t checksum)
  262. {
  263. uint8_t crc_value = 0xff;
  264. // calculate 8-bit checksum with polynomial 0x31 (x^8 + x^5 + x^4 + 1)
  265. for (uint8_t i = 0; i < size; i++) {
  266. crc_value ^= data[i];
  267. for (uint8_t bit = 8; bit > 0; --bit) {
  268. if (crc_value & 0x80) {
  269. crc_value = (crc_value << 1) ^ 0x31;
  270. } else {
  271. crc_value = (crc_value << 1);
  272. }
  273. }
  274. }
  275. // verify checksum
  276. return (crc_value == checksum);
  277. }