Plane: fixed minacc and delay for launch

See
https://discuss.ardupilot.org/t/tkoff-thr-minacc-and-tkoff-thr-delay-doesnt-work-together/19928
This commit is contained in:
Andrew Tridgell 2017-08-28 17:50:57 +10:00
parent 4aa068d63d
commit 4124d371c9
1 changed files with 2 additions and 1 deletions

View File

@ -32,7 +32,8 @@ bool Plane::auto_takeoff_check(void)
}
// Check for launch acceleration if set. NOTE: relies on TECS 50Hz processing
if (!is_zero(g.takeoff_throttle_min_accel) &&
if (!takeoff_state.launchTimerStarted &&
!is_zero(g.takeoff_throttle_min_accel) &&
SpdHgt_Controller->get_VXdot() < g.takeoff_throttle_min_accel) {
goto no_launch;
}