Increase coverage of node_interfaces, including with mocking rcl errors (#1322)

* Increase coverage of node_interfaces, including with mocking rcl errors

Signed-off-by: Stephen Brawner <brawner@gmail.com>

* PR Fixup

Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
brawner 2020-09-22 11:00:07 -07:00
parent e20837bf6a
commit fb76d4b640
8 changed files with 689 additions and 138 deletions

View file

@ -173,7 +173,7 @@ endif()
ament_add_gtest(test_node_interfaces__node_base ament_add_gtest(test_node_interfaces__node_base
rclcpp/node_interfaces/test_node_base.cpp) rclcpp/node_interfaces/test_node_base.cpp)
if(TARGET test_node_interfaces__node_base) if(TARGET test_node_interfaces__node_base)
target_link_libraries(test_node_interfaces__node_base ${PROJECT_NAME}) target_link_libraries(test_node_interfaces__node_base ${PROJECT_NAME} mimick)
endif() endif()
ament_add_gtest(test_node_interfaces__node_clock ament_add_gtest(test_node_interfaces__node_clock
rclcpp/node_interfaces/test_node_clock.cpp) rclcpp/node_interfaces/test_node_clock.cpp)
@ -186,22 +186,22 @@ if(TARGET test_node_interfaces__node_graph)
ament_target_dependencies( ament_target_dependencies(
test_node_interfaces__node_graph test_node_interfaces__node_graph
"test_msgs") "test_msgs")
target_link_libraries(test_node_interfaces__node_graph ${PROJECT_NAME}) target_link_libraries(test_node_interfaces__node_graph ${PROJECT_NAME} mimick)
endif() endif()
ament_add_gtest(test_node_interfaces__node_parameters ament_add_gtest(test_node_interfaces__node_parameters
rclcpp/node_interfaces/test_node_parameters.cpp) rclcpp/node_interfaces/test_node_parameters.cpp)
if(TARGET test_node_interfaces__node_parameters) if(TARGET test_node_interfaces__node_parameters)
target_link_libraries(test_node_interfaces__node_parameters ${PROJECT_NAME}) target_link_libraries(test_node_interfaces__node_parameters ${PROJECT_NAME} mimick)
endif() endif()
ament_add_gtest(test_node_interfaces__node_services ament_add_gtest(test_node_interfaces__node_services
rclcpp/node_interfaces/test_node_services.cpp) rclcpp/node_interfaces/test_node_services.cpp)
if(TARGET test_node_interfaces__node_services) if(TARGET test_node_interfaces__node_services)
target_link_libraries(test_node_interfaces__node_services ${PROJECT_NAME}) target_link_libraries(test_node_interfaces__node_services ${PROJECT_NAME} mimick)
endif() endif()
ament_add_gtest(test_node_interfaces__node_timers ament_add_gtest(test_node_interfaces__node_timers
rclcpp/node_interfaces/test_node_timers.cpp) rclcpp/node_interfaces/test_node_timers.cpp)
if(TARGET test_node_interfaces__node_timers) if(TARGET test_node_interfaces__node_timers)
target_link_libraries(test_node_interfaces__node_timers ${PROJECT_NAME}) target_link_libraries(test_node_interfaces__node_timers ${PROJECT_NAME} mimick)
endif() endif()
ament_add_gtest(test_node_interfaces__node_topics ament_add_gtest(test_node_interfaces__node_topics
rclcpp/node_interfaces/test_node_topics.cpp) rclcpp/node_interfaces/test_node_topics.cpp)
@ -209,12 +209,12 @@ if(TARGET test_node_interfaces__node_topics)
ament_target_dependencies( ament_target_dependencies(
test_node_interfaces__node_topics test_node_interfaces__node_topics
"test_msgs") "test_msgs")
target_link_libraries(test_node_interfaces__node_topics ${PROJECT_NAME}) target_link_libraries(test_node_interfaces__node_topics ${PROJECT_NAME} mimick)
endif() endif()
ament_add_gtest(test_node_interfaces__node_waitables ament_add_gtest(test_node_interfaces__node_waitables
rclcpp/node_interfaces/test_node_waitables.cpp) rclcpp/node_interfaces/test_node_waitables.cpp)
if(TARGET test_node_interfaces__node_waitables) if(TARGET test_node_interfaces__node_waitables)
target_link_libraries(test_node_interfaces__node_waitables ${PROJECT_NAME}) target_link_libraries(test_node_interfaces__node_waitables ${PROJECT_NAME} mimick)
endif() endif()
# TODO(wjwwood): reenable these build failure tests when I can get Jenkins to ignore their output # TODO(wjwwood): reenable these build failure tests when I can get Jenkins to ignore their output

View file

@ -21,6 +21,11 @@
#include "rclcpp/node.hpp" #include "rclcpp/node.hpp"
#include "rclcpp/node_interfaces/node_base.hpp" #include "rclcpp/node_interfaces/node_base.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rmw/validate_namespace.h"
#include "rmw/validate_node_name.h"
#include "../../mocking_utils/patch.hpp"
#include "../../utils/rclcpp_gtest_macros.hpp"
class TestNodeBase : public ::testing::Test class TestNodeBase : public ::testing::Test
{ {
@ -36,6 +41,12 @@ public:
} }
}; };
// Required for mocking_utils below
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, ==)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, !=)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, <)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, >)
TEST_F(TestNodeBase, construct_from_node) TEST_F(TestNodeBase, construct_from_node)
{ {
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns"); std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns");
@ -58,3 +69,125 @@ TEST_F(TestNodeBase, construct_from_node)
EXPECT_NE(nullptr, const_node_base->get_rcl_node_handle()); EXPECT_NE(nullptr, const_node_base->get_rcl_node_handle());
EXPECT_NE(nullptr, const_node_base->get_shared_rcl_node_handle()); EXPECT_NE(nullptr, const_node_base->get_shared_rcl_node_handle());
} }
TEST_F(TestNodeBase, construct_destruct_rcl_guard_condition_init_error) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_guard_condition_init, RCL_RET_ERROR);
EXPECT_THROW(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_error) {
auto mock_node_init = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_node_init, RCL_RET_ERROR);
// This function is called only if rcl_node_init fails, so both mocked functions are required
// This just logs an error, so behavior shouldn't change
auto mock_guard_condition_fini = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_guard_condition_fini, RCL_RET_ERROR);
EXPECT_THROW(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name) {
auto mock_node_init = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAME);
// `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME
auto mock_validate_node_name = mocking_utils::patch_and_return(
"lib:rclcpp", rmw_validate_node_name, RMW_RET_ERROR);
EXPECT_THROW(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name_invalid_argument) {
auto mock_node_init = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAME);
// `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME
auto mock_validate_node_name = mocking_utils::patch_and_return(
"lib:rclcpp", rmw_validate_node_name, RMW_RET_INVALID_ARGUMENT);
EXPECT_THROW(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
rclcpp::exceptions::RCLInvalidArgument);
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name_valid_rmw_node_name) {
auto mock_node_init = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAME);
// `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME
auto mock = mocking_utils::patch(
"lib:rclcpp", rmw_validate_node_name, [](const char *, int * validation_result, size_t *)
{
*validation_result = RMW_NODE_NAME_VALID;
return RMW_RET_OK;
});
RCLCPP_EXPECT_THROW_EQ(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
std::runtime_error("valid rmw node name but invalid rcl node name"));
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace) {
auto mock_node_init = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE);
// `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE
auto mock_validate_namespace = mocking_utils::patch_and_return(
"lib:rclcpp", rmw_validate_namespace, RMW_RET_ERROR);
EXPECT_THROW(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace_rmw_invalid_argument) {
auto mock_node_init = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE);
// `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE
auto mock_validate_namespace = mocking_utils::patch_and_return(
"lib:rclcpp", rmw_validate_namespace, RMW_RET_INVALID_ARGUMENT);
EXPECT_THROW(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
rclcpp::exceptions::RCLInvalidArgument);
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace_valid_rmw_namespace) {
auto mock_node_init = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE);
// `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE
auto mock = mocking_utils::patch(
"lib:rclcpp", rmw_validate_namespace, [](const char *, int * validation_result, size_t *)
{
*validation_result = RMW_NAMESPACE_VALID;
return RMW_RET_OK;
});
RCLCPP_EXPECT_THROW_EQ(
std::make_shared<rclcpp::Node>("node", "ns").reset(),
std::runtime_error("valid rmw node namespace but invalid rcl node namespace"));
}
TEST_F(TestNodeBase, construct_destruct_rcl_node_init_fini_error) {
auto mock_node_fini = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_node_fini, RCL_RET_ERROR);
EXPECT_NO_THROW(std::make_shared<rclcpp::Node>("node", "ns").reset());
}
TEST_F(TestNodeBase, construct_destruct_rcl_guard_condition_fini_error) {
auto mock_node_fini = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_guard_condition_fini, RCL_RET_ERROR);
EXPECT_NO_THROW(std::make_shared<rclcpp::Node>("node", "ns").reset());
}

