Class SensorInterface
Defined in File sensor_interface.hpp
Inheritance Relationships
Base Type
public hardware_interface::HardwareComponentInterface
(Class HardwareComponentInterface)
Class Documentation
-
class SensorInterface : public hardware_interface::HardwareComponentInterface
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 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces() override
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
-
inline virtual return_type write(const rclcpp::Time&, const rclcpp::Duration&) final
Write the current command values to the hardware.
The physical hardware shall be updated with the latest value from the exported command interfaces.
- 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.