From 9d45200a02ab75b5f6db0f0855de462fb43b818a Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 29 Feb 2024 10:29:14 +0100 Subject: [PATCH 1/2] added conditioning to have rolling tags compilable in older versions --- .../controller_interface_base.hpp | 6 ++++++ controller_manager/src/controller_manager.cpp | 13 +++++++++++++ 2 files changed, 19 insertions(+) diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index 6ce483d1ff..4c05dbdb00 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -172,7 +172,13 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy CONTROLLER_INTERFACE_PUBLIC virtual rclcpp::NodeOptions define_custom_node_options() const { +#if RCLCPP_VERSION_MAJOR >= 21 return rclcpp::NodeOptions().enable_logger_service(true); +#else + return rclcpp::NodeOptions() + .allow_undeclared_parameters(true) + .automatically_declare_parameters_from_overrides(true); +#endif } /// Declare and initialize a parameter with a type. diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 0a295d7859..6254f5f756 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -36,10 +36,23 @@ static constexpr const char * kChainableControllerInterfaceClassName = "controller_interface::ChainableControllerInterface"; // Changed services history QoS to keep all so we don't lose any client service calls +#if RCLCPP_VERSION_MAJOR >= 17 rclcpp::QoS qos_services = rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1)) .reliable() .durability_volatile(); +#else +static const rmw_qos_profile_t qos_services = { + RMW_QOS_POLICY_HISTORY_KEEP_ALL, + 1, // message queue depth + RMW_QOS_POLICY_RELIABILITY_RELIABLE, + RMW_QOS_POLICY_DURABILITY_VOLATILE, + RMW_QOS_DEADLINE_DEFAULT, + RMW_QOS_LIFESPAN_DEFAULT, + RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT, + RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT, + false}; +#endif inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller) { From 31a053119096993b632731d9ef499fb443a7eaa8 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 1 Mar 2024 10:59:11 +0100 Subject: [PATCH 2/2] add comments on source-compatibility with Humble --- .../include/controller_interface/controller_interface_base.hpp | 1 + controller_manager/src/controller_manager.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index 4c05dbdb00..2de57d3f83 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -172,6 +172,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy CONTROLLER_INTERFACE_PUBLIC virtual rclcpp::NodeOptions define_custom_node_options() const { +// \note The versions conditioning is added here to support the source-compatibility with Humble #if RCLCPP_VERSION_MAJOR >= 21 return rclcpp::NodeOptions().enable_logger_service(true); #else diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 6254f5f756..6b5077afe2 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -36,6 +36,7 @@ static constexpr const char * kChainableControllerInterfaceClassName = "controller_interface::ChainableControllerInterface"; // Changed services history QoS to keep all so we don't lose any client service calls +// \note The versions conditioning is added here to support the source-compatibility with Humble #if RCLCPP_VERSION_MAJOR >= 17 rclcpp::QoS qos_services = rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1))