diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp index cd3f23c672..9952f6c6ae 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp @@ -142,7 +142,7 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_preflight_calibration_baro MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavlink_command_long_t &mav_command_long) { -#if AC_FENCE +#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return MAV_RESULT_UNSUPPORTED; @@ -160,7 +160,7 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavl } #else return MAV_RESULT_UNSUPPORTED; -#endif // AC_FENCE +#endif // AP_FENCE_ENABLED } /* diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp index f210734de1..59ba140683 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp @@ -582,7 +582,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void) ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<