Plane: fixed accel based launch with timer enabled

when both timer and accel set should meet both conditions
This commit is contained in:
Andrew Tridgell 2016-10-15 20:09:20 +11:00
parent 8b7c60dcd7
commit 29f4fe2398
1 changed files with 2 additions and 3 deletions

View File

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