Skip to content

Commit

Permalink
Merge branch 'master' into rename_load_urdf_method
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Mar 28, 2024
2 parents e6417b0 + 5ae5cc3 commit 01cd760
Show file tree
Hide file tree
Showing 57 changed files with 1,205 additions and 386 deletions.
4 changes: 2 additions & 2 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ repos:
args: ["--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404"]

- repo: https://github.com/psf/black
rev: 24.2.0
rev: 24.3.0
hooks:
- id: black
args: ["--line-length=99"]
Expand All @@ -62,7 +62,7 @@ repos:

# CPP hooks
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v18.1.0
rev: v18.1.2
hooks:
- id: clang-format
args: ['-fallback-style=none', '-i']
Expand Down
11 changes: 11 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,17 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.8.0 (2024-03-27)
------------------
* generate version.h file per package using the ament_generate_version_header (`#1449 <https://github.com/ros-controls/ros2_control/issues/1449>`_)
* Use ament_cmake generated rclcpp version header (`#1448 <https://github.com/ros-controls/ros2_control/issues/1448>`_)
* Contributors: Sai Kishor Kothakota

4.7.0 (2024-03-22)
------------------
* add missing compiler definitions of RCLCPP_VERSION_MAJOR (`#1440 <https://github.com/ros-controls/ros2_control/issues/1440>`_)
* Contributors: Sai Kishor Kothakota