View file

@ -15,105 +15,172 @@
#include <gtest/gtest.h> #include <gtest/gtest.h>
#include <memory> #include <memory>
#include <string>
#include <utility> #include <utility>
#include "rcl/graph.h"
#include "rcl/node_options.h" #include "rcl/node_options.h"
#include "rcl/remap.h"
#include "rclcpp/node.hpp" #include "rclcpp/node.hpp"
#include "rclcpp/node_interfaces/node_base.hpp" #include "rclcpp/node_interfaces/node_base.hpp"
#include "rclcpp/node_interfaces/node_graph.hpp" #include "rclcpp/node_interfaces/node_graph.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rcutils/strdup.h"
#include "test_msgs/msg/empty.hpp" #include "test_msgs/msg/empty.hpp"
#include "test_msgs/srv/empty.hpp" #include "test_msgs/srv/empty.hpp"
#include "../../mocking_utils/patch.hpp"
#include "../../utils/rclcpp_gtest_macros.hpp"
namespace
{
constexpr char node_name[] = "node";
constexpr char node_namespace[] = "ns";
constexpr char absolute_namespace[] = "/ns";
} // namespace
class TestNodeGraph : public ::testing::Test class TestNodeGraph : public ::testing::Test
{ {
public: public:
void SetUp() void SetUp()
{ {
rclcpp::init(0, nullptr); rclcpp::init(0, nullptr);
node_ = std::make_shared<rclcpp::Node>(node_name, node_namespace);
// This dynamic cast is not necessary for the unittests, but instead is used to ensure
// the proper type is being tested and covered.
node_graph_ =
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(node_->get_node_graph_interface().get());
ASSERT_NE(nullptr, node_graph_);
} }
void TearDown() void TearDown()
{ {
rclcpp::shutdown(); rclcpp::shutdown();
} }
protected:
std::shared_ptr<rclcpp::Node> node() {return node_;}
const rclcpp::node_interfaces::NodeGraph * node_graph() const {return node_graph_;}
private:
std::shared_ptr<rclcpp::Node> node_;
rclcpp::node_interfaces::NodeGraph * node_graph_;
}; };
TEST_F(TestNodeGraph, construct_from_node) TEST_F(TestNodeGraph, construct_from_node)
{ {
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns"); auto topic_names_and_types = node_graph()->get_topic_names_and_types(false);
// 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()); EXPECT_LT(0u, topic_names_and_types.size());
auto service_names_and_types = node_graph->get_service_names_and_types(); auto service_names_and_types = node_graph()->get_service_names_and_types();
EXPECT_LT(0u, service_names_and_types.size()); EXPECT_LT(0u, service_names_and_types.size());
auto names = node_graph->get_node_names(); auto names = node_graph()->get_node_names();
EXPECT_EQ(1u, names.size()); EXPECT_EQ(1u, names.size());
auto names_and_namespaces = node_graph->get_node_names_and_namespaces(); auto names_and_namespaces = node_graph()->get_node_names_and_namespaces();
EXPECT_EQ(1u, names_and_namespaces.size()); EXPECT_EQ(1u, names_and_namespaces.size());
EXPECT_EQ(0u, node_graph->count_publishers("not_a_topic")); EXPECT_EQ(0u, node_graph()->count_publishers("not_a_topic"));
EXPECT_EQ(0u, node_graph->count_subscribers("not_a_topic")); EXPECT_EQ(0u, node_graph()->count_subscribers("not_a_topic"));
EXPECT_NE(nullptr, node_graph()->get_graph_guard_condition());
// get_graph_event is non-const
EXPECT_NE(nullptr, node()->get_node_graph_interface()->get_graph_event());
EXPECT_EQ(1u, node()->get_node_graph_interface()->count_graph_users());
} }
TEST_F(TestNodeGraph, get_topic_names_and_types) TEST_F(TestNodeGraph, get_topic_names_and_types)
{ {
auto node = std::make_shared<rclcpp::Node>("node2", "ns"); auto topic_names_and_types = node_graph()->get_topic_names_and_types();
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()); EXPECT_LT(0u, topic_names_and_types.size());
} }
TEST_F(TestNodeGraph, get_topic_names_and_types_rcl_error)
{
auto mock_get_topic_names = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_get_topic_names_and_types, RCL_RET_ERROR);
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_names_and_types_fini, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_topic_names_and_types(),
std::runtime_error(
"failed to get topic names and types: error not set, failed also to cleanup topic names and"
" types, leaking memory: error not set"));
}
TEST_F(TestNodeGraph, get_topic_names_and_types_rcl_names_and_types_fini_error)
{
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_names_and_types_fini, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_topic_names_and_types(),
std::runtime_error("could not destroy topic names and types: error not set"));
}
TEST_F(TestNodeGraph, get_service_names_and_types) TEST_F(TestNodeGraph, get_service_names_and_types)
{ {
auto node = std::make_shared<rclcpp::Node>("node2", "ns"); auto service_names_and_types = node_graph()->get_service_names_and_types();
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()); EXPECT_LT(0u, service_names_and_types.size());
} }
TEST_F(TestNodeGraph, get_service_names_and_types_rcl_error)
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_get_service_names_and_types, RCL_RET_ERROR);
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_names_and_types_fini, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_service_names_and_types(),
std::runtime_error(
"failed to get service names and types: error not set, failed also to cleanup service names"
" and types, leaking memory: error not set"));
}
TEST_F(TestNodeGraph, get_service_names_and_types_rcl_names_and_types_fini)
{
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_names_and_types_fini, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_service_names_and_types(),
std::runtime_error("could not destroy service names and types: error not set"));
}
TEST_F(TestNodeGraph, get_service_names_and_types_by_node) TEST_F(TestNodeGraph, get_service_names_and_types_by_node)
{ {
auto node1 = std::make_shared<rclcpp::Node>("node1", "ns");
auto callback = []( auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr, const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {}; test_msgs::srv::Empty::Response::SharedPtr) {};
auto service = auto service =
node1->create_service<test_msgs::srv::Empty>("node1_service", std::move(callback)); node()->create_service<test_msgs::srv::Empty>("node1_service", std::move(callback));
auto node2 = std::make_shared<rclcpp::Node>("node2", "ns");
const auto * node_graph = const std::string node2_name = "node2";
dynamic_cast<rclcpp::node_interfaces::NodeGraph *>(node1->get_node_graph_interface().get()); auto node2 = std::make_shared<rclcpp::Node>(node2_name, node_namespace);
ASSERT_NE(nullptr, node_graph);
// rcl_get_service_names_and_types_by_node() expects the node to exist, otherwise it fails // rcl_get_service_names_and_types_by_node() expects the node to exist, otherwise it fails
EXPECT_THROW( EXPECT_THROW(
node_graph->get_service_names_and_types_by_node("not_a_node", "not_absolute_namespace"), node_graph()->get_service_names_and_types_by_node("not_a_node", "not_absolute_namespace"),
std::runtime_error); std::runtime_error);
// Check that node1_service exists for node1 but not node2. This shouldn't exercise graph // 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. // discovery as node_graph belongs to node1 anyway. This is just to test the API itself.
auto services_of_node1 = auto services_of_node1 =
node_graph->get_service_names_and_types_by_node("node1", "/ns"); node_graph()->get_service_names_and_types_by_node(node_name, absolute_namespace);
auto services_of_node2 = auto services_of_node2 =
node_graph->get_service_names_and_types_by_node("node2", "/ns"); node_graph()->get_service_names_and_types_by_node(node2_name, absolute_namespace);
auto start = std::chrono::steady_clock::now(); auto start = std::chrono::steady_clock::now();
while (std::chrono::steady_clock::now() - start < std::chrono::seconds(1)) { 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_node1 =
services_of_node2 = node_graph->get_service_names_and_types_by_node("node2", "/ns"); node_graph()->get_service_names_and_types_by_node(node_name, absolute_namespace);
services_of_node2 =
node_graph()->get_service_names_and_types_by_node(node2_name, absolute_namespace);
if (services_of_node1.find("/ns/node1_service") != services_of_node1.end()) { if (services_of_node1.find("/ns/node1_service") != services_of_node1.end()) {
break; break;
} }
@ -123,70 +190,134 @@ TEST_F(TestNodeGraph, get_service_names_and_types_by_node)
EXPECT_FALSE(services_of_node2.find("/ns/node1_service") != services_of_node2.end()); EXPECT_FALSE(services_of_node2.find("/ns/node1_service") != services_of_node2.end());
} }
TEST_F(TestNodeGraph, get_service_names_and_types_by_node_rcl_errors)
{
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service =
node()->create_service<test_msgs::srv::Empty>("node1_service", std::move(callback));
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_get_service_names_and_types_by_node, RCL_RET_ERROR);
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_names_and_types_fini, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_service_names_and_types_by_node(node_name, node_namespace),
std::runtime_error(
"failed to get service names and types by node: error not set, failed also to cleanup"
" service names and types, leaking memory: error not set"));
}
TEST_F(TestNodeGraph, get_service_names_and_types_by_node_names_and_types_fini_error)
{
auto callback = [](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
auto service =
node()->create_service<test_msgs::srv::Empty>("node1_service", std::move(callback));
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_names_and_types_fini, RCL_RET_ERROR);
EXPECT_THROW(
node_graph()->get_service_names_and_types_by_node(node_name, absolute_namespace),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeGraph, get_node_names_and_namespaces) TEST_F(TestNodeGraph, get_node_names_and_namespaces)
{ {
auto node = std::make_shared<rclcpp::Node>("node", "ns"); auto names_and_namespaces = node_graph()->get_node_names_and_namespaces();
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()); EXPECT_EQ(1u, names_and_namespaces.size());
} }
TEST_F(TestNodeGraph, get_node_names_and_namespaces_rcl_errors)
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_get_node_names, RCL_RET_ERROR);
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcutils_string_array_fini, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_node_names_and_namespaces(),
std::runtime_error(
"failed to get node names: error not set, failed also to cleanup node names, leaking memory:"
" error not set, failed also to cleanup node namespaces, leaking memory: error not set"));
}
TEST_F(TestNodeGraph, get_node_names_and_namespaces_fini_errors)
{
auto mock_names_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcutils_string_array_fini, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_node_names_and_namespaces(),
std::runtime_error("could not destroy node names, could not destroy node namespaces"));
}
TEST_F(TestNodeGraph, count_publishers_rcl_error)
{
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_count_publishers, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->count_publishers("topic"),
std::runtime_error("could not count publishers: error not set"));
}
TEST_F(TestNodeGraph, count_subscribers_rcl_error)
{
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_count_subscribers, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->count_subscribers("topic"),
std::runtime_error("could not count subscribers: error not set"));
}
TEST_F(TestNodeGraph, notify_shutdown) TEST_F(TestNodeGraph, notify_shutdown)
{ {
auto node = std::make_shared<rclcpp::Node>("node", "ns"); EXPECT_NO_THROW(node()->get_node_graph_interface()->notify_shutdown());
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) TEST_F(TestNodeGraph, wait_for_graph_change)
{ {
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns"); auto node_graph_interface = node()->get_node_graph_interface();
auto * node_graph = EXPECT_NO_THROW(node_graph_interface->notify_graph_change());
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( EXPECT_THROW(
node_graph->wait_for_graph_change(nullptr, std::chrono::milliseconds(1)), node_graph_interface->wait_for_graph_change(nullptr, std::chrono::milliseconds(1)),
rclcpp::exceptions::InvalidEventError); rclcpp::exceptions::InvalidEventError);
auto event = std::make_shared<rclcpp::Event>(); auto event = std::make_shared<rclcpp::Event>();
EXPECT_THROW( EXPECT_THROW(
node_graph->wait_for_graph_change(event, std::chrono::milliseconds(0)), node_graph_interface->wait_for_graph_change(event, std::chrono::milliseconds(0)),
rclcpp::exceptions::EventNotRegisteredError); rclcpp::exceptions::EventNotRegisteredError);
} }
TEST_F(TestNodeGraph, notify_graph_change_rcl_error)
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
EXPECT_THROW(
node()->get_node_graph_interface()->notify_graph_change(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeGraph, get_info_by_topic) 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); const rclcpp::QoS publisher_qos(1);
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos); auto publisher = node()->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
auto callback = [](const test_msgs::msg::Empty::SharedPtr) {}; auto callback = [](const test_msgs::msg::Empty::SharedPtr) {};
const rclcpp::QoS subscriber_qos(10); const rclcpp::QoS subscriber_qos(10);
auto subscription = auto subscription =
node->create_subscription<test_msgs::msg::Empty>( node()->create_subscription<test_msgs::msg::Empty>(
"topic", subscriber_qos, std::move(callback)); "topic", subscriber_qos, std::move(callback));
const auto * node_graph = EXPECT_EQ(0u, node_graph()->get_publishers_info_by_topic("topic", true).size());
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); auto publishers = node_graph()->get_publishers_info_by_topic("topic", false);
ASSERT_EQ(1u, publishers.size()); ASSERT_EQ(1u, publishers.size());
auto publisher_endpoint_info = publishers[0]; auto publisher_endpoint_info = publishers[0];
const auto const_publisher_endpoint_info = publisher_endpoint_info; const auto const_publisher_endpoint_info = publisher_endpoint_info;
EXPECT_STREQ("node", publisher_endpoint_info.node_name().c_str()); EXPECT_STREQ(node_name, publisher_endpoint_info.node_name().c_str());
EXPECT_STREQ("node", const_publisher_endpoint_info.node_name().c_str()); EXPECT_STREQ(node_name, const_publisher_endpoint_info.node_name().c_str());
EXPECT_STREQ("/ns", publisher_endpoint_info.node_namespace().c_str()); EXPECT_STREQ(absolute_namespace, publisher_endpoint_info.node_namespace().c_str());
EXPECT_STREQ("/ns", const_publisher_endpoint_info.node_namespace().c_str()); EXPECT_STREQ(absolute_namespace, 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", publisher_endpoint_info.topic_type().c_str());
EXPECT_STREQ("test_msgs/msg/Empty", const_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, publisher_endpoint_info.endpoint_type());
@ -225,3 +356,90 @@ TEST_F(TestNodeGraph, get_info_by_topic)
} }
EXPECT_FALSE(endpoint_gid_is_all_zeros); EXPECT_FALSE(endpoint_gid_is_all_zeros);
} }
TEST_F(TestNodeGraph, get_info_by_topic_rcl_node_get_options_error)
{
const rclcpp::QoS publisher_qos(1);
auto publisher = node()->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_node_get_options, nullptr);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_publishers_info_by_topic("topic", false),
std::runtime_error("Need valid node options in get_info_by_topic()"));
}
// Required for mocking_utils below
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, ==)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, !=)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, <)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, >)
TEST_F(TestNodeGraph, get_info_by_topic_rcl_remap_topic_name_error)
{
const rclcpp::QoS publisher_qos(1);
auto publisher = node()->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_remap_topic_name, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_graph()->get_publishers_info_by_topic("topic", false),
std::runtime_error("Failed to remap topic name /ns/topic: error not set"));
}
TEST_F(TestNodeGraph, get_info_by_topic_rcl_remap_topic_name_nullptr)
{
const rclcpp::QoS publisher_qos(1);
auto publisher = node()->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
// Should be cleaned up by get_info_by_topic
char * some_string = rcutils_strdup("", rcl_get_default_allocator());
ASSERT_NE(nullptr, some_string);
auto mock =
mocking_utils::patch(
"lib:rclcpp", rcl_remap_topic_name, [&some_string](
const rcl_arguments_t *, const rcl_arguments_t *, const char *, const char *, const char *,
rcl_allocator_t, char ** output_name)
{
*output_name = some_string;
return RCL_RET_OK;
});
EXPECT_NO_THROW(node_graph()->get_publishers_info_by_topic("topic", false));
}
TEST_F(TestNodeGraph, get_info_by_topic_rcl_errors)
{
const rclcpp::QoS publisher_qos(1);
auto publisher = node()->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_get_publishers_info_by_topic, RCL_RET_ERROR);
auto mock_info_array_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_topic_endpoint_info_array_fini, RCL_RET_ERROR);
EXPECT_THROW(
node_graph()->get_publishers_info_by_topic("topic", false),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeGraph, get_info_by_topic_unsupported)
{
const rclcpp::QoS publisher_qos(1);
auto publisher = node()->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_get_publishers_info_by_topic, RCL_RET_UNSUPPORTED);
EXPECT_THROW(
node_graph()->get_publishers_info_by_topic("topic", false),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeGraph, get_info_by_topic_endpoint_info_array_fini_error)
{
const rclcpp::QoS publisher_qos(1);
auto publisher = node()->create_publisher<test_msgs::msg::Empty>("topic", publisher_qos);
auto mock_info_array_fini = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_topic_endpoint_info_array_fini, RCL_RET_ERROR);
EXPECT_THROW(
node_graph()->get_publishers_info_by_topic("topic", false),
rclcpp::exceptions::RCLError);
}

