AP_WheelEncoder: Support PD Max

This commit is contained in:
Leonard Hall 2023-09-19 11:16:14 +09:30 committed by Andrew Tridgell
parent df014a2c05
commit 8068f72be3
1 changed files with 12 additions and 0 deletions

View File

@ -86,6 +86,12 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: _RATE_PDMX
// @DisplayName: Wheel rate control PD sum maximum
// @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @User: Advanced
AP_SUBGROUPINFO(_rate_pid0, "_RATE_", 3, AP_WheelRateControl, AC_PID),
// @Param: 2_RATE_FF
@ -156,6 +162,12 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced
// @Param: 2_RATE_PDMX
// @DisplayName: Wheel rate control PD sum maximum
// @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @User: Advanced
AP_SUBGROUPINFO(_rate_pid1, "2_RATE_", 4, AP_WheelRateControl, AC_PID),
AP_GROUPEND