Skip to content
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

PID controller feedforward control #1270

Open
christophfroehlich opened this issue Aug 26, 2024 · 4 comments
Open

PID controller feedforward control #1270

christophfroehlich opened this issue Aug 26, 2024 · 4 comments

Comments

@christophfroehlich
Copy link
Contributor

christophfroehlich commented Aug 26, 2024

Originally posted by @catcracker in #1260 (comment)

Is your feature suggestion related to a problem? Please describe.
While using the PID controller and tricycle controller, there might be room for improvement in the following areas:

There seems to be no straightforward method to enable or disable feedforward control.
The controller state topics (~/controller_state or /pid_state) don't appear to include feedforward gain information.
The feedforward gain in the PID controller may not work as expected in some cases.
The tricycle controller might benefit from additional parameters to better support cascaded control scenarios.

Describe the solution you'd like to see
For both PID and Tricycle Controllers:

Consider adding a boolean parameter in the YAML configuration to enable/disable feedforward control, for example:
enable_feedforward: true
Alternatively, it might be worth considering automatically enabling feedforward control when feedforward_gain is non-zero.
It could be beneficial to publish feedforward_gain in the ~/controller_state or /pid_state topics.

For PID Controller:

It might be necessary to investigate and address the issue with feedforward_gain application. Currently, in the pid_controller.cpp file (lines 444-445), the result appears to always be 0.000.
A potential fix to consider might be:
tmp_command= reference_interfaces_[i] * params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;

@christophfroehlich
Copy link
Contributor Author

christophfroehlich commented Aug 26, 2024

Is your feature suggestion related to a problem? Please describe. While using the PID controller and tricycle controller, there might be room for improvement in the following areas:

There seems to be no straightforward method to enable or disable feedforward control.
The controller state topics (~/controller_state or /pid_state) don't appear to include feedforward gain information.
The feedforward gain in the PID controller may not work as expected in some cases.
The tricycle controller might benefit from additional parameters to better support cascaded control scenarios.

Describe the solution you'd like to see For both PID and Tricycle Controllers:

Consider adding a boolean parameter in the YAML configuration to enable/disable feedforward control, for example:
enable_feedforward: true
Alternatively, it might be worth considering automatically enabling feedforward control when feedforward_gain is non-zero.
It could be beneficial to publish feedforward_gain in the ~/controller_state or /pid_state topics.

There is already a service for that: set_feedforward_control? But your problem is that

  1. it is not default on, even if a feedforward gain is set?
  2. you don't have debug info if it is active or not?

For PID Controller:

It might be necessary to investigate and address the issue with feedforward_gain application. Currently, in the pid_controller.cpp file (lines 444-445), the result appears to always be 0.000. A potential fix to consider might be: tmp_command= reference_interfaces_[i] * params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;

The change you are proposing is removing the dof_ from the reference interface index?

tmp_command = reference_interfaces_[dof_ + i] *
params_.gains.dof_names_map[params_.dof_names[i]].feedforward_gain;

The documentation is a bit cryptic here
https://github.com/ros-controls/ros2_controllers/blob/master/pid_controller/doc/userdoc.rst#execution-logic-of-the-controller

But I think the idea was to have position and velocity references, with velocity command interface. Then the feedforward part is the velocity of the reference (and therefore dof_+i). This design could be improved, feel free to propose a change here.

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

No branches or pull requests

4 participants
@christophfroehlich and others