mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: re-init throttle wait on quadplane arm and disarm
this prevents yaw from rudder arming on 2nd flight
This commit is contained in:
parent
312549d773
commit
6cef4c15d1
@ -1324,6 +1324,10 @@ void QuadPlane::set_armed(bool armed)
|
|||||||
if (plane.control_mode == &plane.mode_guided) {
|
if (plane.control_mode == &plane.mode_guided) {
|
||||||
guided_wait_takeoff = armed;
|
guided_wait_takeoff = armed;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// re-init throttle wait on arm and disarm, to prevent rudder
|
||||||
|
// arming on 2nd flight causing yaw
|
||||||
|
init_throttle_wait();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user