View file

@ -28,31 +28,47 @@
#include "rclcpp/node.hpp" #include "rclcpp/node.hpp"
#include "rclcpp/node_interfaces/node_parameters.hpp" #include "rclcpp/node_interfaces/node_parameters.hpp"
#include "../../mocking_utils/patch.hpp"
#include "../../utils/rclcpp_gtest_macros.hpp"
class TestNodeParameters : public ::testing::Test class TestNodeParameters : public ::testing::Test
{ {
public: public:
void SetUp() void SetUp()
{ {
rclcpp::init(0, nullptr); rclcpp::init(0, nullptr);
rclcpp::NodeOptions options;
options.allow_undeclared_parameters(true);
node = std::make_shared<rclcpp::Node>("node", "ns", options);
// This dynamic cast is not necessary for the unittest itself, but instead is used to ensure
// the proper type is being tested and covered.
node_parameters =
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
node->get_node_parameters_interface().get());
ASSERT_NE(nullptr, node_parameters);
} }
void TearDown() void TearDown()
{ {
rclcpp::shutdown(); rclcpp::shutdown();
} }
protected:
std::shared_ptr<rclcpp::Node> node;
rclcpp::node_interfaces::NodeParameters * node_parameters;
}; };
TEST_F(TestNodeParameters, construct_destruct_rcl_errors) {
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_arguments_get_param_overrides, RCL_RET_ERROR);
EXPECT_THROW(
std::make_shared<rclcpp::Node>("node2", "ns").reset(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestNodeParameters, list_parameters) 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; std::vector<std::string> prefixes;
const auto list_result = node_parameters->list_parameters(prefixes, 1u); const auto list_result = node_parameters->list_parameters(prefixes, 1u);
@ -73,17 +89,113 @@ TEST_F(TestNodeParameters, list_parameters)
EXPECT_NE( EXPECT_NE(
std::find(list_result2.names.begin(), list_result2.names.end(), parameter_name), std::find(list_result2.names.begin(), list_result2.names.end(), parameter_name),
list_result2.names.end()); list_result2.names.end());
// Check prefixes
const std::string parameter_name2 = "prefix.new_parameter";
const rclcpp::ParameterValue value2(true);
const rcl_interfaces::msg::ParameterDescriptor descriptor2;
const auto added_parameter_value2 =
node_parameters->declare_parameter(parameter_name2, value2, descriptor2, false);
EXPECT_EQ(value.get<bool>(), added_parameter_value.get<bool>());
prefixes = {"prefix"};
auto list_result3 = node_parameters->list_parameters(prefixes, 2u);
EXPECT_EQ(1u, list_result3.names.size());
EXPECT_NE(
std::find(list_result3.names.begin(), list_result3.names.end(), parameter_name2),
list_result3.names.end());
// Check if prefix equals parameter name
prefixes = {"new_parameter"};
auto list_result4 = node_parameters->list_parameters(prefixes, 2u);
EXPECT_EQ(1u, list_result4.names.size());
EXPECT_NE(
std::find(list_result4.names.begin(), list_result4.names.end(), parameter_name),
list_result4.names.end());
} }
TEST_F(TestNodeParameters, parameter_overrides) TEST_F(TestNodeParameters, parameter_overrides)
{ {
std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>("node", "ns"); rclcpp::NodeOptions node_options;
node_options.automatically_declare_parameters_from_overrides(true);
node_options.append_parameter_override("param1", true);
node_options.append_parameter_override("param2", 42);
auto * node_parameters = std::shared_ptr<rclcpp::Node> node2 = std::make_shared<rclcpp::Node>("node2", "ns", node_options);
auto * node_parameters_interface =
dynamic_cast<rclcpp::node_interfaces::NodeParameters *>( dynamic_cast<rclcpp::node_interfaces::NodeParameters *>(
node->get_node_parameters_interface().get()); node2->get_node_parameters_interface().get());
ASSERT_NE(nullptr, node_parameters); ASSERT_NE(nullptr, node_parameters);
const auto & parameter_overrides = node_parameters->get_parameter_overrides(); const auto & parameter_overrides = node_parameters_interface->get_parameter_overrides();
EXPECT_EQ(0u, parameter_overrides.size()); EXPECT_EQ(2u, parameter_overrides.size());
}
TEST_F(TestNodeParameters, set_parameters) {
rclcpp::NodeOptions node_options;
node_options.allow_undeclared_parameters(true);
rcl_interfaces::msg::ParameterDescriptor bool_descriptor;
bool_descriptor.name = "bool_parameter";
bool_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
bool_descriptor.read_only = false;
node_parameters->declare_parameter(
"bool_parameter", rclcpp::ParameterValue(false), bool_descriptor, false);
rcl_interfaces::msg::ParameterDescriptor read_only_descriptor;
read_only_descriptor.name = "read_only_parameter";
read_only_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
read_only_descriptor.read_only = true;
node_parameters->declare_parameter(
"read_only_parameter", rclcpp::ParameterValue(42), read_only_descriptor, false);
const std::vector<rclcpp::Parameter> parameters = {
rclcpp::Parameter("bool_parameter", true),
rclcpp::Parameter("read_only_parameter", 42),
};
auto result = node_parameters->set_parameters(parameters);
ASSERT_EQ(parameters.size(), result.size());
EXPECT_TRUE(result[0].successful);
EXPECT_FALSE(result[1].successful);
EXPECT_STREQ(
"parameter 'read_only_parameter' cannot be set because it is read-only",
result[1].reason.c_str());
RCLCPP_EXPECT_THROW_EQ(
node_parameters->set_parameters({rclcpp::Parameter("", true)}),
rclcpp::exceptions::InvalidParametersException("parameter name must not be empty"));
result = node_parameters->set_parameters({rclcpp::Parameter("undeclared_parameter", 3.14159)});
ASSERT_EQ(1u, result.size());
EXPECT_TRUE(result[0].successful);
}
TEST_F(TestNodeParameters, add_remove_parameters_callback) {
rcl_interfaces::msg::ParameterDescriptor bool_descriptor;
bool_descriptor.name = "bool_parameter";
bool_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
bool_descriptor.read_only = false;
node_parameters->declare_parameter(
"bool_parameter", rclcpp::ParameterValue(false), bool_descriptor, false);
const std::vector<rclcpp::Parameter> parameters = {rclcpp::Parameter("bool_parameter", true)};
const std::string reason = "some totally not made up reason";
auto callback = [reason](const std::vector<rclcpp::Parameter> &) {
rcl_interfaces::msg::SetParametersResult result;
result.successful = false;
result.reason = reason;
return result;
};
auto handle = node_parameters->add_on_set_parameters_callback(callback);
auto result = node_parameters->set_parameters(parameters);
ASSERT_EQ(1u, result.size());
EXPECT_FALSE(result[0].successful);
EXPECT_EQ(reason, result[0].reason);
EXPECT_NO_THROW(node_parameters->remove_on_set_parameters_callback(handle.get()));
RCLCPP_EXPECT_THROW_EQ(
node_parameters->remove_on_set_parameters_callback(handle.get()),
std::runtime_error("Callback doesn't exist"));
} }

