Skip to content

Remove legacy and deprecated PID parameters #436

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

Draft
wants to merge 5 commits into
base: ros2-master
Choose a base branch
from

Conversation

ViktorCVS
Copy link
Contributor

@ViktorCVS ViktorCVS commented Jul 29, 2025

Overview

This PR removes legacy and deprecated PID parameters from the control_toolbox package.

What was added/changed in this PR

  • Removed the legacy anti‑windup strategy
  • Removed deprecated overloads

Question

I don't know whether I should remove this block now, so I'll link it here for further discussion until the end of this PR.
https://github.com/ros-controls/control_toolbox/blob/ros2-master/control_toolbox/include/control_toolbox/pid.hpp#L416

About tests

The packages compile correctly and have passed the pre‑commit and colcon tests.

About change in tests

Three test files were modified. In addition to the updates required by the removal of the legacy anti‑windup strategy, some tests were deleted and some assertions were swapped, so I think it is relevant to list them here.

  • pid_tests.cpp:

Tests ITermBadIBoundsTestConstructor, ITermBadIBoundsTest, integrationClampTest, integrationClampZeroGainTest, integrationAntiwindupTest and negativeIntegrationAntiwindupTest were removed because they covered only the legacy anti‑windup strategy.

  • pid_ros_parameters_tests.cpp:

    Because the legacy anti‑windup strategy was the only feature that caused initialize_from_ros_parameters() to return false with the default values, the expectation was changed to ASSERT_TRUE.

https://github.com/ros-controls/control_toolbox/blob/ros2-master/control_toolbox/test/pid_ros_parameters_tests.cpp#L611

Test InitPidTestBadParameter was removed because it covered only the legacy anti‑windup strategy.

Related PR's

Final notes

I'm very open to any recommendations to improve this code.

Remove legacy and deprecated PID parameters from the control_toolbox
package.
@codecov-commenter
Copy link

codecov-commenter commented Jul 29, 2025

Codecov Report

❌ Patch coverage is 97.95918% with 1 line in your changes missing coverage. Please review.
✅ Project coverage is 77.55%. Comparing base (c46e3c5) to head (f3a667f).

Files with missing lines Patch % Lines
control_toolbox/include/control_toolbox/pid.hpp 50.00% 0 Missing and 1 partial ⚠️
Additional details and impacted files
@@               Coverage Diff               @@
##           ros2-master     #436      +/-   ##
===============================================
- Coverage        77.75%   77.55%   -0.20%     
===============================================
  Files               30       30              
  Lines             2009     1764     -245     
  Branches           125      120       -5     
===============================================
- Hits              1562     1368     -194     
+ Misses             379      331      -48     
+ Partials            68       65       -3     
Flag Coverage Δ
unittests 77.55% <97.95%> (-0.20%) ⬇️

Flags with carried forward coverage won't be shown. Click here to find out more.

Files with missing lines Coverage Δ
...ontrol_toolbox/include/control_toolbox/pid_ros.hpp 100.00% <ø> (ø)
control_toolbox/src/pid.cpp 84.55% <100.00%> (+10.00%) ⬆️
control_toolbox/src/pid_ros.cpp 63.08% <100.00%> (-1.14%) ⬇️
control_toolbox/test/pid_ros_parameters_tests.cpp 100.00% <100.00%> (ø)
control_toolbox/test/pid_ros_publisher_tests.cpp 93.96% <100.00%> (-0.70%) ⬇️
control_toolbox/test/pid_tests.cpp 100.00% <100.00%> (ø)
control_toolbox/include/control_toolbox/pid.hpp 68.05% <50.00%> (+2.96%) ⬆️
🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks a lot, I made some comments in the code.
Please also remove the default constructor of the Gains struct, I think it's a good time now.

Could you please also open follow-up PRs for the ros2_controllers? (see failing downstream tests).

@bijoua29
Copy link

bijoua29 commented Aug 4, 2025

