Plane: fix error in Qplane wait for rudder neutral

This commit is contained in:
Henry Wurzburg 2023-04-19 18:06:09 -05:00 committed by Andrew Tridgell
parent b05cffeaae
commit c6a822abe1
1 changed files with 1 additions and 1 deletions

View File

@ -2949,7 +2949,7 @@ void QuadPlane::takeoff_controller(void)
// don't takeoff up until rudder is re-centered after rudder arming // don't takeoff up until rudder is re-centered after rudder arming
if (plane.arming.last_arm_method() == AP_Arming::Method::RUDDER && if (plane.arming.last_arm_method() == AP_Arming::Method::RUDDER &&
(takeoff_last_run_ms == 0 || (takeoff_last_run_ms == 0 ||
now - takeoff_last_run_ms < 1000) && now - takeoff_last_run_ms > 1000) &&
!plane.seen_neutral_rudder && !plane.seen_neutral_rudder &&
spool_state <= AP_Motors::DesiredSpoolState::GROUND_IDLE) { spool_state <= AP_Motors::DesiredSpoolState::GROUND_IDLE) {
// start motor spinning if not spinning already so user sees it is armed // start motor spinning if not spinning already so user sees it is armed