From c718b56f64b79ea5efe630a7347d7cb5fe4fca03 Mon Sep 17 00:00:00 2001 From: Emerson Knapp Date: Tue, 9 Apr 2019 12:44:29 -0700 Subject: [PATCH] Remove default params that resulted in ambiguous declarations. Signed-off-by: Emerson Knapp --- rclcpp/include/rclcpp/node.hpp | 7 ++-- rclcpp/include/rclcpp/node_impl.hpp | 2 -- rclcpp/test/test_pub_sub_option_interface.cpp | 33 +++++++++++++------ 3 files changed, 27 insertions(+), 15 deletions(-) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 34e6fbf14d..81c112cc81 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -171,8 +171,9 @@ class Node : public std::enable_shared_from_this [[deprecated]] std::shared_ptr create_publisher( - const std::string & topic_name, size_t qos_history_depth, - std::shared_ptr allocator = nullptr, + const std::string & topic_name, + size_t qos_history_depth, + std::shared_ptr allocator, IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault); /// Create and return a Publisher. @@ -284,7 +285,7 @@ class Node : public std::enable_shared_from_this const std::string & topic_name, CallbackT && callback, size_t qos_history_depth, - rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr, + rclcpp::callback_group::CallbackGroup::SharedPtr group, bool ignore_local_publications = false, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< typename rclcpp::subscription_traits::has_message_type::type, Alloc>::SharedPtr diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 7ed8bea0ee..4cb576f3f4 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -115,7 +115,6 @@ Node::create_publisher( topic_name, qos_history_depth, pub_options); } - template std::shared_ptr Node::create_publisher( @@ -217,7 +216,6 @@ Node::create_subscription( topic_name, std::forward(callback), qos_profile.depth, sub_options, msg_mem_strat); } - template< typename MessageT, typename CallbackT, diff --git a/rclcpp/test/test_pub_sub_option_interface.cpp b/rclcpp/test/test_pub_sub_option_interface.cpp index 35d17f7c54..eb28284f98 100644 --- a/rclcpp/test/test_pub_sub_option_interface.cpp +++ b/rclcpp/test/test_pub_sub_option_interface.cpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" #include "test_msgs/msg/empty.hpp" -class TestPublisher : public ::testing::Test +class TestPubSubOptionAPI : public ::testing::Test { protected: static void SetUpTestCase() @@ -41,17 +41,30 @@ class TestPublisher : public ::testing::Test rclcpp::Node::SharedPtr node; }; -/* - Testing construction and destruction. - */ -TEST_F(TestPublisher, construction_and_destruction) { +TEST_F(TestPubSubOptionAPI, check_for_ambiguous) { rclcpp::PublisherOptions<> pub_options; - auto publisher = node->create_publisher("topic", 5, pub_options); - rclcpp::SubscriptionOptions<> sub_options; - auto subscription = node->create_subscription( - "topic", + + auto topic_only_pub = node->create_publisher( + "topic_only"); + auto topic_depth_pub = node->create_publisher( + "topic_depth", + 10); + auto all_options_pub = node->create_publisher( + "topic_options", + 10, + pub_options); + + auto topic_only_sub = node->create_subscription( + "topic_only", + [](std::shared_ptr test_msg) {(void) test_msg;}); + auto topic_depth_sub = node->create_subscription( + "topic_depth", + [](std::shared_ptr test_msg) {(void) test_msg;}, + 10); + auto all_options_sub = node->create_subscription( + "topic_options", [](std::shared_ptr test_msg) {(void) test_msg;}, - 5, + 10, sub_options); }