I had a couple of comments:

  1. This is a result of the previous PR but the update of the i-term is delayed by one sample iteration since it is updated after the command is calculated. It may not be a big deal in the big picture, but it seems like if the error changes the changes should be applied in the same sample iteration not the next sample. It seems like the code could be modified to apply that change immediately although it might make the code slightly more complex. It just leaves a slightly bad taste when the changes are not applied in the current iteration.

  2. I am probably in the minority but I think there are use cases where you want to limit the contribution of the i-term to the control command i.e. there are cases where you might still want a i_limit (min/max) outside of the anti-windup strategy.

@christophfroehlich
Copy link
Contributor

I had a couple of comments:

1. This is a result of the previous PR but the update of the i-term is delayed by one sample iteration since it is updated after the command is calculated. It may not be a big deal in the big picture, but it seems like if the error changes the changes should be applied in the same sample iteration not the next sample. It seems like the code could be modified to apply that change immediately although it might make the code slightly more complex. It just leaves a slightly bad taste when the changes are not applied in the current iteration.

See the discussion above about forward and backward integration of the integral action.

2. I am probably in the minority but I think there are use cases where you want to limit the contribution of the i-term to the control command i.e. there are cases where you might still want a i_limit (min/max) outside of the anti-windup strategy.

I've already cited the Matlab/Simulink implementation above, and it also has an I_max/I_min limit. Maybe we should add this again, @ViktorCVS what do you think?

@ViktorCVS
Copy link
Contributor Author

I had a couple of comments:

1. This is a result of the previous PR but the update of the i-term is delayed by one sample iteration since it is updated after the command is calculated. It may not be a big deal in the big picture, but it seems like if the error changes the changes should be applied in the same sample iteration not the next sample. It seems like the code could be modified to apply that change immediately although it might make the code slightly more complex. It just leaves a slightly bad taste when the changes are not applied in the current iteration.

See the discussion above about forward and backward integration of the integral action.

2. I am probably in the minority but I think there are use cases where you want to limit the contribution of the i-term to the control command i.e. there are cases where you might still want a i_limit (min/max) outside of the anti-windup strategy.

I've already cited the Matlab/Simulink implementation above, and it also has an I_max/I_min limit. Maybe we should add this again, @ViktorCVS what do you think?

It’s not a problem to add this feature again, but I really can’t see any utility in it since the controller is digital and, as I mentioned, it’s a form of conditional integration that is less effective and harder to tune (according to various sources). Since MATLAB implemented it and we would still have it without this PR, it could be an option to remove it as a strategy and treat it the same way as the output clamp: on by default with default limits at infinity.
If you agree, I can change the entire PR to accomplish that.

@christophfroehlich
Copy link
Contributor

yes please, no additional parameter but setting i_limits to infinity.

@ViktorCVS ViktorCVS marked this pull request as draft August 5, 2025 14:10
@bijoua29
Copy link

bijoua29 commented Aug 5, 2025

I had a couple of comments:

1. This is a result of the previous PR but the update of the i-term is delayed by one sample iteration since it is updated after the command is calculated. It may not be a big deal in the big picture, but it seems like if the error changes the changes should be applied in the same sample iteration not the next sample. It seems like the code could be modified to apply that change immediately although it might make the code slightly more complex. It just leaves a slightly bad taste when the changes are not applied in the current iteration.

See the discussion above about forward and backward integration of the integral action.

2. I am probably in the minority but I think there are use cases where you want to limit the contribution of the i-term to the control command i.e. there are cases where you might still want a i_limit (min/max) outside of the anti-windup strategy.

I've already cited the Matlab/Simulink implementation above, and it also has an I_max/I_min limit. Maybe we should add this again, @ViktorCVS what do you think?

Oh sorry. I didn't see the discussion on forward and backward integration. So the plan is to change it to forward integration in another PR - is that correct?

And I agree, adding a simple clamp for imax/imin is fine with default set to infinity. I assume you will then maintain the i_clamp_min/max ros parameters in PidROS.

@bijoua29
Copy link

bijoua29 commented Aug 5, 2025

@ViktorCVS Please also see related issue I just opened: #442

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants