AC_CustomControl: Support PD Max

This commit is contained in:
Leonard Hall 2023-09-19 11:15:45 +09:30 committed by Andrew Tridgell
parent ac0244e430
commit df014a2c05
1 changed files with 21 additions and 0 deletions

View File

@ -94,6 +94,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Range: 0 200 // @Range: 0 200
// @Increment: 0.5 // @Increment: 0.5
// @User: Advanced // @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_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID), AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID),
// @Param: RAT_PIT_P // @Param: RAT_PIT_P
@ -161,6 +168,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Range: 0 200 // @Range: 0 200
// @Increment: 0.5 // @Increment: 0.5
// @User: Advanced // @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_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID), AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID),
@ -229,6 +243,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Range: 0 200 // @Range: 0 200
// @Increment: 0.5 // @Increment: 0.5
// @User: Advanced // @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_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID), AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID),
AP_GROUPEND AP_GROUPEND