View file

@ -22,6 +22,9 @@
#include "rclcpp/node_interfaces/node_services.hpp" #include "rclcpp/node_interfaces/node_services.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "../../mocking_utils/patch.hpp"
#include "../../utils/rclcpp_gtest_macros.hpp"
class TestService : public rclcpp::ServiceBase class TestService : public rclcpp::ServiceBase
{ {
public: public:
@ -51,25 +54,29 @@ public:
void SetUp() void SetUp()
{ {
rclcpp::init(0, nullptr); rclcpp::init(0, nullptr);
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.
node_services =
dynamic_cast<rclcpp::node_interfaces::NodeServices *>(
node->get_node_services_interface().get());
ASSERT_NE(nullptr, node_services);
} }
void TearDown() void TearDown()
{ {
rclcpp::shutdown(); rclcpp::shutdown();
} }
protected:
std::shared_ptr<rclcpp::Node> node;
rclcpp::node_interfaces::NodeServices * node_services;
}; };
TEST_F(TestNodeService, add_service) 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 service = std::make_shared<TestService>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_NO_THROW( EXPECT_NO_THROW(
@ -80,22 +87,24 @@ TEST_F(TestNodeService, add_service)
auto callback_group_in_different_node = auto callback_group_in_different_node =
different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_THROW( RCLCPP_EXPECT_THROW_EQ(
node_services->add_service(service, callback_group_in_different_node), node_services->add_service(service, callback_group_in_different_node),
std::runtime_error); std::runtime_error("Cannot create service, group not in node."));
}
TEST_F(TestNodeService, add_service_rcl_trigger_guard_condition_error)
{
auto service = std::make_shared<TestService>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_services->add_service(service, callback_group),
std::runtime_error("Failed to notify wait set on service creation: error not set"));
} }
TEST_F(TestNodeService, add_client) 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 client = std::make_shared<TestClient>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_NO_THROW(node_services->add_client(client, callback_group)); EXPECT_NO_THROW(node_services->add_client(client, callback_group));
@ -105,7 +114,18 @@ TEST_F(TestNodeService, add_client)
auto callback_group_in_different_node = auto callback_group_in_different_node =
different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_THROW( RCLCPP_EXPECT_THROW_EQ(
node_services->add_client(client, callback_group_in_different_node), node_services->add_client(client, callback_group_in_different_node),
std::runtime_error); std::runtime_error("Cannot create client, group not in node."));
}
TEST_F(TestNodeService, add_client_rcl_trigger_guard_condition_error)
{
auto client = std::make_shared<TestClient>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_services->add_client(client, callback_group),
std::runtime_error("Failed to notify wait set on client creation: error not set"));
} }

