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_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16AP_AdvancedFailsafe.cpp1718This is an advanced failsafe module originally modelled on the19failsafe rules of the Outback Challenge20*/21#include "AP_AdvancedFailsafe.h"2223#if AP_ADVANCEDFAILSAFE_ENABLED2425#include <AP_HAL/AP_HAL.h>26#include <RC_Channel/RC_Channel.h>27#include <SRV_Channel/SRV_Channel.h>28#include <GCS_MAVLink/GCS.h>29#include <AP_GPS/AP_GPS.h>30#include <AP_Baro/AP_Baro.h>31#include <AP_Mission/AP_Mission.h>32#include <AC_Fence/AC_Fence.h>3334AP_AdvancedFailsafe *AP_AdvancedFailsafe::_singleton;3536extern const AP_HAL::HAL& hal;3738// table of user settable parameters39const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {40// @Param: ENABLE41// @DisplayName: Enable Advanced Failsafe42// @Description: This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect43// @User: Advanced44AP_GROUPINFO_FLAGS("ENABLE", 11, AP_AdvancedFailsafe, _enable, 0, AP_PARAM_FLAG_ENABLE),4546// @Param: MAN_PIN47// @DisplayName: Manual Pin48// @Description: This sets a digital output pin to set high when in manual mode. See the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.49// @User: Advanced50AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1),5152// @Param: HB_PIN53// @DisplayName: Heartbeat Pin54// @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.55// @User: Advanced56// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 557AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),5859// @Param: WP_COMMS60// @DisplayName: Comms Waypoint61// @Description: Waypoint number to navigate to on comms loss62// @User: Advanced63AP_GROUPINFO("WP_COMMS", 2, AP_AdvancedFailsafe, _wp_comms_hold, 0),6465// @Param: WP_GPS_LOSS66// @DisplayName: GPS Loss Waypoint67// @Description: Waypoint number to navigate to on GPS lock loss68// @User: Advanced69AP_GROUPINFO("WP_GPS_LOSS", 4, AP_AdvancedFailsafe, _wp_gps_loss, 0),7071// @Param: TERMINATE72// @DisplayName: Force Terminate73// @Description: Can be set in flight to force termination of the heartbeat signal74// @User: Advanced75AP_GROUPINFO("TERMINATE", 5, AP_AdvancedFailsafe, _terminate, 0),7677// @Param: TERM_ACTION78// @DisplayName: Terminate action79// @Description: This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup ArduPilot to handle it here. Please consult the wiki for more information on the possible values of the parameter80// @User: Advanced81AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),8283// @Param: TERM_PIN84// @DisplayName: Terminate Pin85// @Description: This sets a digital output pin to set high on flight termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.86// @User: Advanced87// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 588AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),8990// @Param: AMSL_LIMIT91// @DisplayName: AMSL limit92// @Description: This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.93// @User: Advanced94// @Units: m95AP_GROUPINFO("AMSL_LIMIT", 8, AP_AdvancedFailsafe, _amsl_limit, 0),9697// @Param: AMSL_ERR_GPS98// @DisplayName: Error margin for GPS based AMSL limit99// @Description: This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.100// @User: Advanced101// @Units: m102AP_GROUPINFO("AMSL_ERR_GPS", 9, AP_AdvancedFailsafe, _amsl_margin_gps, -1),103104// @Param: QNH_PRESSURE105// @DisplayName: QNH pressure106// @Description: This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.107// @Units: hPa108// @User: Advanced109AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),110111// *NOTE* index 11 is "Enable" and is moved to the top to allow AP_PARAM_FLAG_ENABLE112113// *NOTE* index 12 of AP_Int16 RC_FAIL_MS was depreciated. Replaced by RC_FAIL_TIME.114115// @Param: MAX_GPS_LOSS116// @DisplayName: Maximum number of GPS loss events117// @Description: Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.118// @User: Advanced119AP_GROUPINFO("MAX_GPS_LOSS", 13, AP_AdvancedFailsafe, _max_gps_loss, 0),120121// @Param: MAX_COM_LOSS122// @DisplayName: Maximum number of comms loss events123// @Description: Maximum number of comms loss events before the aircraft stops returning to mission on comms recovery. Use zero to allow for any number of comms loss events.124// @User: Advanced125AP_GROUPINFO("MAX_COM_LOSS", 14, AP_AdvancedFailsafe, _max_comms_loss, 0),126127// @Param: GEOFENCE128// @DisplayName: Enable geofence Advanced Failsafe129// @Description: This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1130// @User: Advanced131AP_GROUPINFO("GEOFENCE", 15, AP_AdvancedFailsafe, _enable_geofence_fs, 1),132133// @Param: RC134// @DisplayName: Enable RC Advanced Failsafe135// @Description: This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1136// @User: Advanced137AP_GROUPINFO("RC", 16, AP_AdvancedFailsafe, _enable_RC_fs, 1),138139// @Param: RC_MAN_ONLY140// @DisplayName: Enable RC Termination only in manual control modes141// @Description: If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.142// @User: Advanced143AP_GROUPINFO("RC_MAN_ONLY", 17, AP_AdvancedFailsafe, _rc_term_manual_only, 1),144145// @Param: DUAL_LOSS146// @DisplayName: Enable dual loss terminate due to failure of both GCS and GPS simultaneously147// @Description: This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a "dual loss" and cause termination.148// @User: Advanced149AP_GROUPINFO("DUAL_LOSS", 18, AP_AdvancedFailsafe, _enable_dual_loss, 1),150151// @Param: RC_FAIL_TIME152// @DisplayName: RC failure time153// @Description: This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.154// @User: Advanced155// @Units: s156AP_GROUPINFO("RC_FAIL_TIME", 19, AP_AdvancedFailsafe, _rc_fail_time_seconds, 0),157158// @Param: MAX_RANGE159// @DisplayName: Max allowed range160// @Description: This is the maximum range of the vehicle in kilometers from first arming. If the vehicle goes beyond this range then the TERM_ACTION is performed. A value of zero disables this feature.161// @User: Advanced162// @Units: km163AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0),164165// @Param: OPTIONS166// @DisplayName: AFS options167// @Description: See description for each bitmask bit description168// @Bitmask: 0: Continue the mission even after comms are recovered (does not go to the mission item at the time comms were lost)169// @Bitmask: 1: Enable AFS for all autonomous modes (not just AUTO)170AP_GROUPINFO("OPTIONS", 21, AP_AdvancedFailsafe, options, 0),171172// @Param: GCS_TIMEOUT173// @DisplayName: GCS timeout174// @Description: The time (in seconds) of persistent data link loss before GCS failsafe occurs.175// @User: Advanced176// @Units: s177AP_GROUPINFO("GCS_TIMEOUT", 22, AP_AdvancedFailsafe, _gcs_fail_time_seconds, 10),178179AP_GROUPEND180};181182// check for Failsafe conditions. This is called at 10Hz by the main183// ArduPlane code184void185AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms)186{187if (!_enable) {188return;189}190191#if AP_FENCE_ENABLED192// we always check for fence breach193if(_enable_geofence_fs) {194const AC_Fence *ap_fence = AP::fence();195if ((ap_fence != nullptr && ap_fence->get_breaches() != 0) || check_altlimit()) {196if (!_terminate) {197GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach");198_terminate.set_and_notify(1);199}200}201}202#endif203204// update max range check205max_range_update();206207enum control_mode mode = afs_mode();208209// check if RC termination is enabled210// check for RC failure in manual mode or RC failure when AFS_RC_MANUAL is 0211if (_state != STATE_PREFLIGHT && !_terminate && _enable_RC_fs &&212(mode == AFS_MANUAL || mode == AFS_STABILIZED || !_rc_term_manual_only) &&213_rc_fail_time_seconds > 0 &&214(AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) {215GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure");216_terminate.set_and_notify(1);217}218219// tell the failsafe board if we are in manual control220// mode. This tells it to pass through controls from the221// receiver222if (_manual_pin != -1) {223hal.gpio->pinMode(_manual_pin, HAL_GPIO_OUTPUT);224hal.gpio->write(_manual_pin, mode==AFS_MANUAL);225}226227const uint32_t last_heartbeat_ms = gcs().sysid_myggcs_last_seen_time_ms();228uint32_t now = AP_HAL::millis();229bool gcs_link_ok = ((now - last_heartbeat_ms) < (_gcs_fail_time_seconds*1000.0f));230bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);231232AP_Mission *_mission = AP::mission();233if (_mission == nullptr) {234return;235}236AP_Mission &mission = *_mission;237238switch (_state) {239case STATE_PREFLIGHT:240// we startup in preflight mode. This mode ends when241// we first enter auto.242if (mode == AFS_AUTO) {243GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO");244_state = STATE_AUTO;245}246break;247248case STATE_AUTO:249// this is the normal mode.250if (!gcs_link_ok) {251GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS");252_state = STATE_DATA_LINK_LOSS;253if (_wp_comms_hold) {254_saved_wp = mission.get_current_nav_cmd().index;255mission.set_current_cmd(_wp_comms_hold);256if (mode == AFS_AUTO && option_is_set(Option::GCS_FS_ALL_AUTONOMOUS_MODES)) {257set_mode_auto();258}259}260// if two events happen within 30s we consider it to be part of the same event261if (now - _last_comms_loss_ms > 30*1000UL) {262_comms_loss_count++;263_last_comms_loss_ms = now;264}265break;266}267if (!gps_lock_ok) {268GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS");269_state = STATE_GPS_LOSS;270if (_wp_gps_loss) {271_saved_wp = mission.get_current_nav_cmd().index;272mission.set_current_cmd(_wp_gps_loss);273}274// if two events happen within 30s we consider it to be part of the same event275if (now - _last_gps_loss_ms > 30*1000UL) {276_gps_loss_count++;277_last_gps_loss_ms = now;278}279break;280}281break;282283case STATE_DATA_LINK_LOSS:284if (!gps_lock_ok) {285// losing GPS lock when data link is lost286// leads to termination if AFS_DUAL_LOSS is 1287if(_enable_dual_loss) {288if (!_terminate) {289GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");290_terminate.set_and_notify(1);291}292}293} else if (gcs_link_ok) {294_state = STATE_AUTO;295GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK");296297if (option_is_set(Option::CONTINUE_AFTER_RECOVERED)) {298break;299}300301// we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS302if (_saved_wp != 0 &&303(_max_comms_loss <= 0 ||304_comms_loss_count <= _max_comms_loss)) {305mission.set_current_cmd(_saved_wp);306_saved_wp = 0;307}308}309break;310311case STATE_GPS_LOSS:312if (!gcs_link_ok) {313// losing GCS link when GPS lock lost314// leads to termination if AFS_DUAL_LOSS is 1315if (!_terminate && _enable_dual_loss) {316GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");317_terminate.set_and_notify(1);318}319} else if (gps_lock_ok) {320GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK");321_state = STATE_AUTO;322// we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS323if (_saved_wp != 0 &&324(_max_gps_loss <= 0 || _gps_loss_count <= _max_gps_loss)) {325mission.set_current_cmd(_saved_wp);326_saved_wp = 0;327}328}329break;330}331332// if we are not terminating or if there is a separate terminate333// pin configured then toggle the heartbeat pin at 10Hz334heartbeat();335336// set the terminate pin337if (_terminate_pin != -1) {338hal.gpio->pinMode(_terminate_pin, HAL_GPIO_OUTPUT);339hal.gpio->write(_terminate_pin, _terminate?1:0);340}341}342343344// send heartbeat messages during sensor calibration345void346AP_AdvancedFailsafe::heartbeat(void)347{348if (!_enable) {349return;350}351352// if we are not terminating or if there is a separate terminate353// pin configured then toggle the heartbeat pin at 10Hz354if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {355_heartbeat_pin_value = !_heartbeat_pin_value;356hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);357hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);358}359}360361// check for altitude limit breach362bool363AP_AdvancedFailsafe::check_altlimit(void)364{365if (!_enable) {366return false;367}368if (_amsl_limit == 0 || _qnh_pressure <= 0) {369// no limit set370return false;371}372373// see if the barometer is dead374const AP_Baro &baro = AP::baro();375const AP_GPS &gps = AP::gps();376if (AP_HAL::millis() - baro.get_last_update() > 5000) {377// the barometer has been unresponsive for 5 seconds. See if we can switch to GPS378if (_amsl_margin_gps != -1 &&379gps.status() >= AP_GPS::GPS_OK_FIX_3D &&380gps.location().alt*0.01f <= _amsl_limit - _amsl_margin_gps) {381// GPS based altitude OK382return false;383}384// no barometer - immediate termination385return true;386}387388float alt_amsl = baro.get_altitude_difference(_qnh_pressure*100, baro.get_pressure());389if (alt_amsl > _amsl_limit) {390// pressure altitude breach391return true;392}393394// all OK395return false;396}397398/*399return true if we should crash the vehicle400*/401bool AP_AdvancedFailsafe::should_crash_vehicle(void)402{403if (!_enable) {404return false;405}406// ensure failsafe values are setup for if FMU crashes on PX4/Pixhawk407if (!_failsafe_setup) {408_failsafe_setup = true;409setup_IO_failsafe();410}411412// determine if the vehicle should be crashed413// only possible if FS_TERM_ACTION is 42 and _terminate is non zero414// _terminate may be set via parameters, or a mavlink command415if (_terminate &&416(_terminate_action == TERMINATE_ACTION_TERMINATE ||417_terminate_action == TERMINATE_ACTION_LAND)) {418// we are terminating419return true;420}421422// continue flying423return false;424}425426// update GCS based termination427// returns true if AFS is in the desired termination state428bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {429if (!_enable) {430GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");431return false;432}433434_terminate.set_and_notify(should_terminate ? 1 : 0);435436// evaluate if we will crash or not, as AFS must be enabled, and TERM_ACTION has to be correct437bool is_terminating = should_crash_vehicle();438439if(should_terminate == is_terminating) {440if (is_terminating) {441GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Terminating due to %s", reason);442} else {443GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason);444}445return true;446} else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {447GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured");448}449return false;450}451452/*453update check of maximum range454*/455void AP_AdvancedFailsafe::max_range_update(void)456{457if (_max_range_km <= 0) {458return;459}460461if (!_have_first_location) {462if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {463// wait for 3D fix464return;465}466if (!hal.util->get_soft_armed()) {467// wait for arming468return;469}470_first_location = AP::gps().location();471_have_first_location = true;472}473474if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {475// don't trigger when dead-reckoning476return;477}478479// check distance from first location480float distance_km = _first_location.get_distance(AP::gps().location()) * 0.001;481if (distance_km > _max_range_km) {482uint32_t now = AP_HAL::millis();483if (now - _term_range_notice_ms > 5000) {484GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to range %.1fkm", distance_km);485_term_range_notice_ms = now;486}487_terminate.set_and_notify(1);488}489}490491namespace AP {492493AP_AdvancedFailsafe *advancedfailsafe()494{495return AP_AdvancedFailsafe::get_singleton();496}497498};499500#endif // AP_ADVANCEDFAILSAFE_ENABLED501502503