Skip to content

Commit

Permalink
Fix doxygen syntax
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Feb 28, 2025
1 parent dfb3207 commit 2e53de7
Show file tree
Hide file tree
Showing 3 changed files with 34 additions and 23 deletions.
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 @@ -63,23 +66,25 @@ namespace hardware_interface
* Communication with the hardware is started and it is configured.
* States can be read and command interfaces are available.
*
* TODO(anyone): Implement https://github.com/ros-controls/ros2_control/issues/931
* 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.
*
* 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 Down Expand Up @@ -69,9 +72,6 @@ namespace hardware_interface
* ACTIVE (on_activate):
* States can be read.
*/

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

class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
{
public:
Expand Down
28 changes: 17 additions & 11 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,29 +64,31 @@ 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 command interfaces are available.
*
* TODO(anyone): Implement https://github.com/ros-controls/ros2_control/issues/931
* 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.
*
* 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

0 comments on commit 2e53de7

Please sign in to comment.