AP_Frsky_Telem: change AC_FENCE to AP_FENCE_ENABLED

This commit is contained in:
Iampete1 2022-07-19 12:33:12 +01:00 committed by Andrew Tridgell
parent 19ccf53fa6
commit ad59c62899
2 changed files with 3 additions and 3 deletions

View File

@ -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
}
/*

View File

@ -582,7 +582,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void)
ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<<AP_EKF_FS_OFFSET;
// generic failsafe
ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery||AP_Notify::flags.failsafe_ekf||AP_Notify::flags.failsafe_gcs||AP_Notify::flags.failsafe_radio)<<AP_FS_OFFSET;
#if AC_FENCE
#if AP_FENCE_ENABLED
// fence status
AC_Fence *fence = AP::fence();
if (fence != nullptr) {