From 8068f72be361b342eac221eaa4a67b144cc4dcfb Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 19 Sep 2023 11:16:14 +0930 Subject: [PATCH] AP_WheelEncoder: Support PD Max --- libraries/AP_WheelEncoder/AP_WheelRateControl.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp index ff8739eb45..e23a13b93f 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -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