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

fix failing test with Connext since it doesn't wait for discovery #1246

Merged
merged 2 commits into from
Jul 30, 2020
Merged
Changes from all 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
29 changes: 26 additions & 3 deletions rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "rclcpp/node_interfaces/node_graph.hpp"
#include "rclcpp/rclcpp.hpp"
#include "test_msgs/msg/empty.hpp"
#include "test_msgs/srv/empty.hpp"

class TestNodeGraph : public ::testing::Test
{
Expand Down Expand Up @@ -87,17 +88,39 @@ TEST_F(TestNodeGraph, get_service_names_and_types)
TEST_F(TestNodeGraph, get_service_names_and_types_by_node)
{
auto node1 = std::make_shared<rclcpp::Node>("node1", "ns");
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service =
node1->create_service<test_msgs::srv::Empty>("node1_service", std::move(callback));
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);

// rcl_get_service_names_and_types_by_node() expects the node to exist, otherwise it fails
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());

// Check that node1_service exists for node1 but not node2. This shouldn't exercise graph
// discovery as node_graph belongs to node1 anyway. This is just to test the API itself.
auto services_of_node1 =
node_graph->get_service_names_and_types_by_node("node1", "/ns");
auto services_of_node2 =
node_graph->get_service_names_and_types_by_node("node2", "/ns");

auto start = std::chrono::steady_clock::now();
while (std::chrono::steady_clock::now() - start < std::chrono::seconds(1)) {
services_of_node1 = node_graph->get_service_names_and_types_by_node("node1", "/ns");
services_of_node2 = node_graph->get_service_names_and_types_by_node("node2", "/ns");
if (services_of_node1.find("/ns/node1_service") != services_of_node1.end()) {
break;
}
}

EXPECT_TRUE(services_of_node1.find("/ns/node1_service") != services_of_node1.end());
EXPECT_FALSE(services_of_node2.find("/ns/node1_service") != services_of_node2.end());
}

TEST_F(TestNodeGraph, get_node_names_and_namespaces)
Expand Down