Class ActuatorInterface

Inheritance Relationships

Base Type

Class Documentation

class ActuatorInterface : public hardware_interface::HardwareComponentInterface

Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.

The typical examples are conveyors or motors.

Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following meaning:

The hardware ends after each method in a state with the following meaning:

UNCONFIGURED (on_init, on_cleanup): Hardware is initialized but communication is not started and therefore no interface is available.

INACTIVE (on_configure, on_deactivate): Communication with the hardware is started and it is configured. States can be read, but command interfaces are not available.

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 are available.

Todo:

Implement

Return:

CallbackReturn::SUCCESS method execution was successful.

Return:

CallbackReturn::FAILURE method execution has failed and and can be called again.

Return:

CallbackReturn::ERROR critical error has happened that should be managed in “on_error” method.

Public Functions

virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override = 0

Write the current command values to the hardware.

The physical hardware shall be updated with the latest value from the exported command interfaces.

Parameters:
  • time[in] The time at the start of this control loop iteration

  • period[in] The measured time taken by the last control loop iteration

Returns:

return_type::OK if the read was successful, return_type::ERROR otherwise.