View file

@ -22,6 +22,9 @@
#include "rclcpp/node_interfaces/node_timers.hpp" #include "rclcpp/node_interfaces/node_timers.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "../../mocking_utils/patch.hpp"
#include "../../utils/rclcpp_gtest_macros.hpp"
class TestTimer : public rclcpp::TimerBase class TestTimer : public rclcpp::TimerBase
{ {
public: public:
@ -39,23 +42,27 @@ public:
void SetUp() void SetUp()
{ {
rclcpp::init(0, nullptr); rclcpp::init(0, nullptr);
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.
node_timers =
dynamic_cast<rclcpp::node_interfaces::NodeTimers *>(node->get_node_timers_interface().get());
ASSERT_NE(nullptr, node_timers);
} }
void TearDown() void TearDown()
{ {
rclcpp::shutdown(); rclcpp::shutdown();
} }
protected:
std::shared_ptr<rclcpp::Node> node;
rclcpp::node_interfaces::NodeTimers * node_timers;
}; };
TEST_F(TestNodeTimers, add_timer) 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 timer = std::make_shared<TestTimer>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_NO_THROW(node_timers->add_timer(timer, callback_group)); EXPECT_NO_THROW(node_timers->add_timer(timer, callback_group));
@ -65,7 +72,19 @@ TEST_F(TestNodeTimers, add_timer)
auto callback_group_in_different_node = auto callback_group_in_different_node =
different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); different_node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_THROW( RCLCPP_EXPECT_THROW_EQ(
node_timers->add_timer(timer, callback_group_in_different_node), node_timers->add_timer(timer, callback_group_in_different_node),
std::runtime_error); std::runtime_error("Cannot create timer, group not in node."));
}
TEST_F(TestNodeTimers, add_timer_rcl_trigger_guard_condition_error)
{
auto timer = std::make_shared<TestTimer>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_timers->add_timer(timer, callback_group),
std::runtime_error("Failed to notify wait set on timer creation: error not set"));
} }

