AP_Frsky_Telem: take is_flying from AP_Notify

This commit is contained in:
Peter Barker 2019-03-01 17:26:08 +11:00 committed by Peter Barker
parent e22b29bce4
commit 0194cd69a1
2 changed files with 2 additions and 7 deletions

View File

@ -703,7 +703,7 @@ uint32_t AP_Frsky_Telem::calc_ap_status(void)
// simple/super simple modes flags
ap_status |= (uint8_t)((*_ap.valuep) & AP_SSIMPLE_FLAGS)<<AP_SSIMPLE_OFFSET;
// is_flying flag
ap_status |= (uint8_t)(((*_ap.valuep) & AP_LANDCOMPLETE_FLAG) ^ AP_LANDCOMPLETE_FLAG);
ap_status |= (uint8_t)(AP_Notify::flags.flying) << AP_FLYING_OFFSET;
// armed flag
ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;
// battery failsafe flag

View File

@ -87,8 +87,8 @@ 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_INITIALIZED_FLAG 0x2000
#define AP_FLYING_OFFSET 6
#define AP_ARMED_OFFSET 8
#define AP_BATT_FS_OFFSET 9
#define AP_EKF_FS_OFFSET 10
@ -125,11 +125,6 @@ public:
// add statustext message to FrSky lib message queue
void queue_message(MAV_SEVERITY severity, const char *text);
// update whether we're flying (used for Plane)
// set land_complete flag to 0 if is_flying
// set land_complete flag to 1 if not flying
void set_is_flying(bool is_flying) { (is_flying) ? (_ap.value &= ~AP_LANDCOMPLETE_FLAG) : (_ap.value |= AP_LANDCOMPLETE_FLAG); }
// update error mask of sensors and subsystems. The mask uses the
// MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
// indicates that the sensor or subsystem is present but not