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
This commit is contained in:
Andrew Tridgell 2023-09-03 07:42:22 +10:00
parent 9742997a34
commit 9d98244730
1 changed files with 4 additions and 2 deletions

View File

@ -2946,6 +2946,10 @@ void QuadPlane::setup_target_position(void)
*/ */
void QuadPlane::takeoff_controller(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()) { if (!plane.arming.is_armed_and_safety_off()) {
return; return;
} }
@ -3007,8 +3011,6 @@ void QuadPlane::takeoff_controller(void)
takeoff_last_run_ms = now; takeoff_last_run_ms = now;
if (no_navigation) { if (no_navigation) {
plane.nav_roll_cd = 0;
plane.nav_pitch_cd = 0;
pos_control->relax_velocity_controller_xy(); pos_control->relax_velocity_controller_xy();
} else { } else {
pos_control->set_accel_desired_xy_cmss(zero); pos_control->set_accel_desired_xy_cmss(zero);