Skip to content

Commit 2fb8a20

Browse files
authored
refactor to support init options and context (#313)
* refactor to support init options and context Signed-off-by: William Woodall <[email protected]> * fix security tests Signed-off-by: William Woodall <[email protected]> * pass context to timer api Signed-off-by: William Woodall <[email protected]> * avoid custom main just for init/shutdown Signed-off-by: William Woodall <[email protected]> * avoid terminate in ~thread on exceptions Signed-off-by: William Woodall <[email protected]> * update expected output Signed-off-by: William Woodall <[email protected]> * add missing fini in test fixture Signed-off-by: William Woodall <[email protected]> * fixup pub/sub test fixture Signed-off-by: William Woodall <[email protected]>
1 parent 394f326 commit 2fb8a20

23 files changed

+123
-158
lines changed

Diff for: test_communication/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ ament_auto_find_build_dependencies()
2121
if(BUILD_TESTING)
2222
find_package(ament_cmake REQUIRED)
2323
find_package(test_msgs REQUIRED)
24+
find_package(osrf_testing_tools_cpp REQUIRED)
2425

2526
ament_index_get_resource(interface_files "rosidl_interfaces" "test_msgs")
2627
string(REPLACE "\n" ";" interface_files "${interface_files}")
@@ -124,6 +125,9 @@ if(BUILD_TESTING)
124125
RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation}
125126
RMW_IMPLEMENTATION=${rmw_implementation})
126127
if(TARGET ${target}${target_suffix})
128+
target_include_directories(${target}${target_suffix}
129+
PUBLIC ${osrf_testing_tools_cpp_INCLUDE_DIRS}
130+
)
127131
target_link_libraries(${target}${target_suffix}
128132
${_AMENT_EXPORT_ABSOLUTE_LIBRARIES}
129133
${_AMENT_EXPORT_LIBRARY_TARGETS})

Diff for: test_communication/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
<test_depend>ament_lint_auto</test_depend>
2525
<test_depend>ament_lint_common</test_depend>
2626
<test_depend>launch</test_depend>
27+
<test_depend>osrf_testing_tools_cpp</test_depend>
2728
<test_depend>rcl</test_depend>
2829
<test_depend>rclcpp</test_depend>
2930
<test_depend>rclpy</test_depend>

Diff for: test_communication/test/test_messages_c.cpp

+22-5
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
2121
#include <string>
2222
#include <thread>
2323

24+
#include "osrf_testing_tools_cpp/scope_exit.hpp"
25+
2426
#include "rcl/subscription.h"
2527
#include "rcl/publisher.h"
2628

@@ -83,17 +85,28 @@ make_scope_exit(Callable callable)
8385
class CLASSNAME (TestMessagesFixture, RMW_IMPLEMENTATION) : public ::testing::Test
8486
{
8587
public:
88+
rcl_context_t * context_ptr;
8689
rcl_node_t * node_ptr;
8790
void SetUp()
8891
{
8992
rcl_ret_t ret;
90-
ret = rcl_init(0, nullptr, rcl_get_default_allocator());
91-
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
93+
{
94+
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
95+
ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
96+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
97+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
98+
EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str;
99+
});
100+
this->context_ptr = new rcl_context_t;
101+
*this->context_ptr = rcl_get_zero_initialized_context();
102+
ret = rcl_init(0, nullptr, &init_options, this->context_ptr);
103+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
104+
}
92105
this->node_ptr = new rcl_node_t;
93106
*this->node_ptr = rcl_get_zero_initialized_node();
94-
const char * name = "node_name";
107+
const char * name = "test_message_fixture_node";
95108
rcl_node_options_t node_options = rcl_node_get_default_options();
96-
ret = rcl_node_init(this->node_ptr, name, "", &node_options);
109+
ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options);
97110
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
98111
}
99112

@@ -102,9 +115,13 @@ class CLASSNAME (TestMessagesFixture, RMW_IMPLEMENTATION) : public ::testing::Te
102115
rcl_ret_t ret = rcl_node_fini(this->node_ptr);
103116
delete this->node_ptr;
104117
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
105-
ret = rcl_shutdown();
118+
ret = rcl_shutdown(this->context_ptr);
119+
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
120+
ret = rcl_context_fini(this->context_ptr);
121+
delete this->context_ptr;
106122
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
107123
}
124+
108125
template<typename MessageT>
109126
void test_message_type(const char * topic_name, const rosidl_message_type_support_t * ts)
110127
{

Diff for: test_communication/test/test_publisher_subscriber.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
#include <chrono>
1616
#include <string>
17+
#include <thread>
1718
#include <vector>
1819

1920
#include "rclcpp/rclcpp.hpp"
@@ -45,11 +46,9 @@ void publish(
4546
publisher->publish(messages[message_index]);
4647
++message_index;
4748
message_rate.sleep();
48-
rclcpp::spin_some(node);
4949
}
5050
++cycle_index;
5151
cycle_rate.sleep();
52-
rclcpp::spin_some(node);
5352
}
5453
}
5554

