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/Blimp/events.cpp
Views: 1798
#include "Blimp.h"12/*3* This event will be called when the failsafe changes4* boolean failsafe reflects the current state5*/67#include <AP_Vehicle/AP_MultiCopter.h>89bool Blimp::failsafe_option(FailsafeOption opt) const10{11return (g2.fs_options & (uint32_t)opt);12}1314void Blimp::failsafe_radio_on_event()15{16LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED);1718// set desired action based on FS_THR_ENABLE parameter19Failsafe_Action desired_action;20switch (g.failsafe_throttle) {21case FS_THR_DISABLED:22desired_action = Failsafe_Action_None;23break;24case FS_THR_ENABLED_ALWAYS_LAND:25desired_action = Failsafe_Action_Land;26break;27default:28desired_action = Failsafe_Action_Land;29}3031// Conditions to deviate from FS_THR_ENABLE selection and send specific GCS warning32if (should_disarm_on_failsafe()) {33// should immediately disarm when we're on the ground34gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Disarming");35arming.disarm(AP_Arming::Method::RADIOFAILSAFE);36desired_action = Failsafe_Action_None;3738} else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) {39// Allow landing to continue when battery failsafe requires it (not a user option)40gcs().send_text(MAV_SEVERITY_WARNING, "Radio + Battery Failsafe - Continuing Landing");41desired_action = Failsafe_Action_Land;4243} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) {44// Allow landing to continue when FS_OPTIONS is set to continue landing45gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Landing");46desired_action = Failsafe_Action_Land;4748} else {49gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe");50}5152// Call the failsafe action handler53do_failsafe_action(desired_action, ModeReason::RADIO_FAILSAFE);54}5556// failsafe_off_event - respond to radio contact being regained57void Blimp::failsafe_radio_off_event()58{59// no need to do anything except log the error as resolved60// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode61LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED);62gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared");63}6465void Blimp::handle_battery_failsafe(const char *type_str, const int8_t action)66{67LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED);6869Failsafe_Action desired_action = (Failsafe_Action)action;7071// Conditions to deviate from BATT_FS_XXX_ACT parameter setting72if (should_disarm_on_failsafe()) {73// should immediately disarm when we're on the ground74arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);75desired_action = Failsafe_Action_None;76gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe - Disarming");7778} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING) && desired_action != Failsafe_Action_None) {79// Allow landing to continue when FS_OPTIONS is set to continue when landing80desired_action = Failsafe_Action_Land;81gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe - Continuing Landing");82} else {83gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe");84}8586// Battery FS options already use the Failsafe_Options enum. So use them directly.87do_failsafe_action(desired_action, ModeReason::BATTERY_FAILSAFE);8889}90// failsafe_gcs_check - check for ground station failsafe91void Blimp::failsafe_gcs_check()92{93// Bypass GCS failsafe checks if disabled or GCS never connected94if (g.failsafe_gcs == FS_GCS_DISABLED) {95return;96}9798const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();99if (gcs_last_seen_ms == 0) {100return;101}102103// calc time since last gcs update104// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs105const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;106const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));107108// Determine which event to trigger109if (last_gcs_update_ms < gcs_timeout_ms && failsafe.gcs) {110// Recovery from a GCS failsafe111set_failsafe_gcs(false);112// failsafe_gcs_off_event();113114} else if (last_gcs_update_ms < gcs_timeout_ms && !failsafe.gcs) {115// No problem, do nothing116117} else if (last_gcs_update_ms > gcs_timeout_ms && failsafe.gcs) {118// Already in failsafe, do nothing119120} else if (last_gcs_update_ms > gcs_timeout_ms && !failsafe.gcs) {121// New GCS failsafe event, trigger events122set_failsafe_gcs(true);123arming.disarm(AP_Arming::Method::GCSFAILSAFE); // failsafe_gcs_on_event() should replace this when written124}125}126127bool Blimp::should_disarm_on_failsafe()128{129if (ap.in_arming_delay) {130return true;131}132133switch (control_mode) {134case Mode::Number::MANUAL:135default:136// if landed disarm137return ap.land_complete;138}139}140141142void Blimp::do_failsafe_action(Failsafe_Action action, ModeReason reason)143{144145// Execute the specified desired_action146switch (action) {147case Failsafe_Action_None:148return;149case Failsafe_Action_Land:150set_mode_land_failsafe(reason);151break;152case Failsafe_Action_Terminate: {153arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);154}155break;156}157}158159// check for gps glitch failsafe160void Blimp::gpsglitch_check()161{162// get filter status163nav_filter_status filt_status = inertial_nav.get_filter_status();164bool gps_glitching = filt_status.flags.gps_glitching;165166// log start or stop of gps glitch. AP_Notify update is handled from within AP_AHRS167if (ap.gps_glitching != gps_glitching) {168ap.gps_glitching = gps_glitching;169if (gps_glitching) {170LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH);171gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch");172} else {173LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED);174gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared");175}176}177}178179180