From d5bd30bce0d263d863469afa41f0a626db4450a6 Mon Sep 17 00:00:00 2001 From: magate <69254089+magate@users.noreply.github.com> Date: Wed, 20 Mar 2024 15:23:20 -0700 Subject: [PATCH] Plane: do not set desired vel/accel on takeoff This effectively bypasses the input shaping. Currently this creates a step change in the position controller. --- ArduPlane/quadplane.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 390787425d..0bb00459ee 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3099,8 +3099,6 @@ void QuadPlane::takeoff_controller(void) if (no_navigation) { pos_control->relax_velocity_controller_xy(); } else { - pos_control->set_accel_desired_xy_cmss(zero); - pos_control->set_vel_desired_xy_cms(vel); pos_control->input_vel_accel_xy(vel, zero); // nav roll and pitch are controller by position controller