ros2_control - rolling
Public Member Functions | Protected Attributes | List of all members
hardware_interface::ActuatorInterface Class Referenceabstract
Inheritance diagram for hardware_interface::ActuatorInterface:
Inheritance graph
[legend]
Collaboration diagram for hardware_interface::ActuatorInterface:
Collaboration graph
[legend]

Public Member Functions

 ActuatorInterface (const ActuatorInterface &other)=delete
 ActuatorInterface copy constructor is actively deleted. More...
 
 ActuatorInterface (ActuatorInterface &&other)=default
 
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. More...
 
virtual std::vector< StateInterfaceexport_state_interfaces ()
 Exports all state interfaces for this hardware interface. More...
 
virtual std::vector< hardware_interface::InterfaceDescriptionexport_unlisted_state_interface_descriptions ()
 
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces ()
 
virtual std::vector< CommandInterfaceexport_command_interfaces ()
 Exports all command interfaces for this hardware interface. More...
 
virtual std::vector< hardware_interface::InterfaceDescriptionexport_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. More...
 
virtual return_type perform_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &)
 
return_type trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period)
 Triggers the read method synchronously or asynchronously depending on the HardwareInfo. More...
 
virtual return_type read (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 Read the current state values from the actuator. More...
 
return_type trigger_write (const rclcpp::Time &time, const rclcpp::Duration &period)
 Triggers the write method synchronously or asynchronously depending on the HardwareInfo. More...
 
virtual return_type write (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 Write the current command values to the actuator. More...
 
virtual std::string get_name () const
 Get name of the actuator hardware. More...
 
virtual std::string get_group_name () const
 Get name of the actuator hardware group to which it belongs to. More...
 
const rclcpp_lifecycle::State & get_lifecycle_state () const
 Get life-cycle state of the actuator hardware. More...
 
void set_lifecycle_state (const rclcpp_lifecycle::State &new_state)
 Set life-cycle state of the actuator hardware. More...
 
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. More...
 
rclcpp::Clock::SharedPtr get_clock () const
 Get the clock of the ActuatorInterface. More...
 
const HardwareInfoget_hardware_info () const
 Get the hardware info of the ActuatorInterface. More...
 

Protected Attributes

HardwareInfo info_
 
std::unordered_map< std::string, InterfaceDescriptionjoint_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionjoint_command_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionunlisted_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionunlisted_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_
 

Constructor & Destructor Documentation

◆ ActuatorInterface()

hardware_interface::ActuatorInterface::ActuatorInterface ( const ActuatorInterface other)
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.

Member Function Documentation

◆ export_command_interfaces()

virtual std::vector<CommandInterface> hardware_interface::ActuatorInterface::export_command_interfaces ( )
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.

Returns
vector of state interfaces

Reimplemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback.

◆ export_state_interfaces()

virtual std::vector<StateInterface> hardware_interface::ActuatorInterface::export_state_interfaces ( )
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.

Returns
vector of state interfaces

Reimplemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback.

◆ export_unlisted_command_interface_descriptions()

virtual std::vector<hardware_interface::InterfaceDescription> hardware_interface::ActuatorInterface::export_unlisted_command_interface_descriptions ( )
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.

Returns
vector of descriptions to the unlisted CommandInterfaces

◆ export_unlisted_state_interface_descriptions()

virtual std::vector<hardware_interface::InterfaceDescription> hardware_interface::ActuatorInterface::export_unlisted_state_interface_descriptions ( )
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.

Returns
vector of descriptions to the unlisted StateInterfaces

◆ get_clock()

rclcpp::Clock::SharedPtr hardware_interface::ActuatorInterface::get_clock ( ) const
inline

Get the clock of the ActuatorInterface.

Returns
clock of the ActuatorInterface.

◆ get_group_name()

virtual std::string hardware_interface::ActuatorInterface::get_group_name ( ) const
inlinevirtual

Get name of the actuator hardware group to which it belongs to.

Returns
group name.

◆ get_hardware_info()

const HardwareInfo& hardware_interface::ActuatorInterface::get_hardware_info ( ) const
inline

Get the hardware info of the ActuatorInterface.

Returns
hardware info of the ActuatorInterface.

◆ get_lifecycle_state()

const rclcpp_lifecycle::State& hardware_interface::ActuatorInterface::get_lifecycle_state ( ) const
inline

Get life-cycle state of the actuator hardware.

Returns
state.

◆ get_logger()

rclcpp::Logger hardware_interface::ActuatorInterface::get_logger ( ) const
inline

Get the logger of the ActuatorInterface.

Returns
logger of the ActuatorInterface.

◆ get_name()

virtual std::string hardware_interface::ActuatorInterface::get_name ( ) const
inlinevirtual

Get name of the actuator hardware.

Returns
name.

◆ init()

CallbackReturn hardware_interface::ActuatorInterface::init ( const HardwareInfo hardware_info,
rclcpp::Logger  logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr  clock_interface 
)
inline

Initialization of the hardware interface from data parsed from the robot's URDF and also the clock and logger interfaces.

Parameters
[in]hardware_infostructure with data from URDF.
[in]clock_interfacepointer to the clock interface.
[in]logger_interfacepointer to the logger interface.
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

◆ on_export_command_interfaces()

virtual std::vector<CommandInterface::SharedPtr> hardware_interface::ActuatorInterface::on_export_command_interfaces ( )
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.

Returns
vector of shared pointers to the created and stored CommandInterfaces

◆ on_export_state_interfaces()

virtual std::vector<StateInterface::ConstSharedPtr> hardware_interface::ActuatorInterface::on_export_state_interfaces ( )
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.

Returns
vector of shared pointers to the created and stored StateInterfaces

◆ on_init()

virtual CallbackReturn hardware_interface::ActuatorInterface::on_init ( const HardwareInfo hardware_info)
inlinevirtual

Initialization of the hardware interface from data parsed from the robot's URDF.

Parameters
[in]hardware_infostructure with data from URDF.
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

Reimplemented in ros2_control_demo_example_6::RRBotModularJoint, and ros2_control_demo_example_14::RRBotActuatorWithoutFeedback.

◆ perform_command_mode_switch()

virtual return_type hardware_interface::ActuatorInterface::perform_command_mode_switch ( const std::vector< std::string > &  ,
const std::vector< std::string > &   
)
inlinevirtual

Perform the mode-switching for the new command interface combination.

Note
This is part of the realtime update loop, and should be fast.
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
Parameters
[in]start_interfacesvector of string identifiers for the command interfaces starting.
[in]stop_interfacesvector of string identifiers for the command interfaces stopping.
Returns
return_type::OK if the new command interface combination can be switched to, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.

◆ prepare_command_mode_switch()

virtual return_type hardware_interface::ActuatorInterface::prepare_command_mode_switch ( const std::vector< std::string > &  ,
const std::vector< std::string > &   
)
inlinevirtual

Prepare for a new command interface switch.

Prepare for any mode-switching required by the new command interface combination.

Note
This is a non-realtime evaluation of whether a set of command interface claims are possible, and call to start preparing data structures for the upcoming switch that will occur.
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
Parameters
[in]start_interfacesvector of string identifiers for the command interfaces starting.
[in]stop_interfacesvector of string identifiers for the command interfaces stopping.
Returns
return_type::OK if the new command interface combination can be prepared, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.

◆ read()

virtual return_type hardware_interface::ActuatorInterface::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
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.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implemented in ros2_control_demo_example_6::RRBotModularJoint, and ros2_control_demo_example_14::RRBotActuatorWithoutFeedback.

◆ set_lifecycle_state()

void hardware_interface::ActuatorInterface::set_lifecycle_state ( const rclcpp_lifecycle::State &  new_state)
inline

Set life-cycle state of the actuator hardware.

Returns
state.

◆ trigger_read()

return_type hardware_interface::ActuatorInterface::trigger_read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
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

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

◆ trigger_write()

return_type hardware_interface::ActuatorInterface::trigger_write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
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

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

◆ write()

virtual return_type hardware_interface::ActuatorInterface::write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
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.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implemented in ros2_control_demo_example_6::RRBotModularJoint, and ros2_control_demo_example_14::RRBotActuatorWithoutFeedback.


The documentation for this class was generated from the following file: