Skip to content
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
1 change: 1 addition & 0 deletions doc/migration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,3 +17,4 @@ 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.
* PID state publisher topic changed to ``<controller_name>`` namespace and is initially turned off. It can be turned on by using ``activate_state_publisher`` parameter. (`#1823 <https://github.com/ros-controls/ros2_controllers/pull/1823>`_).
1 change: 1 addition & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -22,3 +22,4 @@ pid_controller
* 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.
* PID state publisher can be turned off or on by using ``activate_state_publisher`` parameter. (`#1823 <https://github.com/ros-controls/ros2_controllers/pull/1823>`_).
3 changes: 3 additions & 0 deletions pid_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,9 @@ If controller parameter ``use_external_measured_states`` is true:
Publishers
,,,,,,,,,,,
- <controller_name>/controller_state [control_msgs/msg/MultiDOFStateStamped]
- <controller_name>/<dof>/pid_state [control_msgs/msg/PidState]

Initially the PidState publisher is turned off. It can be turned on by using ``gains.<dof>.activate_state_publisher`` parameter.

Parameters
,,,,,,,,,,,
Expand Down
5 changes: 2 additions & 3 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,9 +126,8 @@ controller_interface::CallbackReturn PidController::configure_parameters()

for (size_t i = 0; i < dof_; ++i)
{
// prefix should be interpreted as parameters prefix
pids_[i] =
std::make_shared<control_toolbox::PidROS>(get_node(), "gains." + params_.dof_names[i], true);
pids_[i] = std::make_shared<control_toolbox::PidROS>(
get_node(), "gains." + params_.dof_names[i], "~/" + params_.dof_names[i], false);
if (!pids_[i]->initialize_from_ros_parameters())
{
return CallbackReturn::FAILURE;
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 @@ -130,3 +130,8 @@ pid_controller:
default_value: true,
description: "Indicating if integral term is retained after re-activation"
}
activate_state_publisher: {
type: bool,
default_value: false,
description: "Individual state publisher activation for each DOF. If true, the controller will publish the state of each DOF to the topic `/<controller_name>/<dof_name>/pid_state`."
}
Loading