Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improve API/lifecycle docs #2081

Merged
merged 7 commits into from
Mar 1, 2025
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
43 changes: 43 additions & 0 deletions hardware_interface/doc/hardware_components_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,49 @@ Guidelines and Best Practices
Semantic Components <semantic_components.rst>


Lifecycle of a Hardware Component
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Methods return values have type
``rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn`` with the following
meaning:

* ``CallbackReturn::SUCCESS`` method execution was successful.
* ``CallbackReturn::FAILURE`` method execution has failed and the lifecycle transition is unsuccessful.
* ``CallbackReturn::ERROR`` critical error has happened that should be managed in
``on_error`` method.

The hardware transitions to the following state after each method:

* **UNCONFIGURED** (``on_init``, ``on_cleanup``):

Hardware is only initialized, but communication is not started and no interfaces are imported into ``ResourceManager``.

* **INACTIVE** (``on_configure``, ``on_deactivate``):

Communication with the hardware is established and hardware component is configured.
States can be read and command interfaces (System and Actuator only) are available.

As of now, it is left to the hardware component implementation to continue using the command received from the ``CommandInterfaces`` or to skip them completely.

.. note::

We plan to implement safety-critical interfaces, see this `PR in the roadmap <https://github.com/ros-controls/roadmap/pull/51/files>`__. But currently, all command interfaces are available and will be written, see this `issue <https://github.com/ros-controls/ros2_control/issues/931>`__ describing the situation.

* **FINALIZED** (``on_shutdown``):

Hardware interface is ready for unloading/destruction.
Allocated memory is cleaned up.

* **ACTIVE** (``on_activate``):

States can be read.

System and Actuator only:

Power circuits of hardware are active and hardware can be moved, e.g., brakes are disengaged.
Command interfaces are available and the commands should be sent to the hardware


Handling of errors that happen during read() and write() calls
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,9 @@

namespace hardware_interface
{

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

/// Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
/**
* The typical examples are conveyors or motors.
Expand All @@ -61,22 +64,30 @@ namespace hardware_interface
*
* INACTIVE (on_configure, on_deactivate):
* Communication with the hardware is started and it is configured.
* States can be read and non-movement hardware interfaces commanded.
* Hardware interfaces for movement will NOT be available.
* Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.
* States can be read and command interfaces are available.
*
* As of now, it is left to the hardware component implementation to continue using the command
* received from the ``CommandInterfaces`` or to skip them completely.
*
* FINALIZED (on_shutdown):
* Hardware interface is ready for unloading/destruction.
* Allocated memory is cleaned up.
*
* ACTIVE (on_activate):
* Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled.
* Command interfaces for movement are available and have to be accepted.
* Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.
* Command interfaces available.
*
* \todo
* Implement
* * https://github.com/ros-controls/ros2_control/issues/931
* * https://github.com/ros-controls/roadmap/pull/51/files
* * this means in INACTIVE state:
* * States can be read and non-movement hardware interfaces commanded.
* * Hardware interfaces for movement will NOT be available.
* * Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and
* HW_IF_EFFORT.
*/

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,9 @@

namespace hardware_interface
{

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

/// Virtual Class to implement when integrating a stand-alone sensor into ros2_control.
/**
* The typical examples are Force-Torque Sensor (FTS), Interial Measurement Unit (IMU).
Expand All @@ -60,22 +63,15 @@ namespace hardware_interface
*
* INACTIVE (on_configure, on_deactivate):
* Communication with the hardware is started and it is configured.
* States can be read and non-movement hardware interfaces commanded.
* Hardware interfaces for movement will NOT be available.
* Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.
* States can be read.
*
* FINALIZED (on_shutdown):
* Hardware interface is ready for unloading/destruction.
* Allocated memory is cleaned up.
*
* ACTIVE (on_activate):
* Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled.
* Command interfaces for movement are available and have to be accepted.
* Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.
* States can be read.
*/

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
{
public:
Expand Down
30 changes: 21 additions & 9 deletions hardware_interface/include/hardware_interface/system_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,12 @@

namespace hardware_interface
{
/// Virtual Class to implement when integrating a complex system into ros2_control.

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

/**
* @brief Virtual Class to implement when integrating a complex system into ros2_control.
*
* The common examples for these types of hardware are multi-joint systems with or without sensors
* such as industrial or humanoid robots.
*
Expand All @@ -60,26 +64,34 @@ namespace hardware_interface
*
* UNCONFIGURED (on_init, on_cleanup):
* Hardware is initialized but communication is not started and therefore no interface is
* available.
*available.
*
* INACTIVE (on_configure, on_deactivate):
* Communication with the hardware is started and it is configured.
* States can be read and non-movement hardware interfaces commanded.
* Hardware interfaces for movement will NOT be available.
* Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.
* States can be read and command interfaces are available.
*
* As of now, it is left to the hardware component implementation to continue using the command
*received from the ``CommandInterfaces`` or to skip them completely.
*
* FINALIZED (on_shutdown):
* Hardware interface is ready for unloading/destruction.
* Allocated memory is cleaned up.
*
* ACTIVE (on_activate):
* Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled.
* Command interfaces for movement are available and have to be accepted.
* Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.
* Command interfaces available.
*
* \todo
* Implement
* * https://github.com/ros-controls/ros2_control/issues/931
* * https://github.com/ros-controls/roadmap/pull/51/files
* * this means in INACTIVE state:
* * States can be read and non-movement hardware interfaces commanded.
* * Hardware interfaces for movement will NOT be available.
* * Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and
*HW_IF_EFFORT.
*/

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
{
public:
Expand Down