From baea2c33bdaf49a13c08acaea5a2735c35f1d357 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 28 Feb 2021 12:03:39 +1100 Subject: [PATCH] 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. --- ArduPlane/takeoff.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 0b4378906b..4c66331374 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -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;