diff --git a/pid_controller/src/pid_controller.yaml b/pid_controller/src/pid_controller.yaml index 8903085667..a64e3f7433 100644 --- a/pid_controller/src/pid_controller.yaml +++ b/pid_controller/src/pid_controller.yaml @@ -65,10 +65,26 @@ pid_controller: default_value: 0.0, description: "Derivative gain for PID" } + saturation: { + type: bool, + default_value: false, + description: "Enables output saturation. When true, the controller output is + clamped between u_clamp_max and u_clamp_min." + } + u_clamp_max: { + type: double, + default_value: 0.0, + description: "Upper output clamp." + } + u_clamp_min: { + type: double, + default_value: 0.0, + description: "Lower output clamp." + } antiwindup: { type: bool, default_value: false, - description: "Antiwindup functionality. When set to true, limits + description: "Anti-windup functionality. When set to true, limits the integral error to prevent windup; otherwise, constrains the integral contribution to the control output. i_clamp_max and i_clamp_min are applied in both scenarios." @@ -83,6 +99,27 @@ pid_controller: default_value: 0.0, description: "Lower integral clamp." } + antiwindup_strategy: { + type: string, + default_value: "none", + description: "Specifies the anti-windup strategy. Options: 'back_calculation', + 'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the + tracking_time_constant parameter to tune the anti-windup behavior. When a strategy other + than 'none' is selected, it will override the controller's default anti-windup behavior.", + validation: { + one_of<>: [[ + "back_calculation", + "conditional_integration", + "none" + ]] + } + } + tracking_time_constant: { + type: double, + default_value: 0.0, + description: "Specifies the tracking time constant for the 'back_calculation' strategy. If + set to 0.0 when this strategy is selected, a recommended default value will be applied." + } feedforward_gain: { type: double, default_value: 0.0,