From 8a880ee6e467b45059d293751b44d8f1aecf9b7a Mon Sep 17 00:00:00 2001 From: Stephen Brawner Date: Wed, 24 Jun 2020 18:02:32 -0700 Subject: [PATCH 1/4] Unit tests for node interfaces Signed-off-by: Stephen Brawner --- rclcpp/test/CMakeLists.txt | 46 +++++ .../rclcpp/node_interfaces/test_node_base.cpp | 49 +++++ .../node_interfaces/test_node_clock.cpp | 37 ++++ .../node_interfaces/test_node_graph.cpp | 179 ++++++++++++++++++ .../node_interfaces/test_node_parameters.cpp | 84 ++++++++ .../node_interfaces/test_node_services.cpp | 92 +++++++++ .../node_interfaces/test_node_timers.cpp | 56 ++++++ .../node_interfaces/test_node_topics.cpp | 103 ++++++++++ .../node_interfaces/test_node_waitables.cpp | 56 ++++++ 9 files changed, 702 insertions(+) create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp create mode 100644 rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp diff --git a/rclcpp/test/CMakeLists.txt b/rclcpp/test/CMakeLists.txt index 46fe7c15d6..974b3c7c35 100644 --- a/rclcpp/test/CMakeLists.txt +++ b/rclcpp/test/CMakeLists.txt @@ -136,6 +136,52 @@ ament_add_gtest(test_node_interfaces__get_node_interfaces if(TARGET test_node_interfaces__get_node_interfaces) target_link_libraries(test_node_interfaces__get_node_interfaces ${PROJECT_NAME}) endif() +ament_add_gtest(test_node_interfaces__node_base + rclcpp/node_interfaces/test_node_base.cpp) +if(TARGET test_node_interfaces__node_base) + target_link_libraries(test_node_interfaces__node_base ${PROJECT_NAME}) +endif() +ament_add_gtest(test_node_interfaces__node_clock + rclcpp/node_interfaces/test_node_clock.cpp) +if(TARGET test_node_interfaces__node_clock) + target_link_libraries(test_node_interfaces__node_clock ${PROJECT_NAME}) +endif() +ament_add_gtest(test_node_interfaces__node_graph + rclcpp/node_interfaces/test_node_graph.cpp) +if(TARGET test_node_interfaces__node_graph) + ament_target_dependencies( + test_node_interfaces__node_graph + "test_msgs") + target_link_libraries(test_node_interfaces__node_graph ${PROJECT_NAME}) +endif() +ament_add_gtest(test_node_interfaces__node_parameters + rclcpp/node_interfaces/test_node_parameters.cpp) +if(TARGET test_node_interfaces__node_parameters) + target_link_libraries(test_node_interfaces__node_parameters ${PROJECT_NAME}) +endif() +ament_add_gtest(test_node_interfaces__node_services + rclcpp/node_interfaces/test_node_services.cpp) +if(TARGET test_node_interfaces__node_services) + target_link_libraries(test_node_interfaces__node_services ${PROJECT_NAME}) +endif() +ament_add_gtest(test_node_interfaces__node_timers + rclcpp/node_interfaces/test_node_timers.cpp) +if(TARGET test_node_interfaces__node_timers) + target_link_libraries(test_node_interfaces__node_timers ${PROJECT_NAME}) +endif() +ament_add_gtest(test_node_interfaces__node_topics + rclcpp/node_interfaces/test_node_topics.cpp) +if(TARGET test_node_interfaces__node_topics) + ament_target_dependencies( + test_node_interfaces__node_topics + "test_msgs") + target_link_libraries(test_node_interfaces__node_topics ${PROJECT_NAME}) +endif() +ament_add_gtest(test_node_interfaces__node_waitables + rclcpp/node_interfaces/test_node_waitables.cpp) +if(TARGET test_node_interfaces__node_waitables) + target_link_libraries(test_node_interfaces__node_waitables ${PROJECT_NAME}) +endif() # TODO(wjwwood): reenable these build failure tests when I can get Jenkins to ignore their output # rclcpp_add_build_failure_test(build_failure__get_node_topics_interface_const_ref_rclcpp_node diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp new file mode 100644 index 0000000000..8e16960b02 --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp @@ -0,0 +1,49 @@ +// Copyright 2020 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 "rcl/node_options.h" +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_base.hpp" +#include "rclcpp/rclcpp.hpp" + +TEST(TestNodeBase, construct_from_node) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + auto * node_base = + dynamic_cast(node->get_node_base_interface().get()); + ASSERT_NE(nullptr, node_base); + + EXPECT_STREQ("node", node_base->get_name()); + EXPECT_STREQ("/ns", node_base->get_namespace()); + + std::string expected_fully_qualified_name = "/ns/node"; + EXPECT_STREQ(expected_fully_qualified_name.c_str(), node_base->get_fully_qualified_name()); + EXPECT_NE(nullptr, node_base->get_context()); + EXPECT_NE(nullptr, node_base->get_rcl_node_handle()); + EXPECT_NE(nullptr, node_base->get_shared_rcl_node_handle()); + + const auto * const_node_base = node_base; + EXPECT_NE(nullptr, const_node_base->get_rcl_node_handle()); + EXPECT_NE(nullptr, const_node_base->get_shared_rcl_node_handle()); + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp new file mode 100644 index 0000000000..984611ea10 --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp @@ -0,0 +1,37 @@ +// Copyright 2020 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 "rclcpp/node_interfaces/node_clock.hpp" +#include "rclcpp/node.hpp" + +TEST(TestNodeClock, construct_from_node) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + auto * node_clock = + dynamic_cast(node->get_node_clock_interface().get()); + ASSERT_NE(nullptr, node_clock); + EXPECT_NE(nullptr, node_clock->get_clock()); + + const auto * const_node_clock = node_clock; + EXPECT_NE(nullptr, const_node_clock->get_clock()); + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp new file mode 100644 index 0000000000..682acf69a8 --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp @@ -0,0 +1,179 @@ +// Copyright 2020 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 "rcl/node_options.h" +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_base.hpp" +#include "rclcpp/node_interfaces/node_graph.hpp" +#include "rclcpp/rclcpp.hpp" +#include "test_msgs/msg/empty.hpp" + +TEST(TestNodeGraph, construct_from_node) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + const auto * node_graph = + dynamic_cast(node->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + + auto topic_names_and_types = node_graph->get_topic_names_and_types(false); + EXPECT_LT(0u, topic_names_and_types.size()); + + auto service_names_and_types = node_graph->get_service_names_and_types(); + EXPECT_LT(0u, service_names_and_types.size()); + + auto names = node_graph->get_node_names(); + EXPECT_EQ(1u, names.size()); + + auto names_and_namespaces = node_graph->get_node_names_and_namespaces(); + EXPECT_EQ(1u, names_and_namespaces.size()); + + EXPECT_EQ(0u, node_graph->count_publishers("not_a_topic")); + EXPECT_EQ(0u, node_graph->count_subscribers("not_a_topic")); + + rclcpp::shutdown(); +} + +TEST(TestNodeGraph, get_topic_names_and_types) +{ + rclcpp::init(0, nullptr); + auto node = std::make_shared("node2", "ns"); + const auto * node_graph = + dynamic_cast(node->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + auto topic_names_and_types = node_graph->get_topic_names_and_types(); + EXPECT_LT(0u, topic_names_and_types.size()); + rclcpp::shutdown(); +} + +TEST(TestNodeGraph, get_service_names_and_types) +{ + rclcpp::init(0, nullptr); + auto node = std::make_shared("node2", "ns"); + const auto * node_graph = + dynamic_cast(node->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + auto service_names_and_types = node_graph->get_service_names_and_types(); + EXPECT_LT(0u, service_names_and_types.size()); + rclcpp::shutdown(); +} + +TEST(TestNodeGraph, get_service_names_and_types_by_node) +{ + rclcpp::init(0, nullptr); + auto node1 = std::make_shared("node1", "ns"); + auto node2 = std::make_shared("node2", "ns"); + const auto * node_graph = + dynamic_cast(node1->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + + EXPECT_THROW( + node_graph->get_service_names_and_types_by_node("not_a_node", "not_absolute_namespace"), + std::runtime_error); + auto service_names_and_types1 = node_graph->get_service_names_and_types_by_node("node1", "/ns"); + auto service_names_and_types2 = node_graph->get_service_names_and_types_by_node("node2", "/ns"); + EXPECT_EQ(service_names_and_types1.size(), service_names_and_types2.size()); + rclcpp::shutdown(); +} + +TEST(TestNodeGraph, get_node_names_and_namespaces) +{ + rclcpp::init(0, nullptr); + auto node = std::make_shared("node", "ns"); + const auto * node_graph = + dynamic_cast(node->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + + auto names_and_namespaces = node_graph->get_node_names_and_namespaces(); + EXPECT_EQ(1u, names_and_namespaces.size()); + rclcpp::shutdown(); +} + +TEST(TestNodeGraph, notify_shutdown) +{ + rclcpp::init(0, nullptr); + auto node = std::make_shared("node", "ns"); + auto * node_graph = + dynamic_cast(node->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + + EXPECT_NO_THROW(node_graph->notify_shutdown()); + rclcpp::shutdown(); +} + +TEST(TestNodeGraph, wait_for_graph_change) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + auto * node_graph = + dynamic_cast(node->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + + EXPECT_NO_THROW(node_graph->notify_graph_change()); + EXPECT_THROW( + node_graph->wait_for_graph_change(nullptr, std::chrono::milliseconds(1)), + rclcpp::exceptions::InvalidEventError); + + auto event = std::make_shared(); + EXPECT_THROW( + node_graph->wait_for_graph_change(event, std::chrono::milliseconds(0)), + rclcpp::exceptions::EventNotRegisteredError); + rclcpp::shutdown(); +} + +TEST(TestNodeGraph, get_info_by_topic) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + auto publisher = node->create_publisher("topic", 1); + + auto callback = [](const test_msgs::msg::Empty::SharedPtr) {}; + auto subscription = + node->create_subscription( + "topic", rclcpp::QoS(10), std::move(callback)); + const auto * node_graph = + dynamic_cast(node->get_node_graph_interface().get()); + ASSERT_NE(nullptr, node_graph); + + auto publishers = node_graph->get_publishers_info_by_topic("topic", false); + auto publisher_endpoint_info = publishers[0]; + const auto const_publisher_endpoint_info = publisher_endpoint_info; + ASSERT_EQ(1u, publishers.size()); + EXPECT_STREQ("node", publisher_endpoint_info.node_name().c_str()); + EXPECT_STREQ("node", const_publisher_endpoint_info.node_name().c_str()); + EXPECT_STREQ("/ns", publisher_endpoint_info.node_namespace().c_str()); + EXPECT_STREQ("/ns", const_publisher_endpoint_info.node_namespace().c_str()); + EXPECT_STREQ("test_msgs/msg/Empty", publisher_endpoint_info.topic_type().c_str()); + EXPECT_STREQ("test_msgs/msg/Empty", const_publisher_endpoint_info.topic_type().c_str()); + EXPECT_EQ(rclcpp::EndpointType::Publisher, publisher_endpoint_info.endpoint_type()); + EXPECT_EQ(rclcpp::EndpointType::Publisher, const_publisher_endpoint_info.endpoint_type()); + + auto endpoint_gid = publisher_endpoint_info.endpoint_gid(); + auto const_endpoint_gid = const_publisher_endpoint_info.endpoint_gid(); + bool endpoint_gid_is_all_zeros = true; + for (size_t i = 0; i < RMW_GID_STORAGE_SIZE; ++i) { + endpoint_gid_is_all_zeros &= (endpoint_gid[i] == 0); + EXPECT_EQ(endpoint_gid[i], const_endpoint_gid[i]); + } + EXPECT_FALSE(endpoint_gid_is_all_zeros); + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp new file mode 100644 index 0000000000..20b22c3a11 --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp @@ -0,0 +1,84 @@ +// Copyright 2020 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. + +/** + * NodeParameters is a complicated interface with lots of code, but it is tested elsewhere + * very thoroughly. This currently just includes unittests for the currently uncovered + * functionality. + */ + +#include + +#include +#include +#include + +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_parameters.hpp" + +TEST(TestNodeParameters, list_parameters) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + auto * node_parameters = + dynamic_cast( + node->get_node_parameters_interface().get()); + ASSERT_NE(nullptr, node_parameters); + + std::vector prefixes; + const auto list_result = node_parameters->list_parameters(prefixes, 1u); + + // Currently the only default parameter is 'use_sim_time', but that may change. + EXPECT_GE(1u, list_result.names.size()); + size_t number_of_parameters = list_result.names.size(); + + const std::string parameter_name = "new_parameter"; + const rclcpp::ParameterValue value(true); + const rcl_interfaces::msg::ParameterDescriptor descriptor; + const auto added_parameter_value = + node_parameters->declare_parameter(parameter_name, value, descriptor, false); + EXPECT_EQ(value.get(), added_parameter_value.get()); + + auto list_result2 = node_parameters->list_parameters(prefixes, 1u); + EXPECT_EQ(number_of_parameters + 1u, list_result2.names.size()); + + bool parameter_added = false; + for (const auto & name : list_result2.names) { + if (name.compare(parameter_name) == 0) { + parameter_added = true; + break; + } + } + + EXPECT_TRUE(parameter_added); + rclcpp::shutdown(); +} + +TEST(TestNodeParameters, parameter_overrides) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + auto * node_parameters = + dynamic_cast( + node->get_node_parameters_interface().get()); + ASSERT_NE(nullptr, node_parameters); + + const auto & parameter_overrides = node_parameters->get_parameter_overrides(); + EXPECT_EQ(0u, parameter_overrides.size()); + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp new file mode 100644 index 0000000000..e62f8c3eef --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp @@ -0,0 +1,92 @@ +// Copyright 2020 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 "rcl/node_options.h" +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_services.hpp" +#include "rclcpp/rclcpp.hpp" + +class TestService : public rclcpp::ServiceBase +{ +public: + explicit TestService(rclcpp::Node * node) + : rclcpp::ServiceBase(node->get_node_base_interface()->get_shared_rcl_node_handle()) {} + + std::shared_ptr create_request() override {return nullptr;} + std::shared_ptr create_request_header() override {return nullptr;} + void handle_request(std::shared_ptr, std::shared_ptr) override {} +}; + +class TestClient : public rclcpp::ClientBase +{ +public: + explicit TestClient(rclcpp::Node * node) + : rclcpp::ClientBase(node->get_node_base_interface().get(), node->get_node_graph_interface()) {} + + std::shared_ptr create_response() override {return nullptr;} + std::shared_ptr create_request_header() override {return nullptr;} + void handle_response( + std::shared_ptr, std::shared_ptr) override {} +}; + +TEST(TestNodeService, add_service) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + auto * node_services = + dynamic_cast( + node->get_node_services_interface().get()); + ASSERT_NE(nullptr, node_services); + + std::shared_ptr node2 = std::make_shared("node2", "ns"); + + auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto service = std::make_shared(node.get()); + EXPECT_THROW( + node_services->add_service(service, callback_group), + std::runtime_error); + + rclcpp::shutdown(); +} + +TEST(TestNodeService, add_client) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + auto * node_services = + dynamic_cast( + node->get_node_services_interface().get()); + ASSERT_NE(nullptr, node_services); + + std::shared_ptr node2 = std::make_shared("node2", "ns"); + + auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto client = std::make_shared(node.get()); + EXPECT_THROW( + node_services->add_client(client, callback_group), + std::runtime_error); + + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp new file mode 100644 index 0000000000..b9a0bfc5b3 --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp @@ -0,0 +1,56 @@ +// Copyright 2020 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 "rcl/node_options.h" +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_timers.hpp" +#include "rclcpp/rclcpp.hpp" + +class TestTimer : public rclcpp::TimerBase +{ +public: + explicit TestTimer(rclcpp::Node * node) + : TimerBase(node->get_clock(), std::chrono::nanoseconds(1), + node->get_node_base_interface()->get_context()) {} + + void execute_callback() override {} + bool is_steady() override {return false;} +}; + +TEST(TestNodeTimers, add_timer) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + auto node_timers = + dynamic_cast(node->get_node_timers_interface().get()); + ASSERT_NE(nullptr, node_timers); + + std::shared_ptr node2 = std::make_shared("node2", "ns"); + + auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto service = std::make_shared(node.get()); + EXPECT_THROW( + node_timers->add_timer(service, callback_group), + std::runtime_error); + + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp new file mode 100644 index 0000000000..dfac53e1e6 --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp @@ -0,0 +1,103 @@ +// Copyright 2020 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 "rcl/node_options.h" +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_topics.hpp" +#include "rclcpp/rclcpp.hpp" +#include "test_msgs/msg/empty.hpp" + +static const rosidl_message_type_support_t empty_type_support = + *rosidl_typesupport_cpp::get_message_type_support_handle(); + +static const rcl_publisher_options_t publisher_options = + rclcpp::PublisherOptionsWithAllocator>().template + to_rcl_publisher_options(rclcpp::QoS(10)); + +static const rcl_subscription_options_t subscription_options = + rclcpp::SubscriptionOptionsWithAllocator>().template + to_rcl_subscription_options(rclcpp::QoS(10)); + + +class TestPublisher : public rclcpp::PublisherBase +{ +public: + explicit TestPublisher(rclcpp::Node * node) + : rclcpp::PublisherBase( + node->get_node_base_interface().get(), "topic", empty_type_support, publisher_options) {} +}; + +class TestSubscription : public rclcpp::SubscriptionBase +{ +public: + explicit TestSubscription(rclcpp::Node * node) + : rclcpp::SubscriptionBase( + node->get_node_base_interface().get(), empty_type_support, "topic", subscription_options) {} + std::shared_ptr create_message() override {return nullptr;} + + std::shared_ptr + create_serialized_message() override {return nullptr;} + + void handle_message(std::shared_ptr &, const rclcpp::MessageInfo &) override {} + void handle_loaned_message(void *, const rclcpp::MessageInfo &) override {} + void return_message(std::shared_ptr &) override {} + void return_serialized_message(std::shared_ptr &) override {} +}; + + +TEST(TestNodeTopics, add_publisher) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov + // reports these functions uncovered otherwise. + auto * node_topics = + dynamic_cast(node->get_node_topics_interface().get()); + ASSERT_NE(nullptr, node_topics); + + std::shared_ptr node2 = std::make_shared("node2", "ns"); + + auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto publisher = std::make_shared(node.get()); + EXPECT_THROW( + node_topics->add_publisher(publisher, callback_group), + std::runtime_error); + + rclcpp::shutdown(); +} + +TEST(TestNodeTopics, add_subscription) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + auto * node_topics = + dynamic_cast(node->get_node_topics_interface().get()); + ASSERT_NE(nullptr, node_topics); + + std::shared_ptr node2 = std::make_shared("node2", "ns"); + + auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto subscription = std::make_shared(node.get()); + EXPECT_THROW( + node_topics->add_subscription(subscription, callback_group), + std::runtime_error); + + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp new file mode 100644 index 0000000000..b90e74833f --- /dev/null +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp @@ -0,0 +1,56 @@ +// Copyright 2020 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 "rcl/node_options.h" +#include "rclcpp/node.hpp" +#include "rclcpp/node_interfaces/node_waitables.hpp" +#include "rclcpp/rclcpp.hpp" + +class TestWaitable : public rclcpp::Waitable +{ +public: + bool add_to_wait_set(rcl_wait_set_t *) override {return false;} + bool is_ready(rcl_wait_set_t *) override {return false;} + void execute() override {} +}; + +TEST(TestNodeWaitables, add_remove_waitable) +{ + rclcpp::init(0, nullptr); + std::shared_ptr node = std::make_shared("node", "ns"); + + auto * node_waitables = + dynamic_cast( + node->get_node_waitables_interface().get()); + ASSERT_NE(nullptr, node_waitables); + + std::shared_ptr node2 = std::make_shared("node2", "ns"); + + auto callback_group1 = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto callback_group2 = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto waitable = std::make_shared(); + EXPECT_NO_THROW( + node_waitables->add_waitable(waitable, callback_group1)); + EXPECT_THROW( + node_waitables->add_waitable(waitable, callback_group2), + std::runtime_error); + EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group1)); + EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group2)); + rclcpp::shutdown(); +} From a4b1d5ca379278cd47216cebe5f131829c6c2703 Mon Sep 17 00:00:00 2001 From: Stephen Brawner Date: Tue, 30 Jun 2020 14:48:09 -0700 Subject: [PATCH 2/4] Address PR Feedback Signed-off-by: Stephen Brawner --- .../rclcpp/node_interfaces/test_node_base.cpp | 21 +++-- .../node_interfaces/test_node_clock.cpp | 18 ++++- .../node_interfaces/test_node_graph.cpp | 65 +++++++++------- .../node_interfaces/test_node_parameters.cpp | 39 ++++++---- .../node_interfaces/test_node_services.cpp | 51 ++++++++---- .../node_interfaces/test_node_timers.cpp | 31 ++++++-- .../node_interfaces/test_node_topics.cpp | 78 ++++++++++++------- .../node_interfaces/test_node_waitables.cpp | 18 ++++- 8 files changed, 215 insertions(+), 106 deletions(-) diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp index 8e16960b02..8cae2f55e2 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp @@ -22,9 +22,22 @@ #include "rclcpp/node_interfaces/node_base.hpp" #include "rclcpp/rclcpp.hpp" -TEST(TestNodeBase, construct_from_node) +class TestNodeBase : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestNodeBase, construct_from_node) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -36,8 +49,7 @@ TEST(TestNodeBase, construct_from_node) EXPECT_STREQ("node", node_base->get_name()); EXPECT_STREQ("/ns", node_base->get_namespace()); - std::string expected_fully_qualified_name = "/ns/node"; - EXPECT_STREQ(expected_fully_qualified_name.c_str(), node_base->get_fully_qualified_name()); + EXPECT_STREQ("/ns/node", node_base->get_fully_qualified_name()); EXPECT_NE(nullptr, node_base->get_context()); EXPECT_NE(nullptr, node_base->get_rcl_node_handle()); EXPECT_NE(nullptr, node_base->get_shared_rcl_node_handle()); @@ -45,5 +57,4 @@ TEST(TestNodeBase, construct_from_node) const auto * const_node_base = node_base; EXPECT_NE(nullptr, const_node_base->get_rcl_node_handle()); EXPECT_NE(nullptr, const_node_base->get_shared_rcl_node_handle()); - rclcpp::shutdown(); } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp index 984611ea10..ffb83af0f9 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp @@ -19,9 +19,22 @@ #include "rclcpp/node_interfaces/node_clock.hpp" #include "rclcpp/node.hpp" -TEST(TestNodeClock, construct_from_node) +class TestNodeClock : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestNodeClock, construct_from_node) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -33,5 +46,4 @@ TEST(TestNodeClock, construct_from_node) const auto * const_node_clock = node_clock; EXPECT_NE(nullptr, const_node_clock->get_clock()); - rclcpp::shutdown(); } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp index 682acf69a8..315a44e578 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp @@ -24,9 +24,22 @@ #include "rclcpp/rclcpp.hpp" #include "test_msgs/msg/empty.hpp" -TEST(TestNodeGraph, construct_from_node) +class TestNodeGraph : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestNodeGraph, construct_from_node) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -49,37 +62,30 @@ TEST(TestNodeGraph, construct_from_node) EXPECT_EQ(0u, node_graph->count_publishers("not_a_topic")); EXPECT_EQ(0u, node_graph->count_subscribers("not_a_topic")); - - rclcpp::shutdown(); } -TEST(TestNodeGraph, get_topic_names_and_types) +TEST_F(TestNodeGraph, get_topic_names_and_types) { - rclcpp::init(0, nullptr); auto node = std::make_shared("node2", "ns"); const auto * node_graph = dynamic_cast(node->get_node_graph_interface().get()); ASSERT_NE(nullptr, node_graph); auto topic_names_and_types = node_graph->get_topic_names_and_types(); EXPECT_LT(0u, topic_names_and_types.size()); - rclcpp::shutdown(); } -TEST(TestNodeGraph, get_service_names_and_types) +TEST_F(TestNodeGraph, get_service_names_and_types) { - rclcpp::init(0, nullptr); auto node = std::make_shared("node2", "ns"); const auto * node_graph = dynamic_cast(node->get_node_graph_interface().get()); ASSERT_NE(nullptr, node_graph); auto service_names_and_types = node_graph->get_service_names_and_types(); EXPECT_LT(0u, service_names_and_types.size()); - rclcpp::shutdown(); } -TEST(TestNodeGraph, get_service_names_and_types_by_node) +TEST_F(TestNodeGraph, get_service_names_and_types_by_node) { - rclcpp::init(0, nullptr); auto node1 = std::make_shared("node1", "ns"); auto node2 = std::make_shared("node2", "ns"); const auto * node_graph = @@ -92,12 +98,10 @@ TEST(TestNodeGraph, get_service_names_and_types_by_node) auto service_names_and_types1 = node_graph->get_service_names_and_types_by_node("node1", "/ns"); auto service_names_and_types2 = node_graph->get_service_names_and_types_by_node("node2", "/ns"); EXPECT_EQ(service_names_and_types1.size(), service_names_and_types2.size()); - rclcpp::shutdown(); } -TEST(TestNodeGraph, get_node_names_and_namespaces) +TEST_F(TestNodeGraph, get_node_names_and_namespaces) { - rclcpp::init(0, nullptr); auto node = std::make_shared("node", "ns"); const auto * node_graph = dynamic_cast(node->get_node_graph_interface().get()); @@ -105,24 +109,20 @@ TEST(TestNodeGraph, get_node_names_and_namespaces) auto names_and_namespaces = node_graph->get_node_names_and_namespaces(); EXPECT_EQ(1u, names_and_namespaces.size()); - rclcpp::shutdown(); } -TEST(TestNodeGraph, notify_shutdown) +TEST_F(TestNodeGraph, notify_shutdown) { - rclcpp::init(0, nullptr); auto node = std::make_shared("node", "ns"); auto * node_graph = dynamic_cast(node->get_node_graph_interface().get()); ASSERT_NE(nullptr, node_graph); EXPECT_NO_THROW(node_graph->notify_shutdown()); - rclcpp::shutdown(); } -TEST(TestNodeGraph, wait_for_graph_change) +TEST_F(TestNodeGraph, wait_for_graph_change) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); auto * node_graph = dynamic_cast(node->get_node_graph_interface().get()); @@ -137,27 +137,29 @@ TEST(TestNodeGraph, wait_for_graph_change) EXPECT_THROW( node_graph->wait_for_graph_change(event, std::chrono::milliseconds(0)), rclcpp::exceptions::EventNotRegisteredError); - rclcpp::shutdown(); } -TEST(TestNodeGraph, get_info_by_topic) +TEST_F(TestNodeGraph, get_info_by_topic) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); - auto publisher = node->create_publisher("topic", 1); - + rclcpp::QoS publisher_qos(1); + auto publisher = node->create_publisher("topic", publisher_qos); auto callback = [](const test_msgs::msg::Empty::SharedPtr) {}; + + rclcpp::QoS subscriber_qos(10); auto subscription = node->create_subscription( - "topic", rclcpp::QoS(10), std::move(callback)); + "topic", subscriber_qos, std::move(callback)); + const auto * node_graph = dynamic_cast(node->get_node_graph_interface().get()); ASSERT_NE(nullptr, node_graph); auto publishers = node_graph->get_publishers_info_by_topic("topic", false); + ASSERT_EQ(1u, publishers.size()); + auto publisher_endpoint_info = publishers[0]; const auto const_publisher_endpoint_info = publisher_endpoint_info; - ASSERT_EQ(1u, publishers.size()); EXPECT_STREQ("node", publisher_endpoint_info.node_name().c_str()); EXPECT_STREQ("node", const_publisher_endpoint_info.node_name().c_str()); EXPECT_STREQ("/ns", publisher_endpoint_info.node_namespace().c_str()); @@ -167,6 +169,12 @@ TEST(TestNodeGraph, get_info_by_topic) EXPECT_EQ(rclcpp::EndpointType::Publisher, publisher_endpoint_info.endpoint_type()); EXPECT_EQ(rclcpp::EndpointType::Publisher, const_publisher_endpoint_info.endpoint_type()); + rclcpp::QoS actual_qos = publisher_endpoint_info.qos_profile(); + EXPECT_EQ(0u, actual_qos.get_rmw_qos_profile().depth); + + rclcpp::QoS const_actual_qos = const_publisher_endpoint_info.qos_profile(); + EXPECT_EQ(0u, const_actual_qos.get_rmw_qos_profile().depth); + auto endpoint_gid = publisher_endpoint_info.endpoint_gid(); auto const_endpoint_gid = const_publisher_endpoint_info.endpoint_gid(); bool endpoint_gid_is_all_zeros = true; @@ -175,5 +183,4 @@ TEST(TestNodeGraph, get_info_by_topic) EXPECT_EQ(endpoint_gid[i], const_endpoint_gid[i]); } EXPECT_FALSE(endpoint_gid_is_all_zeros); - rclcpp::shutdown(); } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp index 20b22c3a11..c90a4688d1 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp @@ -20,6 +20,7 @@ #include +#include #include #include #include @@ -27,9 +28,22 @@ #include "rclcpp/node.hpp" #include "rclcpp/node_interfaces/node_parameters.hpp" -TEST(TestNodeParameters, list_parameters) +class TestNodeParameters : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestNodeParameters, list_parameters) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -43,8 +57,8 @@ TEST(TestNodeParameters, list_parameters) const auto list_result = node_parameters->list_parameters(prefixes, 1u); // Currently the only default parameter is 'use_sim_time', but that may change. - EXPECT_GE(1u, list_result.names.size()); size_t number_of_parameters = list_result.names.size(); + EXPECT_GE(1u, number_of_parameters); const std::string parameter_name = "new_parameter"; const rclcpp::ParameterValue value(true); @@ -56,21 +70,15 @@ TEST(TestNodeParameters, list_parameters) auto list_result2 = node_parameters->list_parameters(prefixes, 1u); EXPECT_EQ(number_of_parameters + 1u, list_result2.names.size()); - bool parameter_added = false; - for (const auto & name : list_result2.names) { - if (name.compare(parameter_name) == 0) { - parameter_added = true; - break; - } - } - - EXPECT_TRUE(parameter_added); - rclcpp::shutdown(); + EXPECT_NE( + std::find_if( + list_result2.names.begin(), list_result2.names.end(), + [parameter_name](const std::string & s) {return parameter_name.compare(s) == 0;}), + list_result2.names.end()); } -TEST(TestNodeParameters, parameter_overrides) +TEST_F(TestNodeParameters, parameter_overrides) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); auto * node_parameters = @@ -80,5 +88,4 @@ TEST(TestNodeParameters, parameter_overrides) const auto & parameter_overrides = node_parameters->get_parameter_overrides(); EXPECT_EQ(0u, parameter_overrides.size()); - rclcpp::shutdown(); } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp index e62f8c3eef..3fa8c8984c 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp @@ -45,9 +45,22 @@ class TestClient : public rclcpp::ClientBase std::shared_ptr, std::shared_ptr) override {} }; -TEST(TestNodeService, add_service) +class TestNodeService : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestNodeService, add_service) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -57,20 +70,23 @@ TEST(TestNodeService, add_service) node->get_node_services_interface().get()); ASSERT_NE(nullptr, node_services); - std::shared_ptr node2 = std::make_shared("node2", "ns"); - - auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto service = std::make_shared(node.get()); + auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + EXPECT_NO_THROW( + node_services->add_service(service, callback_group)); + + // Check that adding a service from node to a callback group of different_node throws exception. + std::shared_ptr different_node = std::make_shared("node2", "ns"); + + auto callback_group_in_different_node = + different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); EXPECT_THROW( - node_services->add_service(service, callback_group), + node_services->add_service(service, callback_group_in_different_node), std::runtime_error); - - rclcpp::shutdown(); } -TEST(TestNodeService, add_client) +TEST_F(TestNodeService, add_client) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -80,13 +96,16 @@ TEST(TestNodeService, add_client) node->get_node_services_interface().get()); ASSERT_NE(nullptr, node_services); - std::shared_ptr node2 = std::make_shared("node2", "ns"); - - auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto client = std::make_shared(node.get()); + auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + EXPECT_NO_THROW(node_services->add_client(client, callback_group)); + + // Check that adding a client from node to a callback group of different_node throws exception. + std::shared_ptr different_node = std::make_shared("node2", "ns"); + + auto callback_group_in_different_node = + different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); EXPECT_THROW( - node_services->add_client(client, callback_group), + node_services->add_client(client, callback_group_in_different_node), std::runtime_error); - - rclcpp::shutdown(); } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp index b9a0bfc5b3..102283609c 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp @@ -33,9 +33,22 @@ class TestTimer : public rclcpp::TimerBase bool is_steady() override {return false;} }; -TEST(TestNodeTimers, add_timer) +class TestNodeTimers : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestNodeTimers, add_timer) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -43,14 +56,16 @@ TEST(TestNodeTimers, add_timer) auto node_timers = dynamic_cast(node->get_node_timers_interface().get()); ASSERT_NE(nullptr, node_timers); + auto timer = std::make_shared(node.get()); + auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + EXPECT_NO_THROW(node_timers->add_timer(timer, callback_group)); - std::shared_ptr node2 = std::make_shared("node2", "ns"); + // Check that adding timer from node to callback group in different_node throws exception. + std::shared_ptr different_node = std::make_shared("node2", "ns"); - auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - auto service = std::make_shared(node.get()); + auto callback_group_in_different_node = + different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); EXPECT_THROW( - node_timers->add_timer(service, callback_group), + node_timers->add_timer(timer, callback_group_in_different_node), std::runtime_error); - - rclcpp::shutdown(); } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp index dfac53e1e6..706bee8825 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp @@ -16,6 +16,7 @@ #include #include +#include #include "rcl/node_options.h" #include "rclcpp/node.hpp" @@ -23,24 +24,34 @@ #include "rclcpp/rclcpp.hpp" #include "test_msgs/msg/empty.hpp" -static const rosidl_message_type_support_t empty_type_support = - *rosidl_typesupport_cpp::get_message_type_support_handle(); +namespace +{ -static const rcl_publisher_options_t publisher_options = - rclcpp::PublisherOptionsWithAllocator>().template - to_rcl_publisher_options(rclcpp::QoS(10)); +const rosidl_message_type_support_t EmptyTypeSupport() +{ + return *rosidl_typesupport_cpp::get_message_type_support_handle(); +} -static const rcl_subscription_options_t subscription_options = - rclcpp::SubscriptionOptionsWithAllocator>().template - to_rcl_subscription_options(rclcpp::QoS(10)); +const rcl_publisher_options_t PublisherOptions() +{ + return rclcpp::PublisherOptionsWithAllocator>().template + to_rcl_publisher_options(rclcpp::QoS(10)); +} +const rcl_subscription_options_t SubscriptionOptions() +{ + return rclcpp::SubscriptionOptionsWithAllocator>().template + to_rcl_subscription_options(rclcpp::QoS(10)); +} + +} // namespace class TestPublisher : public rclcpp::PublisherBase { public: explicit TestPublisher(rclcpp::Node * node) : rclcpp::PublisherBase( - node->get_node_base_interface().get(), "topic", empty_type_support, publisher_options) {} + node->get_node_base_interface().get(), "topic", EmptyTypeSupport(), PublisherOptions()) {} }; class TestSubscription : public rclcpp::SubscriptionBase @@ -48,7 +59,7 @@ class TestSubscription : public rclcpp::SubscriptionBase public: explicit TestSubscription(rclcpp::Node * node) : rclcpp::SubscriptionBase( - node->get_node_base_interface().get(), empty_type_support, "topic", subscription_options) {} + node->get_node_base_interface().get(), EmptyTypeSupport(), "topic", SubscriptionOptions()) {} std::shared_ptr create_message() override {return nullptr;} std::shared_ptr @@ -60,10 +71,22 @@ class TestSubscription : public rclcpp::SubscriptionBase void return_serialized_message(std::shared_ptr &) override {} }; +class TestNodeTopics : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; -TEST(TestNodeTopics, add_publisher) +TEST_F(TestNodeTopics, add_publisher) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov @@ -71,33 +94,36 @@ TEST(TestNodeTopics, add_publisher) auto * node_topics = dynamic_cast(node->get_node_topics_interface().get()); ASSERT_NE(nullptr, node_topics); + auto publisher = std::make_shared(node.get()); + auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + EXPECT_NO_THROW(node_topics->add_publisher(publisher, callback_group)); - std::shared_ptr node2 = std::make_shared("node2", "ns"); + // Check that adding publisher from node to a callback group in different_node throws exception. + std::shared_ptr different_node = std::make_shared("node2", "ns"); - auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - auto publisher = std::make_shared(node.get()); + auto callback_group_in_different_node = + different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); EXPECT_THROW( - node_topics->add_publisher(publisher, callback_group), + node_topics->add_publisher(publisher, callback_group_in_different_node), std::runtime_error); - - rclcpp::shutdown(); } -TEST(TestNodeTopics, add_subscription) +TEST_F(TestNodeTopics, add_subscription) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); auto * node_topics = dynamic_cast(node->get_node_topics_interface().get()); ASSERT_NE(nullptr, node_topics); + auto subscription = std::make_shared(node.get()); + auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + EXPECT_NO_THROW(node_topics->add_subscription(subscription, callback_group)); - std::shared_ptr node2 = std::make_shared("node2", "ns"); + // Check that adding subscription from node to callback group in different_node throws exception. + std::shared_ptr different_node = std::make_shared("node2", "ns"); - auto callback_group = node2->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - auto subscription = std::make_shared(node.get()); + auto callback_group_in_different_node = + different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); EXPECT_THROW( - node_topics->add_subscription(subscription, callback_group), + node_topics->add_subscription(subscription, callback_group_in_different_node), std::runtime_error); - - rclcpp::shutdown(); } diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp index b90e74833f..19cc63fe07 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp @@ -30,9 +30,22 @@ class TestWaitable : public rclcpp::Waitable void execute() override {} }; -TEST(TestNodeWaitables, add_remove_waitable) +class TestNodeWaitables : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + +TEST_F(TestNodeWaitables, add_remove_waitable) { - rclcpp::init(0, nullptr); std::shared_ptr node = std::make_shared("node", "ns"); auto * node_waitables = @@ -52,5 +65,4 @@ TEST(TestNodeWaitables, add_remove_waitable) std::runtime_error); EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group1)); EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group2)); - rclcpp::shutdown(); } From 5bbdfc9c10493c7511065ecaf1258fbcd79bf0b5 Mon Sep 17 00:00:00 2001 From: Stephen Brawner Date: Wed, 1 Jul 2020 10:33:56 -0700 Subject: [PATCH 3/4] Address PR feedback Signed-off-by: Stephen Brawner --- rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp | 4 ++-- rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp | 4 +--- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp index 315a44e578..2d9d6c40aa 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp @@ -142,11 +142,11 @@ TEST_F(TestNodeGraph, wait_for_graph_change) TEST_F(TestNodeGraph, get_info_by_topic) { std::shared_ptr node = std::make_shared("node", "ns"); - rclcpp::QoS publisher_qos(1); + const rclcpp::QoS publisher_qos(1); auto publisher = node->create_publisher("topic", publisher_qos); auto callback = [](const test_msgs::msg::Empty::SharedPtr) {}; - rclcpp::QoS subscriber_qos(10); + const rclcpp::QoS subscriber_qos(10); auto subscription = node->create_subscription( "topic", subscriber_qos, std::move(callback)); diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp index c90a4688d1..33f3764ded 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp @@ -71,9 +71,7 @@ TEST_F(TestNodeParameters, list_parameters) EXPECT_EQ(number_of_parameters + 1u, list_result2.names.size()); EXPECT_NE( - std::find_if( - list_result2.names.begin(), list_result2.names.end(), - [parameter_name](const std::string & s) {return parameter_name.compare(s) == 0;}), + std::find(list_result2.names.begin(), list_result2.names.end(), parameter_name), list_result2.names.end()); } From caef3e931adb47c6ef3b4704621ea3e727748d31 Mon Sep 17 00:00:00 2001 From: Stephen Brawner Date: Wed, 1 Jul 2020 12:35:08 -0700 Subject: [PATCH 4/4] Adjusting comment Signed-off-by: Stephen Brawner --- rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp | 4 ++-- rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp | 4 ++-- rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp | 4 ++-- .../test/rclcpp/node_interfaces/test_node_parameters.cpp | 4 ++-- rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp | 8 ++++---- rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp | 4 ++-- rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp | 4 ++-- 7 files changed, 16 insertions(+), 16 deletions(-) diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp index 8cae2f55e2..cfe42d7819 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp @@ -40,8 +40,8 @@ TEST_F(TestNodeBase, construct_from_node) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. auto * node_base = dynamic_cast(node->get_node_base_interface().get()); ASSERT_NE(nullptr, node_base); diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp index ffb83af0f9..dec171b655 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp @@ -37,8 +37,8 @@ TEST_F(TestNodeClock, construct_from_node) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. auto * node_clock = dynamic_cast(node->get_node_clock_interface().get()); ASSERT_NE(nullptr, node_clock); diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp index 2d9d6c40aa..db69207f3b 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp @@ -42,8 +42,8 @@ TEST_F(TestNodeGraph, construct_from_node) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. const auto * node_graph = dynamic_cast(node->get_node_graph_interface().get()); ASSERT_NE(nullptr, node_graph); diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp index 33f3764ded..68a7546c83 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp @@ -46,8 +46,8 @@ TEST_F(TestNodeParameters, list_parameters) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. auto * node_parameters = dynamic_cast( node->get_node_parameters_interface().get()); diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp index 3fa8c8984c..893340d33a 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp @@ -63,8 +63,8 @@ TEST_F(TestNodeService, add_service) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. auto * node_services = dynamic_cast( node->get_node_services_interface().get()); @@ -89,8 +89,8 @@ TEST_F(TestNodeService, add_client) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. auto * node_services = dynamic_cast( node->get_node_services_interface().get()); diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp index 102283609c..af340d292e 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp @@ -51,8 +51,8 @@ TEST_F(TestNodeTimers, add_timer) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. auto node_timers = dynamic_cast(node->get_node_timers_interface().get()); ASSERT_NE(nullptr, node_timers); diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp index 706bee8825..86b4e72e36 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp @@ -89,8 +89,8 @@ TEST_F(TestNodeTopics, add_publisher) { std::shared_ptr node = std::make_shared("node", "ns"); - // This dynamic cast is not necessary for the unittest itself, but the coverage utility lcov - // reports these functions uncovered otherwise. + // This dynamic cast is not necessary for the unittest itself, but instead is used to ensure + // the proper type is being tested and covered. auto * node_topics = dynamic_cast(node->get_node_topics_interface().get()); ASSERT_NE(nullptr, node_topics);