Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_Health.cpp
Views: 1798
#include "AP_Airspeed_config.h"12#if AP_AIRSPEED_ENABLED34#include "AP_Airspeed.h"56#include <AP_Common/AP_Common.h>7#include <AP_GPS/AP_GPS.h>8#include <AP_Math/AP_Math.h>9#include <GCS_MAVLink/GCS.h>10#include <AP_AHRS/AP_AHRS.h>11#include <AP_Logger/AP_Logger.h>1213void AP_Airspeed::check_sensor_failures()14{15#ifndef HAL_BUILD_AP_PERIPH16for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {17check_sensor_ahrs_wind_max_failures(i);18}19#endif20}2122void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i)23{24#ifndef HAL_BUILD_AP_PERIPH25const uint32_t now_ms = AP_HAL::millis();26if ((now_ms - state[i].failures.last_check_ms) <= 200) {27// slow the checking rate28return;29}30state[i].failures.last_check_ms = now_ms;3132if (!is_positive(_wind_max) && !is_positive(_wind_gate)) {33// nothing to do34return;35}3637if (state[i].airspeed <= 0) {38// invalid estimate39return;40}4142const AP_GPS &gps = AP::gps();43if (gps.status() < AP_GPS::GPS_Status::GPS_OK_FIX_3D) {44// GPS speed can't be trusted, re-enable airspeed as a fallback45if ((param[i].use == 0) && (state[i].failures.param_use_backup == 1)) {46GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Airspeed sensor %d, Re-enabled as GPS fall-back", i+1);47param[i].use.set_and_notify(state[i].failures.param_use_backup);48state[i].failures.param_use_backup = -1;49}50return;51}5253// check for airspeed consistent with wind and vehicle velocity using the EKF54uint32_t age_ms;55float innovation, innovationVariance;56if (AP::ahrs().airspeed_health_data(innovation, innovationVariance, age_ms) && age_ms < 1000 && is_positive(innovationVariance)) {57state[i].failures.test_ratio = fabsf(innovation) / safe_sqrt(innovationVariance);58} else {59state[i].failures.test_ratio = 0.0f;60}61bool data_is_inconsistent = false;62if (is_positive(_wind_gate) && (AP_Airspeed::OptionsMask::USE_EKF_CONSISTENCY & _options) != 0) {63float gate_size = MAX(_wind_gate, 0.0f);64if (param[i].use == 0) {65// require a smaller inconsistency for a disabled sensor to be declared consistent66gate_size *= 0.7f;67}68data_is_inconsistent = state[i].failures.test_ratio > gate_size;69}7071const auto gps_speed = gps.velocity().length();72const float speed_diff = fabsf(state[i].airspeed-gps_speed);73const bool data_is_implausible = is_positive(_wind_max) && speed_diff > _wind_max;74// update health_probability with LowPassFilter75if (data_is_implausible || data_is_inconsistent) {76// bad, decay fast77const float probability_coeff = 0.90f;78state[i].failures.health_probability = probability_coeff*state[i].failures.health_probability;7980} else if (!data_is_implausible && !data_is_inconsistent) {81// good, grow slow82const float probability_coeff = 0.98f;83state[i].failures.health_probability = probability_coeff*state[i].failures.health_probability + (1.0f-probability_coeff)*1.0f;84}8586// Now check if we need to disable or enable the sensor8788// here are some probability thresholds89static const float DISABLE_PROB_THRESH_CRIT = 0.1f;90static const float RE_ENABLE_PROB_THRESH_OK = 0.95f;9192if (param[i].use > 0) {93if (((AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE & _options) != 0) &&94(state[i].failures.health_probability < DISABLE_PROB_THRESH_CRIT)) {95// if "disable" option is allowed and sensor is enabled and is probably not healthy96GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed sensor %d failure. Disabling", i+1);97state[i].failures.param_use_backup = param[i].use;98param[i].use.set_and_notify(0);99state[i].healthy = false;100}101102// Warn if necessary103104// set warn to max if not set or larger than max105float wind_warn = _wind_warn;106if ((!is_positive(wind_warn) || (wind_warn > _wind_max)) && is_positive(_wind_max)) {107wind_warn = _wind_max;108}109110if (is_positive(wind_warn) && (speed_diff > wind_warn) && ((now_ms - state[i].failures.last_warn_ms) > 15000)) {111state[i].failures.last_warn_ms = now_ms;112GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %d warning %0.1fm/s air to gnd speed diff", i+1, speed_diff);113}114115// if Re-Enable options is allowed, and sensor is disabled but was previously enabled, and is probably healthy116} else if (((AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE & _options) != 0) &&117(state[i].failures.param_use_backup > 0) &&118(state[i].failures.health_probability > RE_ENABLE_PROB_THRESH_OK)) {119120GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Airspeed sensor %d now OK. Re-enabled", i+1);121param[i].use.set_and_notify(state[i].failures.param_use_backup); // resume122state[i].failures.param_use_backup = -1; // set to invalid so we don't use it123}124#endif // HAL_BUILD_AP_PERIPH125}126127#endif // AP_AIRSPEED_ENABLED128129130