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
10 changes: 0 additions & 10 deletions doc/controllers_index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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:

Expand Down
14 changes: 13 additions & 1 deletion doc/migration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,17 @@

Migration Guides: Kilted Kaiju to Lyrical Luth
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

This list summarizes important changes between Kilted Kaiju (previous) and Lyrical Luth (current) releases, where changes to user code might be necessary.


effort_controllers
*****************************
* ``effort_controllers/JointGroupEffortController`` is deprecated. Use :ref:`forward_command_controller <forward_command_controller_userdoc>` instead by adding the ``interface_name`` parameter and set it to ``effort``. (`#1913 <https://github.com/ros-controls/ros2_controllers/pull/1913>`_).

position_controllers
*****************************
* ``position_controllers/JointGroupPositionController`` is deprecated. Use :ref:`forward_command_controller <forward_command_controller_userdoc>` instead by adding the ``interface_name`` parameter and set it to ``position``. (`#1913 <https://github.com/ros-controls/ros2_controllers/pull/1913>`_).

velocity_controllers
*****************************
* ``velocity_controllers/JointGroupVelocityController`` is deprecated. Use :ref:`forward_command_controller <forward_command_controller_userdoc>` instead by adding the ``interface_name`` parameter and set it to ``velocity``. (`#1913 <https://github.com/ros-controls/ros2_controllers/pull/1913>`_).
4 changes: 4 additions & 0 deletions effort_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@ The package contains the following controllers:
effort_controllers/JointGroupEffortController
-------------------------------------------------

.. warning::

``effort_controllers/JointGroupEffortController`` is deprecated. Use :ref:`forward_command_controller <forward_command_controller_userdoc>` instead by adding the ``interface_name`` parameter and set it to ``effort``.

This is specialization of the :ref:`forward_command_controller <forward_command_controller_userdoc>` that works using the "effort" joint interface.


Expand Down
5 changes: 5 additions & 0 deletions effort_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,5 +34,10 @@

<export>
<build_type>ament_cmake</build_type>
<deprecated>
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
</deprecated>
</export>
</package>
5 changes: 5 additions & 0 deletions effort_controllers/src/joint_group_effort_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
10 changes: 5 additions & 5 deletions forward_command_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<>: []
},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<>: []
},
Expand Down
4 changes: 4 additions & 0 deletions position_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@ The package contains the following controllers:
position_controllers/JointGroupPositionController
-------------------------------------------------

.. warning::

``position_controllers/JointGroupPositionController`` is deprecated. Use :ref:`forward_command_controller <forward_command_controller_userdoc>` instead by adding the ``interface_name`` parameter and set it to ``position``.

This is specialization of the :ref:`forward_command_controller <forward_command_controller_userdoc>` that works using the "position" joint interface.


Expand Down
5 changes: 5 additions & 0 deletions position_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,5 +34,10 @@

<export>
<build_type>ament_cmake</build_type>
<deprecated>
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
</deprecated>
</export>
</package>
5 changes: 5 additions & 0 deletions position_controllers/src/joint_group_position_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 4 additions & 0 deletions velocity_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@ The package contains the following controllers:
velocity_controllers/JointGroupVelocityController
-------------------------------------------------

.. warning::

``velocity_controllers/JointGroupVelocityController`` is deprecated. Use :ref:`forward_command_controller <forward_command_controller_userdoc>` instead by adding the ``interface_name`` parameter and set it to ``velocity``.

This is specialization of the :ref:`forward_command_controller <forward_command_controller_userdoc>` that works using the "velocity" joint interface.


Expand Down
5 changes: 5 additions & 0 deletions velocity_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,5 +34,10 @@

<export>
<build_type>ament_cmake</build_type>
<deprecated>
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
</deprecated>
</export>
</package>
5 changes: 5 additions & 0 deletions velocity_controllers/src/joint_group_velocity_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down