From 07746c6834756f7795f315e64fdabd89636a9971 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 14 Oct 2015 16:10:49 -0700 Subject: [PATCH] Removed create_subscription_internal --- rclcpp/include/rclcpp/node.hpp | 60 ++++++++++++----------------- rclcpp/include/rclcpp/node_impl.hpp | 26 ++----------- 2 files changed, 28 insertions(+), 58 deletions(-) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 5c65b63..9c57c8c 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -114,31 +114,6 @@ public: create_publisher( const std::string & topic_name, const rmw_qos_profile_t & qos_profile); - /// Create and return a Subscription. - /** - * \param[in] topic_name The topic to subscribe on. - * \param[in] qos_history_depth The depth of the subscription's incoming message queue. - * \param[in] callback The user-defined callback function. - * \param[in] group The callback group for this subscription. NULL for no callback group. - * \param[in] ignore_local_publications True to ignore local publications. - * \param[in] msg_mem_strat The message memory strategy to use for allocating messages. - * \return Shared pointer to the created subscription. - */ - /* TODO(jacquelinekay): - Windows build breaks when static member function passed as default - argument to msg_mem_strat, nullptr is a workaround. - */ - template - typename rclcpp::subscription::Subscription::SharedPtr - create_subscription( - const std::string & topic_name, - size_t qos_history_depth, - CallbackT callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr, - bool ignore_local_publications = false, - typename rclcpp::message_memory_strategy::MessageMemoryStrategy::SharedPtr - msg_mem_strat = nullptr); - /// Create and return a Subscription. /** * \param[in] topic_name The topic to subscribe on. @@ -164,6 +139,31 @@ public: typename rclcpp::message_memory_strategy::MessageMemoryStrategy::SharedPtr msg_mem_strat = nullptr); + /// Create and return a Subscription. + /** + * \param[in] topic_name The topic to subscribe on. + * \param[in] qos_history_depth The depth of the subscription's incoming message queue. + * \param[in] callback The user-defined callback function. + * \param[in] group The callback group for this subscription. NULL for no callback group. + * \param[in] ignore_local_publications True to ignore local publications. + * \param[in] msg_mem_strat The message memory strategy to use for allocating messages. + * \return Shared pointer to the created subscription. + */ + /* TODO(jacquelinekay): + Windows build breaks when static member function passed as default + argument to msg_mem_strat, nullptr is a workaround. + */ + template + typename rclcpp::subscription::Subscription::SharedPtr + create_subscription( + const std::string & topic_name, + size_t qos_history_depth, + CallbackT callback, + rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr, + bool ignore_local_publications = false, + typename rclcpp::message_memory_strategy::MessageMemoryStrategy::SharedPtr + msg_mem_strat = nullptr); + /// Create a timer. /** * \param[in] period Time interval between triggers of the callback. @@ -262,16 +262,6 @@ private: publisher::Publisher::SharedPtr events_publisher_; - template - typename subscription::Subscription::SharedPtr - create_subscription_internal( - const std::string & topic_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::subscription::AnySubscriptionCallback callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications, - typename message_memory_strategy::MessageMemoryStrategy::SharedPtr msg_mem_strat); - template< typename ServiceT, typename FunctorT, diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 1c0a94a..5f92369 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -216,14 +216,12 @@ Node::create_subscription( typename rclcpp::message_memory_strategy::MessageMemoryStrategy::SharedPtr msg_mem_strat) { - rclcpp::subscription::AnySubscriptionCallback any_subscription_callback; - any_subscription_callback.set(callback); rmw_qos_profile_t qos = rmw_qos_profile_default; qos.depth = qos_history_depth; - return this->create_subscription_internal( + return this->create_subscription( topic_name, qos, - any_subscription_callback, + callback, group, ignore_local_publications, msg_mem_strat); @@ -242,25 +240,7 @@ Node::create_subscription( { rclcpp::subscription::AnySubscriptionCallback any_subscription_callback; any_subscription_callback.set(callback); - return this->create_subscription_internal( - topic_name, - qos_profile, - any_subscription_callback, - group, - ignore_local_publications, - msg_mem_strat); -} -template -typename subscription::Subscription::SharedPtr -Node::create_subscription_internal( - const std::string & topic_name, - const rmw_qos_profile_t & qos_profile, - rclcpp::subscription::AnySubscriptionCallback callback, - rclcpp::callback_group::CallbackGroup::SharedPtr group, - bool ignore_local_publications, - typename message_memory_strategy::MessageMemoryStrategy::SharedPtr msg_mem_strat) -{ using rosidl_generator_cpp::get_message_type_support_handle; if (!msg_mem_strat) { @@ -286,7 +266,7 @@ Node::create_subscription_internal( subscriber_handle, topic_name, ignore_local_publications, - callback, + any_subscription_callback, msg_mem_strat); auto sub_base_ptr = std::dynamic_pointer_cast(sub); // Setup intra process.