View file

@ -24,6 +24,9 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "test_msgs/msg/empty.hpp" #include "test_msgs/msg/empty.hpp"
#include "../../mocking_utils/patch.hpp"
#include "../../utils/rclcpp_gtest_macros.hpp"
namespace namespace
{ {
@ -77,23 +80,27 @@ public:
void SetUp() void SetUp()
{ {
rclcpp::init(0, nullptr); rclcpp::init(0, nullptr);
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.
node_topics =
dynamic_cast<rclcpp::node_interfaces::NodeTopics *>(node->get_node_topics_interface().get());
ASSERT_NE(nullptr, node_topics);
} }
void TearDown() void TearDown()
{ {
rclcpp::shutdown(); rclcpp::shutdown();
} }
protected:
std::shared_ptr<rclcpp::Node> node;
rclcpp::node_interfaces::NodeTopics * node_topics;
}; };
TEST_F(TestNodeTopics, add_publisher) 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 publisher = std::make_shared<TestPublisher>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_NO_THROW(node_topics->add_publisher(publisher, callback_group)); EXPECT_NO_THROW(node_topics->add_publisher(publisher, callback_group));
@ -108,12 +115,20 @@ TEST_F(TestNodeTopics, add_publisher)
std::runtime_error); std::runtime_error);
} }
TEST_F(TestNodeTopics, add_publisher_rcl_trigger_guard_condition_error)
{
auto publisher = std::make_shared<TestPublisher>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_topics->add_publisher(publisher, callback_group),
std::runtime_error("Failed to notify wait set on publisher creation: error not set"));
}
TEST_F(TestNodeTopics, add_subscription) 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 subscription = std::make_shared<TestSubscription>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
EXPECT_NO_THROW(node_topics->add_subscription(subscription, callback_group)); EXPECT_NO_THROW(node_topics->add_subscription(subscription, callback_group));
@ -127,3 +142,15 @@ TEST_F(TestNodeTopics, add_subscription)
node_topics->add_subscription(subscription, callback_group_in_different_node), node_topics->add_subscription(subscription, callback_group_in_different_node),
std::runtime_error); std::runtime_error);
} }
TEST_F(TestNodeTopics, add_subscription_rcl_trigger_guard_condition_error)
{
auto subscription = std::make_shared<TestSubscription>(node.get());
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_topics->add_subscription(subscription, callback_group),
std::runtime_error("failed to notify wait set on subscription creation: error not set"));
}

