Class ActuatorInterface
Defined in File actuator_interface.hpp
Inheritance Relationships
Base Type
public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Class Documentation
-
class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Public Functions
-
inline ActuatorInterface()
-
ActuatorInterface(const ActuatorInterface &other) = delete
ActuatorInterface 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.
-
ActuatorInterface(ActuatorInterface &&other) = default
-
virtual ~ActuatorInterface() = 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 std::vector<CommandInterface> export_command_interfaces() = 0
Exports all command interfaces for this hardware interface.
The command 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 command interfaces
-
inline virtual return_type prepare_command_mode_switch(const std::vector<std::string>&, const std::vector<std::string>&)
Prepare for a new command interface switch.
Prepare for any mode-switching required by the new command interface combination.
Note
This is a non-realtime evaluation of whether a set of command interface claims are possible, and call to start preparing data structures for the upcoming switch that will occur.
Note
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
- Parameters:
start_interfaces – [in] vector of string identifiers for the command interfaces starting.
stop_interfaces – [in] vector of string identifiers for the command interfaces stopping.
- Returns:
return_type::OK if the new command interface combination can be prepared, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
-
inline virtual return_type perform_command_mode_switch(const std::vector<std::string>&, const std::vector<std::string>&)
Perform the mode-switching for the new command interface combination.
Note
This is part of the realtime update loop, and should be fast.
Note
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
- Parameters:
start_interfaces – [in] vector of string identifiers for the command interfaces starting.
stop_interfaces – [in] vector of string identifiers for the command interfaces stopping.
- Returns:
return_type::OK if the new command interface combination can be switched to, or if the interface key is not relevant to this system. Returns 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.
-
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) = 0
Write the current command values to the actuator.
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.
-
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 ActuatorInterface()