|
40 | 40 | #include "rclcpp/logging.hpp"
|
41 | 41 | #include "rclcpp/node_interfaces/node_clock_interface.hpp"
|
42 | 42 | #include "rclcpp/time.hpp"
|
| 43 | +#include "rclcpp/version.h" |
43 | 44 | #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
|
44 | 45 | #include "rclcpp_lifecycle/state.hpp"
|
45 | 46 | #include "realtime_tools/async_function_handler.hpp"
|
46 | 47 |
|
47 | 48 | namespace hardware_interface
|
48 | 49 | {
|
49 | 50 |
|
| 51 | +static inline rclcpp::NodeOptions get_hardware_component_node_options() |
| 52 | +{ |
| 53 | + rclcpp::NodeOptions node_options; |
| 54 | +// \note The versions conditioning is added here to support the source-compatibility with Humble |
| 55 | +#if RCLCPP_VERSION_MAJOR >= 21 |
| 56 | + node_options.enable_logger_service(true); |
| 57 | +#endif |
| 58 | + return node_options; |
| 59 | +} |
| 60 | + |
50 | 61 | using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
|
51 | 62 |
|
52 | 63 | /**
|
@@ -164,7 +175,8 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
|
164 | 175 | node_name.begin(), node_name.end(), node_name.begin(),
|
165 | 176 | [](unsigned char c) { return std::tolower(c); });
|
166 | 177 | std::replace(node_name.begin(), node_name.end(), '/', '_');
|
167 |
| - hardware_component_node_ = std::make_shared<rclcpp::Node>(node_name); |
| 178 | + hardware_component_node_ = |
| 179 | + std::make_shared<rclcpp::Node>(node_name, get_hardware_component_node_options()); |
168 | 180 | locked_executor->add_node(hardware_component_node_->get_node_base_interface());
|
169 | 181 | }
|
170 | 182 | else
|
|
0 commit comments