mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: actually set _ap.value flags based in is_flying
Closes #5017
This commit is contained in:
parent
d967074183
commit
6ccf36439d
|
@ -907,3 +907,12 @@ void AP_Frsky_Telem::calc_gps_position(void)
|
|||
_gps.speed_in_centimeter = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Frsky_Telem::set_is_flying(bool is_flying)
|
||||
{
|
||||
if (is_flying) {
|
||||
_ap.value |= AP_ISFLYING_FLAG;
|
||||
} else {
|
||||
_ap.value &= ~AP_ISFLYING_FLAG;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -127,7 +127,7 @@ public:
|
|||
void update_control_mode(uint8_t mode) { _ap.control_mode = mode; }
|
||||
|
||||
// update whether we're flying (used for Plane)
|
||||
void set_is_flying(bool is_flying) { is_flying ? (_ap.value | AP_ISFLYING_FLAG) : (_ap.value & (~AP_ISFLYING_FLAG)); }
|
||||
void set_is_flying(bool is_flying);
|
||||
|
||||
// update error mask of sensors and subsystems. The mask uses the
|
||||
// MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
|
||||
|
|
Loading…
Reference in New Issue