Class SensorInterface
Defined in File sensor_interface.hpp
Inheritance Relationships
Base Type
public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Class Documentation
-
class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
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) = default
-
virtual ~SensorInterface() = default
-
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.
-
virtual std::vector<StateInterface> export_state_interfaces() = 0
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
-
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 virtual std::string get_name() const
Get name of the actuator hardware.
- Returns:
name.
-
inline const rclcpp_lifecycle::State &get_state() const
Get life-cycle state of the actuator hardware.
- Returns:
state.
-
inline void set_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
- Returns:
state.
-
inline SensorInterface()