ros2_control - humble
Classes | Public Member Functions | List of all members
ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware Class Reference
Inheritance diagram for ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware:
Inheritance graph
[legend]
Collaboration diagram for ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware:
Collaboration graph
[legend]

Public Member Functions

hardware_interface::CallbackReturn on_init (const hardware_interface::HardwareInfo &info) override
 Initialization of the hardware interface from data parsed from the robot's URDF. More...
 
hardware_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
std::vector< hardware_interface::StateInterfaceexport_state_interfaces () override
 Exports all state interfaces for this hardware interface. More...
 
std::vector< hardware_interface::CommandInterfaceexport_command_interfaces () override
 Exports all command interfaces for this hardware interface. More...
 
hardware_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
hardware_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Read the current state values from the actuator. More...
 
hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Write the current command values to the actuator. More...
 
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...
 
- Public Member Functions inherited from hardware_interface::SystemInterface
 SystemInterface (const SystemInterface &other)=delete
 SystemInterface copy constructor is actively deleted. More...
 
 SystemInterface (SystemInterface &&other)=default
 
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 std::string get_name () const
 Get name of the actuator hardware. 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...
 

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 > ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware::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
Precondition
all joint interfaces exist, checked in on_init()

Implements hardware_interface::SystemInterface.

◆ export_state_interfaces()

std::vector< hardware_interface::StateInterface > ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware::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
Precondition
all joint interfaces exist, checked in on_init()

Implements hardware_interface::SystemInterface.

◆ get_clock()

rclcpp::Clock::SharedPtr ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware::get_clock ( ) const
inline

Get the clock of the SystemInterface.

Returns
clock of the SystemInterface.

◆ get_logger()

rclcpp::Logger ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware::get_logger ( ) const
inline

Get the logger of the SystemInterface.

Returns
logger of the SystemInterface.

◆ on_init()

hardware_interface::CallbackReturn ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware::on_init ( const hardware_interface::HardwareInfo hardware_info)
overridevirtual

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.
Note
no need to store the joint and actuator handles, the transmission will keep whatever info it needs after is done with them

Reimplemented from hardware_interface::SystemInterface.

◆ read()

hardware_interface::return_type ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

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.

Implements hardware_interface::SystemInterface.

◆ write()

hardware_interface::return_type ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware::write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

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.

Implements hardware_interface::SystemInterface.


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