ros2_control - galactic
Loading...
Searching...
No Matches
Classes | Public Member Functions | List of all members
joint_state_topic_hardware_interface::JointStateTopicSystem Class Reference
Inheritance diagram for joint_state_topic_hardware_interface::JointStateTopicSystem:
Inheritance graph
[legend]
Collaboration diagram for joint_state_topic_hardware_interface::JointStateTopicSystem:
Collaboration graph
[legend]

Public Member Functions

CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams &params) override
 
std::vector< hardware_interface::StateInterfaceexport_state_interfaces () override
 Exports all state interfaces for this hardware interface.
 
std::vector< hardware_interface::CommandInterfaceexport_command_interfaces () override
 Exports all command interfaces for this hardware interface.
 
hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override
 
hardware_interface::return_type write (const rclcpp::Time &, const rclcpp::Duration &) override
 
- Public Member Functions inherited from hardware_interface::SystemInterface
 SystemInterface (const SystemInterface &other)=delete
 SensorInterface copy constructor is actively deleted.
 
 SystemInterface (SystemInterface &&other)=default
 
virtual CallbackReturn on_init (const HardwareInfo &hardware_info)
 Initialization of the hardware interface from data parsed from the robot's URDF.
 
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 ()=0
 Read the current state values from the actuator.
 
virtual return_type write ()=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.
 

Additional Inherited Members

- Protected Attributes inherited from hardware_interface::SystemInterface
HardwareInfo info_
 
rclcpp_lifecycle::State lifecycle_state_
 

Member Function Documentation

◆ export_command_interfaces()

std::vector< hardware_interface::CommandInterface > joint_state_topic_hardware_interface::JointStateTopicSystem::export_command_interfaces ( )
overridevirtual

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.

Returns
vector of command interfaces

Implements hardware_interface::SystemInterface.

◆ export_state_interfaces()

std::vector< hardware_interface::StateInterface > joint_state_topic_hardware_interface::JointStateTopicSystem::export_state_interfaces ( )
overridevirtual

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.

Returns
vector of state interfaces

Implements hardware_interface::SystemInterface.


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