mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Frsky_Telem: LANDCOMPLETE switched to to ISFLYING flag
This commit is contained in:
parent
4dc98faa48
commit
33bd359463
@ -638,8 +638,8 @@ uint32_t AP_Frsky_Telem::calc_ap_status(void)
|
||||
ap_status = (uint8_t)((_ap.control_mode+1) & AP_CONTROL_MODE_LIMIT);
|
||||
// simple/super simple modes flags
|
||||
ap_status |= (uint8_t)(*_ap.value & AP_SSIMPLE_FLAGS)<<AP_SSIMPLE_OFFSET;
|
||||
// land complete flag
|
||||
ap_status |= (uint8_t)(*_ap.value & AP_LANDCOMPLETE_FLAG);
|
||||
// is_flying flag
|
||||
ap_status |= (uint8_t)((*_ap.value & AP_ISFLYING_FLAG) ^ AP_ISFLYING_FLAG);
|
||||
// armed flag
|
||||
ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;
|
||||
// battery failsafe flag
|
||||
|
@ -90,7 +90,7 @@ for FrSky SPort Passthrough
|
||||
#define AP_CONTROL_MODE_LIMIT 0x1F
|
||||
#define AP_SSIMPLE_FLAGS 0x6
|
||||
#define AP_SSIMPLE_OFFSET 4
|
||||
#define AP_LANDCOMPLETE_FLAG 0x80
|
||||
#define AP_ISFLYING_FLAG 0x80
|
||||
#define AP_ARMED_OFFSET 8
|
||||
#define AP_BATT_FS_OFFSET 9
|
||||
#define AP_EKF_FS_OFFSET 10
|
||||
|
Loading…
Reference in New Issue
Block a user