Skip to content
New issue

Have a question about this project? # for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “#”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? # to your account

Add new members for PID controller parameters #1585

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from
Draft
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
42 changes: 41 additions & 1 deletion pid_controller/src/pid_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,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."
Expand All @@ -78,6 +94,30 @@ 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',
'conditioning_technique', 'conditional_integration', or 'none'. Note that the
'back_calculation' and 'conditioning_technique' strategies 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: {
subset_of<>: [[
"back_calculation",
"conditioning_technique",
"conditional_integration",
"none"
]]
}
}
tracking_time_constant: {
type: double,
default_value: 0.0,
description: "Specifies the tracking time constant for the 'back_calculation'
and 'conditioning_technique' strategies. If set to 0.0 when one of these
strategies is selected, a recommended default value will be applied."
}
feedforward_gain: {
type: double,
default_value: 0.0,
Expand Down
Loading