Skip to content

Commit 974772e

Browse files
authored
Add coverage tests context functions (#1321)
* Add basic tests context access * Add expected interrupt_guard get/release * Add mocking utilities to rclcpp * Add tests interrupt_guard_condition * Add tests ini/fini error context * Add destructor test error * Create context directly in block* Use scope exit to clean context Signed-off-by: Jorge Perez <[email protected]>
1 parent 3defa8f commit 974772e

File tree

2 files changed

+132
-1
lines changed

2 files changed

+132
-1
lines changed

rclcpp/test/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -480,7 +480,7 @@ ament_add_gtest(test_utilities rclcpp/test_utilities.cpp
480480
if(TARGET test_utilities)
481481
ament_target_dependencies(test_utilities
482482
"rcl")
483-
target_link_libraries(test_utilities ${PROJECT_NAME})
483+
target_link_libraries(test_utilities ${PROJECT_NAME} mimick)
484484
endif()
485485

486486
ament_add_gtest(test_init rclcpp/test_init.cpp

rclcpp/test/rclcpp/test_utilities.cpp

Lines changed: 131 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,15 @@
1717
#include <string>
1818
#include <memory>
1919

20+
#include "rcl/init.h"
21+
#include "rcl/logging.h"
22+
2023
#include "rclcpp/contexts/default_context.hpp"
2124
#include "rclcpp/exceptions.hpp"
2225
#include "rclcpp/utilities.hpp"
26+
#include "rclcpp/scope_exit.hpp"
27+
28+
#include "../mocking_utils/patch.hpp"
2329

2430
TEST(TestUtilities, remove_ros_arguments) {
2531
const char * const argv[] = {
@@ -78,3 +84,128 @@ TEST(TestUtilities, multi_init) {
7884
EXPECT_FALSE(rclcpp::ok(context1));
7985
EXPECT_FALSE(rclcpp::ok(context2));
8086
}
87+
88+
TEST(TestUtilities, test_context_basic_access) {
89+
auto context1 = std::make_shared<rclcpp::contexts::DefaultContext>();
90+
EXPECT_NE(nullptr, context1->get_init_options().get_rcl_init_options());
91+
EXPECT_EQ(0u, context1->get_on_shutdown_callbacks().size());
92+
EXPECT_EQ(std::string{""}, context1->shutdown_reason());
93+
}
94+
95+
TEST(TestUtilities, test_context_basic_access_const_methods) {
96+
auto context1 = std::make_shared<const rclcpp::contexts::DefaultContext>();
97+
98+
EXPECT_NE(nullptr, context1->get_init_options().get_rcl_init_options());
99+
EXPECT_EQ(0u, context1->get_on_shutdown_callbacks().size());
100+
// EXPECT_EQ(std::string{""}, context1->shutdown_reason()); not available for const
101+
}
102+
103+
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, ==)
104+
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, !=)
105+
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, >)
106+
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, <)
107+
108+
TEST(TestUtilities, test_context_release_interrupt_guard_condition) {
109+
auto context1 = std::make_shared<rclcpp::contexts::DefaultContext>();
110+
context1->init(0, nullptr);
111+
RCLCPP_SCOPE_EXIT(rclcpp::shutdown(context1););
112+
113+
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
114+
rcl_ret_t ret = rcl_wait_set_init(
115+
&wait_set, 0, 2, 0, 0, 0, 0, context1->get_rcl_context().get(),
116+
rcl_get_default_allocator());
117+
ASSERT_EQ(RCL_RET_OK, ret);
118+
119+
// Expected usage
120+
rcl_guard_condition_t * interrupt_guard_condition =
121+
context1->get_interrupt_guard_condition(&wait_set);
122+
EXPECT_NE(nullptr, interrupt_guard_condition);
123+
EXPECT_NO_THROW(context1->release_interrupt_guard_condition(&wait_set));
124+
125+
{
126+
auto mock = mocking_utils::patch_and_return(
127+
"lib:rclcpp", rcl_guard_condition_init, RCL_RET_ERROR);
128+
EXPECT_THROW(
129+
{interrupt_guard_condition = context1->get_interrupt_guard_condition(&wait_set);},
130+
rclcpp::exceptions::RCLError);
131+
}
132+
133+
{
134+
interrupt_guard_condition = context1->get_interrupt_guard_condition(&wait_set);
135+
auto mock = mocking_utils::inject_on_return(
136+
"lib:rclcpp", rcl_guard_condition_fini, RCL_RET_ERROR);
137+
EXPECT_THROW(
138+
{context1->release_interrupt_guard_condition(&wait_set);},
139+
rclcpp::exceptions::RCLError);
140+
}
141+
142+
{
143+
interrupt_guard_condition = context1->get_interrupt_guard_condition(&wait_set);
144+
auto mock = mocking_utils::inject_on_return(
145+
"lib:rclcpp", rcl_guard_condition_fini, RCL_RET_ERROR);
146+
EXPECT_NO_THROW({context1->release_interrupt_guard_condition(&wait_set, std::nothrow);});
147+
}
148+
149+
{
150+
EXPECT_THROW(
151+
context1->release_interrupt_guard_condition(nullptr),
152+
std::runtime_error);
153+
}
154+
155+
// Test it works after restore mocks
156+
interrupt_guard_condition = context1->get_interrupt_guard_condition(&wait_set);
157+
EXPECT_NE(nullptr, interrupt_guard_condition);
158+
EXPECT_NO_THROW(context1->release_interrupt_guard_condition(&wait_set));
159+
}
160+
161+
162+
TEST(TestUtilities, test_context_init_shutdown_fails) {
163+
{
164+
auto context = std::make_shared<rclcpp::contexts::DefaultContext>();
165+
auto context_fail_init = std::make_shared<rclcpp::contexts::DefaultContext>();
166+
auto mock = mocking_utils::patch_and_return(
167+
"lib:rclcpp", rcl_init, RCL_RET_ERROR);
168+
EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError);
169+
}
170+
171+
{
172+
auto context_fail_init = std::make_shared<rclcpp::contexts::DefaultContext>();
173+
auto mock = mocking_utils::patch_and_return(
174+
"lib:rclcpp", rcl_logging_configure_with_output_handler, RCL_RET_ERROR);
175+
EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError);
176+
}
177+
178+
{
179+
auto context = std::make_shared<rclcpp::contexts::DefaultContext>();
180+
context->init(0, nullptr);
181+
auto mock = mocking_utils::inject_on_return(
182+
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
183+
// This will log a message, no throw expected
184+
EXPECT_NO_THROW(context->shutdown(""));
185+
}
186+
187+
{
188+
auto context = std::make_shared<rclcpp::contexts::DefaultContext>();
189+
context->init(0, nullptr);
190+
auto mock = mocking_utils::inject_on_return(
191+
"lib:rclcpp", rcl_shutdown, RCL_RET_ERROR);
192+
EXPECT_THROW(context->shutdown(""), rclcpp::exceptions::RCLError);
193+
}
194+
195+
{
196+
auto context = std::make_shared<rclcpp::contexts::DefaultContext>();
197+
context->init(0, nullptr);
198+
auto mock = mocking_utils::inject_on_return(
199+
"lib:rclcpp", rcl_logging_fini, RCL_RET_ERROR);
200+
// This will log a message, no throw expected
201+
EXPECT_NO_THROW(context->shutdown(""));
202+
}
203+
204+
{
205+
auto context_to_destroy = std::make_shared<rclcpp::contexts::DefaultContext>();
206+
auto mock = mocking_utils::inject_on_return(
207+
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
208+
// This will log a message, no throw expected
209+
EXPECT_NO_THROW({context_to_destroy.reset();});
210+
}
211+
}

0 commit comments

Comments
 (0)