Skip to content

Commit f4dff7e

Browse files
ViktorCVSmergify[bot]
authored andcommitted
Add new members for PID controller parameters (#1585)
(cherry picked from commit aebe6b1) # Conflicts: # doc/migration.rst # doc/release_notes.rst
1 parent 22e925d commit f4dff7e

File tree

3 files changed

+59
-3
lines changed

3 files changed

+59
-3
lines changed

doc/migration.rst

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ diff_drive_controller
1212

1313
joint_trajectory_controller
1414
*****************************
15+
<<<<<<< HEAD
1516

1617
* Parameter ``allow_nonzero_velocity_at_trajectory_end`` is now per default ``false`` (`#834 <https://github.com/ros-controls/ros2_controllers/pull/834>`_).
1718
* The parameter ``start_with_holding`` is removed, it now always holds the position at activation (`#839 <https://github.com/ros-controls/ros2_controllers/pull/839>`_).
@@ -30,3 +31,8 @@ steering_controllers_library
3031
* *bicycle_steering_controller*: Set ``traction_wheel_radius`` instead of ``front_wheel_radius``, ``rear_wheel_radius``.
3132
* *tricycle_steering_controller*: Set ``traction_wheels_radius`` instead of ``front_wheels_radius``, ``rear_wheels_radius``.
3233
* *ackermann_steering_controller*: Set ``traction_wheels_radius`` instead of ``front_wheels_radius``, ``rear_wheels_radius``, and ``traction_track_width`` (and optionally ``steering_track_width``, if it differs) instead of ``rear_wheel_track``, ``front_wheel_track``.
34+
=======
35+
* 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>`_).
36+
* The legacy ``antiwindup`` boolean and integral clamp parameters ``i_clamp_max``/``i_clamp_min`` have
37+
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.
38+
>>>>>>> aebe6b1 (Add new members for PID controller parameters (#1585))

doc/release_notes.rst

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -86,3 +86,17 @@ gpio_controllers
8686
force_torque_sensor_broadcaster
8787
*******************************
8888
* Multiplier support was added. Users can now specify per–axis scaling factors for both force and torque readings, applied after the existing offset logic. (`#1647 <https://github.com/ros-controls/ros2_controllers/pull/1647/files>`__).
89+
<<<<<<< HEAD
90+
=======
91+
92+
joint_trajectory_controller
93+
*******************************
94+
* 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>`__).
95+
96+
pid_controller
97+
*******************************
98+
* 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>`__).
99+
* Output clamping via ``u_clamp_max`` and ``u_clamp_min`` was added, allowing users to bound the controller output.
100+
* 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.
101+
* A new ``error_deadband`` parameter stops integration when the error is within a specified range.
102+
>>>>>>> aebe6b1 (Add new members for PID controller parameters (#1585))

pid_controller/src/pid_controller.yaml

Lines changed: 39 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -65,23 +65,59 @@ pid_controller:
6565
default_value: 0.0,
6666
description: "Derivative gain for PID"
6767
}
68+
u_clamp_max: {
69+
type: double,
70+
default_value: .inf,
71+
description: "Upper output clamp."
72+
}
73+
u_clamp_min: {
74+
type: double,
75+
default_value: -.inf,
76+
description: "Lower output clamp."
77+
}
6878
antiwindup: {
6979
type: bool,
7080
default_value: false,
71-
description: "Antiwindup functionality. When set to true, limits
81+
description: "[Deprecated, see antiwindup_strategy] Anti-windup functionality. When set to true, limits
7282
the integral error to prevent windup; otherwise, constrains the
7383
integral contribution to the control output. i_clamp_max and
7484
i_clamp_min are applied in both scenarios."
7585
}
7686
i_clamp_max: {
7787
type: double,
7888
default_value: 0.0,
79-
description: "Upper integral clamp."
89+
description: "[Deprecated, see antiwindup_strategy] Upper integral clamp."
8090
}
8191
i_clamp_min: {
8292
type: double,
8393
default_value: 0.0,
84-
description: "Lower integral clamp."
94+
description: "[Deprecated, see antiwindup_strategy] Lower integral clamp."
95+
}
96+
antiwindup_strategy: {
97+
type: string,
98+
default_value: "legacy",
99+
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
100+
'conditional_integration', 'legacy' or 'none'. Note that the 'back_calculation' strategy use the
101+
tracking_time_constant parameter to tune the anti-windup behavior.",
102+
validation: {
103+
one_of<>: [[
104+
"back_calculation",
105+
"conditional_integration",
106+
"legacy",
107+
"none"
108+
]]
109+
}
110+
}
111+
tracking_time_constant: {
112+
type: double,
113+
default_value: 0.0,
114+
description: "Specifies the tracking time constant for the 'back_calculation' strategy. If
115+
set to 0.0 when this strategy is selected, a recommended default value will be applied."
116+
}
117+
error_deadband: {
118+
type: double,
119+
default_value: 1.e-16,
120+
description: "Is used to stop integration when the error is within the given range."
85121
}
86122
feedforward_gain: {
87123
type: double,

0 commit comments

Comments
 (0)