AP_Frsky_Telem: simplified set_is_flying and moved to header file

This commit is contained in:
Florent Martel 2016-11-04 12:52:40 -05:00 committed by Tom Pittenger
parent bc4ab70c1c
commit 75905be376
2 changed files with 3 additions and 10 deletions

View File

@ -889,12 +889,3 @@ 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_LANDCOMPLETE_FLAG; // set land_complete flag to 0
} else {
_ap.value |= AP_LANDCOMPLETE_FLAG; // set land_complete flag to 1
}
}

View File

@ -124,7 +124,9 @@ 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);
// 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