Skip to content

Add new members for PID controller parameters #1585

New issue

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

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

Already on GitHub? Sign in to your account

Merged
merged 14 commits into from
Jun 19, 2025
Merged
Show file tree
Hide file tree
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
2 changes: 2 additions & 0 deletions doc/migration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,5 @@ diff_drive_controller
pid_controller
*****************************
* Parameters ``enable_feedforward`` and service ``set_feedforward_control`` are removed. Instead, set the feedforward_gain to zero or a non-zero value. (`#1553 <https://github.com/ros-controls/ros2_controllers/pull/1553>`_).
* The legacy ``antiwindup`` boolean and integral clamp parameters ``i_clamp_max``/``i_clamp_min`` have
been deprecated in favor of the new ``antiwindup_strategy`` parameter (`#1585 <https://github.com/ros-controls/ros2_controllers/pull/1585>`__). Choose a suitable anti-windup strategy and set the parameters accordingly.
7 changes: 7 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,3 +11,10 @@ force_torque_sensor_broadcaster
joint_trajectory_controller
*******************************
* The controller now supports the new anti-windup strategy of the PID class, which allows for more flexible control of the anti-windup behavior. (`#1759 <https://github.com/ros-controls/ros2_controllers/pull/1759>`__).

pid_controller
*******************************
* The controller now supports the new anti-windup strategy of the PID class, which allows for more flexible control of the anti-windup behavior (`#1585 <https://github.com/ros-controls/ros2_controllers/pull/1585>`__).
* Output clamping via ``u_clamp_max`` and ``u_clamp_min`` was added, allowing users to bound the controller output.
* The legacy ``antiwindup`` boolean and integral clamp parameters ``i_clamp_max``/``i_clamp_min`` have been deprecated in favor of the new ``antiwindup_strategy`` parameter. A ``tracking_time_constant`` parameter has also been introduced to configure the back-calculation strategy.
* A new ``error_deadband`` parameter stops integration when the error is within a specified range.
42 changes: 39 additions & 3 deletions pid_controller/src/pid_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -60,23 +60,59 @@ pid_controller:
default_value: 0.0,
description: "Derivative gain for PID"
}
u_clamp_max: {
type: double,
default_value: .inf,
description: "Upper output clamp."
}
u_clamp_min: {
type: double,
default_value: -.inf,
description: "Lower output clamp."
}
antiwindup: {
type: bool,
default_value: false,
description: "Antiwindup functionality. When set to true, limits
description: "[Deprecated, see antiwindup_strategy] 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."
}
i_clamp_max: {
type: double,
default_value: 0.0,
description: "Upper integral clamp."
description: "[Deprecated, see antiwindup_strategy] Upper integral clamp."
}
i_clamp_min: {
type: double,
default_value: 0.0,
description: "Lower integral clamp."
description: "[Deprecated, see antiwindup_strategy] Lower integral clamp."
}
antiwindup_strategy: {
type: string,
default_value: "legacy",
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
'conditional_integration', 'legacy' or 'none'. Note that the 'back_calculation' strategy use the
tracking_time_constant parameter to tune the anti-windup behavior.",
validation: {
one_of<>: [[
"back_calculation",
"conditional_integration",
"legacy",
"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."
}
error_deadband: {
type: double,
default_value: 1.e-16,
description: "Is used to stop integration when the error is within the given range."
}
feedforward_gain: {
type: double,
Expand Down
Loading