Plane: re-init throttle wait on quadplane arm and disarm

this prevents yaw from rudder arming on 2nd flight
This commit is contained in:
Andrew Tridgell 2023-02-24 20:13:47 +11:00
parent a61a3e19c5
commit b55826e75e

View File

@ -1324,6 +1324,10 @@ void QuadPlane::set_armed(bool armed)
if (plane.control_mode == &plane.mode_guided) {
guided_wait_takeoff = armed;
}
// re-init throttle wait on arm and disarm, to prevent rudder
// arming on 2nd flight causing yaw
init_throttle_wait();
}