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

Public Member Functions

 SystemInterface (const SystemInterface &other)=delete
 SystemInterface copy constructor is actively deleted. More...
 
 SystemInterface (SystemInterface &&other)=default
 
CallbackReturn init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
 
virtual CallbackReturn on_init (const HardwareInfo &)
 Initialization of the hardware interface from data parsed from the robot's URDF. More...
 
virtual std::vector< StateInterfaceexport_state_interfaces ()=0
 Exports all state interfaces for this hardware interface. More...
 
virtual std::vector< CommandInterfaceexport_command_interfaces ()=0
 Exports all command interfaces for this hardware interface. 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 read (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 Read the current state values from the actuator. 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_state () const
 Get life-cycle state of the actuator hardware. More...
 
void set_state (const rclcpp_lifecycle::State &new_state)
 Set life-cycle state of the actuator hardware. More...
 

Protected Member Functions

rclcpp::Logger get_logger () const
 Get the logger of the SystemInterface. More...
 
rclcpp::Clock::SharedPtr get_clock () const
 Get the clock of the SystemInterface. More...
 

Protected Attributes

HardwareInfo info_
 
rclcpp_lifecycle::State lifecycle_state_
 

Constructor & Destructor Documentation

◆ SystemInterface()

hardware_interface::SystemInterface::SystemInterface ( const SystemInterface other)
delete

SystemInterface 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::SystemInterface::export_command_interfaces ( )
pure virtual

◆ export_state_interfaces()

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

◆ get_clock()

rclcpp::Clock::SharedPtr hardware_interface::SystemInterface::get_clock ( ) const
inlineprotected

Get the clock of the SystemInterface.

Returns
clock of the SystemInterface.

◆ get_group_name()

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

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

Returns
group name.

◆ get_logger()

rclcpp::Logger hardware_interface::SystemInterface::get_logger ( ) const
inlineprotected

Get the logger of the SystemInterface.

Returns
logger of the SystemInterface.

◆ get_name()

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

Get name of the actuator hardware.

Returns
name.

◆ get_state()

const rclcpp_lifecycle::State& hardware_interface::SystemInterface::get_state ( ) const
inline

Get life-cycle state of the actuator hardware.

Returns
state.

◆ init()

CallbackReturn hardware_interface::SystemInterface::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_init()

virtual CallbackReturn hardware_interface::SystemInterface::on_init ( const HardwareInfo )
inlinevirtual

◆ perform_command_mode_switch()

virtual return_type hardware_interface::SystemInterface::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.

Reimplemented in mock_components::GenericSystem, gz_ros2_control::GazeboSimSystem, and gazebo_ros2_control::GazeboSystem.

◆ prepare_command_mode_switch()

virtual return_type hardware_interface::SystemInterface::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.

Reimplemented in ros2_control_demo_example_3::RRBotSystemMultiInterfaceHardware, and mock_components::GenericSystem.

◆ read()

virtual return_type hardware_interface::SystemInterface::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
pure virtual

◆ set_state()

void hardware_interface::SystemInterface::set_state ( const rclcpp_lifecycle::State &  new_state)
inline

Set life-cycle state of the actuator hardware.

Returns
state.

◆ write()

virtual return_type hardware_interface::SystemInterface::write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
pure virtual

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