15#ifndef HARDWARE_INTERFACE__ACTUATOR_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__ACTUATOR_INTERFACE_HPP_
21#include <unordered_map>
25#include "hardware_interface/component_parser.hpp"
26#include "hardware_interface/handle.hpp"
27#include "hardware_interface/hardware_info.hpp"
28#include "hardware_interface/types/hardware_interface_return_values.hpp"
29#include "hardware_interface/types/lifecycle_state_names.hpp"
30#include "hardware_interface/types/trigger_type.hpp"
31#include "lifecycle_msgs/msg/state.hpp"
32#include "rclcpp/duration.hpp"
33#include "rclcpp/logger.hpp"
34#include "rclcpp/node_interfaces/node_clock_interface.hpp"
35#include "rclcpp/time.hpp"
36#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
37#include "rclcpp_lifecycle/state.hpp"
38#include "realtime_tools/async_function_handler.hpp"
77using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
83 : lifecycle_state_(rclcpp_lifecycle::State(
84 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
85 actuator_logger_(rclcpp::get_logger(
"actuator_interface"))
110 const HardwareInfo & hardware_info, rclcpp::Logger logger,
111 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
113 clock_interface_ = clock_interface;
114 actuator_logger_ = logger.get_child(
"hardware_component.actuator." + hardware_info.
name);
115 info_ = hardware_info;
120 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
121 async_handler_->init(
122 [
this](
const rclcpp::Time & time,
const rclcpp::Duration & period)
124 if (next_trigger_ == TriggerType::READ)
126 const auto ret =
read(time, period);
127 next_trigger_ = TriggerType::WRITE;
132 const auto ret =
write(time, period);
133 next_trigger_ = TriggerType::READ;
138 async_handler_->start_thread();
151 info_ = hardware_info;
154 return CallbackReturn::SUCCESS;
170 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
173 "by the Framework.")]]
virtual std::vector<StateInterface>
188 virtual std::vector<hardware_interface::InterfaceDescription>
205 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
208 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
209 state_interfaces.reserve(
210 unlisted_interface_descriptions.size() + joint_state_interfaces_.size());
214 for (
const auto & description : unlisted_interface_descriptions)
216 auto name = description.get_name();
217 unlisted_state_interfaces_.insert(std::make_pair(name, description));
218 auto state_interface = std::make_shared<StateInterface>(description);
219 actuator_states_.insert(std::make_pair(name, state_interface));
220 unlisted_states_.push_back(state_interface);
221 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
224 for (
const auto & [name, descr] : joint_state_interfaces_)
226 auto state_interface = std::make_shared<StateInterface>(descr);
227 actuator_states_.insert(std::make_pair(name, state_interface));
228 joint_states_.push_back(state_interface);
229 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
231 return state_interfaces;
247 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
250 "by the Framework.")]]
virtual std::vector<CommandInterface>
265 virtual std::vector<hardware_interface::InterfaceDescription>
282 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
285 std::vector<CommandInterface::SharedPtr> command_interfaces;
286 command_interfaces.reserve(
287 unlisted_interface_descriptions.size() + joint_command_interfaces_.size());
291 for (
const auto & description : unlisted_interface_descriptions)
293 auto name = description.get_name();
294 unlisted_command_interfaces_.insert(std::make_pair(name, description));
295 auto command_interface = std::make_shared<CommandInterface>(description);
296 actuator_commands_.insert(std::make_pair(name, command_interface));
297 unlisted_commands_.push_back(command_interface);
298 command_interfaces.push_back(command_interface);
301 for (
const auto & [name, descr] : joint_command_interfaces_)
303 auto command_interface = std::make_shared<CommandInterface>(descr);
304 actuator_commands_.insert(std::make_pair(name, command_interface));
305 joint_commands_.push_back(command_interface);
306 command_interfaces.push_back(command_interface);
309 return command_interfaces;
325 const std::vector<std::string> & ,
326 const std::vector<std::string> & )
328 return return_type::OK;
344 const std::vector<std::string> & ,
345 const std::vector<std::string> & )
347 return return_type::OK;
361 return_type
trigger_read(
const rclcpp::Time & time,
const rclcpp::Duration & period)
363 return_type result = return_type::ERROR;
366 bool trigger_status =
true;
367 if (next_trigger_ == TriggerType::WRITE)
371 "Trigger read called while write async handler call is still pending for hardware "
372 "interface : '%s'. Skipping read cycle and will wait for a write cycle!",
374 return return_type::OK;
376 std::tie(trigger_status, result) = async_handler_->trigger_async_callback(time, period);
381 "Trigger read called while write async trigger is still in progress for hardware "
382 "interface : '%s'. Failed to trigger read cycle!",
384 return return_type::OK;
389 result =
read(time, period);
404 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
416 return_type
trigger_write(
const rclcpp::Time & time,
const rclcpp::Duration & period)
418 return_type result = return_type::ERROR;
421 bool trigger_status =
true;
422 if (next_trigger_ == TriggerType::READ)
426 "Trigger write called while read async handler call is still pending for hardware "
427 "interface : '%s'. Skipping write cycle and will wait for a read cycle!",
429 return return_type::OK;
431 std::tie(trigger_status, result) = async_handler_->trigger_async_callback(time, period);
436 "Trigger write called while read async trigger is still in progress for hardware "
437 "interface : '%s'. Failed to trigger write cycle!",
439 return return_type::OK;
444 result =
write(time, period);
458 virtual return_type
write(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
484 lifecycle_state_ = new_state;
487 void set_state(
const std::string & interface_name,
const double & value)
489 actuator_states_.at(interface_name)->set_value(value);
492 double get_state(
const std::string & interface_name)
const
494 return actuator_states_.at(interface_name)->get_value();
497 void set_command(
const std::string & interface_name,
const double & value)
499 actuator_commands_.at(interface_name)->set_value(value);
502 double get_command(
const std::string & interface_name)
const
504 return actuator_commands_.at(interface_name)->get_value();
511 rclcpp::Logger
get_logger()
const {
return actuator_logger_; }
517 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_interface_->get_clock(); }
528 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
529 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
531 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
532 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
535 std::vector<StateInterface::SharedPtr> joint_states_;
536 std::vector<CommandInterface::SharedPtr> joint_commands_;
538 std::vector<StateInterface::SharedPtr> unlisted_states_;
539 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
541 rclcpp_lifecycle::State lifecycle_state_;
542 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
545 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
546 rclcpp::Logger actuator_logger_;
548 std::unordered_map<std::string, StateInterface::SharedPtr> actuator_states_;
549 std::unordered_map<std::string, CommandInterface::SharedPtr> actuator_commands_;
550 std::atomic<TriggerType> next_trigger_ = TriggerType::READ;
Definition actuator_interface.hpp:80
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition actuator_interface.hpp:251
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition actuator_interface.hpp:149
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition actuator_interface.hpp:202
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition actuator_interface.hpp:266
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition actuator_interface.hpp:109
virtual std::string get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition actuator_interface.hpp:470
virtual std::string get_name() const
Get name of the actuator hardware.
Definition actuator_interface.hpp:464
return_type trigger_write(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
Definition actuator_interface.hpp:416
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition actuator_interface.hpp:189
rclcpp::Logger get_logger() const
Get the logger of the ActuatorInterface.
Definition actuator_interface.hpp:511
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition actuator_interface.hpp:174
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:482
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition actuator_interface.hpp:279
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:476
const HardwareInfo & get_hardware_info() const
Get the hardware info of the ActuatorInterface.
Definition actuator_interface.hpp:523
ActuatorInterface(const ActuatorInterface &other)=delete
ActuatorInterface copy constructor is actively deleted.
virtual return_type prepare_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Prepare for a new command interface switch.
Definition actuator_interface.hpp:324
return_type trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition actuator_interface.hpp:361
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition actuator_interface.hpp:343
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the ActuatorInterface.
Definition actuator_interface.hpp:517
Definition actuator.hpp:33
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1036
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1003
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition actuator_interface.hpp:77
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:170
int thread_priority
Async thread priority.
Definition hardware_info.hpp:182
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:176
bool is_async
Component is async.
Definition hardware_info.hpp:180
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:191
std::string name
Name of the hardware.
Definition hardware_info.hpp:172