Class DynamixelHardware

Inheritance Relationships

Base Types

  • public hardware_interface::SystemInterface

  • private rclcpp::Node

Class Documentation

class DynamixelHardware : public hardware_interface::SystemInterface, private rclcpp::Node

Class for interfacing with Dynamixel hardware using the ROS2 hardware interface.

This class is responsible for initializing, reading, and writing to Dynamixel actuators. It also handles errors, resets, and publishes state information using ROS2 services and topics.

Public Functions

DynamixelHardware()

Constructor for DynamixelHardware.

~DynamixelHardware()

Destructor for DynamixelHardware.

DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC hardware_interface::CallbackReturn on_init (const hardware_interface::HardwareInfo &info) override

Initialization callback for hardware interface.

Parameters:

info – Hardware information for the system.

Returns:

Callback return indicating success or error.

DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterface > export_state_interfaces () override

Exports state interfaces for ROS2.

Returns:

A vector of state interfaces.

DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterface > export_command_interfaces () override

Exports command interfaces for ROS2.

Returns:

A vector of command interfaces.

DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC hardware_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override

Callback for activating the hardware interface.

Parameters:

previous_state – Previous lifecycle state.

Returns:

Callback return indicating success or error.

DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC hardware_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override

Callback for deactivating the hardware interface.

Parameters:

previous_state – Previous lifecycle state.

Returns:

Callback return indicating success or error.

DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override

Reads data from the hardware.

Parameters:
  • time – Current time.

  • period – Duration since the last read.

Returns:

Hardware interface return type indicating success or error.

DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period) override

Writes data to the hardware.

Parameters:
  • time – Current time.

  • period – Duration since the last write.

Returns:

Hardware interface return type indicating success or error.