diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index bc05b1b953..4f1a960017 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -64,6 +64,24 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Increment: 0.1 // @Units: Hz // @User: Standard + + // @Param: _STR_RAT_FLTT + // @DisplayName: Steering control Target filter frequency in Hz + // @Description: Target filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _STR_RAT_FLTE + // @DisplayName: Steering control Error filter frequency in Hz + // @Description: Error filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _STR_RAT_FLTD + // @DisplayName: Steering control Derivative term filter frequency in Hz + // @Description: Derivative filter frequency in Hz + // @Units: Hz + // @User: Standard AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID), // @Param: _SPEED_P @@ -107,6 +125,24 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Increment: 0.1 // @Units: Hz // @User: Standard + + // @Param: _SPEED_FLTT + // @DisplayName: Speed control Target filter frequency in Hz + // @Description: Target filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _SPEED_FLTE + // @DisplayName: Speed control Error filter frequency in Hz + // @Description: Error filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _SPEED_FLTD + // @DisplayName: Speed control Derivative term filter frequency in Hz + // @Description: Derivative filter frequency in Hz + // @Units: Hz + // @User: Standard AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID), // @Param: _ACCEL_MAX @@ -210,6 +246,24 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Increment: 0.1 // @Units: Hz // @User: Standard + + // @Param: _BAL_FLTT + // @DisplayName: Pitch control Target filter frequency in Hz + // @Description: Target filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _BAL_FLTE + // @DisplayName: Pitch control Error filter frequency in Hz + // @Description: Error filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _BAL_FLTD + // @DisplayName: Pitch control Derivative term filter frequency in Hz + // @Description: Derivative filter frequency in Hz + // @Units: Hz + // @User: Standard AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID), // @Param: _BAL_SPD_FF @@ -261,6 +315,24 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Increment: 0.1 // @Units: Hz // @User: Standard + + // @Param: _SAIL_FLTT + // @DisplayName: Sail Heel Target filter frequency in Hz + // @Description: Target filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _SAIL_FLTE + // @DisplayName: Sail Heel Error filter frequency in Hz + // @Description: Error filter frequency in Hz + // @Units: Hz + // @User: Standard + + // @Param: _SAIL_FLTD + // @DisplayName: Sail Heel Derivative term filter frequency in Hz + // @Description: Derivative filter frequency in Hz + // @Units: Hz + // @User: Standard AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID), AP_GROUPEND