Skip to content

Commit ca9f0d2

Browse files
committed
Add new members for PID controller parameters
Adds new members to PID controller parameters to support saturation and three new anti-windup features.
1 parent b333def commit ca9f0d2

File tree

1 file changed

+41
-1
lines changed

1 file changed

+41
-1
lines changed

pid_controller/src/pid_controller.yaml

+41-1
Original file line numberDiff line numberDiff line change
@@ -60,10 +60,26 @@ pid_controller:
6060
default_value: 0.0,
6161
description: "Derivative gain for PID"
6262
}
63+
saturation: {
64+
type: bool,
65+
default_value: false,
66+
description: "Enables output saturation. When true, the controller output is
67+
clamped between u_clamp_max and u_clamp_min."
68+
}
69+
u_clamp_max: {
70+
type: double,
71+
default_value: 0.0,
72+
description: "Upper output clamp."
73+
}
74+
u_clamp_min: {
75+
type: double,
76+
default_value: 0.0,
77+
description: "Lower output clamp."
78+
}
6379
antiwindup: {
6480
type: bool,
6581
default_value: false,
66-
description: "Antiwindup functionality. When set to true, limits
82+
description: "Anti-windup functionality. When set to true, limits
6783
the integral error to prevent windup; otherwise, constrains the
6884
integral contribution to the control output. i_clamp_max and
6985
i_clamp_min are applied in both scenarios."
@@ -78,6 +94,30 @@ pid_controller:
7894
default_value: 0.0,
7995
description: "Lower integral clamp."
8096
}
97+
antiwindup_strategy: {
98+
type: string,
99+
default_value: "none",
100+
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
101+
'conditioning_technique', 'conditional_integration', or 'none'. Note that the
102+
'back_calculation' and 'conditioning_technique' strategies use the tracking_time_constant
103+
parameter to tune the anti-windup behavior. When a strategy other than 'none' is selected,
104+
it will override the controller's default anti-windup behavior.",
105+
validation: {
106+
subset_of<>: [[
107+
"back_calculation",
108+
"conditioning_technique",
109+
"conditional_integration",
110+
"none"
111+
]]
112+
}
113+
}
114+
tracking_time_constant: {
115+
type: double,
116+
default_value: 0.0,
117+
description: "Specifies the tracking time constant for the 'back_calculation'
118+
and 'conditioning_technique' strategies. If set to 0.0 when one of these
119+
strategies is selected, a recommended default value will be applied."
120+
}
81121
feedforward_gain: {
82122
type: double,
83123
default_value: 0.0,

0 commit comments

Comments
 (0)