AC_AttitudeControl: reduced default quadplane VTOL pos XY gains

This commit is contained in:
Andrew Tridgell 2022-06-16 17:27:01 +10:00
parent ffa625dfb3
commit 395982cd34
1 changed files with 4 additions and 4 deletions

View File

@ -18,10 +18,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