Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Unit tests for node interfaces #1202

Merged
merged 4 commits into from
Jul 1, 2020
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
46 changes: 46 additions & 0 deletions rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
60 changes: 60 additions & 0 deletions rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
// 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 <gtest/gtest.h>

#include <memory>
#include <string>

#include "rcl/node_options.h"
#include "rclcpp/node.hpp"
#include "rclcpp/node_interfaces/node_base.hpp"
#include "rclcpp/rclcpp.hpp"

class TestNodeBase : public ::testing::Test
{
public:
void SetUp()
{
rclcpp::init(0, nullptr);
}

void TearDown()
{
rclcpp::shutdown();
}
};

TEST_F(TestNodeBase, construct_from_node)
{
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("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<rclcpp::node_interfaces::NodeBase *>(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());

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());

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());
}
49 changes: 49 additions & 0 deletions rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp
Original file line number Diff line number Diff line change
@@ -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 <gtest/gtest.h>

#include <memory>

#include "rclcpp/node_interfaces/node_clock.hpp"
#include "rclcpp/node.hpp"

class TestNodeClock : public ::testing::Test
{
public:
void SetUp()
{
rclcpp::init(0, nullptr);
}

void TearDown()
{
rclcpp::shutdown();
}
};

TEST_F(TestNodeClock, construct_from_node)
{
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("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<rclcpp::node_interfaces::NodeClock *>(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());
}
186 changes: 186 additions & 0 deletions rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,186 @@
// 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 <gtest/gtest.h>

#include <memory>
#include <utility>

#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"

class TestNodeGraph : public ::testing::Test
{
public:
void SetUp()
{
rclcpp::init(0, nullptr);
}

void TearDown()
{
rclcpp::shutdown();
}
};

TEST_F(TestNodeGraph, construct_from_node)
{
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("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<rclcpp::node_interfaces::NodeGraph *>(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"));
}

TEST_F(TestNodeGraph, get_topic_names_and_types)
{
auto node = std::make_shared<rclcpp::Node>("node2", "ns");
const auto * node_graph =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(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());
}

TEST_F(TestNodeGraph, get_service_names_and_types)
{
auto node = std::make_shared<rclcpp::Node>("node2", "ns");
const auto * node_graph =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(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());
}

TEST_F(TestNodeGraph, get_service_names_and_types_by_node)
{
auto node1 = std::make_shared<rclcpp::Node>("node1", "ns");
auto node2 = std::make_shared<rclcpp::Node>("node2", "ns");
const auto * node_graph =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(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());
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This test fails for Connext since it doesn't leave any time between the node creation and checking information which relies on discovery information. See #1246 for the proposed fix.

}

TEST_F(TestNodeGraph, get_node_names_and_namespaces)
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
const auto * node_graph =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(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());
}

TEST_F(TestNodeGraph, notify_shutdown)
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto * node_graph =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(node->get_node_graph_interface().get());
ASSERT_NE(nullptr, node_graph);

EXPECT_NO_THROW(node_graph->notify_shutdown());
}

TEST_F(TestNodeGraph, wait_for_graph_change)
{
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
auto * node_graph =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(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<rclcpp::Event>();
EXPECT_THROW(
node_graph->wait_for_graph_change(event, std::chrono::milliseconds(0)),
rclcpp::exceptions::EventNotRegisteredError);
}

TEST_F(TestNodeGraph, get_info_by_topic)
{
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
const rclcpp::QoS publisher_qos(1);
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
auto callback = [](const test_msgs::msg::Empty::SharedPtr) {};

const rclcpp::QoS subscriber_qos(10);
auto subscription =
node->create_subscription<test_msgs::msg::Empty>(
"topic", subscriber_qos, std::move(callback));

const auto * node_graph =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(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;
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());

rclcpp::QoS actual_qos = publisher_endpoint_info.qos_profile();
EXPECT_EQ(0u, actual_qos.get_rmw_qos_profile().depth);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This test fails for Connext as well as CycloneDDS. Also above in line 145 the depth is explicitly initialized with 1. See #1245 for the proposed fix.


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;
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);
}
Loading