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
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_interface – [in] pointer to the clock interface.
logger_interface – [in] pointer to the logger 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 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 actuator_interface.
- Returns:
vector of shared pointers to the created and stored StateInterfaces
-
inline virtual std::vector<CommandInterface> export_command_interfaces()
Exports all command interfaces for this hardware interface.
Old way of exporting the CommandInterfaces. If a empty vector is returned then the on_export_command_interfaces() method is called. If a vector with CommandInterfaces is returned then the exporting of the CommandInterfaces 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_command_interface_descriptions()
Override this method to export custom CommandInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_command_interfaces_ map.
- Returns:
vector of descriptions to the unlisted CommandInterfaces
-
inline virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
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 actuator_interface.
- Returns:
vector of shared pointers to the created and stored CommandInterfaces
-
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.
-
inline return_type 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. The method is called in the resource_manager’s read loop
- 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 return_type trigger_write(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
The physical hardware shall be updated with the latest value from the exported command interfaces. The method is called in the resource_manager’s write loop
- 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 virtual 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.
-
inline void set_state(const std::string &interface_name, const double &value)
-
inline double get_state(const std::string &interface_name) const
-
inline void set_command(const std::string &interface_name, const double &value)
-
inline double get_command(const std::string &interface_name) const
-
inline rclcpp::Logger get_logger() const
Get the logger of the ActuatorInterface.
- Returns:
logger of the ActuatorInterface.
-
inline rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the ActuatorInterface.
- Returns:
clock of the ActuatorInterface.
-
inline const HardwareInfo &get_hardware_info() const
Get the hardware info of the ActuatorInterface.
- Returns:
hardware info of the ActuatorInterface.
Protected Attributes
-
HardwareInfo info_
-
std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_
-
std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_
-
std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_
-
std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_
-
std::vector<StateInterface::SharedPtr> joint_states_
-
std::vector<CommandInterface::SharedPtr> joint_commands_
-
std::vector<StateInterface::SharedPtr> unlisted_states_
-
std::vector<CommandInterface::SharedPtr> unlisted_commands_
-
rclcpp_lifecycle::State lifecycle_state_
-
std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_
-
inline ActuatorInterface()