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/ArduSub/failsafe.cpp
Views: 1798
#include "Sub.h"12/*3* failsafe.cpp4* Failsafe checks and actions5*/67static bool failsafe_enabled = false;8static uint16_t failsafe_last_ticks;9static uint32_t failsafe_last_timestamp;10static bool in_failsafe;1112// Enable mainloop lockup failsafe13void Sub::mainloop_failsafe_enable()14{15failsafe_enabled = true;16failsafe_last_timestamp = AP_HAL::micros();17}1819// Disable mainloop lockup failsafe20// Used when we know we are going to delay the mainloop significantly.21void Sub::mainloop_failsafe_disable()22{23failsafe_enabled = false;24}2526// This function is called from the core timer interrupt at 1kHz.27// This checks that the mainloop is running, and has not locked up.28void Sub::mainloop_failsafe_check()29{30uint32_t tnow = AP_HAL::micros();3132const uint16_t ticks = scheduler.ticks();33if (ticks != failsafe_last_ticks) {34// the main loop is running, all is OK35failsafe_last_ticks = ticks;36failsafe_last_timestamp = tnow;37if (in_failsafe) {38in_failsafe = false;39LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_RESOLVED);40}41return;42}4344if (!in_failsafe && failsafe_enabled && tnow - failsafe_last_timestamp > 2000000) {45// motors are running but we have gone 2 second since the46// main loop ran. That means we're in trouble and should47// disarm the motors.48in_failsafe = true;49// reduce motors to minimum (we do not immediately disarm because we want to log the failure)50if (motors.armed()) {51motors.output_min();52}53LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_OCCURRED);54}5556if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) {57// disarm motors every second58failsafe_last_timestamp = tnow;59if (motors.armed()) {60motors.armed(false);61motors.output();62}63}64}6566void Sub::failsafe_sensors_check()67{68if (!ap.depth_sensor_present) {69return;70}7172// We need a depth sensor to do any sort of auto z control73if (sensor_health.depth) {74if (failsafe.sensor_health) {75LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::ERROR_RESOLVED);76failsafe.sensor_health = false;77}78return;79}8081// only report once82if (failsafe.sensor_health) {83return;84}8586failsafe.sensor_health = true;87gcs().send_text(MAV_SEVERITY_CRITICAL, "Depth sensor error!");88LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::BAD_DEPTH);8990if (control_mode == Mode::Number::ALT_HOLD || control_mode == Mode::Number::SURFACE || sub.flightmode->requires_GPS()) {91// This should always succeed92if (!set_mode(Mode::Number::MANUAL, ModeReason::BAD_DEPTH)) {93// We should never get here94arming.disarm(AP_Arming::Method::BADFLOWOFCONTROL);95}96}97}9899void Sub::failsafe_ekf_check()100{101static uint32_t last_ekf_good_ms = 0;102103if (g.fs_ekf_action == FS_EKF_ACTION_DISABLED) {104last_ekf_good_ms = AP_HAL::millis();105failsafe.ekf = false;106AP_Notify::flags.ekf_bad = false;107return;108}109110float posVar, hgtVar, tasVar;111Vector3f magVar;112float compass_variance;113float vel_variance;114ahrs.get_variances(vel_variance, posVar, hgtVar, magVar, tasVar);115compass_variance = magVar.length();116117if (compass_variance < g.fs_ekf_thresh && vel_variance < g.fs_ekf_thresh) {118last_ekf_good_ms = AP_HAL::millis();119failsafe.ekf = false;120AP_Notify::flags.ekf_bad = false;121return;122}123124// Bad EKF for 2 solid seconds triggers failsafe125if (AP_HAL::millis() < last_ekf_good_ms + 2000) {126failsafe.ekf = false;127AP_Notify::flags.ekf_bad = false;128return;129}130131// Only trigger failsafe once132if (failsafe.ekf) {133return;134}135136failsafe.ekf = true;137AP_Notify::flags.ekf_bad = true;138139LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);140141if (AP_HAL::millis() > failsafe.last_ekf_warn_ms + 20000) {142failsafe.last_ekf_warn_ms = AP_HAL::millis();143gcs().send_text(MAV_SEVERITY_WARNING, "EKF bad");144}145146if (g.fs_ekf_action == FS_EKF_ACTION_DISARM) {147arming.disarm(AP_Arming::Method::EKFFAILSAFE);148}149}150151// Battery failsafe handler152void Sub::handle_battery_failsafe(const char* type_str, const int8_t action)153{154LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED);155156switch((Failsafe_Action)action) {157case Failsafe_Action_Surface:158set_mode(Mode::Number::SURFACE, ModeReason::BATTERY_FAILSAFE);159break;160case Failsafe_Action_Disarm:161arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);162break;163case Failsafe_Action_Warn:164case Failsafe_Action_None:165break;166}167}168169// Make sure that we are receiving pilot input at an appropriate interval170void Sub::failsafe_pilot_input_check()171{172#if CONFIG_HAL_BOARD != HAL_BOARD_SITL173if (g.failsafe_pilot_input == FS_PILOT_INPUT_DISABLED) {174failsafe.pilot_input = false;175return;176}177178if (AP_HAL::millis() < failsafe.last_pilot_input_ms + g.failsafe_pilot_input_timeout * 1000.0f) {179failsafe.pilot_input = false; // We've received an update from the pilot within the timeout period180return;181}182183if (failsafe.pilot_input) {184return; // only act once185}186187failsafe.pilot_input = true;188189LOGGER_WRITE_ERROR(LogErrorSubsystem::PILOT_INPUT, LogErrorCode::FAILSAFE_OCCURRED);190gcs().send_text(MAV_SEVERITY_CRITICAL, "Lost manual control");191192set_neutral_controls();193194if(g.failsafe_pilot_input == FS_PILOT_INPUT_DISARM) {195arming.disarm(AP_Arming::Method::PILOT_INPUT_FAILSAFE);196}197#endif198}199200// Internal pressure failsafe check201// Check if the internal pressure of the watertight electronics enclosure202// has exceeded the maximum specified by the FS_PRESS_MAX parameter203void Sub::failsafe_internal_pressure_check()204{205206if (g.failsafe_pressure == FS_PRESS_DISABLED) {207return; // Nothing to do208}209210uint32_t tnow = AP_HAL::millis();211static uint32_t last_pressure_warn_ms;212static uint32_t last_pressure_good_ms;213if (barometer.get_pressure(0) < g.failsafe_pressure_max) {214last_pressure_good_ms = tnow;215last_pressure_warn_ms = tnow;216failsafe.internal_pressure = false;217return;218}219220// 2 seconds with no readings below threshold triggers failsafe221if (tnow > last_pressure_good_ms + 2000) {222failsafe.internal_pressure = true;223}224225// Warn every 30 seconds226if (failsafe.internal_pressure && tnow > last_pressure_warn_ms + 30000) {227last_pressure_warn_ms = tnow;228gcs().send_text(MAV_SEVERITY_WARNING, "Internal pressure critical!");229}230}231232// Internal temperature failsafe check233// Check if the internal temperature of the watertight electronics enclosure234// has exceeded the maximum specified by the FS_TEMP_MAX parameter235void Sub::failsafe_internal_temperature_check()236{237238if (g.failsafe_temperature == FS_TEMP_DISABLED) {239return; // Nothing to do240}241242uint32_t tnow = AP_HAL::millis();243static uint32_t last_temperature_warn_ms;244static uint32_t last_temperature_good_ms;245if (barometer.get_temperature(0) < g.failsafe_temperature_max) {246last_temperature_good_ms = tnow;247last_temperature_warn_ms = tnow;248failsafe.internal_temperature = false;249return;250}251252// 2 seconds with no readings below threshold triggers failsafe253if (tnow > last_temperature_good_ms + 2000) {254failsafe.internal_temperature = true;255}256257// Warn every 30 seconds258if (failsafe.internal_temperature && tnow > last_temperature_warn_ms + 30000) {259last_temperature_warn_ms = tnow;260gcs().send_text(MAV_SEVERITY_WARNING, "Internal temperature critical!");261}262}263264// Check if we are leaking and perform appropriate action265void Sub::failsafe_leak_check()266{267bool status = leak_detector.get_status();268269// Do nothing if we are dry, or if leak failsafe action is disabled270if (status == false || g.failsafe_leak == FS_LEAK_DISABLED) {271if (failsafe.leak) {272LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_RESOLVED);273}274AP_Notify::flags.leak_detected = false;275failsafe.leak = false;276return;277}278279AP_Notify::flags.leak_detected = status;280281uint32_t tnow = AP_HAL::millis();282283// We have a leak284// Always send a warning every 20 seconds285if (tnow > failsafe.last_leak_warn_ms + 20000) {286failsafe.last_leak_warn_ms = tnow;287gcs().send_text(MAV_SEVERITY_CRITICAL, "Leak Detected");288}289290// Do nothing if we have already triggered the failsafe action, or if the motors are disarmed291if (failsafe.leak) {292return;293}294295failsafe.leak = true;296297LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_OCCURRED);298299// Handle failsafe action300if (failsafe.leak && g.failsafe_leak == FS_LEAK_SURFACE && motors.armed()) {301set_mode(Mode::Number::SURFACE, ModeReason::LEAK_FAILSAFE);302}303}304305// failsafe_gcs_check - check for ground station failsafe306void Sub::failsafe_gcs_check()307{308// return immediately if we have never had contact with a gcs, or if gcs failsafe action is disabled309// this also checks to see if we have a GCS failsafe active, if we do, then must continue to process the logic for recovery from this state.310if (!g.failsafe_gcs && g.failsafe_gcs == FS_GCS_DISABLED) {311return;312}313314const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();315if (gcs_last_seen_ms == 0) {316// we've never seen a GCS, so we don't failsafe if we stop seeing it317return;318}319320uint32_t tnow = AP_HAL::millis();321322// Check if we have gotten a GCS heartbeat recently (GCS sysid must match SYSID_MYGCS parameter)323const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g.failsafe_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));324if (tnow - gcs_last_seen_ms < gcs_timeout_ms) {325// Log event if we are recovering from previous gcs failsafe326if (failsafe.gcs) {327LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED);328}329failsafe.gcs = false;330return;331}332333//////////////////////////////334// GCS heartbeat has timed out335//////////////////////////////336337// Send a warning every 30 seconds338if (tnow - failsafe.last_gcs_warn_ms > 30000) {339failsafe.last_gcs_warn_ms = tnow;340gcs().send_text(MAV_SEVERITY_WARNING, "MYGCS: %u, heartbeat lost", g.sysid_my_gcs.get());341}342343// do nothing if we have already triggered the failsafe action, or if the motors are disarmed344if (failsafe.gcs || !motors.armed()) {345return;346}347348failsafe.gcs = true;349LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED);350351// handle failsafe action352if (g.failsafe_gcs == FS_GCS_DISARM) {353arming.disarm(AP_Arming::Method::GCSFAILSAFE);354} else if (g.failsafe_gcs == FS_GCS_HOLD && motors.armed()) {355if (!set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_FAILSAFE)) {356arming.disarm(AP_Arming::Method::GCS_FAILSAFE_HOLDFAILED);357}358} else if (g.failsafe_gcs == FS_GCS_SURFACE && motors.armed()) {359if (!set_mode(Mode::Number::SURFACE, ModeReason::GCS_FAILSAFE)) {360arming.disarm(AP_Arming::Method::GCS_FAILSAFE_SURFACEFAILED);361}362}363}364365#define CRASH_CHECK_TRIGGER_MS 2000 // 2 seconds inverted indicates a crash366#define CRASH_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees beyond angle max is signal we are inverted367368// Check for a crash369// The vehicle is considered crashed if the angle error exceeds a specified limit for more than 2 seconds370void Sub::failsafe_crash_check()371{372static uint32_t last_crash_check_pass_ms;373uint32_t tnow = AP_HAL::millis();374375// return immediately if disarmed, or crash checking disabled376if (!motors.armed() || g.fs_crash_check == FS_CRASH_DISABLED) {377last_crash_check_pass_ms = tnow;378failsafe.crash = false;379return;380}381382// return immediately if we are not in an angle stabilized flight mode383if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::MANUAL) {384last_crash_check_pass_ms = tnow;385failsafe.crash = false;386return;387}388389// check for angle error over 30 degrees390const float angle_error = attitude_control.get_att_error_angle_deg();391if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {392last_crash_check_pass_ms = tnow;393failsafe.crash = false;394return;395}396397if (tnow < last_crash_check_pass_ms + CRASH_CHECK_TRIGGER_MS) {398return;399}400401// Conditions met, we are in failsafe402403// Send warning to GCS404if (tnow > failsafe.last_crash_warn_ms + 20000) {405failsafe.last_crash_warn_ms = tnow;406gcs().send_text(MAV_SEVERITY_WARNING,"Crash detected");407}408409// Only perform failsafe action once410if (failsafe.crash) {411return;412}413414failsafe.crash = true;415LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);416417// disarm motors418if (g.fs_crash_check == FS_CRASH_DISARM) {419arming.disarm(AP_Arming::Method::CRASH);420}421}422423// executes terrain failsafe if data is missing for longer than a few seconds424// missing_data should be set to true if the vehicle failed to navigate because of missing data, false if navigation is proceeding successfully425void Sub::failsafe_terrain_check()426{427// trigger with 5 seconds of failures while in AUTO mode428bool valid_mode = (control_mode == Mode::Number::AUTO || control_mode == Mode::Number::GUIDED);429bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;430bool trigger_event = valid_mode && timeout;431432// check for clearing of event433if (trigger_event != failsafe.terrain) {434if (trigger_event) {435gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe terrain triggered");436failsafe_terrain_on_event();437} else {438LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED);439failsafe.terrain = false;440}441}442}443444// This gets called if mission items are in ALT_ABOVE_TERRAIN frame445// Terrain failure occurs when terrain data is not found, or rangefinder is not enabled or healthy446// set terrain data status (found or not found)447void Sub::failsafe_terrain_set_status(bool data_ok)448{449uint32_t now = AP_HAL::millis();450451// record time of first and latest failures (i.e. duration of failures)452if (!data_ok) {453failsafe.terrain_last_failure_ms = now;454if (failsafe.terrain_first_failure_ms == 0) {455failsafe.terrain_first_failure_ms = now;456}457} else {458// failures cleared after 0.1 seconds of persistent successes459if (now - failsafe.terrain_last_failure_ms > 100) {460failsafe.terrain_last_failure_ms = 0;461failsafe.terrain_first_failure_ms = 0;462}463}464}465466// terrain failsafe action467void Sub::failsafe_terrain_on_event()468{469failsafe.terrain = true;470LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED);471472// If rangefinder is enabled, we can recover from this failsafe473if (!rangefinder_state.enabled || !sub.mode_auto.auto_terrain_recover_start()) {474failsafe_terrain_act();475}476477478}479480// Recovery failed, take action481void Sub::failsafe_terrain_act()482{483switch (g.failsafe_terrain) {484case FS_TERRAIN_HOLD:485if (!set_mode(Mode::Number::POSHOLD, ModeReason::TERRAIN_FAILSAFE)) {486set_mode(Mode::Number::ALT_HOLD, ModeReason::TERRAIN_FAILSAFE);487}488AP_Notify::events.failsafe_mode_change = 1;489break;490491case FS_TERRAIN_SURFACE:492set_mode(Mode::Number::SURFACE, ModeReason::TERRAIN_FAILSAFE);493AP_Notify::events.failsafe_mode_change = 1;494break;495496case FS_TERRAIN_DISARM:497default:498arming.disarm(AP_Arming::Method::TERRAINFAILSAFE);499}500}501502503