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/introspection.hpp"
29#include "hardware_interface/types/hardware_interface_return_values.hpp"
30#include "hardware_interface/types/lifecycle_state_names.hpp"
31#include "hardware_interface/types/trigger_type.hpp"
32#include "lifecycle_msgs/msg/state.hpp"
33#include "rclcpp/duration.hpp"
34#include "rclcpp/logger.hpp"
35#include "rclcpp/node_interfaces/node_clock_interface.hpp"
36#include "rclcpp/time.hpp"
37#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
38#include "rclcpp_lifecycle/state.hpp"
39#include "realtime_tools/async_function_handler.hpp"
44using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
96 rclcpp_lifecycle::State(
97 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
98 actuator_logger_(rclcpp::get_logger(
"actuator_interface"))
122 [[deprecated(
"Use init(HardwareInfo, rclcpp::Logger, rclcpp::Clock::SharedPtr) instead.")]]
124 const HardwareInfo & hardware_info, rclcpp::Logger logger,
125 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
127 return this->
init(hardware_info, logger, clock_interface->get_clock());
140 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
142 actuator_clock_ = clock;
143 actuator_logger_ = logger.get_child(
"hardware_component.actuator." + hardware_info.
name);
144 info_ = hardware_info;
149 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
150 async_handler_->init(
151 [
this](
const rclcpp::Time & time,
const rclcpp::Duration & period)
153 const auto read_start_time = std::chrono::steady_clock::now();
154 const auto ret_read =
read(time, period);
155 const auto read_end_time = std::chrono::steady_clock::now();
156 read_return_info_.store(ret_read, std::memory_order_release);
157 read_execution_time_.store(
158 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
159 std::memory_order_release);
160 if (ret_read != return_type::OK)
164 const auto write_start_time = std::chrono::steady_clock::now();
165 const auto ret_write =
write(time, period);
166 const auto write_end_time = std::chrono::steady_clock::now();
167 write_return_info_.store(ret_write, std::memory_order_release);
168 write_execution_time_.store(
169 std::chrono::duration_cast<std::chrono::nanoseconds>(write_end_time - write_start_time),
170 std::memory_order_release);
174 async_handler_->start_thread();
187 info_ = hardware_info;
190 return CallbackReturn::SUCCESS;
206 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
209 "by the Framework.")]]
virtual std::vector<StateInterface>
224 virtual std::vector<hardware_interface::InterfaceDescription>
241 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
244 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
245 state_interfaces.reserve(
246 unlisted_interface_descriptions.size() + joint_state_interfaces_.size());
250 for (
const auto & description : unlisted_interface_descriptions)
252 auto name = description.get_name();
253 unlisted_state_interfaces_.insert(std::make_pair(name, description));
254 auto state_interface = std::make_shared<StateInterface>(description);
255 actuator_states_.insert(std::make_pair(name, state_interface));
256 unlisted_states_.push_back(state_interface);
257 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
260 for (
const auto & [name, descr] : joint_state_interfaces_)
262 auto state_interface = std::make_shared<StateInterface>(descr);
263 actuator_states_.insert(std::make_pair(name, state_interface));
264 joint_states_.push_back(state_interface);
265 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
267 return state_interfaces;
283 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
286 "by the Framework.")]]
virtual std::vector<CommandInterface>
301 virtual std::vector<hardware_interface::InterfaceDescription>
318 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
321 std::vector<CommandInterface::SharedPtr> command_interfaces;
322 command_interfaces.reserve(
323 unlisted_interface_descriptions.size() + joint_command_interfaces_.size());
327 for (
const auto & description : unlisted_interface_descriptions)
329 auto name = description.get_name();
330 unlisted_command_interfaces_.insert(std::make_pair(name, description));
331 auto command_interface = std::make_shared<CommandInterface>(description);
332 actuator_commands_.insert(std::make_pair(name, command_interface));
333 unlisted_commands_.push_back(command_interface);
334 command_interfaces.push_back(command_interface);
337 for (
const auto & [name, descr] : joint_command_interfaces_)
339 auto command_interface = std::make_shared<CommandInterface>(descr);
340 actuator_commands_.insert(std::make_pair(name, command_interface));
341 joint_commands_.push_back(command_interface);
342 command_interfaces.push_back(command_interface);
345 return command_interfaces;
361 const std::vector<std::string> & ,
362 const std::vector<std::string> & )
364 return return_type::OK;
380 const std::vector<std::string> & ,
381 const std::vector<std::string> & )
383 return return_type::OK;
398 const rclcpp::Time & time,
const rclcpp::Duration & period)
401 status.result = return_type::ERROR;
404 status.result = read_return_info_.load(std::memory_order_acquire);
405 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
406 if (read_exec_time.count() > 0)
408 status.execution_time = read_exec_time;
410 const auto result = async_handler_->trigger_async_callback(time, period);
411 status.successful = result.first;
412 if (!status.successful)
416 "Trigger read/write called while the previous async trigger is still in progress for "
417 "hardware interface : '%s'. Failed to trigger read/write cycle!",
419 status.result = return_type::OK;
425 const auto start_time = std::chrono::steady_clock::now();
426 status.successful =
true;
427 status.result =
read(time, period);
428 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
429 std::chrono::steady_clock::now() - start_time);
444 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
457 const rclcpp::Time & time,
const rclcpp::Duration & period)
460 status.result = return_type::ERROR;
463 status.successful =
true;
464 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
465 if (write_exec_time.count() > 0)
467 status.execution_time = write_exec_time;
469 status.result = write_return_info_.load(std::memory_order_acquire);
473 const auto start_time = std::chrono::steady_clock::now();
474 status.successful =
true;
475 status.result =
write(time, period);
476 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
477 std::chrono::steady_clock::now() - start_time);
491 virtual return_type
write(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
517 lifecycle_state_ = new_state;
520 template <
typename T>
521 void set_state(
const std::string & interface_name,
const T & value)
523 auto it = actuator_states_.find(interface_name);
524 if (it == actuator_states_.end())
526 throw std::runtime_error(
527 "State interface not found: " + interface_name +
528 " in actuator hardware component: " + info_.
name +
". This should not happen.");
530 auto & handle = it->second;
531 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
532 std::ignore = handle->set_value(lock, value);
535 template <
typename T =
double>
536 T get_state(
const std::string & interface_name)
const
538 auto it = actuator_states_.find(interface_name);
539 if (it == actuator_states_.end())
541 throw std::runtime_error(
542 "State interface not found: " + interface_name +
543 " in actuator hardware component: " + info_.
name +
". This should not happen.");
545 auto & handle = it->second;
546 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
547 const auto opt_value = handle->get_optional<T>(lock);
550 throw std::runtime_error(
551 "Failed to get state value from interface: " + interface_name +
552 ". This should not happen.");
554 return opt_value.value();
557 void set_command(
const std::string & interface_name,
const double & value)
559 auto it = actuator_commands_.find(interface_name);
560 if (it == actuator_commands_.end())
562 throw std::runtime_error(
563 "Command interface not found: " + interface_name +
564 " in actuator hardware component: " + info_.
name +
". This should not happen.");
566 auto & handle = it->second;
567 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
568 std::ignore = handle->set_value(lock, value);
571 template <
typename T =
double>
572 T get_command(
const std::string & interface_name)
const
574 auto it = actuator_commands_.find(interface_name);
575 if (it == actuator_commands_.end())
577 throw std::runtime_error(
578 "Command interface not found: " + interface_name +
579 " in actuator hardware component: " + info_.
name +
". This should not happen.");
581 auto & handle = it->second;
582 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
583 const auto opt_value = handle->get_optional<
double>(lock);
586 throw std::runtime_error(
587 "Failed to get command value from interface: " + interface_name +
588 ". This should not happen.");
590 return opt_value.value();
597 rclcpp::Logger
get_logger()
const {
return actuator_logger_; }
603 rclcpp::Clock::SharedPtr
get_clock()
const {
return actuator_clock_; }
617 read_return_info_.store(return_type::OK, std::memory_order_release);
618 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
619 write_return_info_.store(return_type::OK, std::memory_order_release);
620 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
631 stats_registrations_.enableAll();
635 stats_registrations_.disableAll();
642 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
643 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
645 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
646 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
649 std::vector<StateInterface::SharedPtr> joint_states_;
650 std::vector<CommandInterface::SharedPtr> joint_commands_;
652 std::vector<StateInterface::SharedPtr> unlisted_states_;
653 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
655 rclcpp_lifecycle::State lifecycle_state_;
656 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
659 rclcpp::Clock::SharedPtr actuator_clock_;
660 rclcpp::Logger actuator_logger_;
662 std::unordered_map<std::string, StateInterface::SharedPtr> actuator_states_;
663 std::unordered_map<std::string, CommandInterface::SharedPtr> actuator_commands_;
664 std::atomic<return_type> read_return_info_ = return_type::OK;
665 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
666 std::atomic<return_type> write_return_info_ = return_type::OK;
667 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
670 pal_statistics::RegistrationsRAII stats_registrations_;
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition actuator_interface.hpp:92
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:287
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:185
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition actuator_interface.hpp:238
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition actuator_interface.hpp:503
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition actuator_interface.hpp:302
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition actuator_interface.hpp:123
HardwareComponentCycleStatus 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:397
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition actuator_interface.hpp:139
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition actuator_interface.hpp:225
rclcpp::Logger get_logger() const
Get the logger of the ActuatorInterface.
Definition actuator_interface.hpp:597
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition actuator_interface.hpp:210
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:515
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition actuator_interface.hpp:315
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:509
const HardwareInfo & get_hardware_info() const
Get the hardware info of the ActuatorInterface.
Definition actuator_interface.hpp:609
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition actuator_interface.hpp:627
const std::string & get_name() const
Get name of the actuator hardware.
Definition actuator_interface.hpp:497
HardwareComponentCycleStatus 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:456
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition actuator_interface.hpp:615
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:360
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition actuator_interface.hpp:379
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the ActuatorInterface.
Definition actuator_interface.hpp:603
Definition actuator.hpp:33
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1045
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1012
Definition hardware_interface_return_values.hpp:41
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:232
int thread_priority
Async thread priority.
Definition hardware_info.hpp:244
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:238
bool is_async
Component is async.
Definition hardware_info.hpp:242
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:253
std::string name
Name of the hardware.
Definition hardware_info.hpp:234