AP_Airspeed_Health.cpp 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  1. #include "AP_Airspeed.h"
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <AP_GPS/AP_GPS.h>
  5. #include <AP_Math/AP_Math.h>
  6. #include <GCS_MAVLink/GCS.h>
  7. void AP_Airspeed::check_sensor_failures()
  8. {
  9. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  10. check_sensor_ahrs_wind_max_failures(i);
  11. }
  12. }
  13. void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)
  14. {
  15. const uint32_t now_ms = AP_HAL::millis();
  16. if ((now_ms - state[i].failures.last_check_ms) <= 200) {
  17. // slow the checking rate
  18. return;
  19. }
  20. const float aspeed = get_airspeed();
  21. const float wind_max = AP::ahrs().get_max_wind();
  22. if (aspeed <= 0 || wind_max <= 0) {
  23. // invalid estimates
  24. return;
  25. }
  26. state[i].failures.last_check_ms = now_ms;
  27. // update state[i].failures.health_probability via LowPassFilter
  28. float speed_accuracy;
  29. const AP_GPS &gps = AP::gps();
  30. if (gps.speed_accuracy(speed_accuracy)) {
  31. const float gnd_speed = gps.ground_speed();
  32. if (aspeed > (gnd_speed + wind_max) || aspeed < (gnd_speed - wind_max)) {
  33. // bad, decay fast
  34. const float probability_coeff = 0.90f;
  35. //state[i].failures.health_probability = probability_coeff*state[i].failures.health_probability + (1.0f-probability_coeff)*0.0f;
  36. state[i].failures.health_probability = probability_coeff*state[i].failures.health_probability; // equivalent
  37. } else if (aspeed < (gnd_speed + wind_max) && aspeed > (gnd_speed - wind_max)) {
  38. // good, grow slow
  39. const float probability_coeff = 0.98f;
  40. state[i].failures.health_probability = probability_coeff*state[i].failures.health_probability + (1.0f-probability_coeff)*1.0f;
  41. }
  42. }
  43. // Now check if we need to disable or enable the sensor
  44. // here are some probability thresholds
  45. static const float DISABLE_PROB_THRESH_CRIT = 0.1f;
  46. static const float DISABLE_PROB_THRESH_WARN = 0.5f;
  47. static const float RE_ENABLE_PROB_THRESH_OK = 0.95f;
  48. // if "disable" option is allowed and sensor is enabled
  49. if (param[i].use > 0 && (AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE & _options)) {
  50. // and is probably not healthy
  51. if (state[i].failures.health_probability < DISABLE_PROB_THRESH_CRIT) {
  52. gcs().send_text(MAV_SEVERITY_ERROR, "Airspeed sensor %d failure. Disabling", i+1);
  53. state[i].failures.param_use_backup = param[i].use;
  54. param[i].use.set_and_notify(0);
  55. state[i].healthy = false;
  56. // and is probably getting close to not healthy
  57. } else if ((state[i].failures.health_probability < DISABLE_PROB_THRESH_WARN) && !state[i].failures.has_warned) {
  58. state[i].failures.has_warned = true;
  59. gcs().send_text(MAV_SEVERITY_WARNING, "Airspeed sensor %d warning", i+1);
  60. } else if (state[i].failures.health_probability > RE_ENABLE_PROB_THRESH_OK) {
  61. state[i].failures.has_warned = false;
  62. }
  63. // if Re-Enable options is allowed, and sensor is disabled but was previously enabled, and is probably healthy
  64. } else if (param[i].use == 0 &&
  65. (AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE & _options) &&
  66. state[i].failures.param_use_backup > 0 &&
  67. state[i].failures.health_probability > RE_ENABLE_PROB_THRESH_OK) {
  68. gcs().send_text(MAV_SEVERITY_NOTICE, "Airspeed sensor %d now OK. Re-enabled", i+1);
  69. param[i].use.set_and_notify(state[i].failures.param_use_backup); // resume
  70. state[i].failures.param_use_backup = -1; // set to invalid so we don't use it
  71. state[i].failures.has_warned = false;
  72. }
  73. }