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

Reset PID controllers on activation and add save_iterm parameter #1507

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
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
1 change: 1 addition & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ mecanum_drive_controller
pid_controller
************************
* 🚀 The PID controller was added 🎉 (`#434 <https://github.com/ros-controls/ros2_controllers/pull/434>`_).
* Add ``save_iterm`` parameter to control retention of integral state after re-activation (`#1507 <https://github.com/ros-controls/ros2_controllers/pull/1507>`_).

steering_controllers_library
********************************
Expand Down
5 changes: 5 additions & 0 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -440,6 +440,11 @@ controller_interface::CallbackReturn PidController::on_activate(
measured_state_values_.assign(
measured_state_values_.size(), std::numeric_limits<double>::quiet_NaN());

// prefixed save_iterm parameter is read from ROS parameters
for (auto & pid : pids_)
{
pid->reset();
}
return controller_interface::CallbackReturn::SUCCESS;
}

Expand Down
5 changes: 5 additions & 0 deletions pid_controller/src/pid_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -89,3 +89,8 @@ pid_controller:
description: "For joints that wrap around (i.e., are continuous).
Normalizes position-error to -pi to pi."
}
save_iterm: {
type: bool,
default_value: true,
description: "Indicating if integral term is retained after re-activation"
}