15 #ifndef HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
16 #define HARDWARE_INTERFACE__SYSTEM_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/hardware_interface_type_values.hpp"
30 #include "hardware_interface/types/lifecycle_state_names.hpp"
31 #include "lifecycle_msgs/msg/state.hpp"
32 #include "rclcpp/duration.hpp"
33 #include "rclcpp/logger.hpp"
34 #include "rclcpp/logging.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"
79 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
81 class SystemInterface :
public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
85 : lifecycle_state_(rclcpp_lifecycle::State(
86 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
87 system_logger_(rclcpp::get_logger(
"system_interface"))
112 const HardwareInfo & hardware_info, rclcpp::Logger logger,
113 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
115 clock_interface_ = clock_interface;
116 system_logger_ = logger.get_child(
"hardware_component.system." + hardware_info.
name);
117 info_ = hardware_info;
122 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
123 async_handler_->init(
124 [
this](
const rclcpp::Time & time,
const rclcpp::Duration & period)
126 if (next_trigger_ == TriggerType::READ)
128 const auto ret =
read(time, period);
129 next_trigger_ = TriggerType::WRITE;
134 const auto ret =
write(time, period);
135 next_trigger_ = TriggerType::READ;
140 async_handler_->start_thread();
153 info_ = hardware_info;
159 return CallbackReturn::SUCCESS;
175 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
176 "Exporting is handled "
177 "by the Framework.")]]
virtual std::vector<StateInterface>
192 virtual std::vector<hardware_interface::InterfaceDescription>
209 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
212 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
213 state_interfaces.reserve(
214 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
215 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
219 for (
const auto & description : unlisted_interface_descriptions)
221 auto name = description.get_name();
222 unlisted_state_interfaces_.insert(std::make_pair(name, description));
223 auto state_interface = std::make_shared<StateInterface>(description);
224 system_states_.insert(std::make_pair(name, state_interface));
225 unlisted_states_.push_back(state_interface);
226 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
229 for (
const auto & [name, descr] : joint_state_interfaces_)
231 auto state_interface = std::make_shared<StateInterface>(descr);
232 system_states_.insert(std::make_pair(name, state_interface));
233 joint_states_.push_back(state_interface);
234 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
236 for (
const auto & [name, descr] : sensor_state_interfaces_)
238 auto state_interface = std::make_shared<StateInterface>(descr);
239 system_states_.insert(std::make_pair(name, state_interface));
240 sensor_states_.push_back(state_interface);
241 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
243 for (
const auto & [name, descr] : gpio_state_interfaces_)
245 auto state_interface = std::make_shared<StateInterface>(descr);
246 system_states_.insert(std::make_pair(name, state_interface));
247 gpio_states_.push_back(state_interface);
248 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
250 return state_interfaces;
266 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
269 "by the Framework.")]]
virtual std::vector<CommandInterface>
284 virtual std::vector<hardware_interface::InterfaceDescription>
301 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
304 std::vector<CommandInterface::SharedPtr> command_interfaces;
305 command_interfaces.reserve(
306 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
307 gpio_command_interfaces_.size());
311 for (
const auto & description : unlisted_interface_descriptions)
313 auto name = description.get_name();
314 unlisted_command_interfaces_.insert(std::make_pair(name, description));
315 auto command_interface = std::make_shared<CommandInterface>(description);
316 system_commands_.insert(std::make_pair(name, command_interface));
317 unlisted_commands_.push_back(command_interface);
318 command_interfaces.push_back(command_interface);
321 for (
const auto & [name, descr] : joint_command_interfaces_)
323 auto command_interface = std::make_shared<CommandInterface>(descr);
324 system_commands_.insert(std::make_pair(name, command_interface));
325 joint_commands_.push_back(command_interface);
326 command_interfaces.push_back(command_interface);
329 for (
const auto & [name, descr] : gpio_command_interfaces_)
331 auto command_interface = std::make_shared<CommandInterface>(descr);
332 system_commands_.insert(std::make_pair(name, command_interface));
333 gpio_commands_.push_back(command_interface);
334 command_interfaces.push_back(command_interface);
336 return command_interfaces;
353 const std::vector<std::string> & ,
354 const std::vector<std::string> & )
356 return return_type::OK;
372 const std::vector<std::string> & ,
373 const std::vector<std::string> & )
375 return return_type::OK;
389 return_type
trigger_read(
const rclcpp::Time & time,
const rclcpp::Duration & period)
391 return_type result = return_type::ERROR;
394 bool trigger_status =
true;
395 if (next_trigger_ == TriggerType::WRITE)
399 "Trigger read called while write async handler call is still pending for hardware "
400 "interface : '%s'. Skipping read cycle and will wait for a write cycle!",
402 return return_type::OK;
404 std::tie(trigger_status, result) = async_handler_->trigger_async_callback(time, period);
409 "Trigger read called while write async trigger is still in progress for hardware "
410 "interface : '%s'. Failed to trigger read cycle!",
412 return return_type::OK;
417 result =
read(time, period);
432 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
444 return_type
trigger_write(
const rclcpp::Time & time,
const rclcpp::Duration & period)
446 return_type result = return_type::ERROR;
449 bool trigger_status =
true;
450 if (next_trigger_ == TriggerType::READ)
454 "Trigger write called while read async handler call is still pending for hardware "
455 "interface : '%s'. Skipping write cycle and will wait for a read cycle!",
457 return return_type::OK;
459 std::tie(trigger_status, result) = async_handler_->trigger_async_callback(time, period);
464 "Trigger write called while read async trigger is still in progress for hardware "
465 "interface : '%s'. Failed to trigger write cycle!",
467 return return_type::OK;
472 result =
write(time, period);
486 virtual return_type
write(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
512 lifecycle_state_ = new_state;
515 void set_state(
const std::string & interface_name,
const double & value)
517 system_states_.at(interface_name)->set_value(value);
520 double get_state(
const std::string & interface_name)
const
522 return system_states_.at(interface_name)->get_value();
525 void set_command(
const std::string & interface_name,
const double & value)
527 system_commands_.at(interface_name)->set_value(value);
530 double get_command(
const std::string & interface_name)
const
532 return system_commands_.at(interface_name)->get_value();
545 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_interface_->get_clock(); }
556 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
557 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
559 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
561 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
562 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
564 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
565 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
567 rclcpp_lifecycle::State lifecycle_state_;
568 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
571 std::vector<StateInterface::SharedPtr> joint_states_;
572 std::vector<CommandInterface::SharedPtr> joint_commands_;
574 std::vector<StateInterface::SharedPtr> sensor_states_;
576 std::vector<StateInterface::SharedPtr> gpio_states_;
577 std::vector<CommandInterface::SharedPtr> gpio_commands_;
579 std::vector<StateInterface::SharedPtr> unlisted_states_;
580 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
583 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
584 rclcpp::Logger system_logger_;
586 std::unordered_map<std::string, StateInterface::SharedPtr> system_states_;
587 std::unordered_map<std::string, CommandInterface::SharedPtr> system_commands_;
588 enum class TriggerType
593 std::atomic<TriggerType> next_trigger_ = TriggerType::READ;
Definition: system_interface.hpp:82
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition: system_interface.hpp:193
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition: system_interface.hpp:270
return_type trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition: system_interface.hpp:389
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition: system_interface.hpp:371
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition: system_interface.hpp:298
virtual std::string get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition: system_interface.hpp:498
virtual std::string get_name() const
Get name of the actuator hardware.
Definition: system_interface.hpp:492
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: system_interface.hpp:151
rclcpp::Logger get_logger() const
Get the logger of the SystemInterface.
Definition: system_interface.hpp:539
return_type trigger_write(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
Definition: system_interface.hpp:444
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition: system_interface.hpp:510
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: system_interface.hpp:352
const HardwareInfo & get_hardware_info() const
Get the hardware info of the SystemInterface.
Definition: system_interface.hpp:551
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SystemInterface.
Definition: system_interface.hpp:545
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition: system_interface.hpp:111
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition: system_interface.hpp:206
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition: system_interface.hpp:178
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition: system_interface.hpp:504
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition: system_interface.hpp:285
SystemInterface(const SystemInterface &other)=delete
SystemInterface copy constructor is actively deleted.
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
Definition: actuator.hpp:34
HARDWARE_INTERFACE_PUBLIC std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition: component_parser.cpp:1031
HARDWARE_INTERFACE_PUBLIC std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition: component_parser.cpp:998
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition: actuator_interface.hpp:76
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 > gpios
Definition: hardware_info.hpp:205
std::vector< ComponentInfo > joints
Definition: hardware_info.hpp:191
std::string name
Name of the hardware.
Definition: hardware_info.hpp:172
std::vector< ComponentInfo > sensors
Definition: hardware_info.hpp:200