ros2_control - jazzy
Loading...
Searching...
No Matches
Public Member Functions | List of all members
hardware_interface::SensorInterface Class Reference

Virtual Class to implement when integrating a stand-alone sensor into ros2_control. More...

#include <sensor_interface.hpp>

Inheritance diagram for hardware_interface::SensorInterface:
Inheritance graph
[legend]
Collaboration diagram for hardware_interface::SensorInterface:
Collaboration graph
[legend]

Public Member Functions

std::vector< CommandInterface::SharedPtr > on_export_command_interfaces () override
 
return_type write (const rclcpp::Time &, const rclcpp::Duration &) final
 Write the current command values to the hardware.
 
- Public Member Functions inherited from hardware_interface::HardwareComponentInterface
 HardwareComponentInterface (const HardwareComponentInterface &other)=delete
 HardwareComponentInterface copy constructor is actively deleted.
 
 HardwareComponentInterface (HardwareComponentInterface &&other)=delete
 
CallbackReturn init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
 
CallbackReturn init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
 
CallbackReturn init (const hardware_interface::HardwareComponentParams &params)
 
virtual CallbackReturn on_init (const HardwareInfo &hardware_info)
 Initialization of the hardware interface from data parsed from the robot's URDF.
 
virtual CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams &params)
 Initialization of the hardware interface from data parsed from the robot's URDF.
 
virtual std::vector< StateInterfaceexport_state_interfaces ()
 Exports all state interfaces for this hardware interface.
 
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.
 
virtual std::vector< hardware_interface::InterfaceDescriptionexport_unlisted_command_interface_descriptions ()
 
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 > &)
 
HardwareComponentCycleStatus trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period)
 Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
 
virtual return_type read (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 Read the current state values from the hardware.
 
HardwareComponentCycleStatus trigger_write (const rclcpp::Time &time, const rclcpp::Duration &period)
 Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
 
const std::string & get_name () const
 Get name of the hardware.
 
const std::string & get_group_name () const
 Get name of the hardware group to which it belongs to.
 
const rclcpp_lifecycle::State & get_lifecycle_state () const
 Get life-cycle state of the hardware.
 
void set_lifecycle_state (const rclcpp_lifecycle::State &new_state)
 Set life-cycle state of the hardware.
 
template<typename T >
void set_state (const std::string &interface_name, const T &value)
 
template<typename T = double>
get_state (const std::string &interface_name) const
 
template<typename T >
void set_command (const std::string &interface_name, const T &value)
 
template<typename T = double>
get_command (const std::string &interface_name) const
 
rclcpp::Logger get_logger () const
 Get the logger of the Interface.
 
rclcpp::Clock::SharedPtr get_clock () const
 Get the clock of the Interface.
 
rclcpp::Node::SharedPtr get_node () const
 Get the default node of the Interface.
 
const HardwareInfoget_hardware_info () const
 Get the hardware info of the Interface.
 
void prepare_for_activation ()
 Prepare for the activation of the hardware.
 
void enable_introspection (bool enable)
 Enable or disable introspection of the hardware.
 

Additional Inherited Members

- Protected Attributes inherited from hardware_interface::HardwareComponentInterface
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_
 
pal_statistics::RegistrationsRAII stats_registrations_
 

Detailed Description

Virtual Class to implement when integrating a stand-alone sensor into ros2_control.

The typical examples are Force-Torque Sensor (FTS), Interial Measurement Unit (IMU).

Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following meaning:

Returns
CallbackReturn::SUCCESS method execution was successful.
CallbackReturn::FAILURE method execution has failed and and can be called again.
CallbackReturn::ERROR critical error has happened that should be managed in "on_error" method.

The hardware ends after each method in a state with the following meaning:

UNCONFIGURED (on_init, on_cleanup): Hardware is initialized but communication is not started and therefore no interface is available.

INACTIVE (on_configure, on_deactivate): Communication with the hardware is started and it is configured. States can be read.

FINALIZED (on_shutdown): Hardware interface is ready for unloading/destruction. Allocated memory is cleaned up.

ACTIVE (on_activate): States can be read.

Member Function Documentation

◆ on_export_command_interfaces()

std::vector< CommandInterface::SharedPtr > hardware_interface::SensorInterface::on_export_command_interfaces ( )
inlineoverridevirtual

Default implementation for exporting the CommandInterfaces. The CommandInterfaces are created according to the InterfaceDescription. The memory accessed by the controllers and hardware is assigned here and resides in the system_interface.

Actuator and System components should override this method. Sensor components can use the default.

Returns
vector of shared pointers to the created and stored CommandInterfaces

Reimplemented from hardware_interface::HardwareComponentInterface.

◆ write()

return_type hardware_interface::SensorInterface::write ( const rclcpp::Time &  ,
const rclcpp::Duration &   
)
inlinefinalvirtual

Write the current command values to the hardware.

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.

Reimplemented from hardware_interface::HardwareComponentInterface.


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