Path: blob/master/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
9448 views
/*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 557// @Range: -1 12758AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),5960// @Param: WP_COMMS61// @DisplayName: Comms Waypoint62// @Description: Waypoint number to navigate to on comms loss63// @User: Advanced64AP_GROUPINFO("WP_COMMS", 2, AP_AdvancedFailsafe, _wp_comms_hold, 0),6566// @Param: WP_GPS_LOSS67// @DisplayName: GPS Loss Waypoint68// @Description: Waypoint number to navigate to on GPS lock loss69// @User: Advanced70AP_GROUPINFO("WP_GPS_LOSS", 4, AP_AdvancedFailsafe, _wp_gps_loss, 0),7172// @Param: TERMINATE73// @DisplayName: Force Terminate74// @Description: Can be set in flight to force termination of the heartbeat signal75// @User: Advanced76AP_GROUPINFO("TERMINATE", 5, AP_AdvancedFailsafe, _terminate, 0),7778// @Param: TERM_ACTION79// @DisplayName: Terminate action80// @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 parameter81// @User: Advanced82AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),8384// @Param: TERM_PIN85// @DisplayName: Terminate Pin86// @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.87// @User: Advanced88// @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 589// @Range: -1 12790AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),9192// @Param: AMSL_LIMIT93// @DisplayName: AMSL limit94// @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.95// @User: Advanced96// @Units: m97AP_GROUPINFO("AMSL_LIMIT", 8, AP_AdvancedFailsafe, _amsl_limit, 0),9899// @Param: AMSL_ERR_GPS100// @DisplayName: Error margin for GPS based AMSL limit101// @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.102// @User: Advanced103// @Units: m104AP_GROUPINFO("AMSL_ERR_GPS", 9, AP_AdvancedFailsafe, _amsl_margin_gps, -1),105106// @Param: QNH_PRESSURE107// @DisplayName: QNH pressure108// @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.109// @Units: hPa110// @User: Advanced111AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),112113// *NOTE* index 11 is "Enable" and is moved to the top to allow AP_PARAM_FLAG_ENABLE114115// *NOTE* index 12 of AP_Int16 RC_FAIL_MS was depreciated. Replaced by RC_FAIL_TIME.116117// @Param: MAX_GPS_LOSS118// @DisplayName: Maximum number of GPS loss events119// @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.120// @User: Advanced121AP_GROUPINFO("MAX_GPS_LOSS", 13, AP_AdvancedFailsafe, _max_gps_loss, 0),122123// @Param: MAX_COM_LOSS124// @DisplayName: Maximum number of comms loss events125// @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.126// @User: Advanced127AP_GROUPINFO("MAX_COM_LOSS", 14, AP_AdvancedFailsafe, _max_comms_loss, 0),128129// @Param: GEOFENCE130// @DisplayName: Enable geofence Advanced Failsafe131// @Description: This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1132// @User: Advanced133AP_GROUPINFO("GEOFENCE", 15, AP_AdvancedFailsafe, _enable_geofence_fs, 1),134135// @Param: RC136// @DisplayName: Enable RC Advanced Failsafe137// @Description: This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1138// @User: Advanced139AP_GROUPINFO("RC", 16, AP_AdvancedFailsafe, _enable_RC_fs, 1),140141// @Param: RC_MAN_ONLY142// @DisplayName: Enable RC Termination only in manual control modes143// @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.144// @User: Advanced145AP_GROUPINFO("RC_MAN_ONLY", 17, AP_AdvancedFailsafe, _rc_term_manual_only, 1),146147// @Param: DUAL_LOSS148// @DisplayName: Enable dual loss terminate due to failure of both GCS and GPS simultaneously149// @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.150// @User: Advanced151AP_GROUPINFO("DUAL_LOSS", 18, AP_AdvancedFailsafe, _enable_dual_loss, 1),152153// @Param: RC_FAIL_TIME154// @DisplayName: RC failure time155// @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.156// @User: Advanced157// @Units: s158AP_GROUPINFO("RC_FAIL_TIME", 19, AP_AdvancedFailsafe, _rc_fail_time_seconds, 0),159160// @Param: MAX_RANGE161// @DisplayName: Max allowed range162// @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.163// @User: Advanced164// @Units: km165AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0),166167// @Param: OPTIONS168// @DisplayName: AFS options169// @Description: See description for each bitmask bit description170// @Bitmask: 0: Continue the mission even after comms are recovered (does not go to the mission item at the time comms were lost)171// @Bitmask: 1: Enable AFS for all autonomous modes (not just AUTO)172// @Bitmask: 2: Option to not jump to AFS_WP_COMMS if already in the return path173AP_GROUPINFO("OPTIONS", 21, AP_AdvancedFailsafe, options, 0),174175// @Param: GCS_TIMEOUT176// @DisplayName: GCS timeout177// @Description: The time (in seconds) of persistent data link loss before GCS failsafe occurs.178// @User: Advanced179// @Units: s180AP_GROUPINFO("GCS_TIMEOUT", 22, AP_AdvancedFailsafe, _gcs_fail_time_seconds, 10),181182AP_GROUPEND183};184185// check for Failsafe conditions. This is called at 10Hz by the main186// ArduPlane code187void188AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms)189{190if (!_enable) {191return;192}193194#if AP_FENCE_ENABLED195// we always check for fence breach196if(_enable_geofence_fs) {197const AC_Fence *ap_fence = AP::fence();198if ((ap_fence != nullptr && ap_fence->get_breaches() != 0) || check_altlimit()) {199if (!_terminate) {200GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach");201_terminate.set_and_notify(1);202}203}204}205#endif206207// update max range check208max_range_update();209210enum control_mode mode = afs_mode();211212// check if RC termination is enabled213// check for RC failure in manual mode or RC failure when AFS_RC_MANUAL is 0214if (_state != STATE_PREFLIGHT && !_terminate && _enable_RC_fs &&215(mode == AFS_MANUAL || mode == AFS_STABILIZED || !_rc_term_manual_only) &&216_rc_fail_time_seconds > 0 &&217(AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) {218GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure");219_terminate.set_and_notify(1);220}221222// tell the failsafe board if we are in manual control223// mode. This tells it to pass through controls from the224// receiver225if (_manual_pin != -1) {226hal.gpio->pinMode(_manual_pin, HAL_GPIO_OUTPUT);227hal.gpio->write(_manual_pin, mode==AFS_MANUAL);228}229230const uint32_t last_heartbeat_ms = gcs().sysid_mygcs_last_seen_time_ms();231uint32_t now = AP_HAL::millis();232bool gcs_link_ok = ((now - last_heartbeat_ms) < (_gcs_fail_time_seconds*1000.0f));233bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);234235AP_Mission *_mission = AP::mission();236if (_mission == nullptr) {237return;238}239AP_Mission &mission = *_mission;240241switch (_state) {242case STATE_PREFLIGHT:243// we startup in preflight mode. This mode ends when244// we first enter auto.245if (mode == AFS_AUTO) {246GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO");247_state = STATE_AUTO;248}249break;250251case STATE_AUTO:252// this is the normal mode.253if (!gcs_link_ok) {254GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS");255_state = STATE_DATA_LINK_LOSS;256257if (should_use_comms_hold()) {258_saved_wp = mission.get_current_nav_cmd().index;259mission.set_current_cmd(_wp_comms_hold);260261if (mode == AFS_AUTO && option_is_set(Option::GCS_FS_ALL_AUTONOMOUS_MODES)) {262set_mode_auto();263}264}265266// if two events happen within 30s we consider it to be part of the same event267if (now - _last_comms_loss_ms > 30*1000UL) {268_comms_loss_count++;269_last_comms_loss_ms = now;270}271break;272}273if (!gps_lock_ok) {274GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS");275_state = STATE_GPS_LOSS;276if (_wp_gps_loss) {277_saved_wp = mission.get_current_nav_cmd().index;278mission.set_current_cmd(_wp_gps_loss);279}280// if two events happen within 30s we consider it to be part of the same event281if (now - _last_gps_loss_ms > 30*1000UL) {282_gps_loss_count++;283_last_gps_loss_ms = now;284}285break;286}287break;288289case STATE_DATA_LINK_LOSS:290if (!gps_lock_ok) {291// losing GPS lock when data link is lost292// leads to termination if AFS_DUAL_LOSS is 1293if(_enable_dual_loss) {294if (!_terminate) {295GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");296_terminate.set_and_notify(1);297}298}299} else if (gcs_link_ok) {300_state = STATE_AUTO;301GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK");302303if (option_is_set(Option::CONTINUE_AFTER_RECOVERED)) {304break;305}306307// we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS308if (_saved_wp != 0 &&309(_max_comms_loss <= 0 ||310_comms_loss_count <= _max_comms_loss)) {311mission.set_current_cmd(_saved_wp);312_saved_wp = 0;313}314}315break;316317case STATE_GPS_LOSS:318if (!gcs_link_ok) {319// losing GCS link when GPS lock lost320// leads to termination if AFS_DUAL_LOSS is 1321if (!_terminate && _enable_dual_loss) {322GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");323_terminate.set_and_notify(1);324}325} else if (gps_lock_ok) {326GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK");327_state = STATE_AUTO;328// we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS329if (_saved_wp != 0 &&330(_max_gps_loss <= 0 || _gps_loss_count <= _max_gps_loss)) {331mission.set_current_cmd(_saved_wp);332_saved_wp = 0;333}334}335break;336}337338// if we are not terminating or if there is a separate terminate339// pin configured then toggle the heartbeat pin at 10Hz340heartbeat();341342// set the terminate pin343if (_terminate_pin != -1) {344hal.gpio->pinMode(_terminate_pin, HAL_GPIO_OUTPUT);345hal.gpio->write(_terminate_pin, _terminate?1:0);346}347}348349350// send heartbeat messages during sensor calibration351void352AP_AdvancedFailsafe::heartbeat(void)353{354if (!_enable) {355return;356}357358// if we are not terminating or if there is a separate terminate359// pin configured then toggle the heartbeat pin at 10Hz360if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {361_heartbeat_pin_value = !_heartbeat_pin_value;362hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);363hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);364}365}366367bool368AP_AdvancedFailsafe::gps_altitude_ok() const369{370if (_amsl_margin_gps == -1) {371return false;372}373const AP_GPS &gps = AP::gps();374if (gps.status() < AP_GPS::GPS_OK_FIX_3D) {375return false;376}377const auto &location = gps.location();378float alt;379if (!location.get_alt_m(Location::AltFrame::ABSOLUTE, alt)) {380return false;381}382if (alt > _amsl_limit - _amsl_margin_gps) {383return false;384}385return true;386}387388// check for altitude limit breach389bool390AP_AdvancedFailsafe::check_altlimit(void)391{392if (!_enable) {393return false;394}395if (_amsl_limit == 0 || _qnh_pressure <= 0) {396// no limit set397return false;398}399400// see if the barometer is dead401const AP_Baro &baro = AP::baro();402if (AP_HAL::millis() - baro.get_last_update() > 5000) {403// the barometer has been unresponsive for 5 seconds. See if we can switch to GPS404if (gps_altitude_ok()) {405// GPS based altitude OK406return false;407}408// no barometer - immediate termination409return true;410}411412float alt_amsl = baro.get_altitude_difference(_qnh_pressure*100, baro.get_pressure());413if (alt_amsl > _amsl_limit) {414// pressure altitude breach415return true;416}417418// all OK419return false;420}421422/*423return true if we should jump to _wp_comms_hold424*/425bool AP_AdvancedFailsafe::should_use_comms_hold(void){426427AP_Mission *_mission = AP::mission();428429if (_mission == nullptr) {430return false;431}432433if (_wp_comms_hold <= 0) {434return false;435}436437if ((_mission->state() == AP_Mission::MISSION_RUNNING) && _mission->get_in_return_path_flag() && option_is_set(Option::CONTINUE_IF_ALREADY_IN_RETURN_PATH)) {438return false;439}440441return true;442}443/*444return true if we should crash the vehicle445*/446bool AP_AdvancedFailsafe::should_crash_vehicle(void)447{448if (!_enable) {449return false;450}451// ensure failsafe values are setup for if FMU crashes on PX4/Pixhawk452if (!_failsafe_setup) {453_failsafe_setup = true;454setup_IO_failsafe();455}456457// determine if the vehicle should be crashed458// only possible if FS_TERM_ACTION is 42 and _terminate is non zero459// _terminate may be set via parameters, or a mavlink command460if (_terminate &&461(_terminate_action == TERMINATE_ACTION_TERMINATE ||462_terminate_action == TERMINATE_ACTION_LAND)) {463// we are terminating464return true;465}466467// continue flying468return false;469}470471// update GCS based termination472// returns true if AFS is in the desired termination state473bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {474if (!_enable) {475GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");476return false;477}478479_terminate.set_and_notify(should_terminate ? 1 : 0);480481// evaluate if we will crash or not, as AFS must be enabled, and TERM_ACTION has to be correct482bool is_terminating = should_crash_vehicle();483484if(should_terminate == is_terminating) {485if (is_terminating) {486GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Terminating due to %s", reason);487} else {488GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason);489}490return true;491} else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {492GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured");493}494return false;495}496497/*498update check of maximum range499*/500void AP_AdvancedFailsafe::max_range_update(void)501{502if (_max_range_km <= 0) {503return;504}505506if (!_have_first_location) {507if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {508// wait for 3D fix509return;510}511if (!hal.util->get_soft_armed()) {512// wait for arming513return;514}515_first_location = AP::gps().location();516_have_first_location = true;517}518519if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {520// don't trigger when dead-reckoning521return;522}523524// check distance from first location525float distance_km = _first_location.get_distance(AP::gps().location()) * 0.001;526if (distance_km > _max_range_km) {527uint32_t now = AP_HAL::millis();528if (now - _term_range_notice_ms > 5000) {529GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to range %.1fkm", distance_km);530_term_range_notice_ms = now;531}532_terminate.set_and_notify(1);533}534}535536namespace AP {537538AP_AdvancedFailsafe *advancedfailsafe()539{540return AP_AdvancedFailsafe::get_singleton();541}542543};544545#endif // AP_ADVANCEDFAILSAFE_ENABLED546547548