From 9d98244730cdadf5b1eb8401efd5e641e4099b9b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 3 Sep 2023 07:42:22 +1000 Subject: [PATCH] Plane: fixed nav_roll/nav_pitch when waiting for VTOL takeoff the nav_roll_cd and nav_pitch_cd were not being set in the VTOL takeoff code when disarmed. This led to small increments accumulating in the stick mixing code, leading to large control surface movements before arming --- ArduPlane/quadplane.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 5a8a895f1e..c88529fc27 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2946,6 +2946,10 @@ void QuadPlane::setup_target_position(void) */ void QuadPlane::takeoff_controller(void) { + // reset fixed wing controller to neutral as base output + plane.nav_roll_cd = 0; + plane.nav_pitch_cd = 0; + if (!plane.arming.is_armed_and_safety_off()) { return; } @@ -3007,8 +3011,6 @@ void QuadPlane::takeoff_controller(void) takeoff_last_run_ms = now; if (no_navigation) { - plane.nav_roll_cd = 0; - plane.nav_pitch_cd = 0; pos_control->relax_velocity_controller_xy(); } else { pos_control->set_accel_desired_xy_cmss(zero);