AC_AttitudeControl: Support PD Max

This commit is contained in:
Leonard Hall 2023-09-19 11:14:54 +09:30 committed by Andrew Tridgell
parent 3de0bcefdb
commit ac0244e430
3 changed files with 49 additions and 0 deletions

View File

@ -74,6 +74,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: RAT_RLL_PDMX
// @DisplayName: Roll axis rate controller PD sum maximum
// @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Advanced
AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID),
// @Param: RAT_PIT_P
@ -142,6 +149,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: RAT_PIT_PDMX
// @DisplayName: Pitch axis rate controller PD sum maximum
// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Advanced
AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID),
// @Param: RAT_YAW_P
@ -210,6 +224,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: RAT_YAW_PDMX
// @DisplayName: Yaw axis rate controller PD sum maximum
// @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Advanced
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID),
// @Param: THR_MIX_MIN

View File

@ -73,6 +73,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: RAT_RLL_PDMX
// @DisplayName: Roll axis rate controller PD sum maximum
// @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Advanced
AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Sub, AC_PID),
// @Param: RAT_PIT_P
@ -141,6 +148,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: RAT_PIT_PDMX
// @DisplayName: Pitch axis rate controller PD sum maximum
// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Advanced
AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Sub, AC_PID),
// @Param: RAT_YAW_P
@ -209,6 +223,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: RAT_YAW_PDMX
// @DisplayName: Yaw axis rate controller PD sum maximum
// @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Advanced
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Sub, AC_PID),
// @Param: THR_MIX_MIN

View File

@ -204,6 +204,13 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: _ACCZ_PDMX
// @DisplayName: Acceleration (vertical) controller PD sum maximum
// @Description: Acceleration (vertical) controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1000
// @Units: d%
// @User: Advanced
AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID),
// @Param: _POSXY_P