mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
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:
parent
7829e6652d
commit
fdc6a30a35
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user