mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: fix complation without fence
This commit is contained in:
parent
cababad66b
commit
df3affc38c
|
@ -142,6 +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
|
||||
AC_Fence *fence = AP::fence();
|
||||
if (fence == nullptr) {
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
|
@ -157,6 +158,9 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavl
|
|||
default:
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
#else
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
#endif // AC_FENCE
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -582,12 +582,14 @@ 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
|
||||
// fence status
|
||||
AC_Fence *fence = AP::fence();
|
||||
if (fence != nullptr) {
|
||||
ap_status |= (uint8_t)(fence->enabled() && fence->present()) << AP_FENCE_PRESENT_OFFSET;
|
||||
ap_status |= (uint8_t)(fence->get_breaches()>0) << AP_FENCE_BREACH_OFFSET;
|
||||
}
|
||||
#endif
|
||||
// signed throttle [-100,100] scaled down to [-63,63] on 7 bits, MSB for sign + 6 bits for 0-63
|
||||
ap_status |= prep_number(gcs().get_hud_throttle()*0.63, 2, 0)<<AP_THROTTLE_OFFSET;
|
||||
// IMU temperature
|
||||
|
|
Loading…
Reference in New Issue