Browse Source

AP_AdvancedFailsafe: Report MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION

master
Michael du Breuil 7 years ago committed by Randy Mackay
parent
commit
200aacea43
  1. 3
      libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp

3
libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp

@ -156,6 +156,9 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u @@ -156,6 +156,9 @@ AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, u
if (!_enable) {
return;
}
// only set the termination capability, clearing it can mess up copter and sub which can always be terminated
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION);
// we always check for fence breach
if(_enable_geofence_fs) {
if (geofence_breached || check_altlimit()) {

Loading…
Cancel
Save