diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index f164b0f830..8866fd63a4 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1277,15 +1277,6 @@ void Copter::mavlink_delay_cb() logger.EnableWrites(true); } -AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const -{ -#if ADVANCED_FAILSAFE == ENABLED - return &copter.g2.afs; -#else - return nullptr; -#endif -} - MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_long_t &packet) { MAV_RESULT result = MAV_RESULT_FAILED; diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 642eea6b17..7b60a03947 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -14,7 +14,6 @@ protected: uint32_t telem_delay() const override; MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; - AP_AdvancedFailsafe *get_advanced_failsafe() const override; uint8_t sysid_my_gcs() const override; bool sysid_enforce() const override;