Skip to content

Commit

Permalink
Remove default params that resulted in ambiguous declarations.
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <eknapp@amazon.com>
  • Loading branch information
Emerson Knapp committed Apr 9, 2019
1 parent 6f4e332 commit c718b56
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 15 deletions.
7 changes: 4 additions & 3 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,8 +171,9 @@ class Node : public std::enable_shared_from_this<Node>
[[deprecated]]
std::shared_ptr<PublisherT>
create_publisher(
const std::string & topic_name, size_t qos_history_depth,
std::shared_ptr<Alloc> allocator = nullptr,
const std::string & topic_name,
size_t qos_history_depth,
std::shared_ptr<Alloc> allocator,
IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault);

/// Create and return a Publisher.
Expand Down Expand Up @@ -284,7 +285,7 @@ class Node : public std::enable_shared_from_this<Node>
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<CallbackT>::type, Alloc>::SharedPtr
Expand Down
2 changes: 0 additions & 2 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,6 @@ Node::create_publisher(
topic_name, qos_history_depth, pub_options);
}


template<typename MessageT, typename Alloc, typename PublisherT>
std::shared_ptr<PublisherT>
Node::create_publisher(
Expand Down Expand Up @@ -217,7 +216,6 @@ Node::create_subscription(
topic_name, std::forward<CallbackT>(callback), qos_profile.depth, sub_options, msg_mem_strat);
}


template<
typename MessageT,
typename CallbackT,
Expand Down
33 changes: 23 additions & 10 deletions rclcpp/test/test_pub_sub_option_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand All @@ -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<test_msgs::msg::Empty>("topic", 5, pub_options);

rclcpp::SubscriptionOptions<> sub_options;
auto subscription = node->create_subscription<test_msgs::msg::Empty>(
"topic",

auto topic_only_pub = node->create_publisher<test_msgs::msg::Empty>(
"topic_only");
auto topic_depth_pub = node->create_publisher<test_msgs::msg::Empty>(
"topic_depth",
10);
auto all_options_pub = node->create_publisher<test_msgs::msg::Empty>(
"topic_options",
10,
pub_options);

auto topic_only_sub = node->create_subscription<test_msgs::msg::Empty>(
"topic_only",
[](std::shared_ptr<test_msgs::msg::Empty> test_msg) {(void) test_msg;});
auto topic_depth_sub = node->create_subscription<test_msgs::msg::Empty>(
"topic_depth",
[](std::shared_ptr<test_msgs::msg::Empty> test_msg) {(void) test_msg;},
10);
auto all_options_sub = node->create_subscription<test_msgs::msg::Empty>(
"topic_options",
[](std::shared_ptr<test_msgs::msg::Empty> test_msg) {(void) test_msg;},
5,
10,
sub_options);
}

0 comments on commit c718b56

Please sign in to comment.