From 7ea2f92e22a7f8c1a46672f553bd19f2bca48e50 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Tue, 16 Sep 2025 18:47:12 +0000 Subject: [PATCH 1/5] Deprecate specializations --- effort_controllers/doc/userdoc.rst | 4 ++++ effort_controllers/src/joint_group_effort_controller.cpp | 5 +++++ position_controllers/doc/userdoc.rst | 4 ++++ position_controllers/src/joint_group_position_controller.cpp | 5 +++++ velocity_controllers/doc/userdoc.rst | 4 ++++ velocity_controllers/src/joint_group_velocity_controller.cpp | 5 +++++ 6 files changed, 27 insertions(+) diff --git a/effort_controllers/doc/userdoc.rst b/effort_controllers/doc/userdoc.rst index 62e98a75f9..d6189f0483 100644 --- a/effort_controllers/doc/userdoc.rst +++ b/effort_controllers/doc/userdoc.rst @@ -12,6 +12,10 @@ The package contains the following controllers: effort_controllers/JointGroupEffortController ------------------------------------------------- +.. warning:: + + ``effort_controllers/JointGroupEffortController`` is deprecated. Use :ref:`forward_command_controller ` instead by adding the ``interface_name`` parameter and set it to ``effort``. + This is specialization of the :ref:`forward_command_controller ` that works using the "effort" joint interface. diff --git a/effort_controllers/src/joint_group_effort_controller.cpp b/effort_controllers/src/joint_group_effort_controller.cpp index 6ae0d84ede..e1dc67b57e 100644 --- a/effort_controllers/src/joint_group_effort_controller.cpp +++ b/effort_controllers/src/joint_group_effort_controller.cpp @@ -29,6 +29,11 @@ JointGroupEffortController::JointGroupEffortController() controller_interface::CallbackReturn JointGroupEffortController::on_init() { + RCLCPP_WARN( + get_node()->get_logger(), + "'effort_controllers/JointGroupEffortController' is deprecated. " + "Use 'forward_command_controller/ForwardCommandController' instead by adding the " + "'interface_name' parameter and set it to 'effort'."); try { // Explicitly set the interface parameter declared by the forward_command_controller diff --git a/position_controllers/doc/userdoc.rst b/position_controllers/doc/userdoc.rst index 89766df9d4..7e54747ae0 100644 --- a/position_controllers/doc/userdoc.rst +++ b/position_controllers/doc/userdoc.rst @@ -12,6 +12,10 @@ The package contains the following controllers: position_controllers/JointGroupPositionController ------------------------------------------------- +.. warning:: + + ``position_controllers/JointGroupPositionController`` is deprecated. Use :ref:`forward_command_controller ` instead by adding the ``interface_name`` parameter and set it to ``position``. + This is specialization of the :ref:`forward_command_controller ` that works using the "position" joint interface. diff --git a/position_controllers/src/joint_group_position_controller.cpp b/position_controllers/src/joint_group_position_controller.cpp index a5bf512fe2..510d8e337d 100644 --- a/position_controllers/src/joint_group_position_controller.cpp +++ b/position_controllers/src/joint_group_position_controller.cpp @@ -29,6 +29,11 @@ JointGroupPositionController::JointGroupPositionController() controller_interface::CallbackReturn JointGroupPositionController::on_init() { + RCLCPP_WARN( + get_node()->get_logger(), + "'position_controllers/JointGroupPositionController' is deprecated. " + "Use 'forward_command_controller/ForwardCommandController' instead by adding the " + "'interface_name' parameter and set it to 'position'."); try { // Explicitly set the interface parameter declared by the forward_command_controller diff --git a/velocity_controllers/doc/userdoc.rst b/velocity_controllers/doc/userdoc.rst index 469b975a97..ce98a7fc45 100644 --- a/velocity_controllers/doc/userdoc.rst +++ b/velocity_controllers/doc/userdoc.rst @@ -12,6 +12,10 @@ The package contains the following controllers: velocity_controllers/JointGroupVelocityController ------------------------------------------------- +.. warning:: + + ``velocity_controllers/JointGroupVelocityController`` is deprecated. Use :ref:`forward_command_controller ` instead by adding the ``interface_name`` parameter and set it to ``velocity``. + This is specialization of the :ref:`forward_command_controller ` that works using the "velocity" joint interface. diff --git a/velocity_controllers/src/joint_group_velocity_controller.cpp b/velocity_controllers/src/joint_group_velocity_controller.cpp index 1dbb93f72d..fc67ead82b 100644 --- a/velocity_controllers/src/joint_group_velocity_controller.cpp +++ b/velocity_controllers/src/joint_group_velocity_controller.cpp @@ -29,6 +29,11 @@ JointGroupVelocityController::JointGroupVelocityController() controller_interface::CallbackReturn JointGroupVelocityController::on_init() { + RCLCPP_WARN( + get_node()->get_logger(), + "'velocity_controllers/JointGroupVelocityController' is deprecated. " + "Use 'forward_command_controller/ForwardCommandController' instead by adding the " + "'interface_name' parameter and set it to 'velocity'."); try { // Explicitly set the interface parameter declared by the forward_command_controller From d85f6dae0e204c49ea654476bdbe074c0a886e29 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Tue, 16 Sep 2025 18:47:27 +0000 Subject: [PATCH 2/5] Improve docs of forward_command_controller --- forward_command_controller/doc/userdoc.rst | 10 +++++----- .../src/forward_command_controller_parameters.yaml | 2 +- ...nterface_forward_command_controller_parameters.yaml | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/forward_command_controller/doc/userdoc.rst b/forward_command_controller/doc/userdoc.rst index cd623a5acb..ac16fe1664 100644 --- a/forward_command_controller/doc/userdoc.rst +++ b/forward_command_controller/doc/userdoc.rst @@ -5,16 +5,16 @@ forward_command_controller ========================== -This is a base class implementing a feedforward controller. Specific implementations of this base class can be found in: +A selection of controllers that forward commands of different types. -* :ref:`position_controllers_userdoc` -* :ref:`velocity_controllers_userdoc` -* :ref:`effort_controllers_userdoc` +forward_command_controller and multi_interface_forward_command_controller +######################################################################### +Both controllers forward ``std_msgs::msg::Float64MultiArray`` to a set of interfaces, which can be parameterized as follows: While ``forward_command_controller/ForwardCommandController`` only claims a single interface type per joint (``joint[i] + "/" + interface_name``), the ``forward_command_controller/MultiInterfaceForwardCommandController`` claims the combination of all interfaces specified in the ``interface_names`` parameter (``joint[i] + "/" + interface_names[j]``). Hardware interface type ----------------------- -This controller can be used for every type of command interface. +This controller can be used for every type of command interface, not only limited to joints. ROS 2 interface of the controller diff --git a/forward_command_controller/src/forward_command_controller_parameters.yaml b/forward_command_controller/src/forward_command_controller_parameters.yaml index 5210b3e8c9..9c964a12cd 100644 --- a/forward_command_controller/src/forward_command_controller_parameters.yaml +++ b/forward_command_controller/src/forward_command_controller_parameters.yaml @@ -9,7 +9,7 @@ forward_command_controller: } interface_name: { type: string, - description: "Name of the interface to command", + description: "Name of the interface of the joint", validation: { not_empty<>: [] }, diff --git a/forward_command_controller/src/multi_interface_forward_command_controller_parameters.yaml b/forward_command_controller/src/multi_interface_forward_command_controller_parameters.yaml index 7bb99041c0..e8bfb53348 100644 --- a/forward_command_controller/src/multi_interface_forward_command_controller_parameters.yaml +++ b/forward_command_controller/src/multi_interface_forward_command_controller_parameters.yaml @@ -9,7 +9,7 @@ multi_interface_forward_command_controller: } interface_names: { type: string_array, - description: "Names of the interfaces to command", + description: "Names of the interfaces per joint to claim", validation: { not_empty<>: [] }, From 8ef27f9b7be194f3463a5c225efb22cc50037bf3 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Tue, 16 Sep 2025 18:55:14 +0000 Subject: [PATCH 3/5] Update migration notes --- doc/migration.rst | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/doc/migration.rst b/doc/migration.rst index 72de6cabb0..ff7b36d1a3 100644 --- a/doc/migration.rst +++ b/doc/migration.rst @@ -4,17 +4,30 @@ Migration Guides: Jazzy to Kilted ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This list summarizes important changes between Jazzy (previous) and Kilted (current) releases, where changes to user code might be necessary. -GripperActionController -***************************** -The ``effort_controllers/GripperActionController`` and ``position_controllers/GripperActionController`` have been removed. The ``parallel_gripper_action_controller/GripperActionController`` should be used instead. `(#1652 `__). diff_drive_controller ***************************** * Parameters ``has_velocity_limits``, ``has_acceleration_limits``, and ``has_jerk_limits`` are removed. Instead, set the respective limits to ``.NAN``. (`#1653 `_). +effort_controllers +***************************** + ``effort_controllers/JointGroupEffortController`` is deprecated. Use :ref:`forward_command_controller ` instead by adding the ``interface_name`` parameter and set it to ``effort``. (`#1913 `_). + +GripperActionController +***************************** +The ``effort_controllers/GripperActionController`` and ``position_controllers/GripperActionController`` have been removed. The ``parallel_gripper_action_controller/GripperActionController`` should be used instead. `(#1652 `__). + 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 `_). * 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 `__). Choose a suitable anti-windup strategy and set the parameters accordingly. * PID state publisher topic changed to ```` namespace and is initially turned off. It can be turned on by using ``activate_state_publisher`` parameter. (`#1823 `_). + +position_controllers +***************************** + ``position_controllers/JointGroupPositionController`` is deprecated. Use :ref:`forward_command_controller ` instead by adding the ``interface_name`` parameter and set it to ``position``. (`#1913 `_). + +velocity_controllers +***************************** + ``velocity_controllers/JointGroupVelocityController`` is deprecated. Use :ref:`forward_command_controller ` instead by adding the ``interface_name`` parameter and set it to ``velocity``. (`#1913 `_). From d3e7bb61d7a9939fac88f3551f18cd3164a97c53 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Tue, 16 Sep 2025 19:22:42 +0000 Subject: [PATCH 4/5] Remove paragraph in index --- doc/controllers_index.rst | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/doc/controllers_index.rst b/doc/controllers_index.rst index 4bbe6eb673..7b286a61d5 100644 --- a/doc/controllers_index.rst +++ b/doc/controllers_index.rst @@ -36,16 +36,6 @@ Controllers for Wheeled Mobile Robots Controllers for Manipulators and Other Robots ********************************************* -The controllers are using `common hardware interface definitions`_, and may use namespaces depending on the following command interface types: - - - ``position_controllers``: ``hardware_interface::HW_IF_POSITION`` - - ``velocity_controller``: ``hardware_interface::HW_IF_VELOCITY`` - - ``effort_controllers``: ``hardware_interface::HW_IF_ACCELERATION`` - - ``effort_controllers``: ``hardware_interface::HW_IF_EFFORT`` - -.. _common hardware interface definitions: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp - - .. toctree:: :titlesonly: From 4f9269c89a8abc7f3e7e5c52e9b1be72aa59d26b Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 19 Nov 2025 11:28:05 +0000 Subject: [PATCH 5/5] Add deprecation warning to package.xml --- effort_controllers/package.xml | 5 +++++ position_controllers/package.xml | 5 +++++ velocity_controllers/package.xml | 5 +++++ 3 files changed, 15 insertions(+) diff --git a/effort_controllers/package.xml b/effort_controllers/package.xml index 64c93bc373..deee0cd3a0 100644 --- a/effort_controllers/package.xml +++ b/effort_controllers/package.xml @@ -34,5 +34,10 @@ ament_cmake + + This package will be removed in ROS 2 Lyrical Luth. Instead, use + forward_command_controller, see migration guides for details: + https://control.ros.org/rolling/doc/ros2_controllers/doc/migration.html + diff --git a/position_controllers/package.xml b/position_controllers/package.xml index ad02afd38f..5f63464946 100644 --- a/position_controllers/package.xml +++ b/position_controllers/package.xml @@ -34,5 +34,10 @@ ament_cmake + + This package will be removed in ROS 2 Lyrical Luth. Instead, use + forward_command_controller, see migration guides for details: + https://control.ros.org/rolling/doc/ros2_controllers/doc/migration.html + diff --git a/velocity_controllers/package.xml b/velocity_controllers/package.xml index a03e873017..4b6d7a5902 100644 --- a/velocity_controllers/package.xml +++ b/velocity_controllers/package.xml @@ -34,5 +34,10 @@ ament_cmake + + This package will be removed in ROS 2 Lyrical Luth. Instead, use + forward_command_controller, see migration guides for details: + https://control.ros.org/rolling/doc/ros2_controllers/doc/migration.html +