From 7e4fb803a238b0397b1c390158b1f8e2a4e5488f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Jun 2022 17:27:01 +1000 Subject: [PATCH] AC_AttitudeControl: reduced default quadplane VTOL pos XY gains --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index bbee0577ee..000f63ed4a 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -20,10 +20,10 @@ extern const AP_HAL::HAL& hal; # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default # define POSCONTROL_ACC_Z_FILT_HZ 10.0f // vertical acceleration controller input filter default # define POSCONTROL_ACC_Z_DT 0.02f // vertical acceleration controller dt default - # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default - # define POSCONTROL_VEL_XY_P 1.4f // horizontal velocity controller P gain default - # define POSCONTROL_VEL_XY_I 0.7f // horizontal velocity controller I gain default - # define POSCONTROL_VEL_XY_D 0.35f // horizontal velocity controller D gain default + # define POSCONTROL_POS_XY_P 0.5f // horizontal position controller P gain default + # define POSCONTROL_VEL_XY_P 0.7f // horizontal velocity controller P gain default + # define POSCONTROL_VEL_XY_I 0.35f // horizontal velocity controller I gain default + # define POSCONTROL_VEL_XY_D 0.17f // horizontal velocity controller D gain default # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D