AP_Frsky_Telem: added (generic) failsafe status bit to frame 0x5001

This commit is contained in:
yaapu 2021-05-05 12:26:35 +02:00 committed by Peter Barker
parent dcf85bcf3b
commit c32676adf5
1 changed files with 3 additions and 0 deletions

View File

@ -44,6 +44,7 @@ for FrSky SPort Passthrough
#define AP_ARMED_OFFSET 8
#define AP_BATT_FS_OFFSET 9
#define AP_EKF_FS_OFFSET 10
#define AP_FS_OFFSET 12
#define AP_FENCE_PRESENT_OFFSET 13
#define AP_FENCE_BREACH_OFFSET 14
#define AP_IMU_TEMP_MIN 19.0f
@ -525,6 +526,8 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void)
ap_status |= (uint8_t)(AP_Notify::flags.failsafe_battery)<<AP_BATT_FS_OFFSET;
// bad ekf flag
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;
// fence status
AC_Fence *fence = AP::fence();
if (fence != nullptr) {