@@ -134,6 +133,10 @@ int main(int argc, char ** argv)
134133
auto messages_static_array_nested = get_messages_static_array_nested();
135134
auto messages_builtins = get_messages_builtins();
136135

136+
std::thread spin_thread([node]() {
137+
rclcpp::spin(node);
138+
});
139+
137140
if (message == "Empty") {
138141
subscriber = subscribe<test_msgs::msg::Empty>(
139142
node, message, messages_empty, received_messages);
@@ -202,11 +205,10 @@ int main(int argc, char ** argv)
202205
publish<test_msgs::msg::Builtins>(node, message, messages_builtins);
203206
} else {
204207
fprintf(stderr, "Unknown message argument '%s'\n", message.c_str());
205-
rclcpp::shutdown();
206208
return 1;
207209
}
208210

209-
rclcpp::spin_some(node);
211+
spin_thread.join();
210212

211213
auto end = std::chrono::steady_clock::now();
212214
std::chrono::duration<float> diff = (end - start);

Diff for: test_rclcpp/CMakeLists.txt

+14-4
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,16 @@ if(BUILD_TESTING)
6666
"rclcpp")
6767
endfunction()
6868

69+
function(custom_gtest_executable target)
70+
ament_add_gtest_executable(${target} ${ARGN})
71+
target_compile_definitions(${target}
72+
PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}")
73+
rosidl_target_interfaces(${target}
74+
${PROJECT_NAME} "rosidl_typesupport_cpp")
75+
ament_target_dependencies(${target}
76+
"rclcpp")
77+
endfunction()
78+
6979
macro(custom_launch_test_two_executables test_name executable1 executable2)
7080
cmake_parse_arguments(_ARG "" "ARGS1;ARGS2;RMW1;RMW2" "" ${ARGN})
7181
set(TEST_NAME "${test_name}")
@@ -270,29 +280,29 @@ if(BUILD_TESTING)
270280

271281
# Parameter tests single implementation
272282
custom_executable(test_parameters_server_cpp "test/test_parameters_server.cpp")
273-
custom_executable(test_remote_parameters_cpp "test/test_remote_parameters.cpp")
283+
custom_gtest_executable(test_remote_parameters_cpp "test/test_remote_parameters.cpp")
274284
target_include_directories(test_remote_parameters_cpp
275285
PUBLIC ${GTEST_INCLUDE_DIRS})
276286
target_link_libraries(test_remote_parameters_cpp
277287
${GTEST_LIBRARIES})
278288

279289
# Service tests single implementation
280290
custom_executable(test_services_server_cpp "test/test_services_server.cpp")
281-
custom_executable(test_services_client_cpp "test/test_services_client.cpp")
291+
custom_gtest_executable(test_services_client_cpp "test/test_services_client.cpp")
282292
target_include_directories(test_services_client_cpp
283293
PUBLIC ${GTEST_INCLUDE_DIRS})
284294
target_link_libraries(test_services_client_cpp
285295
${GTEST_LIBRARIES})
286296

287297
custom_executable(test_client_scope_server_cpp "test/test_client_scope_server.cpp")
288-
custom_executable(test_client_scope_client_cpp "test/test_client_scope_client.cpp")
298+
custom_gtest_executable(test_client_scope_client_cpp "test/test_client_scope_client.cpp")
289299
target_include_directories(test_client_scope_client_cpp
290300
PUBLIC ${GTEST_INCLUDE_DIRS})
291301
target_link_libraries(test_client_scope_client_cpp
292302
${GTEST_LIBRARIES})
293303

294304
custom_executable(test_client_scope_consistency_server_cpp "test/test_client_scope_consistency_server.cpp")
295-
custom_executable(test_client_scope_consistency_client_cpp "test/test_client_scope_consistency_client.cpp")
305+
custom_gtest_executable(test_client_scope_consistency_client_cpp "test/test_client_scope_consistency_client.cpp")
296306
target_include_directories(test_client_scope_consistency_client_cpp
297307
PUBLIC ${GTEST_INCLUDE_DIRS})
298308
target_link_libraries(test_client_scope_consistency_client_cpp

Diff for: test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp

+1-9
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ TEST(
3737
CLASSNAME(test_avoid_ros_namespace_conventions_qos, RMW_IMPLEMENTATION),
3838
pub_sub_works
3939
) {
40+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
4041
// topic name
4142
std::string topic_name = "test_avoid_ros_namespace_conventions_qos";
4243
// code to create the callback and subscription
@@ -72,12 +73,3 @@ TEST(
7273
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
7374
topic_name, counter, create_subscription_func, publish_func, custom_qos);
7475
}
75-
76-
int main(int argc, char ** argv)
77-
{
78-
rclcpp::init(argc, argv);
79-
::testing::InitGoogleTest(&argc, argv);
80-
int ret = RUN_ALL_TESTS();
81-
rclcpp::shutdown();
82-
return ret;
83-
}

Diff for: test_rclcpp/test/test_client_scope_client.cpp

+1-9
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
using namespace std::chrono_literals;
3232

3333
TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test) {
34+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
3435
auto node = rclcpp::Node::make_shared("client_scope_regression_test");
3536

3637
// Extra scope so the first client will be deleted afterwards
@@ -89,12 +90,3 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test
8990
std::cout.flush();
9091
}
9192
}
92-
93-
int main(int argc, char ** argv)
94-
{
95-
rclcpp::init(argc, argv);
96-
::testing::InitGoogleTest(&argc, argv);
97-
int ret = RUN_ALL_TESTS();
98-
rclcpp::shutdown();
99-
return ret;
100-
}

