mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Frsky_Telem: fix setting of land_complete flag
When is_flying is true, land_complete should be set to 0, and conversely.
This commit is contained in:
parent
bae9ce20c1
commit
5386edb791
@ -684,8 +684,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.valuep & AP_SSIMPLE_FLAGS)<<AP_SSIMPLE_OFFSET;
|
||||
// is_flying flag
|
||||
ap_status |= (uint8_t)((*_ap.valuep & AP_ISFLYING_FLAG) ^ AP_ISFLYING_FLAG);
|
||||
// is_flying flag which is the inverse of the land_complete flag
|
||||
ap_status |= (uint8_t)((*_ap.valuep & AP_LANDCOMPLETE_FLAG) ^ AP_LANDCOMPLETE_FLAG);
|
||||
// armed flag
|
||||
ap_status |= (uint8_t)(AP_Notify::flags.armed)<<AP_ARMED_OFFSET;
|
||||
// battery failsafe flag
|
||||
@ -910,8 +910,8 @@ void AP_Frsky_Telem::calc_gps_position(void)
|
||||
void AP_Frsky_Telem::set_is_flying(bool is_flying)
|
||||
{
|
||||
if (is_flying) {
|
||||
_ap.value |= AP_ISFLYING_FLAG;
|
||||
_ap.value &= ~AP_LANDCOMPLETE_FLAG; // set land_complete flag to 0
|
||||
} else {
|
||||
_ap.value &= ~AP_ISFLYING_FLAG;
|
||||
_ap.value |= AP_LANDCOMPLETE_FLAG; // set land_complete flag to 1
|
||||
}
|
||||
}
|
||||
|
@ -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_ISFLYING_FLAG 0x80
|
||||
#define AP_LANDCOMPLETE_FLAG 0x80
|
||||
#define AP_INITIALIZED_FLAG 0x2000
|
||||
#define AP_ARMED_OFFSET 8
|
||||
#define AP_BATT_FS_OFFSET 9
|
||||
|
Loading…
Reference in New Issue
Block a user