Unit tests for node interfaces (#1202)
* Unit tests for node interfaces Signed-off-by: Stephen Brawner <brawner@gmail.com> * Address PR Feedback Signed-off-by: Stephen Brawner <brawner@gmail.com> * Address PR feedback Signed-off-by: Stephen Brawner <brawner@gmail.com> * Adjusting comment Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
parent
25286ac1c3
commit
30e9fae395
9 changed files with 809 additions and 0 deletions
|
@ -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
|
||||
|
|
60
rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp
Normal file
60
rclcpp/test/rclcpp/node_interfaces/test_node_base.cpp
Normal file
|
@ -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 instead is used to ensure
|
||||
// the proper type is being tested and covered.
|
||||
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
rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp
Normal file
49
rclcpp/test/rclcpp/node_interfaces/test_node_clock.cpp
Normal file
|
@ -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 instead is used to ensure
|
||||
// the proper type is being tested and covered.
|
||||
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
rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp
Normal file
186
rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp
Normal file
|
@ -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 instead is used to ensure
|
||||
// the proper type is being tested and covered.
|
||||
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());
|
||||
}
|
||||
|
||||
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);
|
||||
|
||||
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);
|
||||
}
|
89
rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp
Normal file
89
rclcpp/test/rclcpp/node_interfaces/test_node_parameters.cpp
Normal file
|
@ -0,0 +1,89 @@
|
|||
// 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 <gtest/gtest.h>
|
||||
|
||||
#include <algorithm>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "rclcpp/node.hpp"
|
||||
#include "rclcpp/node_interfaces/node_parameters.hpp"
|
||||
|
||||
class TestNodeParameters : public ::testing::Test
|
||||
{
|
||||
public:
|
||||
void SetUp()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void TearDown()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(TestNodeParameters, list_parameters)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
|
||||
// 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<rclcpp::node_interfaces::NodeParameters *>(
|
||||
node->get_node_parameters_interface().get());
|
||||
ASSERT_NE(nullptr, node_parameters);
|
||||
|
||||
std::vector<std::string> prefixes;
|
||||
const auto list_result = node_parameters->list_parameters(prefixes, 1u);
|
||||
|
||||
// Currently the only default parameter is 'use_sim_time', but that may change.
|
||||
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);
|
||||
const rcl_interfaces::msg::ParameterDescriptor descriptor;
|
||||
const auto added_parameter_value =
|
||||
node_parameters->declare_parameter(parameter_name, value, descriptor, false);
|
||||
EXPECT_EQ(value.get<bool>(), added_parameter_value.get<bool>());
|
||||
|
||||
auto list_result2 = node_parameters->list_parameters(prefixes, 1u);
|
||||
EXPECT_EQ(number_of_parameters + 1u, list_result2.names.size());
|
||||
|
||||
EXPECT_NE(
|
||||
std::find(list_result2.names.begin(), list_result2.names.end(), parameter_name),
|
||||
list_result2.names.end());
|
||||
}
|
||||
|
||||
TEST_F(TestNodeParameters, parameter_overrides)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
|
||||
auto * node_parameters =
|
||||
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
|
||||
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());
|
||||
}
|
111
rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp
Normal file
111
rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp
Normal file
|
@ -0,0 +1,111 @@
|
|||
// 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_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<void> create_request() override {return nullptr;}
|
||||
std::shared_ptr<rmw_request_id_t> create_request_header() override {return nullptr;}
|
||||
void handle_request(std::shared_ptr<rmw_request_id_t>, std::shared_ptr<void>) 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<void> create_response() override {return nullptr;}
|
||||
std::shared_ptr<rmw_request_id_t> create_request_header() override {return nullptr;}
|
||||
void handle_response(
|
||||
std::shared_ptr<rmw_request_id_t>, std::shared_ptr<void>) override {}
|
||||
};
|
||||
|
||||
class TestNodeService : public ::testing::Test
|
||||
{
|
||||
public:
|
||||
void SetUp()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void TearDown()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(TestNodeService, add_service)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
|
||||
// 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<rclcpp::node_interfaces::NodeServices *>(
|
||||
node->get_node_services_interface().get());
|
||||
ASSERT_NE(nullptr, node_services);
|
||||
|
||||
auto service = std::make_shared<TestService>(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<rclcpp::Node> different_node = std::make_shared<rclcpp::Node>("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_in_different_node),
|
||||
std::runtime_error);
|
||||
}
|
||||
|
||||
TEST_F(TestNodeService, add_client)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
|
||||
// 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<rclcpp::node_interfaces::NodeServices *>(
|
||||
node->get_node_services_interface().get());
|
||||
ASSERT_NE(nullptr, node_services);
|
||||
|
||||
auto client = std::make_shared<TestClient>(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<rclcpp::Node> different_node = std::make_shared<rclcpp::Node>("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_in_different_node),
|
||||
std::runtime_error);
|
||||
}
|
71
rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp
Normal file
71
rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp
Normal file
|
@ -0,0 +1,71 @@
|
|||
// 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_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;}
|
||||
};
|
||||
|
||||
class TestNodeTimers : public ::testing::Test
|
||||
{
|
||||
public:
|
||||
void SetUp()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void TearDown()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(TestNodeTimers, add_timer)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
|
||||
// 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<rclcpp::node_interfaces::NodeTimers *>(node->get_node_timers_interface().get());
|
||||
ASSERT_NE(nullptr, node_timers);
|
||||
auto timer = std::make_shared<TestTimer>(node.get());
|
||||
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
|
||||
EXPECT_NO_THROW(node_timers->add_timer(timer, callback_group));
|
||||
|
||||
// Check that adding timer from node to callback group in different_node throws exception.
|
||||
std::shared_ptr<rclcpp::Node> different_node = std::make_shared<rclcpp::Node>("node2", "ns");
|
||||
|
||||
auto callback_group_in_different_node =
|
||||
different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
|
||||
EXPECT_THROW(
|
||||
node_timers->add_timer(timer, callback_group_in_different_node),
|
||||
std::runtime_error);
|
||||
}
|
129
rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp
Normal file
129
rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp
Normal file
|
@ -0,0 +1,129 @@
|
|||
// 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 <type_traits>
|
||||
|
||||
#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"
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
const rosidl_message_type_support_t EmptyTypeSupport()
|
||||
{
|
||||
return *rosidl_typesupport_cpp::get_message_type_support_handle<test_msgs::msg::Empty>();
|
||||
}
|
||||
|
||||
const rcl_publisher_options_t PublisherOptions()
|
||||
{
|
||||
return rclcpp::PublisherOptionsWithAllocator<std::allocator<void>>().template
|
||||
to_rcl_publisher_options<test_msgs::msg::Empty>(rclcpp::QoS(10));
|
||||
}
|
||||
|
||||
const rcl_subscription_options_t SubscriptionOptions()
|
||||
{
|
||||
return rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void>>().template
|
||||
to_rcl_subscription_options<test_msgs::msg::Empty>(rclcpp::QoS(10));
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
class TestPublisher : public rclcpp::PublisherBase
|
||||
{
|
||||
public:
|
||||
explicit TestPublisher(rclcpp::Node * node)
|
||||
: rclcpp::PublisherBase(
|
||||
node->get_node_base_interface().get(), "topic", EmptyTypeSupport(), PublisherOptions()) {}
|
||||
};
|
||||
|
||||
class TestSubscription : public rclcpp::SubscriptionBase
|
||||
{
|
||||
public:
|
||||
explicit TestSubscription(rclcpp::Node * node)
|
||||
: rclcpp::SubscriptionBase(
|
||||
node->get_node_base_interface().get(), EmptyTypeSupport(), "topic", SubscriptionOptions()) {}
|
||||
std::shared_ptr<void> create_message() override {return nullptr;}
|
||||
|
||||
std::shared_ptr<rclcpp::SerializedMessage>
|
||||
create_serialized_message() override {return nullptr;}
|
||||
|
||||
void handle_message(std::shared_ptr<void> &, const rclcpp::MessageInfo &) override {}
|
||||
void handle_loaned_message(void *, const rclcpp::MessageInfo &) override {}
|
||||
void return_message(std::shared_ptr<void> &) override {}
|
||||
void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> &) override {}
|
||||
};
|
||||
|
||||
class TestNodeTopics : public ::testing::Test
|
||||
{
|
||||
public:
|
||||
void SetUp()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void TearDown()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(TestNodeTopics, add_publisher)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
|
||||
// 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<rclcpp::node_interfaces::NodeTopics *>(node->get_node_topics_interface().get());
|
||||
ASSERT_NE(nullptr, node_topics);
|
||||
auto publisher = std::make_shared<TestPublisher>(node.get());
|
||||
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
|
||||
EXPECT_NO_THROW(node_topics->add_publisher(publisher, callback_group));
|
||||
|
||||
// Check that adding publisher from node to a callback group in different_node throws exception.
|
||||
std::shared_ptr<rclcpp::Node> different_node = std::make_shared<rclcpp::Node>("node2", "ns");
|
||||
|
||||
auto callback_group_in_different_node =
|
||||
different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
|
||||
EXPECT_THROW(
|
||||
node_topics->add_publisher(publisher, callback_group_in_different_node),
|
||||
std::runtime_error);
|
||||
}
|
||||
|
||||
TEST_F(TestNodeTopics, add_subscription)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
auto * node_topics =
|
||||
dynamic_cast<rclcpp::node_interfaces::NodeTopics *>(node->get_node_topics_interface().get());
|
||||
ASSERT_NE(nullptr, node_topics);
|
||||
auto subscription = std::make_shared<TestSubscription>(node.get());
|
||||
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
|
||||
EXPECT_NO_THROW(node_topics->add_subscription(subscription, callback_group));
|
||||
|
||||
// Check that adding subscription from node to callback group in different_node throws exception.
|
||||
std::shared_ptr<rclcpp::Node> different_node = std::make_shared<rclcpp::Node>("node2", "ns");
|
||||
|
||||
auto callback_group_in_different_node =
|
||||
different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
|
||||
EXPECT_THROW(
|
||||
node_topics->add_subscription(subscription, callback_group_in_different_node),
|
||||
std::runtime_error);
|
||||
}
|
68
rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp
Normal file
68
rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp
Normal file
|
@ -0,0 +1,68 @@
|
|||
// 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_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 {}
|
||||
};
|
||||
|
||||
class TestNodeWaitables : public ::testing::Test
|
||||
{
|
||||
public:
|
||||
void SetUp()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void TearDown()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(TestNodeWaitables, add_remove_waitable)
|
||||
{
|
||||
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
|
||||
|
||||
auto * node_waitables =
|
||||
dynamic_cast<rclcpp::node_interfaces::NodeWaitables *>(
|
||||
node->get_node_waitables_interface().get());
|
||||
ASSERT_NE(nullptr, node_waitables);
|
||||
|
||||
std::shared_ptr<rclcpp::Node> node2 = std::make_shared<rclcpp::Node>("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<TestWaitable>();
|
||||
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));
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue