ros2_control - rolling
Public Member Functions | List of all members
ros2_control_demo_example_12::RRBotSystemPositionOnlyHardware Class Reference
Inheritance diagram for ros2_control_demo_example_12::RRBotSystemPositionOnlyHardware:
Inheritance graph
[legend]
Collaboration diagram for ros2_control_demo_example_12::RRBotSystemPositionOnlyHardware:
Collaboration graph
[legend]

Public Member Functions

 RCLCPP_SHARED_PTR_DEFINITIONS (RRBotSystemPositionOnlyHardware)
 
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
 
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...
 
- Public Member Functions inherited from hardware_interface::SystemInterface
 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 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...
 
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 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 SystemInterface. More...
 
rclcpp::Clock::SharedPtr get_clock () const
 Get the clock of the SystemInterface. More...
 
const HardwareInfoget_hardware_info () const
 Get the hardware info of the SystemInterface. More...
 

Additional Inherited Members

- Protected Attributes inherited from hardware_interface::SystemInterface
HardwareInfo info_
 
std::unordered_map< std::string, InterfaceDescriptionjoint_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionjoint_command_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionsensor_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptiongpio_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptiongpio_command_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionunlisted_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionunlisted_command_interfaces_
 
rclcpp_lifecycle::State lifecycle_state_
 
std::unique_ptr< realtime_tools::AsyncFunctionHandler< return_type > > async_handler_
 
std::vector< StateInterface::SharedPtr > joint_states_
 
std::vector< CommandInterface::SharedPtr > joint_commands_
 
std::vector< StateInterface::SharedPtr > sensor_states_
 
std::vector< StateInterface::SharedPtr > gpio_states_
 
std::vector< CommandInterface::SharedPtr > gpio_commands_
 
std::vector< StateInterface::SharedPtr > unlisted_states_
 
std::vector< CommandInterface::SharedPtr > unlisted_commands_
 

Member Function Documentation

◆ on_init()

hardware_interface::CallbackReturn ros2_control_demo_example_12::RRBotSystemPositionOnlyHardware::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.

Reimplemented from hardware_interface::SystemInterface.

◆ read()

hardware_interface::return_type ros2_control_demo_example_12::RRBotSystemPositionOnlyHardware::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_12::RRBotSystemPositionOnlyHardware::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: