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/ArduCopter/events.cpp
Views: 1798
#include "Copter.h"12/*3* This event will be called when the failsafe changes4* boolean failsafe reflects the current state5*/67bool Copter::failsafe_option(FailsafeOption opt) const8{9return (g2.fs_options & (uint32_t)opt);10}1112void Copter::failsafe_radio_on_event()13{14LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED);1516// set desired action based on FS_THR_ENABLE parameter17FailsafeAction desired_action;18switch (g.failsafe_throttle) {19case FS_THR_DISABLED:20desired_action = FailsafeAction::NONE;21break;22case FS_THR_ENABLED_ALWAYS_RTL:23case FS_THR_ENABLED_CONTINUE_MISSION:24desired_action = FailsafeAction::RTL;25break;26case FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL:27desired_action = FailsafeAction::SMARTRTL;28break;29case FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND:30desired_action = FailsafeAction::SMARTRTL_LAND;31break;32case FS_THR_ENABLED_ALWAYS_LAND:33desired_action = FailsafeAction::LAND;34break;35case FS_THR_ENABLED_AUTO_RTL_OR_RTL:36desired_action = FailsafeAction::AUTO_DO_LAND_START;37break;38case FS_THR_ENABLED_BRAKE_OR_LAND:39desired_action = FailsafeAction::BRAKE_LAND;40break;41default:42desired_action = FailsafeAction::LAND;43}4445// Conditions to deviate from FS_THR_ENABLE selection and send specific GCS warning46if (should_disarm_on_failsafe()) {47// should immediately disarm when we're on the ground48announce_failsafe("Radio", "Disarming");49arming.disarm(AP_Arming::Method::RADIOFAILSAFE);50desired_action = FailsafeAction::NONE;5152} else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) {53// Allow landing to continue when battery failsafe requires it (not a user option)54announce_failsafe("Radio + Battery", "Continuing Landing");55desired_action = FailsafeAction::LAND;5657} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) {58// Allow landing to continue when FS_OPTIONS is set to continue landing59announce_failsafe("Radio", "Continuing Landing");60desired_action = FailsafeAction::LAND;6162} else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::RC_CONTINUE_IF_AUTO)) {63// Allow mission to continue when FS_OPTIONS is set to continue mission64announce_failsafe("Radio", "Continuing Auto");65desired_action = FailsafeAction::NONE;6667} else if ((flightmode->in_guided_mode()) && failsafe_option(FailsafeOption::RC_CONTINUE_IF_GUIDED)) {68// Allow guided mode to continue when FS_OPTIONS is set to continue in guided mode69announce_failsafe("Radio", "Continuing Guided Mode");70desired_action = FailsafeAction::NONE;7172} else {73announce_failsafe("Radio");74}7576// Call the failsafe action handler77do_failsafe_action(desired_action, ModeReason::RADIO_FAILSAFE);78}7980// failsafe_off_event - respond to radio contact being regained81void Copter::failsafe_radio_off_event()82{83// no need to do anything except log the error as resolved84// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode85LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED);86gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared");87}8889void Copter::announce_failsafe(const char *type, const char *action_undertaken)90{91if (action_undertaken != nullptr) {92gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe - %s", type, action_undertaken);93} else {94gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe", type);95}96}9798void Copter::handle_battery_failsafe(const char *type_str, const int8_t action)99{100LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED);101102FailsafeAction desired_action = (FailsafeAction)action;103104// Conditions to deviate from BATT_FS_XXX_ACT parameter setting105if (should_disarm_on_failsafe()) {106// should immediately disarm when we're on the ground107arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);108desired_action = FailsafeAction::NONE;109announce_failsafe("Battery", "Disarming");110111} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING) && desired_action != FailsafeAction::NONE) {112// Allow landing to continue when FS_OPTIONS is set to continue when landing113desired_action = FailsafeAction::LAND;114announce_failsafe("Battery", "Continuing Landing");115} else {116announce_failsafe("Battery");117}118119// Battery FS options already use the Failsafe_Options enum. So use them directly.120do_failsafe_action(desired_action, ModeReason::BATTERY_FAILSAFE);121122}123124// failsafe_gcs_check - check for ground station failsafe125void Copter::failsafe_gcs_check()126{127// Bypass GCS failsafe checks if disabled or GCS never connected128if (g.failsafe_gcs == FS_GCS_DISABLED) {129return;130}131132const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();133if (gcs_last_seen_ms == 0) {134return;135}136137// calc time since last gcs update138// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs139const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;140const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));141142// Determine which event to trigger143if (last_gcs_update_ms < gcs_timeout_ms && failsafe.gcs) {144// Recovery from a GCS failsafe145set_failsafe_gcs(false);146failsafe_gcs_off_event();147148} else if (last_gcs_update_ms < gcs_timeout_ms && !failsafe.gcs) {149// No problem, do nothing150151} else if (last_gcs_update_ms > gcs_timeout_ms && failsafe.gcs) {152// Already in failsafe, do nothing153154} else if (last_gcs_update_ms > gcs_timeout_ms && !failsafe.gcs) {155// New GCS failsafe event, trigger events156set_failsafe_gcs(true);157failsafe_gcs_on_event();158}159}160161// failsafe_gcs_on_event - actions to take when GCS contact is lost162void Copter::failsafe_gcs_on_event(void)163{164LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED);165RC_Channels::clear_overrides();166167// convert the desired failsafe response to the FailsafeAction enum168FailsafeAction desired_action;169switch (g.failsafe_gcs) {170case FS_GCS_DISABLED:171desired_action = FailsafeAction::NONE;172break;173case FS_GCS_ENABLED_ALWAYS_RTL:174case FS_GCS_ENABLED_CONTINUE_MISSION:175desired_action = FailsafeAction::RTL;176break;177case FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL:178desired_action = FailsafeAction::SMARTRTL;179break;180case FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND:181desired_action = FailsafeAction::SMARTRTL_LAND;182break;183case FS_GCS_ENABLED_ALWAYS_LAND:184desired_action = FailsafeAction::LAND;185break;186case FS_GCS_ENABLED_AUTO_RTL_OR_RTL:187desired_action = FailsafeAction::AUTO_DO_LAND_START;188break;189case FS_GCS_ENABLED_BRAKE_OR_LAND:190desired_action = FailsafeAction::BRAKE_LAND;191break;192default: // if an invalid parameter value is set, the fallback is RTL193desired_action = FailsafeAction::RTL;194}195196// Conditions to deviate from FS_GCS_ENABLE parameter setting197if (!motors->armed()) {198desired_action = FailsafeAction::NONE;199announce_failsafe("GCS");200201} else if (should_disarm_on_failsafe()) {202// should immediately disarm when we're on the ground203arming.disarm(AP_Arming::Method::GCSFAILSAFE);204desired_action = FailsafeAction::NONE;205announce_failsafe("GCS", "Disarming");206207} else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) {208// Allow landing to continue when battery failsafe requires it (not a user option)209announce_failsafe("GCS + Battery", "Continuing Landing");210desired_action = FailsafeAction::LAND;211212} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) {213// Allow landing to continue when FS_OPTIONS is set to continue landing214announce_failsafe("GCS", "Continuing Landing");215desired_action = FailsafeAction::LAND;216217} else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::GCS_CONTINUE_IF_AUTO)) {218// Allow mission to continue when FS_OPTIONS is set to continue mission219announce_failsafe("GCS", "Continuing Auto Mode");220desired_action = FailsafeAction::NONE;221222} else if (failsafe_option(FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL) && !flightmode->is_autopilot()) {223// should continue when in a pilot controlled mode because FS_OPTIONS is set to continue in pilot controlled modes224announce_failsafe("GCS", "Continuing Pilot Control");225desired_action = FailsafeAction::NONE;226} else {227announce_failsafe("GCS");228}229230// Call the failsafe action handler231do_failsafe_action(desired_action, ModeReason::GCS_FAILSAFE);232}233234// failsafe_gcs_off_event - actions to take when GCS contact is restored235void Copter::failsafe_gcs_off_event(void)236{237gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe Cleared");238LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED);239}240241// executes terrain failsafe if data is missing for longer than a few seconds242void Copter::failsafe_terrain_check()243{244// trigger within <n> milliseconds of failures while in various modes245bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;246bool trigger_event = timeout && flightmode->requires_terrain_failsafe();247248// check for clearing of event249if (trigger_event != failsafe.terrain) {250if (trigger_event) {251failsafe_terrain_on_event();252} else {253LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED);254failsafe.terrain = false;255}256}257}258259// set terrain data status (found or not found)260void Copter::failsafe_terrain_set_status(bool data_ok)261{262uint32_t now = millis();263264// record time of first and latest failures (i.e. duration of failures)265if (!data_ok) {266failsafe.terrain_last_failure_ms = now;267if (failsafe.terrain_first_failure_ms == 0) {268failsafe.terrain_first_failure_ms = now;269}270} else {271// failures cleared after 0.1 seconds of persistent successes272if (now - failsafe.terrain_last_failure_ms > 100) {273failsafe.terrain_last_failure_ms = 0;274failsafe.terrain_first_failure_ms = 0;275}276}277}278279// terrain failsafe action280void Copter::failsafe_terrain_on_event()281{282failsafe.terrain = true;283gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing");284LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED);285286if (should_disarm_on_failsafe()) {287arming.disarm(AP_Arming::Method::TERRAINFAILSAFE);288#if MODE_RTL_ENABLED289} else if (flightmode->mode_number() == Mode::Number::RTL) {290mode_rtl.restart_without_terrain();291#endif292} else {293set_mode_RTL_or_land_with_pause(ModeReason::TERRAIN_FAILSAFE);294}295}296297// check for gps glitch failsafe298void Copter::gpsglitch_check()299{300// get filter status301nav_filter_status filt_status = inertial_nav.get_filter_status();302bool gps_glitching = filt_status.flags.gps_glitching;303304// log start or stop of gps glitch. AP_Notify update is handled from within AP_AHRS305if (ap.gps_glitching != gps_glitching) {306ap.gps_glitching = gps_glitching;307if (gps_glitching) {308LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH);309gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch or Compass error");310} else {311LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED);312gcs().send_text(MAV_SEVERITY_CRITICAL,"Glitch cleared");313}314}315}316317// dead reckoning alert and failsafe318void Copter::failsafe_deadreckon_check()319{320// update dead reckoning state321const char* dr_prefix_str = "Dead Reckoning";322323// get EKF filter status324bool ekf_dead_reckoning = inertial_nav.get_filter_status().flags.dead_reckoning;325326// alert user to start or stop of dead reckoning327const uint32_t now_ms = AP_HAL::millis();328if (dead_reckoning.active != ekf_dead_reckoning) {329dead_reckoning.active = ekf_dead_reckoning;330if (dead_reckoning.active) {331dead_reckoning.start_ms = now_ms;332gcs().send_text(MAV_SEVERITY_CRITICAL,"%s started", dr_prefix_str);333} else {334dead_reckoning.start_ms = 0;335dead_reckoning.timeout = false;336gcs().send_text(MAV_SEVERITY_CRITICAL,"%s stopped", dr_prefix_str);337}338}339340// check for timeout341if (dead_reckoning.active && !dead_reckoning.timeout) {342const uint32_t dr_timeout_ms = uint32_t(constrain_float(g2.failsafe_dr_timeout * 1000.0f, 0.0f, UINT32_MAX));343if (now_ms - dead_reckoning.start_ms > dr_timeout_ms) {344dead_reckoning.timeout = true;345gcs().send_text(MAV_SEVERITY_CRITICAL,"%s timeout", dr_prefix_str);346}347}348349// exit immediately if deadreckon failsafe is disabled350if (g2.failsafe_dr_enable <= 0) {351failsafe.deadreckon = false;352return;353}354355// check for failsafe action356if (failsafe.deadreckon != ekf_dead_reckoning) {357failsafe.deadreckon = ekf_dead_reckoning;358359// only take action in modes requiring position estimate360if (failsafe.deadreckon && copter.flightmode->requires_GPS()) {361362// log error363LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_DEADRECKON, LogErrorCode::FAILSAFE_OCCURRED);364365// immediately disarm while landed366if (should_disarm_on_failsafe()) {367arming.disarm(AP_Arming::Method::DEADRECKON_FAILSAFE);368return;369}370371// take user specified action372do_failsafe_action((FailsafeAction)g2.failsafe_dr_enable.get(), ModeReason::DEADRECKON_FAILSAFE);373}374}375}376377// set_mode_RTL_or_land_with_pause - sets mode to RTL if possible or LAND with 4 second delay before descent starts378// this is always called from a failsafe so we trigger notification to pilot379void Copter::set_mode_RTL_or_land_with_pause(ModeReason reason)380{381#if MODE_RTL_ENABLED382// attempt to switch to RTL, if this fails then switch to Land383if (set_mode(Mode::Number::RTL, reason)) {384AP_Notify::events.failsafe_mode_change = 1;385return;386}387#endif388// set mode to land will trigger mode change notification to pilot389set_mode_land_with_pause(reason);390}391392// set_mode_SmartRTL_or_land_with_pause - sets mode to SMART_RTL if possible or LAND with 4 second delay before descent starts393// this is always called from a failsafe so we trigger notification to pilot394void Copter::set_mode_SmartRTL_or_land_with_pause(ModeReason reason)395{396#if MODE_SMARTRTL_ENABLED397// attempt to switch to SMART_RTL, if this failed then switch to Land398if (set_mode(Mode::Number::SMART_RTL, reason)) {399AP_Notify::events.failsafe_mode_change = 1;400return;401}402#endif403gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode");404set_mode_land_with_pause(reason);405}406407// set_mode_SmartRTL_or_RTL - sets mode to SMART_RTL if possible or RTL if possible or LAND with 4 second delay before descent starts408// this is always called from a failsafe so we trigger notification to pilot409void Copter::set_mode_SmartRTL_or_RTL(ModeReason reason)410{411#if MODE_SMARTRTL_ENABLED412// attempt to switch to SmartRTL, if this failed then attempt to RTL413// if that fails, then land414if (set_mode(Mode::Number::SMART_RTL, reason)) {415AP_Notify::events.failsafe_mode_change = 1;416return;417}418#endif419gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode");420set_mode_RTL_or_land_with_pause(reason);421}422423// Sets mode to Auto and jumps to DO_LAND_START, as set with AUTO_RTL param424// This can come from failsafe or RC option425void Copter::set_mode_auto_do_land_start_or_RTL(ModeReason reason)426{427#if MODE_AUTO_ENABLED428if (set_mode(Mode::Number::AUTO_RTL, reason)) {429AP_Notify::events.failsafe_mode_change = 1;430return;431}432#endif433434gcs().send_text(MAV_SEVERITY_WARNING, "Trying RTL Mode");435set_mode_RTL_or_land_with_pause(reason);436}437438// Sets mode to Brake or LAND with 4 second delay before descent starts439// This can come from failsafe or RC option440void Copter::set_mode_brake_or_land_with_pause(ModeReason reason)441{442#if MODE_BRAKE_ENABLED443if (set_mode(Mode::Number::BRAKE, reason)) {444AP_Notify::events.failsafe_mode_change = 1;445return;446}447#endif448449gcs().send_text(MAV_SEVERITY_WARNING, "Trying Land Mode");450set_mode_land_with_pause(reason);451}452453bool Copter::should_disarm_on_failsafe() {454if (ap.in_arming_delay) {455return true;456}457458switch (flightmode->mode_number()) {459case Mode::Number::STABILIZE:460case Mode::Number::ACRO:461// if throttle is zero OR vehicle is landed disarm motors462return ap.throttle_zero || ap.land_complete;463case Mode::Number::AUTO:464case Mode::Number::AUTO_RTL:465// if mission has not started AND vehicle is landed, disarm motors466return !ap.auto_armed && ap.land_complete;467default:468// used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold469// if landed disarm470return ap.land_complete;471}472}473474475void Copter::do_failsafe_action(FailsafeAction action, ModeReason reason){476477// Execute the specified desired_action478switch (action) {479case FailsafeAction::NONE:480return;481case FailsafeAction::LAND:482set_mode_land_with_pause(reason);483break;484case FailsafeAction::RTL:485set_mode_RTL_or_land_with_pause(reason);486break;487case FailsafeAction::SMARTRTL:488set_mode_SmartRTL_or_RTL(reason);489break;490case FailsafeAction::SMARTRTL_LAND:491set_mode_SmartRTL_or_land_with_pause(reason);492break;493case FailsafeAction::TERMINATE: {494#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED495g2.afs.gcs_terminate(true, "Failsafe");496#else497arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);498#endif499break;500}501case FailsafeAction::AUTO_DO_LAND_START:502set_mode_auto_do_land_start_or_RTL(reason);503break;504case FailsafeAction::BRAKE_LAND:505set_mode_brake_or_land_with_pause(reason);506break;507}508509#if AP_GRIPPER_ENABLED510if (failsafe_option(FailsafeOption::RELEASE_GRIPPER)) {511gripper.release();512}513#endif514}515516517518