![]() |
ros2_control - rolling
|
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)=delete | |
CallbackReturn | init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface) |
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 () |
Exports all state interfaces for this hardware interface. | |
virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_state_interface_descriptions () |
virtual std::vector< StateInterface::ConstSharedPtr > | on_export_state_interfaces () |
virtual std::vector< CommandInterface > | export_command_interfaces () |
Exports all command interfaces for this hardware interface. | |
virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_command_interface_descriptions () |
virtual std::vector< CommandInterface::SharedPtr > | on_export_command_interfaces () |
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 > &) |
HardwareComponentCycleStatus | trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period) |
Triggers the read method synchronously or asynchronously depending on the HardwareInfo. | |
virtual return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
Read the current state values from the actuator. | |
HardwareComponentCycleStatus | trigger_write (const rclcpp::Time &time, const rclcpp::Duration &period) |
Triggers the write method synchronously or asynchronously depending on the HardwareInfo. | |
virtual return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
Write the current command values to the actuator. | |
const std::string & | get_name () const |
Get name of the actuator hardware. | |
const std::string & | get_group_name () const |
Get name of the actuator hardware group to which it belongs to. | |
const rclcpp_lifecycle::State & | get_lifecycle_state () const |
Get life-cycle state of the actuator hardware. | |
void | set_lifecycle_state (const rclcpp_lifecycle::State &new_state) |
Set life-cycle state of the actuator hardware. | |
void | set_state (const std::string &interface_name, const double &value) |
double | get_state (const std::string &interface_name) const |
void | set_command (const std::string &interface_name, const double &value) |
double | get_command (const std::string &interface_name) const |
rclcpp::Logger | get_logger () const |
Get the logger of the ActuatorInterface. | |
rclcpp::Clock::SharedPtr | get_clock () const |
Get the clock of the ActuatorInterface. | |
const HardwareInfo & | get_hardware_info () const |
Get the hardware info of the ActuatorInterface. | |
void | prepare_for_activation () |
Prepare for the activation of the hardware. | |
void | enable_introspection (bool enable) |
Enable or disable introspection of the hardware. | |
Protected Attributes | |
HardwareInfo | info_ |
std::unordered_map< std::string, InterfaceDescription > | joint_state_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | joint_command_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | unlisted_state_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | unlisted_command_interfaces_ |
std::vector< StateInterface::SharedPtr > | joint_states_ |
std::vector< CommandInterface::SharedPtr > | joint_commands_ |
std::vector< StateInterface::SharedPtr > | unlisted_states_ |
std::vector< CommandInterface::SharedPtr > | unlisted_commands_ |
rclcpp_lifecycle::State | lifecycle_state_ |
std::unique_ptr< realtime_tools::AsyncFunctionHandler< return_type > > | async_handler_ |
pal_statistics::RegistrationsRAII | stats_registrations_ |
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.
|
inline |
Enable or disable introspection of the hardware.
[in] | enable | Enable introspection if true, disable otherwise. |
|
inlinevirtual |
Exports all command interfaces for this hardware interface.
Old way of exporting the CommandInterfaces. If a empty vector is returned then the on_export_command_interfaces() method is called. If a vector with CommandInterfaces is returned then the exporting of the CommandInterfaces is only done with this function and the ownership is transferred to the resource manager. The set_command(...), get_command(...), ..., can then not be used.
Note the ownership over the state interfaces is transferred to the caller.
|
inlinevirtual |
Exports all state interfaces for this hardware interface.
Old way of exporting the StateInterfaces. If a empty vector is returned then the on_export_state_interfaces() method is called. If a vector with StateInterfaces is returned then the exporting of the StateInterfaces is only done with this function and the ownership is transferred to the resource manager. The set_command(...), get_command(...), ..., can then not be used.
Note the ownership over the state interfaces is transferred to the caller.
|
inlinevirtual |
Override this method to export custom CommandInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_command_interfaces_ map.
|
inlinevirtual |
Override this method to export custom StateInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_state_interfaces_ map.
|
inline |
Get the clock of the ActuatorInterface.
|
inline |
Get name of the actuator hardware group to which it belongs to.
|
inline |
Get the hardware info of the ActuatorInterface.
|
inline |
Get life-cycle state of the actuator hardware.
|
inline |
Get the logger of the ActuatorInterface.
|
inline |
Get name of the actuator hardware.
|
inline |
Initialization of the hardware interface from data parsed from the robot's URDF and also the clock and logger interfaces.
[in] | hardware_info | structure with data from URDF. |
[in] | clock_interface | pointer to the clock interface. |
[in] | logger_interface | pointer to the logger interface. |
|
inlinevirtual |
Default implementation for exporting the CommandInterfaces. The CommandInterfaces are created according to the InterfaceDescription. The memory accessed by the controllers and hardware is assigned here and resides in the actuator_interface.
|
inlinevirtual |
Default implementation for exporting the StateInterfaces. The StateInterfaces are created according to the InterfaceDescription. The memory accessed by the controllers and hardware is assigned here and resides in the actuator_interface.
|
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. |
|
inline |
Prepare for the activation of the hardware.
This method is called before the hardware is activated by the resource manager.
|
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.
|
inline |
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
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. The method is called in the resource_manager's read loop
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time taken by the last control loop iteration |
|
inline |
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
The physical hardware shall be updated with the latest value from the exported command interfaces. The method is called in the resource_manager's write loop
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time taken by the last control loop iteration |
|
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.