diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index df866a99c6..c5334466d1 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -248,6 +248,15 @@ if(BUILD_TESTING) ) target_link_libraries(test_publisher ${PROJECT_NAME}) endif() + ament_add_gtest(test_pub_sub_option_interface test/test_pub_sub_option_interface.cpp) + if(TARGET test_pub_sub_option_interface) + ament_target_dependencies(test_pub_sub_option_interface + test_msgs + ) + target_link_libraries(test_pub_sub_option_interface + ${PROJECT_NAME} + ) + endif() ament_add_gtest(test_publisher_subscription_count_api test/test_publisher_subscription_count_api.cpp) if(TARGET test_publisher_subscription_count_api) ament_target_dependencies(test_publisher_subscription_count_api diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 49cb322da4..11066eebdb 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -106,7 +106,7 @@ Node::create_publisher( const PublisherOptions & options, rclcpp::callback_group::CallbackGroup::SharedPtr group) { - std::shared_ptr allocator = options.allocator(); + std::shared_ptr allocator = options.allocator; if (!allocator) { allocator = std::make_shared(); } @@ -114,8 +114,8 @@ Node::create_publisher( return rclcpp::create_publisher( this->node_topics_.get(), extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()), - options.qos_profile(), - options.event_callbacks(), + options.qos_profile, + options.event_callbacks, group, this->get_node_options().use_intra_process_comms(), allocator); @@ -179,7 +179,7 @@ Node::create_subscription( { using CallbackMessageT = typename rclcpp::subscription_traits::has_message_type::type; - std::shared_ptr allocator = options.allocator(); + std::shared_ptr allocator = options.allocator; if (!allocator) { allocator = std::make_shared(); } @@ -193,10 +193,10 @@ Node::create_subscription( this->node_topics_.get(), extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()), std::forward(callback), - options.qos_profile(), - options.event_callbacks(), + options.qos_profile, + options.event_callbacks, group, - options.ignore_local_publications(), + options.ignore_local_publications, this->get_node_options().use_intra_process_comms(), msg_mem_strat, allocator); diff --git a/rclcpp/test/test_pub_sub_option_interface.cpp b/rclcpp/test/test_pub_sub_option_interface.cpp new file mode 100644 index 0000000000..b3030958ff --- /dev/null +++ b/rclcpp/test/test_pub_sub_option_interface.cpp @@ -0,0 +1,56 @@ +// Copyright 2019 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "test_msgs/msg/empty.hpp" + +class TestPublisher : public ::testing::Test +{ +protected: + static void SetUpTestCase() + { + rclcpp::init(0, nullptr); + } + + void SetUp() + { + node = std::make_shared("my_node", "/ns"); + } + + void TearDown() + { + node.reset(); + } + + rclcpp::Node::SharedPtr node; +}; + +/* + Testing construction and destruction. + */ +TEST_F(TestPublisher, construction_and_destruction) { + rclcpp::PublisherOptions<> pub_options; + auto publisher = node->create_publisher("topic", pub_options); + + rclcpp::SubscriptionOptions<> sub_options; + auto subscription = node->create_subscription( + "topic", + [](std::shared_ptr test_msg) {(void) test_msg;}, + sub_options); +}