From c1480315f54432117f725d1e0657b3d6113267ad Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 16 Aug 2016 08:57:21 +1000 Subject: [PATCH] AP_AdvancedFailsafe: update AFS_TERMINATE on GCS on termination --- libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index 5424f6e591..7e84ddbb53 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -162,7 +162,7 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u if (geofence_breached || check_altlimit()) { if (!_terminate) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Fence TERMINATE"); - _terminate.set(1); + _terminate.set_and_notify(1); } } } @@ -176,7 +176,7 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u _rc_fail_time_seconds > 0 && (AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "RC failure terminate"); - _terminate.set(1); + _terminate.set_and_notify(1); } // tell the failsafe board if we are in manual control @@ -240,7 +240,7 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u if(_enable_dual_loss) { if (!_terminate) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Dual loss TERMINATE"); - _terminate.set(1); + _terminate.set_and_notify(1); } } } else if (gcs_link_ok) { @@ -262,7 +262,7 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u // leads to termination if AFS_DUAL_LOSS is 1 if (!_terminate && _enable_dual_loss) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Dual loss TERMINATE"); - _terminate.set(1); + _terminate.set_and_notify(1); } } else if (gps_lock_ok) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS OK");