ROS2 Control
Public Member Functions | List of all members
hardware_interface::ActuatorInterface Class Referenceabstract

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

#include <actuator_interface.hpp>

Inheritance diagram for hardware_interface::ActuatorInterface:
Inheritance graph
[legend]

Public Member Functions

virtual return_type configure (const HardwareInfo &actuator_info)=0
 Configuration of the actuator from data parsed from the robot's URDF. More...
 
virtual std::vector< StateInterfaceexport_state_interfaces ()=0
 Exports all state interfaces for this actuator. More...
 
virtual std::vector< CommandInterfaceexport_command_interfaces ()=0
 Exports all command interfaces for this actuator. More...
 
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 > &)
 
virtual return_type start ()=0
 Start exchange data with the hardware. More...
 
virtual return_type stop ()=0
 Stop exchange data with the hardware. More...
 
virtual std::string get_name () const =0
 Get name of the actuator hardware. More...
 
virtual status get_status () const =0
 Get current state of the actuator hardware. More...
 
virtual return_type read ()=0
 Read the current state values from the actuator. More...
 
virtual return_type write ()=0
 Write the current command values to the actuator. More...
 

Detailed Description

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

The typical examples are conveyors or motors.

Member Function Documentation

◆ configure()

virtual return_type hardware_interface::ActuatorInterface::configure ( const HardwareInfo actuator_info)
pure virtual

Configuration of the actuator from data parsed from the robot's URDF.

Parameters
[in]actuator_infostructure with data from URDF.
Returns
return_type::OK if required data are provided and can be parsed, return_type::ERROR otherwise.

◆ export_command_interfaces()

virtual std::vector<CommandInterface> hardware_interface::ActuatorInterface::export_command_interfaces ( )
pure virtual

Exports all command interfaces for this actuator.

The command interfaces have to be created and transferred according to the actuator info passed in for the configuration.

Note the ownership over the state interfaces is transferred to the caller.

Returns
vector of command interfaces

◆ export_state_interfaces()

virtual std::vector<StateInterface> hardware_interface::ActuatorInterface::export_state_interfaces ( )
pure virtual

Exports all state interfaces for this actuator.

The state interfaces have to be created and transferred according to the actuator info passed in for the configuration.

Note the ownership over the state interfaces is transferred to the caller.

Returns
vector of state interfaces

◆ get_name()

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

Get name of the actuator hardware.

Returns
name.

◆ get_status()

virtual status hardware_interface::ActuatorInterface::get_status ( ) const
pure virtual

Get current state of the actuator hardware.

Returns
current status.

◆ 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 interfacs 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 interfacs 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 ( )
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.

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

◆ start()

virtual return_type hardware_interface::ActuatorInterface::start ( )
pure virtual

Start exchange data with the hardware.

Returns
return_type:OK if everything worked as expected, return_type::ERROR otherwise.

◆ stop()

virtual return_type hardware_interface::ActuatorInterface::stop ( )
pure virtual

Stop exchange data with the hardware.

Returns
return_type:OK if everything worked as expected, return_type::ERROR otherwise.

◆ write()

virtual return_type hardware_interface::ActuatorInterface::write ( )
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.

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

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