Class SensorInterface

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface

Class Documentation

class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface

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:

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.

Return:

CallbackReturn::SUCCESS method execution was successful.

Return:

CallbackReturn::FAILURE method execution has failed and and can be called again.

Return:

CallbackReturn::ERROR critical error has happened that should be managed in “on_error” method.

Public Functions

inline SensorInterface()
SensorInterface(const SensorInterface &other) = delete

SensorInterface 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.

SensorInterface(SensorInterface &&other) = delete
virtual ~SensorInterface() = default
inline CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)

Initialization of the hardware interface from data parsed from the robot’s URDF and also the clock and logger interfaces.

Parameters:
  • hardware_info[in] structure with data from URDF.

  • logger[in] Logger for the hardware component.

  • clock_interface[in] pointer to the clock interface.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

inline CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)

Initialization of the hardware interface from data parsed from the robot’s URDF and also the clock and logger interfaces.

Parameters:
  • hardware_info[in] structure with data from URDF.

  • clock[in] pointer to the resource manager clock.

  • logger[in] Logger for the hardware component.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

inline virtual CallbackReturn on_init(const HardwareInfo &hardware_info)

Initialization of the hardware interface from data parsed from the robot’s URDF.

Parameters:

hardware_info[in] structure with data from URDF.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

inline virtual std::vector<StateInterface> export_state_interfaces()

Exports all state interfaces for this hardware interface.

Old way of exporting the StateInterfaces. If a empty vector is returned then the on_export_state_interfaces() method is called. If a vector with StateInterfaces is returned then the exporting of the StateInterfaces is only done with this function and the ownership is transferred to the resource manager. The set_command(…), get_command(…), …, can then not be used.

Note the ownership over the state interfaces is transferred to the caller.

Returns:

vector of state interfaces

inline virtual std::vector<hardware_interface::InterfaceDescription> export_unlisted_state_interface_descriptions()

Override this method to export custom StateInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_state_interfaces_ map.

Returns:

vector of descriptions to the unlisted StateInterfaces

inline virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()

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

Returns:

vector of shared pointers to the created and stored StateInterfaces

inline HardwareComponentCycleStatus trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)

Triggers the read method synchronously or asynchronously depending on the HardwareInfo.

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:
  • time[in] The time at the start of this control loop iteration

  • period[in] The measured time taken by the last control loop iteration

Returns:

return_type::OK if the read was successful, return_type::ERROR otherwise.

virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) = 0

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:
  • time[in] The time at the start of this control loop iteration

  • period[in] The measured time taken by the last control loop iteration

Returns:

return_type::OK if the read was successful, return_type::ERROR otherwise.

inline const std::string &get_name() const

Get name of the actuator hardware.

Returns:

name.

inline const std::string &get_group_name() const

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

Returns:

group name.

inline const rclcpp_lifecycle::State &get_lifecycle_state() const

Get life-cycle state of the actuator hardware.

Returns:

state.

inline void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)

Set life-cycle state of the actuator hardware.

Returns:

state.

template<typename T>
inline void set_state(const std::string &interface_name, const T &value)
template<typename T = double>
inline T get_state(const std::string &interface_name) const
inline rclcpp::Logger get_logger() const

Get the logger of the SensorInterface.

Returns:

logger of the SensorInterface.

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

Get the clock of the SensorInterface.

Returns:

clock of the SensorInterface.

inline const HardwareInfo &get_hardware_info() const

Get the hardware info of the SensorInterface.

Returns:

hardware info of the SensorInterface.

inline void enable_introspection(bool enable)

Enable or disable introspection of the sensor hardware.

Parameters:

enable[in] Enable introspection if true, disable otherwise.

Protected Attributes

HardwareInfo info_
std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_
std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_
std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_
std::vector<StateInterface::SharedPtr> joint_states_
std::vector<StateInterface::SharedPtr> sensor_states_
std::vector<StateInterface::SharedPtr> unlisted_states_
rclcpp_lifecycle::State lifecycle_state_
std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> read_async_handler_
pal_statistics::RegistrationsRAII stats_registrations_