Skip to content

Commit 0f51de6

Browse files
Apply API change of PidROS (#1823)
1 parent bf253f1 commit 0f51de6

File tree

5 files changed

+12
-3
lines changed

5 files changed

+12
-3
lines changed

doc/migration.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,3 +17,4 @@ pid_controller
1717
* 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>`_).
1818
* The legacy ``antiwindup`` boolean and integral clamp parameters ``i_clamp_max``/``i_clamp_min`` have
1919
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.
20+
* 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>`_).

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,3 +22,4 @@ pid_controller
2222
* Output clamping via ``u_clamp_max`` and ``u_clamp_min`` was added, allowing users to bound the controller output.
2323
* 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.
2424
* A new ``error_deadband`` parameter stops integration when the error is within a specified range.
25+
* 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>`_).

pid_controller/doc/userdoc.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,9 @@ If controller parameter ``use_external_measured_states`` is true:
7272
Publishers
7373
,,,,,,,,,,,
7474
- <controller_name>/controller_state [control_msgs/msg/MultiDOFStateStamped]
75+
- <controller_name>/<dof>/pid_state [control_msgs/msg/PidState]
76+
77+
Initially the PidState publisher is turned off. It can be turned on by using ``gains.<dof>.activate_state_publisher`` parameter.
7578

7679
Parameters
7780
,,,,,,,,,,,

pid_controller/src/pid_controller.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -126,9 +126,8 @@ controller_interface::CallbackReturn PidController::configure_parameters()
126126

127127
for (size_t i = 0; i < dof_; ++i)
128128
{
129-
// prefix should be interpreted as parameters prefix
130-
pids_[i] =
131-
std::make_shared<control_toolbox::PidROS>(get_node(), "gains." + params_.dof_names[i], true);
129+
pids_[i] = std::make_shared<control_toolbox::PidROS>(
130+
get_node(), "gains." + params_.dof_names[i], "~/" + params_.dof_names[i], false);
132131
if (!pids_[i]->initialize_from_ros_parameters())
133132
{
134133
return CallbackReturn::FAILURE;

pid_controller/src/pid_controller.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -130,3 +130,8 @@ pid_controller:
130130
default_value: true,
131131
description: "Indicating if integral term is retained after re-activation"
132132
}
133+
activate_state_publisher: {
134+
type: bool,
135+
default_value: false,
136+
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`."
137+
}

0 commit comments

Comments
 (0)