2013-08-29 02:34:34 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2012-07-08 22:49:26 -03:00
/*
2016-07-22 04:35:45 -03:00
AP_AdvancedFailsafe . cpp
2012-07-08 22:49:26 -03:00
2016-08-14 22:41:55 -03:00
This is an advanced failsafe module originally modelled on the
failsafe rules of the Outback Challenge
2012-07-08 22:49:26 -03:00
*/
2015-08-11 03:28:41 -03:00
# include <AP_HAL/AP_HAL.h>
2016-07-22 04:35:45 -03:00
# include "AP_AdvancedFailsafe.h"
2015-08-11 03:28:41 -03:00
# include <RC_Channel/RC_Channel.h>
2017-01-03 05:56:20 -04:00
# include <SRV_Channel/SRV_Channel.h>
2015-08-11 03:28:41 -03:00
# include <GCS_MAVLink/GCS.h>
2019-06-14 00:13:31 -03:00
# include <AP_GPS/AP_GPS.h>
2019-06-26 23:34:37 -03:00
# include <AP_Baro/AP_Baro.h>
2021-07-30 09:25:40 -03:00
# include <AP_Mission/AP_Mission.h>
2012-07-08 22:49:26 -03:00
2019-09-14 01:39:28 -03:00
AP_AdvancedFailsafe * AP_AdvancedFailsafe : : _singleton ;
2012-11-12 17:34:14 -04:00
extern const AP_HAL : : HAL & hal ;
2012-07-08 22:49:26 -03:00
// table of user settable parameters
2016-07-22 04:35:45 -03:00
const AP_Param : : GroupInfo AP_AdvancedFailsafe : : var_info [ ] = {
2016-08-04 15:32:02 -03:00
// @Param: ENABLE
// @DisplayName: Enable Advanced Failsafe
// @Description: This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO_FLAGS ( " ENABLE " , 11 , AP_AdvancedFailsafe , _enable , 0 , AP_PARAM_FLAG_ENABLE ) ,
2016-08-04 15:32:02 -03:00
2012-07-08 22:49:26 -03:00
// @Param: MAN_PIN
// @DisplayName: Manual Pin
2022-04-22 10:14:44 -03:00
// @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.
2012-07-08 22:49:26 -03:00
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " MAN_PIN " , 0 , AP_AdvancedFailsafe , _manual_pin , - 1 ) ,
2012-07-08 22:49:26 -03:00
// @Param: HB_PIN
// @DisplayName: Heartbeat Pin
2022-04-22 10:14:44 -03:00
// @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.
2012-07-08 22:49:26 -03:00
// @User: Advanced
2019-06-18 02:01:06 -03:00
// @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 5
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " HB_PIN " , 1 , AP_AdvancedFailsafe , _heartbeat_pin , - 1 ) ,
2012-07-08 22:49:26 -03:00
// @Param: WP_COMMS
// @DisplayName: Comms Waypoint
// @Description: Waypoint number to navigate to on comms loss
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " WP_COMMS " , 2 , AP_AdvancedFailsafe , _wp_comms_hold , 0 ) ,
2012-07-08 22:49:26 -03:00
2020-02-18 19:01:45 -04:00
// @Param: WP_GPS_LOSS
2012-07-08 22:49:26 -03:00
// @DisplayName: GPS Loss Waypoint
// @Description: Waypoint number to navigate to on GPS lock loss
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " WP_GPS_LOSS " , 4 , AP_AdvancedFailsafe , _wp_gps_loss , 0 ) ,
2012-07-08 22:49:26 -03:00
// @Param: TERMINATE
// @DisplayName: Force Terminate
// @Description: Can be set in flight to force termination of the heartbeat signal
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " TERMINATE " , 5 , AP_AdvancedFailsafe , _terminate , 0 ) ,
2012-07-08 22:49:26 -03:00
2012-08-28 02:51:32 -03:00
// @Param: TERM_ACTION
// @DisplayName: Terminate action
2021-04-01 06:13:29 -03:00
// @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 parameter
2012-08-28 02:51:32 -03:00
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " TERM_ACTION " , 6 , AP_AdvancedFailsafe , _terminate_action , 0 ) ,
2012-08-28 02:51:32 -03:00
2012-09-06 22:44:02 -03:00
// @Param: TERM_PIN
// @DisplayName: Terminate Pin
2022-04-22 10:14:44 -03:00
// @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.
2012-09-06 22:44:02 -03:00
// @User: Advanced
2019-06-18 02:01:06 -03:00
// @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 5
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " TERM_PIN " , 7 , AP_AdvancedFailsafe , _terminate_pin , - 1 ) ,
2012-09-06 22:44:02 -03:00
2014-04-11 03:35:01 -03:00
// @Param: AMSL_LIMIT
// @DisplayName: AMSL limit
// @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.
// @User: Advanced
2017-05-02 10:40:16 -03:00
// @Units: m
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " AMSL_LIMIT " , 8 , AP_AdvancedFailsafe , _amsl_limit , 0 ) ,
2014-04-11 03:35:01 -03:00
// @Param: AMSL_ERR_GPS
// @DisplayName: Error margin for GPS based AMSL limit
// @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.
// @User: Advanced
2017-05-02 10:40:16 -03:00
// @Units: m
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " AMSL_ERR_GPS " , 9 , AP_AdvancedFailsafe , _amsl_margin_gps , - 1 ) ,
2014-04-11 03:35:01 -03:00
// @Param: QNH_PRESSURE
// @DisplayName: QNH pressure
// @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.
2019-09-15 21:00:00 -03:00
// @Units: hPa
2014-04-11 03:35:01 -03:00
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " QNH_PRESSURE " , 10 , AP_AdvancedFailsafe , _qnh_pressure , 0 ) ,
2014-04-11 03:35:01 -03:00
2016-08-04 15:32:02 -03:00
// *NOTE* index 11 is "Enable" and is moved to the top to allow AP_PARAM_FLAG_ENABLE
2014-08-17 05:06:42 -03:00
2016-04-22 20:03:46 -03:00
// *NOTE* index 12 of AP_Int16 RC_FAIL_MS was depreciated. Replaced by RC_FAIL_TIME.
2014-08-17 05:06:42 -03:00
// @Param: MAX_GPS_LOSS
// @DisplayName: Maximum number of GPS loss events
// @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.
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " MAX_GPS_LOSS " , 13 , AP_AdvancedFailsafe , _max_gps_loss , 0 ) ,
2014-08-17 05:06:42 -03:00
// @Param: MAX_COM_LOSS
// @DisplayName: Maximum number of comms loss events
// @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.
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " MAX_COM_LOSS " , 14 , AP_AdvancedFailsafe , _max_comms_loss , 0 ) ,
2014-08-08 00:30:00 -03:00
2016-03-21 16:44:48 -03:00
// @Param: GEOFENCE
// @DisplayName: Enable geofence Advanced Failsafe
// @Description: This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " GEOFENCE " , 15 , AP_AdvancedFailsafe , _enable_geofence_fs , 1 ) ,
2016-03-21 16:44:48 -03:00
// @Param: RC
// @DisplayName: Enable RC Advanced Failsafe
// @Description: This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " RC " , 16 , AP_AdvancedFailsafe , _enable_RC_fs , 1 ) ,
2016-03-21 16:44:48 -03:00
// @Param: RC_MAN_ONLY
// @DisplayName: Enable RC Termination only in manual control modes
// @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.
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " RC_MAN_ONLY " , 17 , AP_AdvancedFailsafe , _rc_term_manual_only , 1 ) ,
2016-03-21 16:44:48 -03:00
// @Param: DUAL_LOSS
// @DisplayName: Enable dual loss terminate due to failure of both GCS and GPS simultaneously
// @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.
// @User: Advanced
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " DUAL_LOSS " , 18 , AP_AdvancedFailsafe , _enable_dual_loss , 1 ) ,
2016-03-21 16:44:48 -03:00
2016-04-22 20:03:46 -03:00
// @Param: RC_FAIL_TIME
// @DisplayName: RC failure time
// @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.
// @User: Advanced
2017-05-02 10:40:16 -03:00
// @Units: s
2016-07-22 04:35:45 -03:00
AP_GROUPINFO ( " RC_FAIL_TIME " , 19 , AP_AdvancedFailsafe , _rc_fail_time_seconds , 0 ) ,
2016-04-22 20:03:46 -03:00
2019-08-21 02:58:41 -03:00
// @Param: MAX_RANGE
// @DisplayName: Max allowed range
// @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.
// @User: Advanced
// @Units: km
AP_GROUPINFO ( " MAX_RANGE " , 20 , AP_AdvancedFailsafe , _max_range_km , 0 ) ,
2012-07-08 22:49:26 -03:00
AP_GROUPEND
} ;
// check for Failsafe conditions. This is called at 10Hz by the main
// ArduPlane code
void
2021-02-04 22:28:07 -04:00
AP_AdvancedFailsafe : : check ( bool geofence_breached , uint32_t last_valid_rc_ms )
2014-06-01 21:47:02 -03:00
{
2014-08-08 00:30:00 -03:00
if ( ! _enable ) {
return ;
}
2018-02-02 15:20:19 -04:00
2014-06-01 21:47:02 -03:00
// we always check for fence breach
2016-03-21 16:44:48 -03:00
if ( _enable_geofence_fs ) {
if ( geofence_breached | | check_altlimit ( ) ) {
if ( ! _terminate ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Terminating due to fence breach " ) ;
2016-08-15 19:57:21 -03:00
_terminate . set_and_notify ( 1 ) ;
2016-03-21 16:44:48 -03:00
}
2014-06-01 21:47:02 -03:00
}
}
2014-08-17 05:06:42 -03:00
2019-08-21 02:58:41 -03:00
// update max range check
max_range_update ( ) ;
2016-07-22 05:14:30 -03:00
enum control_mode mode = afs_mode ( ) ;
2016-03-21 16:44:48 -03:00
// check if RC termination is enabled
2016-04-22 20:03:46 -03:00
// check for RC failure in manual mode or RC failure when AFS_RC_MANUAL is 0
2016-04-22 19:22:58 -03:00
if ( _state ! = STATE_PREFLIGHT & & ! _terminate & & _enable_RC_fs & &
2016-07-22 05:14:30 -03:00
( mode = = AFS_MANUAL | | mode = = AFS_STABILIZED | | ! _rc_term_manual_only ) & &
2016-04-22 20:03:46 -03:00
_rc_fail_time_seconds > 0 & &
( AP_HAL : : millis ( ) - last_valid_rc_ms ) > ( _rc_fail_time_seconds * 1000.0f ) ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Terminating due to RC failure " ) ;
2016-08-15 19:57:21 -03:00
_terminate . set_and_notify ( 1 ) ;
2016-04-22 20:03:46 -03:00
}
2014-06-01 21:47:02 -03:00
// tell the failsafe board if we are in manual control
// mode. This tells it to pass through controls from the
// receiver
if ( _manual_pin ! = - 1 ) {
2014-06-01 20:28:45 -03:00
hal . gpio - > pinMode ( _manual_pin , HAL_GPIO_OUTPUT ) ;
2016-07-22 04:44:52 -03:00
hal . gpio - > write ( _manual_pin , mode = = AFS_MANUAL ) ;
2014-06-01 21:47:02 -03:00
}
2021-02-04 22:28:07 -04:00
const uint32_t last_heartbeat_ms = gcs ( ) . sysid_myggcs_last_seen_time_ms ( ) ;
2015-11-19 23:05:59 -04:00
uint32_t now = AP_HAL : : millis ( ) ;
2014-06-01 21:47:02 -03:00
bool gcs_link_ok = ( ( now - last_heartbeat_ms ) < 10000 ) ;
2019-06-14 00:13:31 -03:00
bool gps_lock_ok = ( ( now - AP : : gps ( ) . last_fix_time_ms ( ) ) < 3000 ) ;
2014-06-01 21:47:02 -03:00
2021-07-30 09:25:40 -03:00
AP_Mission * _mission = AP : : mission ( ) ;
if ( _mission = = nullptr ) {
return ;
}
AP_Mission & mission = * _mission ;
2014-06-01 21:47:02 -03:00
switch ( _state ) {
case STATE_PREFLIGHT :
// we startup in preflight mode. This mode ends when
// we first enter auto.
2016-07-22 04:44:52 -03:00
if ( mode = = AFS_AUTO ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_DEBUG , " AFS State: AFS_AUTO " ) ;
2014-06-01 21:47:02 -03:00
_state = STATE_AUTO ;
}
break ;
case STATE_AUTO :
// this is the normal mode.
if ( ! gcs_link_ok ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_DEBUG , " AFS State: DATA_LINK_LOSS " ) ;
2014-06-01 21:47:02 -03:00
_state = STATE_DATA_LINK_LOSS ;
if ( _wp_comms_hold ) {
2014-08-08 00:30:00 -03:00
_saved_wp = mission . get_current_nav_cmd ( ) . index ;
2014-06-01 21:47:02 -03:00
mission . set_current_cmd ( _wp_comms_hold ) ;
}
2014-08-17 05:06:42 -03:00
// if two events happen within 30s we consider it to be part of the same event
if ( now - _last_comms_loss_ms > 30 * 1000UL ) {
_comms_loss_count + + ;
_last_comms_loss_ms = now ;
}
2014-06-01 21:47:02 -03:00
break ;
}
if ( ! gps_lock_ok ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_DEBUG , " AFS State: GPS_LOSS " ) ;
2014-06-01 21:47:02 -03:00
_state = STATE_GPS_LOSS ;
if ( _wp_gps_loss ) {
2014-08-08 00:30:00 -03:00
_saved_wp = mission . get_current_nav_cmd ( ) . index ;
2014-06-01 21:47:02 -03:00
mission . set_current_cmd ( _wp_gps_loss ) ;
}
2014-08-17 05:06:42 -03:00
// if two events happen within 30s we consider it to be part of the same event
if ( now - _last_gps_loss_ms > 30 * 1000UL ) {
_gps_loss_count + + ;
_last_gps_loss_ms = now ;
}
2014-06-01 21:47:02 -03:00
break ;
}
break ;
case STATE_DATA_LINK_LOSS :
if ( ! gps_lock_ok ) {
// losing GPS lock when data link is lost
2016-03-21 16:44:48 -03:00
// leads to termination if AFS_DUAL_LOSS is 1
if ( _enable_dual_loss ) {
if ( ! _terminate ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Terminating due to dual loss " ) ;
2016-08-15 19:57:21 -03:00
_terminate . set_and_notify ( 1 ) ;
2016-03-21 16:44:48 -03:00
}
2014-08-08 00:30:00 -03:00
}
2014-06-01 21:47:02 -03:00
} else if ( gcs_link_ok ) {
_state = STATE_AUTO ;
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_DEBUG , " AFS State: AFS_AUTO, GCS now OK " ) ;
2014-08-17 05:06:42 -03:00
// we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS
if ( _saved_wp ! = 0 & &
( _max_comms_loss < = 0 | |
_comms_loss_count < = _max_comms_loss ) ) {
2014-08-08 00:30:00 -03:00
mission . set_current_cmd ( _saved_wp ) ;
2014-06-01 21:47:02 -03:00
_saved_wp = 0 ;
}
}
break ;
case STATE_GPS_LOSS :
if ( ! gcs_link_ok ) {
// losing GCS link when GPS lock lost
2016-03-21 16:44:48 -03:00
// leads to termination if AFS_DUAL_LOSS is 1
2016-04-22 19:22:58 -03:00
if ( ! _terminate & & _enable_dual_loss ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Terminating due to dual loss " ) ;
2016-08-15 19:57:21 -03:00
_terminate . set_and_notify ( 1 ) ;
2016-04-22 20:03:46 -03:00
}
2014-06-01 21:47:02 -03:00
} else if ( gps_lock_ok ) {
2017-07-29 17:29:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_DEBUG , " AFS State: AFS_AUTO, GPS now OK " ) ;
2014-06-01 21:47:02 -03:00
_state = STATE_AUTO ;
2014-08-17 05:06:42 -03:00
// we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS
if ( _saved_wp ! = 0 & &
2016-04-22 19:22:58 -03:00
( _max_gps_loss < = 0 | | _gps_loss_count < = _max_gps_loss ) ) {
2014-06-01 21:47:02 -03:00
mission . set_current_cmd ( _saved_wp ) ;
_saved_wp = 0 ;
}
}
break ;
}
// if we are not terminating or if there is a separate terminate
// pin configured then toggle the heartbeat pin at 10Hz
if ( _heartbeat_pin ! = - 1 & & ( _terminate_pin ! = - 1 | | ! _terminate ) ) {
_heartbeat_pin_value = ! _heartbeat_pin_value ;
2014-06-01 20:28:45 -03:00
hal . gpio - > pinMode ( _heartbeat_pin , HAL_GPIO_OUTPUT ) ;
2014-06-01 21:47:02 -03:00
hal . gpio - > write ( _heartbeat_pin , _heartbeat_pin_value ) ;
}
2012-09-06 22:44:02 -03:00
2014-06-01 21:47:02 -03:00
// set the terminate pin
if ( _terminate_pin ! = - 1 ) {
2014-06-01 20:28:45 -03:00
hal . gpio - > pinMode ( _terminate_pin , HAL_GPIO_OUTPUT ) ;
2014-06-01 21:47:02 -03:00
hal . gpio - > write ( _terminate_pin , _terminate ? 1 : 0 ) ;
}
2012-07-08 22:49:26 -03:00
}
2014-04-11 03:35:01 -03:00
2014-09-23 22:03:19 -03:00
// send heartbeat messages during sensor calibration
void
2016-07-22 04:35:45 -03:00
AP_AdvancedFailsafe : : heartbeat ( void )
2014-09-23 22:03:19 -03:00
{
if ( ! _enable ) {
return ;
}
// if we are not terminating or if there is a separate terminate
// pin configured then toggle the heartbeat pin at 10Hz
if ( _heartbeat_pin ! = - 1 & & ( _terminate_pin ! = - 1 | | ! _terminate ) ) {
_heartbeat_pin_value = ! _heartbeat_pin_value ;
hal . gpio - > pinMode ( _heartbeat_pin , HAL_GPIO_OUTPUT ) ;
hal . gpio - > write ( _heartbeat_pin , _heartbeat_pin_value ) ;
}
}
2014-04-11 03:35:01 -03:00
// check for altitude limit breach
bool
2016-07-22 04:35:45 -03:00
AP_AdvancedFailsafe : : check_altlimit ( void )
2014-06-01 21:47:02 -03:00
{
2014-08-08 00:30:00 -03:00
if ( ! _enable ) {
return false ;
}
2014-04-11 03:35:01 -03:00
if ( _amsl_limit = = 0 | | _qnh_pressure < = 0 ) {
// no limit set
return false ;
}
// see if the barometer is dead
2018-03-05 16:34:43 -04:00
const AP_Baro & baro = AP : : baro ( ) ;
2019-06-14 00:13:31 -03:00
const AP_GPS & gps = AP : : gps ( ) ;
2015-11-19 23:05:59 -04:00
if ( AP_HAL : : millis ( ) - baro . get_last_update ( ) > 5000 ) {
2014-04-11 03:35:01 -03:00
// the barometer has been unresponsive for 5 seconds. See if we can switch to GPS
if ( _amsl_margin_gps ! = - 1 & &
gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D & &
gps . location ( ) . alt * 0.01f < = _amsl_limit - _amsl_margin_gps ) {
// GPS based altitude OK
return false ;
}
// no barometer - immediate termination
return true ;
}
float alt_amsl = baro . get_altitude_difference ( _qnh_pressure * 100 , baro . get_pressure ( ) ) ;
if ( alt_amsl > _amsl_limit ) {
// pressure altitude breach
return true ;
}
// all OK
return false ;
}
2014-04-20 21:35:39 -03:00
/*
2016-07-22 05:14:30 -03:00
return true if we should crash the vehicle
2014-04-20 21:35:39 -03:00
*/
2016-07-22 05:14:30 -03:00
bool AP_AdvancedFailsafe : : should_crash_vehicle ( void )
2014-04-20 21:35:39 -03:00
{
2014-08-08 00:30:00 -03:00
if ( ! _enable ) {
2016-07-22 05:14:30 -03:00
return false ;
2014-08-08 00:30:00 -03:00
}
2014-04-20 21:35:39 -03:00
// ensure failsafe values are setup for if FMU crashes on PX4/Pixhawk
if ( ! _failsafe_setup ) {
_failsafe_setup = true ;
2016-07-22 05:14:30 -03:00
setup_IO_failsafe ( ) ;
2014-04-20 21:35:39 -03:00
}
2017-07-25 03:34:09 -03:00
// determine if the vehicle should be crashed
// only possible if FS_TERM_ACTION is 42 and _terminate is non zero
// _terminate may be set via parameters, or a mavlink command
2017-08-30 16:31:31 -03:00
if ( _terminate & &
( _terminate_action = = TERMINATE_ACTION_TERMINATE | |
_terminate_action = = TERMINATE_ACTION_LAND ) ) {
// we are terminating
2017-07-25 03:34:09 -03:00
return true ;
}
// continue flying
return false ;
}
// update GCS based termination
// returns true if AFS is in the desired termination state
2017-11-09 18:32:59 -04:00
bool AP_AdvancedFailsafe : : gcs_terminate ( bool should_terminate , const char * reason ) {
2017-07-25 03:34:09 -03:00
if ( ! _enable ) {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " AFS not enabled, can't terminate the vehicle " ) ;
2016-07-22 05:14:30 -03:00
return false ;
2014-06-01 21:47:02 -03:00
}
2014-04-20 21:35:39 -03:00
2017-07-25 03:34:09 -03:00
_terminate . set_and_notify ( should_terminate ? 1 : 0 ) ;
// evaluate if we will crash or not, as AFS must be enabled, and TERM_ACTION has to be correct
bool is_terminating = should_crash_vehicle ( ) ;
if ( should_terminate = = is_terminating ) {
if ( is_terminating ) {
2017-11-09 18:32:59 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Terminating due to %s " , reason ) ;
2017-07-25 03:34:09 -03:00
} else {
2017-11-09 18:32:59 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Aborting termination due to %s " , reason ) ;
2017-07-25 03:34:09 -03:00
}
return true ;
2017-08-30 16:31:31 -03:00
} else if ( should_terminate & & _terminate_action ! = TERMINATE_ACTION_TERMINATE ) {
2017-07-25 03:34:09 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Unable to terminate, termination is not configured " ) ;
}
return false ;
2014-04-20 21:35:39 -03:00
}
2019-08-21 02:58:41 -03:00
/*
update check of maximum range
*/
void AP_AdvancedFailsafe : : max_range_update ( void )
{
if ( _max_range_km < = 0 ) {
return ;
}
if ( ! _have_first_location ) {
if ( AP : : gps ( ) . status ( ) < AP_GPS : : GPS_OK_FIX_3D ) {
// wait for 3D fix
return ;
}
if ( ! hal . util - > get_soft_armed ( ) ) {
// wait for arming
return ;
}
_first_location = AP : : gps ( ) . location ( ) ;
_have_first_location = true ;
}
if ( AP : : gps ( ) . status ( ) < AP_GPS : : GPS_OK_FIX_2D ) {
// don't trigger when dead-reckoning
return ;
}
// check distance from first location
float distance_km = _first_location . get_distance ( AP : : gps ( ) . location ( ) ) * 0.001 ;
if ( distance_km > _max_range_km ) {
uint32_t now = AP_HAL : : millis ( ) ;
if ( now - _term_range_notice_ms > 5000 ) {
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Terminating due to range %.1fkm " , distance_km ) ;
_term_range_notice_ms = now ;
}
_terminate . set_and_notify ( 1 ) ;
}
}
2019-09-14 01:39:28 -03:00
namespace AP {
AP_AdvancedFailsafe * advancedfailsafe ( )
{
return AP_AdvancedFailsafe : : get_singleton ( ) ;
}
} ;