View file

@ -22,6 +22,9 @@
#include "rclcpp/node_interfaces/node_waitables.hpp" #include "rclcpp/node_interfaces/node_waitables.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "../../mocking_utils/patch.hpp"
#include "../../utils/rclcpp_gtest_macros.hpp"
class TestWaitable : public rclcpp::Waitable class TestWaitable : public rclcpp::Waitable
{ {
public: public:
@ -36,23 +39,26 @@ public:
void SetUp() void SetUp()
{ {
rclcpp::init(0, nullptr); rclcpp::init(0, nullptr);
node = std::make_shared<rclcpp::Node>("node", "ns");
node_waitables =
dynamic_cast<rclcpp::node_interfaces::NodeWaitables *>(
node->get_node_waitables_interface().get());
ASSERT_NE(nullptr, node_waitables);
} }
void TearDown() void TearDown()
{ {
rclcpp::shutdown(); rclcpp::shutdown();
} }
protected:
std::shared_ptr<rclcpp::Node> node;
rclcpp::node_interfaces::NodeWaitables * node_waitables;
}; };
TEST_F(TestNodeWaitables, add_remove_waitable) 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"); 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_group1 = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
@ -60,9 +66,25 @@ TEST_F(TestNodeWaitables, add_remove_waitable)
auto waitable = std::make_shared<TestWaitable>(); auto waitable = std::make_shared<TestWaitable>();
EXPECT_NO_THROW( EXPECT_NO_THROW(
node_waitables->add_waitable(waitable, callback_group1)); node_waitables->add_waitable(waitable, callback_group1));
EXPECT_THROW( RCLCPP_EXPECT_THROW_EQ(
node_waitables->add_waitable(waitable, callback_group2), node_waitables->add_waitable(waitable, callback_group2),
std::runtime_error); std::runtime_error("Cannot create waitable, group not in node."));
EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group1)); EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group1));
EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group2)); EXPECT_NO_THROW(node_waitables->remove_waitable(waitable, callback_group2));
auto waitable2 = std::make_shared<TestWaitable>();
EXPECT_NO_THROW(node_waitables->add_waitable(waitable2, nullptr));
EXPECT_NO_THROW(node_waitables->remove_waitable(waitable2, nullptr));
}
TEST_F(TestNodeWaitables, add_waitable_rcl_trigger_guard_condition_error)
{
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto waitable = std::make_shared<TestWaitable>();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_waitables->add_waitable(waitable, callback_group),
std::runtime_error("Failed to notify wait set on waitable creation: error not set"));
} }