AP_Airspeed_MS4525.cpp 6.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259
  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 MS4525D0 sensor
  15. */
  16. #include "AP_Airspeed_MS4525.h"
  17. #include <AP_Common/AP_Common.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_HAL/I2CDevice.h>
  20. #include <AP_Math/AP_Math.h>
  21. #include <stdio.h>
  22. #include <utility>
  23. extern const AP_HAL::HAL &hal;
  24. #define MS4525D0_I2C_ADDR 0x28
  25. AP_Airspeed_MS4525::AP_Airspeed_MS4525(AP_Airspeed &_frontend, uint8_t _instance) :
  26. AP_Airspeed_Backend(_frontend, _instance)
  27. {
  28. }
  29. // probe and initialise the sensor
  30. bool AP_Airspeed_MS4525::init()
  31. {
  32. const struct {
  33. uint8_t bus;
  34. uint8_t addr;
  35. } addresses[] = {
  36. { 1, MS4525D0_I2C_ADDR },
  37. { 0, MS4525D0_I2C_ADDR },
  38. { 2, MS4525D0_I2C_ADDR },
  39. { 3, MS4525D0_I2C_ADDR },
  40. };
  41. bool found = false;
  42. for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {
  43. _dev = hal.i2c_mgr->get_device(addresses[i].bus, addresses[i].addr);
  44. if (!_dev) {
  45. continue;
  46. }
  47. WITH_SEMAPHORE(_dev->get_semaphore());
  48. // lots of retries during probe
  49. _dev->set_retries(10);
  50. _measure();
  51. hal.scheduler->delay(10);
  52. _collect();
  53. found = (_last_sample_time_ms != 0);
  54. if (found) {
  55. printf("MS4525: Found sensor on bus %u address 0x%02x\n", addresses[i].bus, addresses[i].addr);
  56. break;
  57. }
  58. }
  59. if (!found) {
  60. printf("MS4525: no sensor found\n");
  61. return false;
  62. }
  63. // drop to 2 retries for runtime
  64. _dev->set_retries(2);
  65. _dev->register_periodic_callback(20000,
  66. FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS4525::_timer, void));
  67. return true;
  68. }
  69. // start a measurement
  70. void AP_Airspeed_MS4525::_measure()
  71. {
  72. _measurement_started_ms = 0;
  73. uint8_t cmd = 0;
  74. if (_dev->transfer(&cmd, 1, nullptr, 0)) {
  75. _measurement_started_ms = AP_HAL::millis();
  76. }
  77. }
  78. /*
  79. this equation is an inversion of the equation in the
  80. pressure transfer function figure on page 4 of the datasheet
  81. We negate the result so that positive differential pressures
  82. are generated when the bottom port is used as the static
  83. port on the pitot and top port is used as the dynamic port
  84. */
  85. float AP_Airspeed_MS4525::_get_pressure(int16_t dp_raw) const
  86. {
  87. const float P_max = get_psi_range();
  88. const float P_min = - P_max;
  89. const float PSI_to_Pa = 6894.757f;
  90. float diff_press_PSI = -((dp_raw - 0.1f*16383) * (P_max-P_min)/(0.8f*16383) + P_min);
  91. float press = diff_press_PSI * PSI_to_Pa;
  92. return press;
  93. }
  94. /*
  95. convert raw temperature to temperature in degrees C
  96. */
  97. float AP_Airspeed_MS4525::_get_temperature(int16_t dT_raw) const
  98. {
  99. float temp = ((200.0f * dT_raw) / 2047) - 50;
  100. return temp;
  101. }
  102. // read the values from the sensor
  103. void AP_Airspeed_MS4525::_collect()
  104. {
  105. uint8_t data[4];
  106. uint8_t data2[4];
  107. _measurement_started_ms = 0;
  108. if (!_dev->transfer(nullptr, 0, data, sizeof(data))) {
  109. return;
  110. }
  111. // reread the data, so we can attempt to detect bad inputs
  112. if (!_dev->transfer(nullptr, 0, data2, sizeof(data2))) {
  113. return;
  114. }
  115. uint8_t status = (data[0] & 0xC0) >> 6;
  116. // only check the status on the first read, the second read is expected to be stale
  117. if (status == 2 || status == 3) {
  118. return;
  119. }
  120. int16_t dp_raw, dT_raw;
  121. dp_raw = (data[0] << 8) + data[1];
  122. dp_raw = 0x3FFF & dp_raw;
  123. dT_raw = (data[2] << 8) + data[3];
  124. dT_raw = (0xFFE0 & dT_raw) >> 5;
  125. int16_t dp_raw2, dT_raw2;
  126. dp_raw2 = (data2[0] << 8) + data2[1];
  127. dp_raw2 = 0x3FFF & dp_raw2;
  128. dT_raw2 = (data2[2] << 8) + data2[3];
  129. dT_raw2 = (0xFFE0 & dT_raw2) >> 5;
  130. // reject any values that are the absolute minimum or maximums these
  131. // can happen due to gnd lifts or communication errors on the bus
  132. if (dp_raw == 0x3FFF || dp_raw == 0 || dT_raw == 0x7FF || dT_raw == 0 ||
  133. dp_raw2 == 0x3FFF || dp_raw2 == 0 || dT_raw2 == 0x7FF || dT_raw2 == 0) {
  134. return;
  135. }
  136. // reject any double reads where the value has shifted in the upper more than
  137. // 0xFF
  138. if (abs(dp_raw - dp_raw2) > 0xFF || abs(dT_raw - dT_raw2) > 0xFF) {
  139. return;
  140. }
  141. float press = _get_pressure(dp_raw);
  142. float press2 = _get_pressure(dp_raw2);
  143. float temp = _get_temperature(dT_raw);
  144. float temp2 = _get_temperature(dT_raw2);
  145. _voltage_correction(press, temp);
  146. _voltage_correction(press2, temp2);
  147. WITH_SEMAPHORE(sem);
  148. _press_sum += press + press2;
  149. _temp_sum += temp + temp2;
  150. _press_count += 2;
  151. _temp_count += 2;
  152. _last_sample_time_ms = AP_HAL::millis();
  153. }
  154. /**
  155. correct for 5V rail voltage if the system_power ORB topic is
  156. available
  157. See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of
  158. offset versus voltage for 3 sensors
  159. */
  160. void AP_Airspeed_MS4525::_voltage_correction(float &diff_press_pa, float &temperature)
  161. {
  162. const float slope = 65.0f;
  163. const float temp_slope = 0.887f;
  164. /*
  165. apply a piecewise linear correction within range given by above graph
  166. */
  167. float voltage_diff = hal.analogin->board_voltage() - 5.0f;
  168. voltage_diff = constrain_float(voltage_diff, -0.7f, 0.5f);
  169. diff_press_pa -= voltage_diff * slope;
  170. temperature -= voltage_diff * temp_slope;
  171. }
  172. // 50Hz timer
  173. void AP_Airspeed_MS4525::_timer()
  174. {
  175. if (_measurement_started_ms == 0) {
  176. _measure();
  177. return;
  178. }
  179. if ((AP_HAL::millis() - _measurement_started_ms) > 10) {
  180. _collect();
  181. // start a new measurement
  182. _measure();
  183. }
  184. }
  185. // return the current differential_pressure in Pascal
  186. bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)
  187. {
  188. if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
  189. return false;
  190. }
  191. WITH_SEMAPHORE(sem);
  192. if (_press_count > 0) {
  193. _pressure = _press_sum / _press_count;
  194. _press_count = 0;
  195. _press_sum = 0;
  196. }
  197. pressure = _pressure;
  198. return true;
  199. }
  200. // return the current temperature in degrees C, if available
  201. bool AP_Airspeed_MS4525::get_temperature(float &temperature)
  202. {
  203. if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
  204. return false;
  205. }
  206. WITH_SEMAPHORE(sem);
  207. if (_temp_count > 0) {
  208. _temperature = _temp_sum / _temp_count;
  209. _temp_count = 0;
  210. _temp_sum = 0;
  211. }
  212. temperature = _temperature;
  213. return true;
  214. }