AP_Airspeed.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550
  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. * AP_Airspeed.cpp - airspeed (pitot) driver
  15. */
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_HAL/I2CDevice.h>
  19. #include <AP_Math/AP_Math.h>
  20. #include <GCS_MAVLink/GCS.h>
  21. #include <SRV_Channel/SRV_Channel.h>
  22. #include <AP_Logger/AP_Logger.h>
  23. #include <utility>
  24. #include "AP_Airspeed.h"
  25. #include "AP_Airspeed_MS4525.h"
  26. #include "AP_Airspeed_MS5525.h"
  27. #include "AP_Airspeed_SDP3X.h"
  28. #include "AP_Airspeed_DLVR.h"
  29. #include "AP_Airspeed_analog.h"
  30. #include "AP_Airspeed_Backend.h"
  31. #if HAL_WITH_UAVCAN
  32. #include "AP_Airspeed_UAVCAN.h"
  33. #endif
  34. extern const AP_HAL::HAL &hal;
  35. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  36. #define ARSPD_DEFAULT_TYPE TYPE_ANALOG
  37. #define ARSPD_DEFAULT_PIN 1
  38. #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
  39. #define ARSPD_DEFAULT_TYPE TYPE_NONE
  40. #define ARSPD_DEFAULT_PIN 15
  41. #else
  42. #define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
  43. #ifdef HAL_DEFAULT_AIRSPEED_PIN
  44. #define ARSPD_DEFAULT_PIN HAL_DEFAULT_AIRSPEED_PIN
  45. #else
  46. #define ARSPD_DEFAULT_PIN 15
  47. #endif
  48. #endif
  49. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
  50. #define PSI_RANGE_DEFAULT 0.05
  51. #endif
  52. #ifndef PSI_RANGE_DEFAULT
  53. #define PSI_RANGE_DEFAULT 1.0f
  54. #endif
  55. // table of user settable parameters
  56. const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
  57. // @Param: _TYPE
  58. // @DisplayName: Airspeed type
  59. // @Description: Type of airspeed sensor
  60. // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:UAVCAN,9:I2C-DLVR-10in
  61. // @User: Standard
  62. AP_GROUPINFO_FLAGS("_TYPE", 0, AP_Airspeed, param[0].type, ARSPD_DEFAULT_TYPE, AP_PARAM_FLAG_ENABLE),
  63. // @Param: _USE
  64. // @DisplayName: Airspeed use
  65. // @Description: Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).
  66. // @Values: 0:DoNotUse,1:Use,2:UseWhenZeroThrottle
  67. // @User: Standard
  68. AP_GROUPINFO("_USE", 1, AP_Airspeed, param[0].use, 0),
  69. // @Param: _OFFSET
  70. // @DisplayName: Airspeed offset
  71. // @Description: Airspeed calibration offset
  72. // @Increment: 0.1
  73. // @User: Advanced
  74. AP_GROUPINFO("_OFFSET", 2, AP_Airspeed, param[0].offset, 0),
  75. // @Param: _RATIO
  76. // @DisplayName: Airspeed ratio
  77. // @Description: Calibrates pitot tube pressure to velocity. Increasing this value will indicate a higher airspeed at any given dynamic pressure.
  78. // @Increment: 0.1
  79. // @User: Advanced
  80. AP_GROUPINFO("_RATIO", 3, AP_Airspeed, param[0].ratio, 1.9936f),
  81. // @Param: _PIN
  82. // @DisplayName: Airspeed pin
  83. // @Description: The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port.
  84. // @User: Advanced
  85. AP_GROUPINFO("_PIN", 4, AP_Airspeed, param[0].pin, ARSPD_DEFAULT_PIN),
  86. // @Param: _AUTOCAL
  87. // @DisplayName: Automatic airspeed ratio calibration
  88. // @Description: Enables automatic adjustment of ARSPD_RATIO during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.
  89. // @User: Advanced
  90. AP_GROUPINFO("_AUTOCAL", 5, AP_Airspeed, param[0].autocal, 0),
  91. // @Param: _TUBE_ORDER
  92. // @DisplayName: Control pitot tube order
  93. // @Description: Changes the pitot tube order to specify the dynamic pressure side of the sensor. Accepts either if set to 2. Accepts only one side if set to 0 or 1 and can help detect excessive pressure on the static port without indicating positive airspeed.
  94. // @User: Advanced
  95. AP_GROUPINFO("_TUBE_ORDER", 6, AP_Airspeed, param[0].tube_order, 2),
  96. // @Param: _SKIP_CAL
  97. // @DisplayName: Skip airspeed calibration on startup
  98. // @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
  99. // @Values: 0:Disable,1:Enable
  100. // @User: Advanced
  101. AP_GROUPINFO("_SKIP_CAL", 7, AP_Airspeed, param[0].skip_cal, 0),
  102. // @Param: _PSI_RANGE
  103. // @DisplayName: The PSI range of the device
  104. // @Description: This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
  105. // @User: Advanced
  106. AP_GROUPINFO("_PSI_RANGE", 8, AP_Airspeed, param[0].psi_range, PSI_RANGE_DEFAULT),
  107. // @Param: _BUS
  108. // @DisplayName: Airspeed I2C bus
  109. // @Description: Bus number of the I2C bus where the airspeed sensor is connected
  110. // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxillary)
  111. // @User: Advanced
  112. AP_GROUPINFO("_BUS", 9, AP_Airspeed, param[0].bus, 1),
  113. // @Param: _PRIMARY
  114. // @DisplayName: Primary airspeed sensor
  115. // @Description: This selects which airspeed sensor will be the primary if multiple sensors are found
  116. // @Values: 0:FirstSensor,1:2ndSensor
  117. // @User: Advanced
  118. AP_GROUPINFO("_PRIMARY", 10, AP_Airspeed, primary_sensor, 0),
  119. // @Param: _OPTIONS
  120. // @DisplayName: Airspeed options bitmask
  121. // @Description: Bitmask of options to use with airspeed.
  122. // @Bitmask: 0:Disable on sensor failure,1:Re-enable on sensor recovery
  123. // @User: Advanced
  124. AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, 0),
  125. // @Param: 2_TYPE
  126. // @DisplayName: Second Airspeed type
  127. // @Description: Type of 2nd airspeed sensor
  128. // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:UAVCAN,9:I2C-DLVR-10in
  129. // @User: Standard
  130. AP_GROUPINFO_FLAGS("2_TYPE", 11, AP_Airspeed, param[1].type, 0, AP_PARAM_FLAG_ENABLE),
  131. // @Param: 2_USE
  132. // @DisplayName: Enable use of 2nd airspeed sensor
  133. // @Description: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller
  134. // @Values: 0:Don't Use,1:use,2:UseWhenZeroThrottle
  135. // @User: Standard
  136. AP_GROUPINFO("2_USE", 12, AP_Airspeed, param[1].use, 0),
  137. // @Param: 2_OFFSET
  138. // @DisplayName: Airspeed offset for 2nd airspeed sensor
  139. // @Description: Airspeed calibration offset
  140. // @Increment: 0.1
  141. // @User: Advanced
  142. AP_GROUPINFO("2_OFFSET", 13, AP_Airspeed, param[1].offset, 0),
  143. // @Param: 2_RATIO
  144. // @DisplayName: Airspeed ratio for 2nd airspeed sensor
  145. // @Description: Airspeed calibration ratio
  146. // @Increment: 0.1
  147. // @User: Advanced
  148. AP_GROUPINFO("2_RATIO", 14, AP_Airspeed, param[1].ratio, 2),
  149. // @Param: 2_PIN
  150. // @DisplayName: Airspeed pin for 2nd airspeed sensor
  151. // @Description: Pin number indicating location of analog airspeed sensors. Pixhawk/Cube if set to 15.
  152. // @User: Advanced
  153. AP_GROUPINFO("2_PIN", 15, AP_Airspeed, param[1].pin, 0),
  154. // @Param: 2_AUTOCAL
  155. // @DisplayName: Automatic airspeed ratio calibration for 2nd airspeed sensor
  156. // @Description: If this is enabled then the autopilot will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended.
  157. // @User: Advanced
  158. AP_GROUPINFO("2_AUTOCAL", 16, AP_Airspeed, param[1].autocal, 0),
  159. // @Param: 2_TUBE_ORDR
  160. // @DisplayName: Control pitot tube order of 2nd airspeed sensor
  161. // @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the top connector on the sensor needs to be the dynamic pressure. If set to 1 then the bottom connector needs to be the dynamic pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft it receiving excessive pressure on the static port, which would otherwise be seen as a positive airspeed.
  162. // @User: Advanced
  163. AP_GROUPINFO("2_TUBE_ORDR", 17, AP_Airspeed, param[1].tube_order, 2),
  164. // @Param: 2_SKIP_CAL
  165. // @DisplayName: Skip airspeed calibration on startup for 2nd sensor
  166. // @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.
  167. // @Values: 0:Disable,1:Enable
  168. // @User: Advanced
  169. AP_GROUPINFO("2_SKIP_CAL", 18, AP_Airspeed, param[1].skip_cal, 0),
  170. // @Param: 2_PSI_RANGE
  171. // @DisplayName: The PSI range of the device for 2nd sensor
  172. // @Description: This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device
  173. // @User: Advanced
  174. AP_GROUPINFO("2_PSI_RANGE", 19, AP_Airspeed, param[1].psi_range, PSI_RANGE_DEFAULT),
  175. // @Param: 2_BUS
  176. // @DisplayName: Airspeed I2C bus for 2nd sensor
  177. // @Description: The bus number of the I2C bus to look for the sensor on
  178. // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxillary)
  179. // @User: Advanced
  180. AP_GROUPINFO("2_BUS", 20, AP_Airspeed, param[1].bus, 1),
  181. // Note that 21 is used above by the _OPTIONS parameter. Do not use 21.
  182. AP_GROUPEND
  183. };
  184. /*
  185. this scaling factor converts from the old system where we used a
  186. 0 to 4095 raw ADC value for 0-5V to the new system which gets the
  187. voltage in volts directly from the ADC driver
  188. */
  189. #define SCALING_OLD_CALIBRATION 819 // 4095/5
  190. AP_Airspeed::AP_Airspeed()
  191. {
  192. AP_Param::setup_object_defaults(this, var_info);
  193. if (_singleton != nullptr) {
  194. AP_HAL::panic("AP_Airspeed must be singleton");
  195. }
  196. _singleton = this;
  197. }
  198. void AP_Airspeed::init()
  199. {
  200. // cope with upgrade from old system
  201. if (param[0].pin.load() && param[0].pin.get() != 65) {
  202. param[0].type.set_default(TYPE_ANALOG);
  203. }
  204. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  205. state[i].calibration.init(param[i].ratio);
  206. state[i].last_saved_ratio = param[i].ratio;
  207. // Set the enable automatically to false and set the probability that the airspeed is healhy to start with
  208. state[i].failures.health_probability = 1.0f;
  209. switch ((enum airspeed_type)param[i].type.get()) {
  210. case TYPE_NONE:
  211. // nothing to do
  212. break;
  213. case TYPE_I2C_MS4525:
  214. sensor[i] = new AP_Airspeed_MS4525(*this, i);
  215. break;
  216. case TYPE_ANALOG:
  217. sensor[i] = new AP_Airspeed_Analog(*this, i);
  218. break;
  219. case TYPE_I2C_MS5525:
  220. sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);
  221. break;
  222. case TYPE_I2C_MS5525_ADDRESS_1:
  223. sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1);
  224. break;
  225. case TYPE_I2C_MS5525_ADDRESS_2:
  226. sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2);
  227. break;
  228. case TYPE_I2C_SDP3X:
  229. sensor[i] = new AP_Airspeed_SDP3X(*this, i);
  230. break;
  231. case TYPE_I2C_DLVR_5IN:
  232. #if !HAL_MINIMIZE_FEATURES
  233. sensor[i] = new AP_Airspeed_DLVR(*this, i, 5);
  234. #endif // !HAL_MINIMIZE_FEATURES
  235. break;
  236. case TYPE_I2C_DLVR_10IN:
  237. #if !HAL_MINIMIZE_FEATURES
  238. sensor[i] = new AP_Airspeed_DLVR(*this, i, 10);
  239. #endif // !HAL_MINIMIZE_FEATURES
  240. break;
  241. case TYPE_UAVCAN:
  242. #if HAL_WITH_UAVCAN
  243. sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i);
  244. #endif
  245. break;
  246. }
  247. if (sensor[i] && !sensor[i]->init()) {
  248. gcs().send_text(MAV_SEVERITY_INFO, "Airspeed %u init failed", i + 1);
  249. delete sensor[i];
  250. sensor[i] = nullptr;
  251. }
  252. }
  253. }
  254. // read the airspeed sensor
  255. float AP_Airspeed::get_pressure(uint8_t i)
  256. {
  257. if (!enabled(i)) {
  258. return 0;
  259. }
  260. if (state[i].hil_set) {
  261. state[i].healthy = true;
  262. return state[i].hil_pressure;
  263. }
  264. float pressure = 0;
  265. if (sensor[i]) {
  266. state[i].healthy = sensor[i]->get_differential_pressure(pressure);
  267. }
  268. return pressure;
  269. }
  270. // get a temperature reading if possible
  271. bool AP_Airspeed::get_temperature(uint8_t i, float &temperature)
  272. {
  273. if (!enabled(i)) {
  274. return false;
  275. }
  276. if (sensor[i]) {
  277. return sensor[i]->get_temperature(temperature);
  278. }
  279. return false;
  280. }
  281. // calibrate the zero offset for the airspeed. This must be called at
  282. // least once before the get_airspeed() interface can be used
  283. void AP_Airspeed::calibrate(bool in_startup)
  284. {
  285. if (hal.util->was_watchdog_reset()) {
  286. gcs().send_text(MAV_SEVERITY_INFO,"Airspeed: skipping cal");
  287. return;
  288. }
  289. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  290. if (!enabled(i)) {
  291. continue;
  292. }
  293. if (state[i].use_zero_offset) {
  294. param[i].offset.set(0);
  295. continue;
  296. }
  297. if (in_startup && param[i].skip_cal) {
  298. continue;
  299. }
  300. state[i].cal.start_ms = AP_HAL::millis();
  301. state[i].cal.count = 0;
  302. state[i].cal.sum = 0;
  303. state[i].cal.read_count = 0;
  304. }
  305. gcs().send_text(MAV_SEVERITY_INFO,"Airspeed calibration started");
  306. }
  307. /*
  308. update async airspeed zero offset calibration
  309. */
  310. void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
  311. {
  312. if (!enabled(i) || state[i].cal.start_ms == 0) {
  313. return;
  314. }
  315. // consider calibration complete when we have at least 15 samples
  316. // over at least 1 second
  317. if (AP_HAL::millis() - state[i].cal.start_ms >= 1000 &&
  318. state[i].cal.read_count > 15) {
  319. if (state[i].cal.count == 0) {
  320. gcs().send_text(MAV_SEVERITY_INFO, "Airspeed %u unhealthy", i + 1);
  321. } else {
  322. gcs().send_text(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1);
  323. param[i].offset.set_and_save(state[i].cal.sum / state[i].cal.count);
  324. }
  325. state[i].cal.start_ms = 0;
  326. return;
  327. }
  328. // we discard the first 5 samples
  329. if (state[i].healthy && state[i].cal.read_count > 5) {
  330. state[i].cal.sum += raw_pressure;
  331. state[i].cal.count++;
  332. }
  333. state[i].cal.read_count++;
  334. }
  335. // read one airspeed sensor
  336. void AP_Airspeed::read(uint8_t i)
  337. {
  338. float airspeed_pressure;
  339. if (!enabled(i) || !sensor[i]) {
  340. return;
  341. }
  342. bool prev_healthy = state[i].healthy;
  343. float raw_pressure = get_pressure(i);
  344. if (state[i].cal.start_ms != 0) {
  345. update_calibration(i, raw_pressure);
  346. }
  347. airspeed_pressure = raw_pressure - param[i].offset;
  348. // remember raw pressure for logging
  349. state[i].corrected_pressure = airspeed_pressure;
  350. // filter before clamping positive
  351. if (!prev_healthy) {
  352. // if the previous state was not healthy then we should not
  353. // use an IIR filter, otherwise a bad reading will last for
  354. // some time after the sensor becomees healthy again
  355. state[i].filtered_pressure = airspeed_pressure;
  356. } else {
  357. state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;
  358. }
  359. /*
  360. we support different pitot tube setups so user can choose if
  361. they want to be able to detect pressure on the static port
  362. */
  363. switch ((enum pitot_tube_order)param[i].tube_order.get()) {
  364. case PITOT_TUBE_ORDER_NEGATIVE:
  365. state[i].last_pressure = -airspeed_pressure;
  366. state[i].raw_airspeed = sqrtf(MAX(-airspeed_pressure, 0) * param[i].ratio);
  367. state[i].airspeed = sqrtf(MAX(-state[i].filtered_pressure, 0) * param[i].ratio);
  368. break;
  369. case PITOT_TUBE_ORDER_POSITIVE:
  370. state[i].last_pressure = airspeed_pressure;
  371. state[i].raw_airspeed = sqrtf(MAX(airspeed_pressure, 0) * param[i].ratio);
  372. state[i].airspeed = sqrtf(MAX(state[i].filtered_pressure, 0) * param[i].ratio);
  373. break;
  374. case PITOT_TUBE_ORDER_AUTO:
  375. default:
  376. state[i].last_pressure = fabsf(airspeed_pressure);
  377. state[i].raw_airspeed = sqrtf(fabsf(airspeed_pressure) * param[i].ratio);
  378. state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);
  379. break;
  380. }
  381. if (state[i].last_pressure < -32) {
  382. // we're reading more than about -8m/s. The user probably has
  383. // the ports the wrong way around
  384. state[i].healthy = false;
  385. }
  386. state[i].last_update_ms = AP_HAL::millis();
  387. }
  388. // read all airspeed sensors
  389. void AP_Airspeed::update(bool log)
  390. {
  391. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  392. read(i);
  393. }
  394. #if 1
  395. // debugging until we get MAVLink support for 2nd airspeed sensor
  396. if (enabled(1)) {
  397. gcs().send_named_float("AS2", get_airspeed(1));
  398. }
  399. #endif
  400. // setup primary
  401. if (healthy(primary_sensor.get())) {
  402. primary = primary_sensor.get();
  403. } else {
  404. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  405. if (healthy(i)) {
  406. primary = i;
  407. break;
  408. }
  409. }
  410. }
  411. check_sensor_failures();
  412. if (log) {
  413. Log_Airspeed();
  414. }
  415. }
  416. void AP_Airspeed::Log_Airspeed()
  417. {
  418. const uint64_t now = AP_HAL::micros64();
  419. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  420. if (!enabled(i)) {
  421. continue;
  422. }
  423. float temperature;
  424. if (!get_temperature(i, temperature)) {
  425. temperature = 0;
  426. }
  427. struct log_AIRSPEED pkt = {
  428. LOG_PACKET_HEADER_INIT(i==0?LOG_ARSP_MSG:LOG_ASP2_MSG),
  429. time_us : now,
  430. airspeed : get_raw_airspeed(i),
  431. diffpressure : get_differential_pressure(i),
  432. temperature : (int16_t)(temperature * 100.0f),
  433. rawpressure : get_corrected_pressure(i),
  434. offset : get_offset(i),
  435. use : use(i),
  436. healthy : healthy(i),
  437. health_prob : get_health_failure_probability(i),
  438. primary : get_primary()
  439. };
  440. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  441. }
  442. }
  443. void AP_Airspeed::setHIL(float airspeed, float diff_pressure, float temperature)
  444. {
  445. state[0].raw_airspeed = airspeed;
  446. state[0].airspeed = airspeed;
  447. state[0].last_pressure = diff_pressure;
  448. state[0].last_update_ms = AP_HAL::millis();
  449. state[0].hil_pressure = diff_pressure;
  450. state[0].hil_set = true;
  451. state[0].healthy = true;
  452. }
  453. bool AP_Airspeed::use(uint8_t i) const
  454. {
  455. if (!enabled(i) || !param[i].use) {
  456. return false;
  457. }
  458. if (param[i].use == 2 && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) != 0) {
  459. // special case for gliders with airspeed sensors behind the
  460. // propeller. Allow airspeed to be disabled when throttle is
  461. // running
  462. return false;
  463. }
  464. return true;
  465. }
  466. /*
  467. return true if all enabled sensors are healthy
  468. */
  469. bool AP_Airspeed::all_healthy(void) const
  470. {
  471. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  472. if (enabled(i) && !healthy(i)) {
  473. return false;
  474. }
  475. }
  476. return true;
  477. }
  478. // singleton instance
  479. AP_Airspeed *AP_Airspeed::_singleton;
  480. namespace AP {
  481. AP_Airspeed *airspeed()
  482. {
  483. return AP_Airspeed::get_singleton();
  484. }
  485. };