diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index fe93590862..c4aa22a73c 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -156,8 +156,6 @@ 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) { diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h index b7ba803ad1..77f2b8a04a 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h @@ -65,6 +65,8 @@ public: _saved_wp = 0; } + bool enabled() { return _enable; } + // check that everything is OK void check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms);