Copter: AP_Stats flighttime

This commit is contained in:
Peter Barker 2016-10-13 21:40:13 +11:00 committed by Randy Mackay
parent 77064852c4
commit d2b7749af3

View File

@ -104,6 +104,8 @@ void Copter::set_land_complete(bool b)
}
ap.land_complete = b;
g2.stats.set_flying(!b);
// trigger disarm-on-land if configured
bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
bool mode_disarms_on_land = mode_allows_arming(control_mode,false) && !mode_has_manual_throttle(control_mode);