diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index ad15853c02..c107f1fa63 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -21,8 +21,25 @@ extern const AP_HAL::HAL& hal; # 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 +#elif APM_BUILD_TYPE(APM_BUILD_ArduSub) + // default gains for Sub + # define POSCONTROL_POS_Z_P 3.0f // vertical position controller P gain default + # define POSCONTROL_VEL_Z_P 8.0f // vertical velocity controller P gain default + # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default + # define POSCONTROL_ACC_Z_I 0.1f // vertical acceleration controller I gain default + # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default + # define POSCONTROL_ACC_Z_IMAX 100 // vertical acceleration controller IMAX gain default + # define POSCONTROL_ACC_Z_FILT_HZ 20.0f // vertical acceleration controller input filter default + # define POSCONTROL_ACC_Z_DT 0.0025f // vertical acceleration controller dt default + # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default + # define POSCONTROL_VEL_XY_P 1.0f // horizontal velocity controller P gain default + # define POSCONTROL_VEL_XY_I 0.5f // horizontal velocity controller I gain default + # define POSCONTROL_VEL_XY_D 0.0f // 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 #else - // default gains for Copter and Sub + // default gains for Copter / TradHeli # define POSCONTROL_POS_Z_P 1.0f // vertical position controller P gain default # define POSCONTROL_VEL_Z_P 5.0f // vertical velocity controller P gain default # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default