2121#include " rclcpp/node.hpp"
2222#include " rclcpp/node_interfaces/node_base.hpp"
2323#include " rclcpp/rclcpp.hpp"
24+ #include " rmw/validate_namespace.h"
25+ #include " rmw/validate_node_name.h"
26+
27+ #include " ../../mocking_utils/patch.hpp"
28+ #include " ../../utils/rclcpp_gtest_macros.hpp"
2429
2530class TestNodeBase : public ::testing::Test
2631{
@@ -36,6 +41,12 @@ class TestNodeBase : public ::testing::Test
3641 }
3742};
3843
44+ // Required for mocking_utils below
45+ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE (rcl_guard_condition_options_t , ==)
46+ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t , !=)
47+ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t , <)
48+ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t , >)
49+
3950TEST_F(TestNodeBase, construct_from_node)
4051{
4152 std::shared_ptr<rclcpp::Node> node = std::make_shared<rclcpp::Node>(" node" , " ns" );
@@ -58,3 +69,125 @@ TEST_F(TestNodeBase, construct_from_node)
5869 EXPECT_NE (nullptr , const_node_base->get_rcl_node_handle ());
5970 EXPECT_NE (nullptr , const_node_base->get_shared_rcl_node_handle ());
6071}
72+
73+ TEST_F (TestNodeBase, construct_destruct_rcl_guard_condition_init_error) {
74+ auto mock = mocking_utils::patch_and_return (
75+ " lib:rclcpp" , rcl_guard_condition_init, RCL_RET_ERROR);
76+ EXPECT_THROW (
77+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
78+ rclcpp::exceptions::RCLError);
79+ }
80+
81+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_error) {
82+ auto mock_node_init = mocking_utils::patch_and_return (
83+ " lib:rclcpp" , rcl_node_init, RCL_RET_ERROR);
84+
85+ // This function is called only if rcl_node_init fails, so both mocked functions are required
86+ // This just logs an error, so behavior shouldn't change
87+ auto mock_guard_condition_fini = mocking_utils::inject_on_return (
88+ " lib:rclcpp" , rcl_guard_condition_fini, RCL_RET_ERROR);
89+
90+ EXPECT_THROW (
91+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
92+ rclcpp::exceptions::RCLError);
93+ }
94+
95+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name) {
96+ auto mock_node_init = mocking_utils::patch_and_return (
97+ " lib:rclcpp" , rcl_node_init, RCL_RET_NODE_INVALID_NAME);
98+
99+ // `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME
100+ auto mock_validate_node_name = mocking_utils::patch_and_return (
101+ " lib:rclcpp" , rmw_validate_node_name, RMW_RET_ERROR);
102+
103+ EXPECT_THROW (
104+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
105+ rclcpp::exceptions::RCLError);
106+ }
107+
108+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name_invalid_argument) {
109+ auto mock_node_init = mocking_utils::patch_and_return (
110+ " lib:rclcpp" , rcl_node_init, RCL_RET_NODE_INVALID_NAME);
111+
112+ // `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME
113+ auto mock_validate_node_name = mocking_utils::patch_and_return (
114+ " lib:rclcpp" , rmw_validate_node_name, RMW_RET_INVALID_ARGUMENT);
115+
116+ EXPECT_THROW (
117+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
118+ rclcpp::exceptions::RCLInvalidArgument);
119+ }
120+
121+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_node_name_valid_rmw_node_name) {
122+ auto mock_node_init = mocking_utils::patch_and_return (
123+ " lib:rclcpp" , rcl_node_init, RCL_RET_NODE_INVALID_NAME);
124+
125+ // `rmw_validate_node_name` is only called if `rcl_node_init` returns INVALID_NAME
126+ auto mock = mocking_utils::patch (
127+ " lib:rclcpp" , rmw_validate_node_name, [](const char *, int * validation_result, size_t *)
128+ {
129+ *validation_result = RMW_NODE_NAME_VALID;
130+ return RMW_RET_OK;
131+ });
132+
133+ RCLCPP_EXPECT_THROW_EQ (
134+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
135+ std::runtime_error (" valid rmw node name but invalid rcl node name" ));
136+ }
137+
138+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace) {
139+ auto mock_node_init = mocking_utils::patch_and_return (
140+ " lib:rclcpp" , rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE);
141+
142+ // `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE
143+ auto mock_validate_namespace = mocking_utils::patch_and_return (
144+ " lib:rclcpp" , rmw_validate_namespace, RMW_RET_ERROR);
145+
146+ EXPECT_THROW (
147+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
148+ rclcpp::exceptions::RCLError);
149+ }
150+
151+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace_rmw_invalid_argument) {
152+ auto mock_node_init = mocking_utils::patch_and_return (
153+ " lib:rclcpp" , rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE);
154+
155+ // `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE
156+ auto mock_validate_namespace = mocking_utils::patch_and_return (
157+ " lib:rclcpp" , rmw_validate_namespace, RMW_RET_INVALID_ARGUMENT);
158+
159+ EXPECT_THROW (
160+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
161+ rclcpp::exceptions::RCLInvalidArgument);
162+ }
163+
164+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_rcl_invalid_namespace_valid_rmw_namespace) {
165+ auto mock_node_init = mocking_utils::patch_and_return (
166+ " lib:rclcpp" , rcl_node_init, RCL_RET_NODE_INVALID_NAMESPACE);
167+
168+ // `rmw_validate_namespace` is only called if `rcl_node_init` returns INVALID_NAMESPACE
169+ auto mock = mocking_utils::patch (
170+ " lib:rclcpp" , rmw_validate_namespace, [](const char *, int * validation_result, size_t *)
171+ {
172+ *validation_result = RMW_NAMESPACE_VALID;
173+ return RMW_RET_OK;
174+ });
175+
176+ RCLCPP_EXPECT_THROW_EQ (
177+ std::make_shared<rclcpp::Node>(" node" , " ns" ).reset (),
178+ std::runtime_error (" valid rmw node namespace but invalid rcl node namespace" ));
179+ }
180+
181+ TEST_F (TestNodeBase, construct_destruct_rcl_node_init_fini_error) {
182+ auto mock_node_fini = mocking_utils::inject_on_return (
183+ " lib:rclcpp" , rcl_node_fini, RCL_RET_ERROR);
184+
185+ EXPECT_NO_THROW (std::make_shared<rclcpp::Node>(" node" , " ns" ).reset ());
186+ }
187+
188+ TEST_F (TestNodeBase, construct_destruct_rcl_guard_condition_fini_error) {
189+ auto mock_node_fini = mocking_utils::inject_on_return (
190+ " lib:rclcpp" , rcl_guard_condition_fini, RCL_RET_ERROR);
191+
192+ EXPECT_NO_THROW (std::make_shared<rclcpp::Node>(" node" , " ns" ).reset ());
193+ }
0 commit comments