mirror of https://github.com/ArduPilot/ardupilot
Plane: remove unnecessary call to setTakeoffExpected
This is already set from inside Plane::set_servos_controlled when throttle up and or launch accel is detected.
This commit is contained in:
parent
246b80dc06
commit
baea2c33bd
|
@ -60,9 +60,6 @@ bool Plane::auto_takeoff_check(void)
|
|||
}
|
||||
}
|
||||
|
||||
// let EKF know to start GSF yaw estimator before takeoff movement starts so that yaw angle is better estimated
|
||||
plane.ahrs.setTakeoffExpected(arming.is_armed());
|
||||
|
||||
// we've reached the acceleration threshold, so start the timer
|
||||
if (!takeoff_state.launchTimerStarted) {
|
||||
takeoff_state.launchTimerStarted = true;
|
||||
|
|
Loading…
Reference in New Issue