4.6.0 (2024-03-02)
------------------
* Add -Werror=missing-braces to compile options (`#1423 <https://github.com/ros-controls/ros2_control/issues/1423>`_)
Expand Down
1 change: 1 addition & 0 deletions controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -89,3 +89,4 @@ install(TARGETS controller_interface
ament_export_targets(export_controller_interface HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
ament_generate_version_header(${PROJECT_NAME})
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "hardware_interface/loaned_state_interface.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/version.h"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

namespace controller_interface
Expand Down
3 changes: 2 additions & 1 deletion controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,14 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_interface</name>
<version>4.6.0</version>
<version>4.8.0</version>
<description>Description of controller_interface</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_gen_version_h</buildtool_depend>

<build_depend>hardware_interface</build_depend>
<build_depend>rclcpp_lifecycle</build_depend>
Expand Down
15 changes: 15 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,21 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.8.0 (2024-03-27)
------------------
* generate version.h file per package using the ament_generate_version_header (`#1449 <https://github.com/ros-controls/ros2_control/issues/1449>`_)
* Use ament_cmake generated rclcpp version header (`#1448 <https://github.com/ros-controls/ros2_control/issues/1448>`_)
* Replace random_shuffle with shuffle. (`#1446 <https://github.com/ros-controls/ros2_control/issues/1446>`_)
* Contributors: Chris Lalancette, Sai Kishor Kothakota

4.7.0 (2024-03-22)
------------------
* add missing compiler definitions of RCLCPP_VERSION_MAJOR (`#1440 <https://github.com/ros-controls/ros2_control/issues/1440>`_)
* Codeformat from new pre-commit config (`#1433 <https://github.com/ros-controls/ros2_control/issues/1433>`_)
* add conditioning to get_parameter_value method import (`#1428 <https://github.com/ros-controls/ros2_control/issues/1428>`_)
* Change the controller sorting with an approach similar to directed acyclic graphs (`#1384 <https://github.com/ros-controls/ros2_control/issues/1384>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota

4.6.0 (2024-03-02)
------------------
* Add -Werror=missing-braces to compile options (`#1423 <https://github.com/ros-controls/ros2_control/issues/1423>`_)
Expand Down
1 change: 1 addition & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -225,3 +225,4 @@ ament_python_install_package(controller_manager
ament_export_targets(export_controller_manager HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
ament_generate_version_header(${PROJECT_NAME})
17 changes: 9 additions & 8 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,15 @@ Alternatives to the standard kernel include
Though installing a realtime-kernel will definitely get the best results when it comes to low
jitter, using a lowlatency kernel can improve things a lot with being really easy to install.

Subscribers
-----------

~/robot_description [std_msgs::msg::String]
String with the URDF xml, e.g., from ``robot_state_publisher``.
Reloading of the URDF is not supported yet.
All joints defined in the ``<ros2_control>``-tag have to be present in the URDF.


Parameters
-----------

Expand Down Expand Up @@ -74,18 +83,10 @@ update_rate (mandatory; integer)
The frequency of controller manager's real-time update loop.
This loop reads states from hardware, updates controller and writes commands to hardware.


<controller_name>.type
Name of a plugin exported using ``pluginlib`` for a controller.
This is a class from which controller's instance with name "``controller_name``" is created.

Subscribers
-----------

robot_description (std_msgs/msg/String)
The URDF string as robot description.
This is usually published by the ``robot_state_publisher`` node.

Handling Multiple Controller Managers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Expand Down
3 changes: 2 additions & 1 deletion controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,14 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_manager</name>
<version>4.6.0</version>
<version>4.8.0</version>
<description>Description of controller_manager</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_gen_version_h</buildtool_depend>
<buildtool_depend>ament_cmake_python</buildtool_depend>

<depend>ament_index_cpp</depend>
Expand Down
1 change: 1 addition & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/version.h"
#include "rclcpp_lifecycle/state.hpp"

namespace // utility
Expand Down
5 changes: 4 additions & 1 deletion controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <memory>
#include <random>
#include <string>
#include <vector>

Expand Down Expand Up @@ -1503,7 +1504,9 @@ TEST_F(TestControllerManagerSrvs, list_sorted_large_chained_controller_tree)
}

// Now shuffle the list to be able to configure controller later randomly
std::random_shuffle(controllers_list.begin(), controllers_list.end());
std::random_device rnd;
std::mt19937 mers(rnd());
std::shuffle(controllers_list.begin(), controllers_list.end(), mers);

{
ControllerManagerRunner cm_runner(this);
Expand Down
6 changes: 6 additions & 0 deletions controller_manager_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package controller_manager_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.8.0 (2024-03-27)
------------------

4.7.0 (2024-03-22)
------------------

4.6.0 (2024-03-02)
------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_manager_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>controller_manager_msgs</name>
<version>4.6.0</version>
<version>4.8.0</version>
<description>Messages and services for the controller manager.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
51 changes: 51 additions & 0 deletions doc/migration/Foxy.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
Foxy to Galactic
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

hardware_interface
**************************************
Between Foxy and Galactic we made substantial changes to the interface of hardware components to enable management of their lifecycle.
The following list shows a set of quick changes to port existing hardware components to Galactic:

1. Rename ``configure`` to ``on_init`` and change return type to ``CallbackReturn``

2. If using BaseInterface as base class then you should remove it. Specifically, change:

.. code-block:: c++

hardware_interface::BaseInterface<hardware_interface::[Actuator|Sensor|System]Interface>

to

.. code-block:: c++

hardware_interface::[Actuator|Sensor|System]Interface

3. Remove include of headers ``base_interface.hpp`` and ``hardware_interface_status_values.hpp``

4. Add include of header ``rclcpp_lifecycle/state.hpp`` although this may not be strictly necessary

5. replace first three lines in ``on_init`` to

.. code-block:: c++

if (hardware_interface::[Actuator|Sensor|System]Interface::on_init(info) != CallbackReturn::SUCCESS)
{
return CallbackReturn::ERROR;
}


6. Change last return of ``on_init`` to ``return CallbackReturn::SUCCESS;``

7. Remove all lines with ``status_ = ...`` or ``status::...``

8. Rename ``start()`` to ``on_activate(const rclcpp_lifecycle::State & previous_state)`` and
``stop()`` to ``on_deactivate(const rclcpp_lifecycle::State & previous_state)``

9. Change return type of ``on_activate`` and ``on_deactivate`` to ``CallbackReturn``

10. Change last return of ``on_activate`` and ``on_deactivate`` to ``return CallbackReturn::SUCCESS;``

11. If you have any ``return_type::ERROR`` in ``on_init``, ``on_activate``, or ``in_deactivate`` change to ``CallbackReturn::ERROR``

12. If you get link errors with undefined refernences to symbols in ``rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface``, then add
``rclcpp_lifecyle`` package dependency to ``CMakeLists.txt`` and ``package.xml``
50 changes: 50 additions & 0 deletions doc/migration/Iron.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
Iron to Jazzy
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

component parser
*****************
Changes from `(PR #1256) <https://github.com/ros-controls/ros2_control/pull/1256>`__

* All ``joints`` defined in the ``<ros2_control>``-tag have to be present in the URDF received :ref:`by the controller manager <doc/ros2_control/controller_manager/doc/userdoc:subscribers>`, otherwise a ``std::runtime_error`` is thrown. This is to ensure that the URDF and the ``<ros2_control>``-tag are consistent. E.g., for configuration ports use ``gpio`` tags instead.
* The syntax for mimic joints is changed to the `official URDF specification <https://wiki.ros.org/urdf/XML/joint>`__. The parameters within the ``ros2_control`` tag are not supported any more. Instead of

.. code-block:: xml
<ros2_control name="GazeboSystem" type="system">
<joint name="right_finger_joint">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.15</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_finger_joint">
<param name="mimic">right_finger_joint</param>
<param name="multiplier">1</param>
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
define your mimic joints directly in the joint definitions:

.. code-block:: xml
<joint name="right_finger_joint" type="prismatic">
<axis xyz="0 1 0"/>
<origin xyz="0.0 -0.48 1" rpy="0.0 0.0 0.0"/>
<parent link="base"/>
<child link="finger_right"/>
<limit effort="1000.0" lower="0" upper="0.38" velocity="10"/>
</joint>
<joint name="left_finger_joint" type="prismatic">
<mimic joint="right_finger_joint" multiplier="1" offset="0"/>
<axis xyz="0 1 0"/>
<origin xyz="0.0 0.48 1" rpy="0.0 0.0 3.1415926535"/>
<parent link="base"/>
<child link="finger_left"/>
<limit effort="1000.0" lower="0" upper="0.38" velocity="10"/>
</joint>
10 changes: 10 additions & 0 deletions hardware_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,16 @@
Changelog for package hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.8.0 (2024-03-27)
------------------
* generate version.h file per package using the ament_generate_version_header (`#1449 <https://github.com/ros-controls/ros2_control/issues/1449>`_)
* Contributors: Sai Kishor Kothakota

4.7.0 (2024-03-22)
------------------
* Codeformat from new pre-commit config (`#1433 <https://github.com/ros-controls/ros2_control/issues/1433>`_)
* Contributors: Christoph Fröhlich

4.6.0 (2024-03-02)
------------------
* Add -Werror=missing-braces to compile options (`#1423 <https://github.com/ros-controls/ros2_control/issues/1423>`_)
Expand Down
2 changes: 2 additions & 0 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
rcutils
TinyXML2
tinyxml2_vendor
urdf
)

find_package(ament_cmake REQUIRED)
Expand Down Expand Up @@ -122,3 +123,4 @@ install(
ament_export_targets(export_hardware_interface HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
ament_generate_version_header(${PROJECT_NAME})
50 changes: 0 additions & 50 deletions hardware_interface/doc/hardware_components_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -27,53 +27,3 @@ If ``hardware_interface::return_type::ERROR`` is returned from ``read()`` or ``w
Error handling follows the `node lifecycle <https://design.ros2.org/articles/node_lifecycle.html>`_.
If successful ``CallbackReturn::SUCCESS`` is returned and hardware is again in ``UNCONFIGURED`` state, if any ``ERROR`` or ``FAILURE`` happens the hardware ends in ``FINALIZED`` state and can not be recovered.
The only option is to reload the complete plugin, but there is currently no service for this in the Controller Manager.

Migration from Foxy to newer versions
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Between Foxy and Galactic we made substantial changes to the interface of hardware components to enable management of their lifecycle.
The following list shows a set of quick changes to port existing hardware components to Galactic:

1. Rename ``configure`` to ``on_init`` and change return type to ``CallbackReturn``

2. If using BaseInterface as base class then you should remove it. Specifically, change:

.. code-block:: c++

hardware_interface::BaseInterface<hardware_interface::[Actuator|Sensor|System]Interface>

to

.. code-block:: c++

hardware_interface::[Actuator|Sensor|System]Interface

3. Remove include of headers ``base_interface.hpp`` and ``hardware_interface_status_values.hpp``

4. Add include of header ``rclcpp_lifecycle/state.hpp`` although this may not be strictly necessary

5. replace first three lines in ``on_init`` to

.. code-block:: c++

if (hardware_interface::[Actuator|Sensor|System]Interface::on_init(info) != CallbackReturn::SUCCESS)
{
return CallbackReturn::ERROR;
}


6. Change last return of ``on_init`` to ``return CallbackReturn::SUCCESS;``

7. Remove all lines with ``status_ = ...`` or ``status::...``

8. Rename ``start()`` to ``on_activate(const rclcpp_lifecycle::State & previous_state)`` and
``stop()`` to ``on_deactivate(const rclcpp_lifecycle::State & previous_state)``

9. Change return type of ``on_activate`` and ``on_deactivate`` to ``CallbackReturn``

10. Change last return of ``on_activate`` and ``on_deactivate`` to ``return CallbackReturn::SUCCESS;``

11. If you have any ``return_type::ERROR`` in ``on_init``, ``on_activate``, or ``in_deactivate`` change to ``CallbackReturn::ERROR``

12. If you get link errors with undefined refernences to symbols in ``rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface``, then add
``rclcpp_lifecyle`` package dependency to ``CMakeLists.txt`` and ``package.xml``
2 changes: 2 additions & 0 deletions hardware_interface/doc/hardware_interface_types_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@ Joints
``<joint>``-tag groups the interfaces associated with the joints of physical robots and actuators.
They have command and state interfaces to set the goal values for hardware and read its current state.

All joints defined in the ``<ros2_control>``-tag have to be present in the URDF received :ref:`by the controller manager <doc/ros2_control/controller_manager/doc/userdoc:subscribers>`.

State interfaces of joints can be published as a ROS topic by means of the :ref:`joint_state_broadcaster <joint_state_broadcaster_userdoc>`

Sensors
Expand Down
Loading

0 comments on commit 01cd760

Please sign in to comment.