AP_AdvancedFailsafe: update AFS_TERMINATE on GCS on termination

This commit is contained in:
Andrew Tridgell 2016-08-16 08:57:21 +10:00
parent cee1e37391
commit c1480315f5
1 changed files with 4 additions and 4 deletions

View File

@ -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");