From d7cff5b067761cb2d050dfb7a3b0ea45e5952f99 Mon Sep 17 00:00:00 2001 From: Dominik Authaler Date: Tue, 13 Feb 2024 12:36:30 +0000 Subject: [PATCH] deprecation warnings for second template parameter Co-authored-by: Jonas Otto Signed-off-by: Dominik Authaler --- include/message_filters/subscriber.h | 45 ++++++++++++++++++++-------- 1 file changed, 32 insertions(+), 13 deletions(-) diff --git a/include/message_filters/subscriber.h b/include/message_filters/subscriber.h index 6cda5d0..ac4e633 100644 --- a/include/message_filters/subscriber.h +++ b/include/message_filters/subscriber.h @@ -62,11 +62,12 @@ class SubscriberBase using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces; - SubscriberBase() { - if constexpr (not std::is_same_v) { - // TODO: deprecation warning, similar to static_assert but only throwing a warning - } - } + template{}, int> = 0> + SubscriberBase() {} + + template{}, int> = 0> + [[deprecated("Template parameter of SubscriberBase class has been deprecated and will be removed in future releases")]] + SubscriberBase() {} virtual ~SubscriberBase() = default; @@ -175,6 +176,30 @@ class Subscriber using NodeParametersInterface = typename SubscriberBase::NodeParametersInterface; using NodeTopicsInterface = typename SubscriberBase::NodeTopicsInterface; + /** + * \brief Solely for highlighting deprecated template parameters with a compiler warning + */ + template{}, int> = 0> + [[deprecated("Second template parameter of Subscriber class is deprecated and will be removed in a future release")]] + Subscriber(RequiredInterfaces node_interfaces, + const std::string& topic, + const rmw_qos_profile_t qos, + rclcpp::SubscriptionOptions options) + { + subscribe(node_interfaces, topic, qos, options); + } + + /** + * \brief Solely for highlighting deprecated template parameters with a compiler warning + */ + template{}, int> = 0> + [[deprecated("Second template parameter of Subscriber class is deprecated and will be removed in a future release")]] + Subscriber(RequiredInterfaces node_interfaces, const std::string& topic, + const rmw_qos_profile_t qos = rmw_qos_profile_default) + { + subscribe(node_interfaces, topic, qos); + } + /** * \brief Constructor for rclcpp::Node / rclcpp_lifecycle::LifecycleNode. * @@ -182,13 +207,10 @@ class Subscriber * \param topic The topic to subscribe to. * \param qos (optional) The rmw qos profile to use to subscribe */ + template{}, int> = 0> Subscriber(RequiredInterfaces node_interfaces, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) { - if constexpr (not std::is_same_v) { - // TODO: deprecation warning, similar to static_assert but only throwing a warning - } - subscribe(node_interfaces, topic, qos); } @@ -222,15 +244,12 @@ class Subscriber * \param qos The rmw qos profile to use to subscribe. * \param options The subscription options to use to subscribe. */ + template{}, int> = 0> Subscriber(RequiredInterfaces node_interfaces, const std::string& topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options) { - if constexpr (not std::is_same_v) { - // TODO: deprecation warning, similar to static_assert but only throwing a warning - } - subscribe(node_interfaces, topic, qos, options); }