ros2_control - rolling
Loading...
Searching...
No Matches
hardware_component_interface.hpp
1// Copyright 2025 ros2_control Development Team
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
17
18#include <fmt/compile.h>
19
20#include <limits>
21#include <memory>
22#include <string>
23#include <unordered_map>
24#include <utility>
25#include <vector>
26
27#include "control_msgs/msg/hardware_status.hpp"
28#include "hardware_interface/component_parser.hpp"
29#include "hardware_interface/handle.hpp"
30#include "hardware_interface/hardware_info.hpp"
31#include "hardware_interface/introspection.hpp"
32#include "hardware_interface/types/hardware_component_interface_params.hpp"
33#include "hardware_interface/types/hardware_component_params.hpp"
34#include "hardware_interface/types/hardware_interface_return_values.hpp"
35#include "hardware_interface/types/hardware_interface_type_values.hpp"
36#include "hardware_interface/types/lifecycle_state_names.hpp"
37#include "hardware_interface/types/trigger_type.hpp"
38#include "lifecycle_msgs/msg/state.hpp"
39#include "rclcpp/duration.hpp"
40#include "rclcpp/logger.hpp"
41#include "rclcpp/logging.hpp"
42#include "rclcpp/node_interfaces/node_clock_interface.hpp"
43#include "rclcpp/time.hpp"
44#include "rclcpp/version.h"
45#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
46#include "rclcpp_lifecycle/state.hpp"
47#include "realtime_tools/async_function_handler.hpp"
48#include "realtime_tools/realtime_publisher.hpp"
49#include "realtime_tools/realtime_thread_safe_box.hpp"
50
51namespace hardware_interface
52{
53
54using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
55
64class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
65{
66public:
68
70
75
77
79
82
92 CallbackReturn init(const hardware_interface::HardwareComponentParams & params);
93
95
104 virtual CallbackReturn init_hardware_status_message(
105 control_msgs::msg::HardwareStatus & msg_template);
106
108
116 virtual return_type update_hardware_status_message(control_msgs::msg::HardwareStatus & msg);
117
119
128 virtual CallbackReturn on_init(
130
132
136 virtual rclcpp::NodeOptions define_custom_node_options() const;
137
139
150 [[deprecated(
151 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
152 "Exporting is handled by the Framework.")]] virtual std::vector<StateInterface>
154
161 virtual std::vector<hardware_interface::InterfaceDescription>
163
171 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces();
172
174
185 [[deprecated(
186 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
187 "Exporting is handled by the Framework.")]] virtual std::vector<CommandInterface>
189
196 virtual std::vector<hardware_interface::InterfaceDescription>
198
209 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces();
210
212
222 virtual return_type prepare_command_mode_switch(
223 const std::vector<std::string> & start_interfaces,
224 const std::vector<std::string> & stop_interfaces);
225
226 // Perform switching to the new command interface.
236 virtual return_type perform_command_mode_switch(
237 const std::vector<std::string> & start_interfaces,
238 const std::vector<std::string> & stop_interfaces);
239
241
252 const rclcpp::Time & time, const rclcpp::Duration & period);
253
255
264 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
265
267
277 const rclcpp::Time & time, const rclcpp::Duration & period);
278
280
288 virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period);
289
291
294 const std::string & get_name() const;
295
297
300 const std::string & get_group_name() const;
301
303
309 const rclcpp_lifecycle::State & get_lifecycle_state() const;
310
312
318 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state);
319
321 uint8_t get_lifecycle_id() const;
322
324
328 virtual bool has_state(const std::string & interface_name) const;
329
331
337 virtual const StateInterface::SharedPtr & get_state_interface_handle(
338 const std::string & interface_name) const;
339
341
351 template <typename T>
353 const StateInterface::SharedPtr & interface_handle, const T & value, bool wait_until_set)
354 {
355 if (!interface_handle)
356 {
357 throw std::runtime_error(
358 fmt::format(
359 "State interface handle is null in hardware component: {}, while calling set_state "
360 "method. This should not happen.",
361 info_.name));
362 }
363 return interface_handle->set_value(value, wait_until_set);
364 }
365
367
375 template <typename T>
376 void set_state(const std::string & interface_name, const T & value)
377 {
378 std::ignore = set_state(get_state_interface_handle(interface_name), value, true);
379 }
380
391 template <typename T>
393 const StateInterface::SharedPtr & interface_handle, T & state, bool wait_until_get) const
394 {
395 if (!interface_handle)
396 {
397 throw std::runtime_error(
398 fmt::format(
399 "State interface handle is null in hardware component: {}, while calling get_state "
400 "method. This should not happen.",
401 info_.name));
402 }
403 const bool success = interface_handle->get_value(state, wait_until_get);
404 if (!success && wait_until_get)
405 {
406 throw std::runtime_error(
407 fmt::format(
408 "Failed to get state value from interface: {} in hardware component: {}. This should "
409 "not happen.",
410 interface_handle->get_name(), info_.name));
411 }
412 return success;
413 }
414
416
424 template <typename T = double>
425 T get_state(const std::string & interface_name) const
426 {
427 T state;
428 get_state<T>(get_state_interface_handle(interface_name), state, true);
429 return state;
430 }
431
433
437 virtual bool has_command(const std::string & interface_name) const;
438
440
446 virtual const CommandInterface::SharedPtr & get_command_interface_handle(
447 const std::string & interface_name) const;
448
450
459 template <typename T>
461 const CommandInterface::SharedPtr & interface_handle, const T & value, bool wait_until_set)
462 {
463 if (!interface_handle)
464 {
465 throw std::runtime_error(
466 fmt::format(
467 "Command interface handle is null in hardware component: {}, while calling set_command "
468 "method. This should not happen.",
469 info_.name));
470 }
471 return interface_handle->set_value(value, wait_until_set);
472 }
473
475
483 template <typename T>
484 void set_command(const std::string & interface_name, const T & value)
485 {
486 std::ignore = set_command(get_command_interface_handle(interface_name), value, true);
487 }
488
499 template <typename T>
501 const CommandInterface::SharedPtr & interface_handle, T & command, bool wait_until_get) const
502 {
503 if (!interface_handle)
504 {
505 throw std::runtime_error(
506 fmt::format(
507 "Command interface handle is null in hardware component: {}, while calling get_command "
508 "method. This should not happen.",
509 info_.name));
510 }
511 const bool success = interface_handle->get_value(command, wait_until_get);
512 if (!success && wait_until_get)
513 {
514 throw std::runtime_error(
515 fmt::format(
516 "Failed to get command value from interface: {} in hardware component: {}. This should "
517 "not happen.",
518 interface_handle->get_name(), info_.name));
519 }
520 return success;
521 }
522
524
532 template <typename T = double>
533 T get_command(const std::string & interface_name) const
534 {
535 T command;
536 get_command<T>(get_command_interface_handle(interface_name), command, true);
537 return command;
538 }
539
541
544 virtual rclcpp::Logger get_logger() const;
545
547
550 virtual rclcpp::Clock::SharedPtr get_clock() const;
551
553
556 virtual rclcpp::Node::SharedPtr get_node() const;
557
559
562 const HardwareInfo & get_hardware_info() const;
563
565
570
572
576
578
581 void enable_introspection(bool enable);
582
583protected:
584 HardwareInfo info_;
585 // interface names to InterfaceDescription
586 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
587 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
588
589 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
590
591 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
592 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
593
594 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
595 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
596
597 rclcpp_lifecycle::State lifecycle_state_;
598 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
599
600 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
601 std::vector<StateInterface::SharedPtr> joint_states_;
602 std::vector<CommandInterface::SharedPtr> joint_commands_;
603
604 std::vector<StateInterface::SharedPtr> sensor_states_;
605
606 std::vector<StateInterface::SharedPtr> gpio_states_;
607 std::vector<CommandInterface::SharedPtr> gpio_commands_;
608
609 std::vector<StateInterface::SharedPtr> unlisted_states_;
610 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
611
612private:
613 class HardwareComponentInterfaceImpl;
614 std::unique_ptr<HardwareComponentInterfaceImpl> impl_;
615
616protected:
617 pal_statistics::RegistrationsRAII stats_registrations_;
618};
619
620} // namespace hardware_interface
621#endif // HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
Virtual base class for all hardware components (Actuators, Sensors, and Systems).
Definition hardware_component_interface.hpp:65
const std::string & get_name() const
Get name of the hardware.
Definition hardware_component_interface.cpp:486
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.cpp:564
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.cpp:294
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:425
bool get_state(const StateInterface::SharedPtr &interface_handle, T &state, bool wait_until_get) const
Definition hardware_component_interface.hpp:392
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.cpp:490
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the hardware.
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)
Write the current command values to the hardware.
Definition hardware_component_interface.cpp:480
bool set_command(const CommandInterface::SharedPtr &interface_handle, const T &value, bool wait_until_set)
Set the value of a command interface.
Definition hardware_component_interface.hpp:460
virtual rclcpp::NodeOptions define_custom_node_options() const
Define custom node options for the hardware component interface.
Definition hardware_component_interface.cpp:275
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:376
HardwareComponentCycleStatus trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition hardware_component_interface.cpp:417
virtual return_type update_hardware_status_message(control_msgs::msg::HardwareStatus &msg)
User-overridable method to fill the hardware status message with real-time data.
Definition hardware_component_interface.cpp:243
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.cpp:362
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.cpp:495
virtual bool has_command(const std::string &interface_name) const
Does the command interface exist?
Definition hardware_component_interface.cpp:525
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.cpp:555
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.cpp:488
virtual CallbackReturn init_hardware_status_message(control_msgs::msg::HardwareStatus &msg_template)
User-overridable method to configure the structure of the HardwareStatus message.
Definition hardware_component_interface.cpp:236
HardwareComponentCycleStatus trigger_write(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
Definition hardware_component_interface.cpp:454
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.cpp:356
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.cpp:347
bool get_command(const CommandInterface::SharedPtr &interface_handle, T &command, bool wait_until_get) const
Definition hardware_component_interface.hpp:500
virtual const StateInterface::SharedPtr & get_state_interface_handle(const std::string &interface_name) const
Get the state interface handle.
Definition hardware_component_interface.cpp:511
HardwareComponentInterface(const HardwareComponentInterface &other)=delete
HardwareComponentInterface copy constructor is actively deleted.
uint8_t get_lifecycle_id() const
Get the lifecycle id of the hardware component interface.
Definition hardware_component_interface.cpp:501
bool set_state(const StateInterface::SharedPtr &interface_handle, const T &value, bool wait_until_set)
Set the value of a state interface.
Definition hardware_component_interface.hpp:352
void set_command(const std::string &interface_name, const T &value)
Set the value of a command interface.
Definition hardware_component_interface.hpp:484
virtual return_type prepare_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces)
Prepare for a new command interface switch.
Definition hardware_component_interface.cpp:403
virtual rclcpp::Node::SharedPtr get_node() const
Get the default node of the HardwareComponentInterface.
Definition hardware_component_interface.cpp:548
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.cpp:300
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.cpp:285
CallbackReturn init(const hardware_interface::HardwareComponentParams &params)
Definition hardware_component_interface.cpp:67
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition hardware_component_interface.cpp:572
virtual const CommandInterface::SharedPtr & get_command_interface_handle(const std::string &interface_name) const
Get the command interface handle.
Definition hardware_component_interface.cpp:530
virtual rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition hardware_component_interface.cpp:544
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:533
virtual rclcpp::Clock::SharedPtr get_clock() const
Get the clock.
Definition hardware_component_interface.cpp:546
virtual CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams &params)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition hardware_component_interface.cpp:250
const HardwareInfo & get_hardware_info() const
Get the hardware info of the HardwareComponentInterface.
Definition hardware_component_interface.cpp:553
virtual return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces)
Definition hardware_component_interface.cpp:410
virtual bool has_state(const std::string &interface_name) const
Does the state interface exist?
Definition hardware_component_interface.cpp:506
Definition actuator.hpp:22
Definition hardware_interface_return_values.hpp:41
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_interface_params.hpp:32
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_params.hpp:33
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:367
std::string name
Name of the hardware.
Definition hardware_info.hpp:369