Diff for: test_rclcpp/test/test_client_scope_consistency_client.cpp

+1-9
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ using namespace std::chrono_literals;
3535
// This test is concerned with the consistency of the two clients' behavior, not necessarily whether
3636
// or not they are successful.
3737
TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_regression_test) {
38+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
3839
auto node = rclcpp::Node::make_shared("client_scope_consistency_regression_test");
3940

4041
// Replicate the settings that caused https://github.com/ros2/system_tests/issues/153
@@ -123,12 +124,3 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_reg
123124
std::cout.flush();
124125
}
125126
}
126-
127-
int main(int argc, char ** argv)
128-
{
129-
rclcpp::init(argc, argv);
130-
::testing::InitGoogleTest(&argc, argv);
131-
int ret = RUN_ALL_TESTS();
132-
rclcpp::shutdown();
133-
return ret;
134-
}

Diff for: test_rclcpp/test/test_client_wait_for_service_shutdown.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "gtest/gtest.h"
1919
#include "rclcpp/rclcpp.hpp"
20+
#include "rclcpp/scope_exit.hpp"
2021
#include "test_rclcpp/srv/add_two_ints.hpp"
2122

2223
#ifdef RMW_IMPLEMENTATION
@@ -35,14 +36,14 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) {
3536

3637
auto client = node->create_client<test_rclcpp::srv::AddTwoInts>("wait_for_service_shutdown");
3738

38-
auto shutdown_thread = std::thread(
39+
std::thread shutdown_thread(
3940
[]() {
4041
std::this_thread::sleep_for(1s);
4142
rclcpp::shutdown();
4243
});
44+
RCLCPP_SCOPE_EXIT({shutdown_thread.join();});
4345
auto start = std::chrono::steady_clock::now();
4446
client->wait_for_service(15s);
4547
auto end = std::chrono::steady_clock::now();
4648
ASSERT_LE(end - start, 10s);
47-
shutdown_thread.join();
4849
}

Diff for: test_rclcpp/test/test_executor.cpp

+5-9
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040
using namespace std::chrono_literals;
4141

4242
TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) {
43+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
4344
rclcpp::executors::SingleThreadedExecutor executor;
4445
auto node = rclcpp::Node::make_shared("recursive_spin_call");
4546
auto timer = node->create_wall_timer(
@@ -55,6 +56,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) {
5556
}
5657

5758
TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) {
59+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
5860
rclcpp::executors::SingleThreadedExecutor executor;
5961
auto node = rclcpp::Node::make_shared("spin_some_max_duration");
6062
auto timer = node->create_wall_timer(
@@ -73,6 +75,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) {
7375
}
7476

7577
TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) {
78+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
7679
rclcpp::executors::SingleThreadedExecutor executor;
7780
auto node = rclcpp::Node::make_shared("multithreaded_spin_call");
7881
std::mutex m;
@@ -105,6 +108,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) {
105108

106109
// Try spinning 2 single-threaded executors in two separate threads.
107110
TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multiple_executors) {
111+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
108112
std::atomic_uint counter1;
109113
counter1 = 0;
110114
std::atomic_uint counter2;
@@ -165,6 +169,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multiple_executors) {
165169
// Check that the executor is notified when a node adds a new timer, publisher, subscription,
166170
// service or client.
167171
TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), notify) {
172+
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
168173
rclcpp::executors::SingleThreadedExecutor executor;
169174
auto executor_spin_lambda = [&executor]() {
170175
executor.spin();
@@ -254,12 +259,3 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), notify) {
254259
// test removing a node
255260

256261
// test notify with multiple nodes
257-
258-
int main(int argc, char ** argv)
259-
{
260-
rclcpp::init(argc, argv);
261-
::testing::InitGoogleTest(&argc, argv);
262-
int ret = RUN_ALL_TESTS();
263-
rclcpp::shutdown();
264-
return ret;
265-
}

0 commit comments

Comments
 (0)