Virtual Class to implement when integrating a 1 DoF actuator into ros2_control. More...
#include <actuator_interface.hpp>
Public Member Functions | |
ActuatorInterface (const ActuatorInterface &other)=delete | |
ActuatorInterface copy constructor is actively deleted. | |
ActuatorInterface (ActuatorInterface &&other)=default | |
virtual CallbackReturn | on_init (const HardwareInfo &hardware_info) |
Initialization of the hardware interface from data parsed from the robot's URDF. | |
virtual std::vector< StateInterface > | export_state_interfaces ()=0 |
Exports all state interfaces for this hardware interface. | |
virtual std::vector< CommandInterface > | export_command_interfaces ()=0 |
Exports all command interfaces for this hardware interface. | |
virtual return_type | prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
Prepare for a new command interface switch. | |
virtual return_type | perform_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
virtual return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
Read the current state values from the actuator. | |
virtual return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
Write the current command values to the actuator. | |
virtual std::string | get_name () const |
Get name of the actuator hardware. | |
const rclcpp_lifecycle::State & | get_state () const |
Get life-cycle state of the actuator hardware. | |
void | set_state (const rclcpp_lifecycle::State &new_state) |
Set life-cycle state of the actuator hardware. | |
Protected Attributes | |
HardwareInfo | info_ |
rclcpp_lifecycle::State | lifecycle_state_ |
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 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 available.
|
delete |
ActuatorInterface copy constructor is actively deleted.
Hardware interfaces are having a unique ownership and thus can't be copied in order to avoid failed or simultaneous access to hardware.
|
pure virtual |
Exports all command interfaces for this hardware interface.
The command interfaces have to be created and transferred according to the hardware info passed in for the configuration.
Note the ownership over the state interfaces is transferred to the caller.
Implemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, and ros2_control_demo_example_6::RRBotModularJoint.
|
pure virtual |
Exports all state interfaces for this hardware interface.
The state interfaces have to be created and transferred according to the hardware info passed in for the configuration.
Note the ownership over the state interfaces is transferred to the caller.
Implemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, and ros2_control_demo_example_6::RRBotModularJoint.
|
inlinevirtual |
Get name of the actuator hardware.
|
inline |
Get life-cycle state of the actuator hardware.
|
inlinevirtual |
Initialization of the hardware interface from data parsed from the robot's URDF.
[in] | hardware_info | structure with data from URDF. |
Reimplemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, and ros2_control_demo_example_6::RRBotModularJoint.
|
inlinevirtual |
Perform the mode-switching for the new command interface combination.
[in] | start_interfaces | vector of string identifiers for the command interfaces starting. |
[in] | stop_interfaces | vector of string identifiers for the command interfaces stopping. |
|
inlinevirtual |
Prepare for a new command interface switch.
Prepare for any mode-switching required by the new command interface combination.
[in] | start_interfaces | vector of string identifiers for the command interfaces starting. |
[in] | stop_interfaces | vector of string identifiers for the command interfaces stopping. |
|
pure virtual |
Read the current state values from the actuator.
The data readings from the physical hardware has to be updated and reflected accordingly in the exported state interfaces. That is, the data pointed by the interfaces shall be updated.
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time taken by the last control loop iteration |
Implemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, and ros2_control_demo_example_6::RRBotModularJoint.
|
inline |
Set life-cycle state of the actuator hardware.
|
pure virtual |
Write the current command values to the actuator.
The physical hardware shall be updated with the latest value from the exported command interfaces.
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time taken by the last control loop iteration |
Implemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, and ros2_control_demo_example_6::RRBotModularJoint.