From 2fb8a204700ea99f9075fc0b6a84a00bfd987295 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Thu, 29 Nov 2018 21:33:57 -0800 Subject: [PATCH] refactor to support init options and context (#313) * refactor to support init options and context Signed-off-by: William Woodall * fix security tests Signed-off-by: William Woodall * pass context to timer api Signed-off-by: William Woodall * avoid custom main just for init/shutdown Signed-off-by: William Woodall * avoid terminate in ~thread on exceptions Signed-off-by: William Woodall * update expected output Signed-off-by: William Woodall * add missing fini in test fixture Signed-off-by: William Woodall * fixup pub/sub test fixture Signed-off-by: William Woodall --- test_communication/CMakeLists.txt | 4 +++ test_communication/package.xml | 1 + test_communication/test/test_messages_c.cpp | 27 +++++++++++++++---- .../test/test_publisher_subscriber.cpp | 10 ++++--- test_rclcpp/CMakeLists.txt | 18 ++++++++++--- ...st_avoid_ros_namespace_conventions_qos.cpp | 10 +------ test_rclcpp/test/test_client_scope_client.cpp | 10 +------ .../test_client_scope_consistency_client.cpp | 10 +------ .../test_client_wait_for_service_shutdown.cpp | 5 ++-- test_rclcpp/test/test_executor.cpp | 14 ++++------ test_rclcpp/test/test_local_parameters.cpp | 15 ++++++++--- .../test/test_multiple_service_calls.cpp | 12 +++------ test_rclcpp/test/test_multithreaded.cpp | 17 +++++------- test_rclcpp/test/test_publisher.cpp | 10 +------ test_rclcpp/test/test_remote_parameters.cpp | 12 +++------ test_rclcpp/test/test_services_client.cpp | 12 +++------ .../test/test_services_in_constructor.cpp | 12 ++------- ...ndler_before_shutdown__expected_output.txt | 2 +- test_rclcpp/test/test_spin.cpp | 15 ++++------- test_rclcpp/test/test_subscription.cpp | 22 +++++++-------- test_rclcpp/test/test_timer.cpp | 13 +++------ test_rclcpp/test/test_waitable.cpp | 19 ++++++------- .../test_invalid_secure_node_creation_c.cpp | 11 +++++--- 23 files changed, 123 insertions(+), 158 deletions(-) diff --git a/test_communication/CMakeLists.txt b/test_communication/CMakeLists.txt index 87412aa7..a6d52d4a 100644 --- a/test_communication/CMakeLists.txt +++ b/test_communication/CMakeLists.txt @@ -21,6 +21,7 @@ ament_auto_find_build_dependencies() if(BUILD_TESTING) find_package(ament_cmake REQUIRED) find_package(test_msgs REQUIRED) + find_package(osrf_testing_tools_cpp REQUIRED) ament_index_get_resource(interface_files "rosidl_interfaces" "test_msgs") string(REPLACE "\n" ";" interface_files "${interface_files}") @@ -124,6 +125,9 @@ if(BUILD_TESTING) RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} RMW_IMPLEMENTATION=${rmw_implementation}) if(TARGET ${target}${target_suffix}) + target_include_directories(${target}${target_suffix} + PUBLIC ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ) target_link_libraries(${target}${target_suffix} ${_AMENT_EXPORT_ABSOLUTE_LIBRARIES} ${_AMENT_EXPORT_LIBRARY_TARGETS}) diff --git a/test_communication/package.xml b/test_communication/package.xml index 99341852..0aef6be2 100644 --- a/test_communication/package.xml +++ b/test_communication/package.xml @@ -24,6 +24,7 @@ ament_lint_auto ament_lint_common launch + osrf_testing_tools_cpp rcl rclcpp rclpy diff --git a/test_communication/test/test_messages_c.cpp b/test_communication/test/test_messages_c.cpp index cea2a310..47a00f53 100644 --- a/test_communication/test/test_messages_c.cpp +++ b/test_communication/test/test_messages_c.cpp @@ -21,6 +21,8 @@ #include #include +#include "osrf_testing_tools_cpp/scope_exit.hpp" + #include "rcl/subscription.h" #include "rcl/publisher.h" @@ -83,17 +85,28 @@ make_scope_exit(Callable callable) class CLASSNAME (TestMessagesFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); - const char * name = "node_name"; + const char * name = "test_message_fixture_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -102,9 +115,13 @@ class CLASSNAME (TestMessagesFixture, RMW_IMPLEMENTATION) : public ::testing::Te rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } + template void test_message_type(const char * topic_name, const rosidl_message_type_support_t * ts) { diff --git a/test_communication/test/test_publisher_subscriber.cpp b/test_communication/test/test_publisher_subscriber.cpp index 593595fe..e6a17ef5 100644 --- a/test_communication/test/test_publisher_subscriber.cpp +++ b/test_communication/test/test_publisher_subscriber.cpp @@ -14,6 +14,7 @@ #include #include +#include #include #include "rclcpp/rclcpp.hpp" @@ -45,11 +46,9 @@ void publish( publisher->publish(messages[message_index]); ++message_index; message_rate.sleep(); - rclcpp::spin_some(node); } ++cycle_index; cycle_rate.sleep(); - rclcpp::spin_some(node); } } @@ -134,6 +133,10 @@ int main(int argc, char ** argv) auto messages_static_array_nested = get_messages_static_array_nested(); auto messages_builtins = get_messages_builtins(); + std::thread spin_thread([node]() { + rclcpp::spin(node); + }); + if (message == "Empty") { subscriber = subscribe( node, message, messages_empty, received_messages); @@ -202,11 +205,10 @@ int main(int argc, char ** argv) publish(node, message, messages_builtins); } else { fprintf(stderr, "Unknown message argument '%s'\n", message.c_str()); - rclcpp::shutdown(); return 1; } - rclcpp::spin_some(node); + spin_thread.join(); auto end = std::chrono::steady_clock::now(); std::chrono::duration diff = (end - start); diff --git a/test_rclcpp/CMakeLists.txt b/test_rclcpp/CMakeLists.txt index f64ca129..700b291b 100644 --- a/test_rclcpp/CMakeLists.txt +++ b/test_rclcpp/CMakeLists.txt @@ -66,6 +66,16 @@ if(BUILD_TESTING) "rclcpp") endfunction() + function(custom_gtest_executable target) + ament_add_gtest_executable(${target} ${ARGN}) + target_compile_definitions(${target} + PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}") + rosidl_target_interfaces(${target} + ${PROJECT_NAME} "rosidl_typesupport_cpp") + ament_target_dependencies(${target} + "rclcpp") + endfunction() + macro(custom_launch_test_two_executables test_name executable1 executable2) cmake_parse_arguments(_ARG "" "ARGS1;ARGS2;RMW1;RMW2" "" ${ARGN}) set(TEST_NAME "${test_name}") @@ -270,7 +280,7 @@ if(BUILD_TESTING) # Parameter tests single implementation custom_executable(test_parameters_server_cpp "test/test_parameters_server.cpp") - custom_executable(test_remote_parameters_cpp "test/test_remote_parameters.cpp") + custom_gtest_executable(test_remote_parameters_cpp "test/test_remote_parameters.cpp") target_include_directories(test_remote_parameters_cpp PUBLIC ${GTEST_INCLUDE_DIRS}) target_link_libraries(test_remote_parameters_cpp @@ -278,21 +288,21 @@ if(BUILD_TESTING) # Service tests single implementation custom_executable(test_services_server_cpp "test/test_services_server.cpp") - custom_executable(test_services_client_cpp "test/test_services_client.cpp") + custom_gtest_executable(test_services_client_cpp "test/test_services_client.cpp") target_include_directories(test_services_client_cpp PUBLIC ${GTEST_INCLUDE_DIRS}) target_link_libraries(test_services_client_cpp ${GTEST_LIBRARIES}) custom_executable(test_client_scope_server_cpp "test/test_client_scope_server.cpp") - custom_executable(test_client_scope_client_cpp "test/test_client_scope_client.cpp") + custom_gtest_executable(test_client_scope_client_cpp "test/test_client_scope_client.cpp") target_include_directories(test_client_scope_client_cpp PUBLIC ${GTEST_INCLUDE_DIRS}) target_link_libraries(test_client_scope_client_cpp ${GTEST_LIBRARIES}) custom_executable(test_client_scope_consistency_server_cpp "test/test_client_scope_consistency_server.cpp") - custom_executable(test_client_scope_consistency_client_cpp "test/test_client_scope_consistency_client.cpp") + custom_gtest_executable(test_client_scope_consistency_client_cpp "test/test_client_scope_consistency_client.cpp") target_include_directories(test_client_scope_consistency_client_cpp PUBLIC ${GTEST_INCLUDE_DIRS}) target_link_libraries(test_client_scope_consistency_client_cpp diff --git a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp index a69785f1..55536a2a 100644 --- a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp +++ b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp @@ -37,6 +37,7 @@ TEST( CLASSNAME(test_avoid_ros_namespace_conventions_qos, RMW_IMPLEMENTATION), pub_sub_works ) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} // topic name std::string topic_name = "test_avoid_ros_namespace_conventions_qos"; // code to create the callback and subscription @@ -72,12 +73,3 @@ TEST( single_message_pub_sub_fixture( topic_name, counter, create_subscription_func, publish_func, custom_qos); } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_client_scope_client.cpp b/test_rclcpp/test/test_client_scope_client.cpp index 99814832..329caa4a 100644 --- a/test_rclcpp/test/test_client_scope_client.cpp +++ b/test_rclcpp/test/test_client_scope_client.cpp @@ -31,6 +31,7 @@ using namespace std::chrono_literals; TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("client_scope_regression_test"); // Extra scope so the first client will be deleted afterwards @@ -89,12 +90,3 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test std::cout.flush(); } } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_client_scope_consistency_client.cpp b/test_rclcpp/test/test_client_scope_consistency_client.cpp index 33ee2a8e..181e709b 100644 --- a/test_rclcpp/test/test_client_scope_consistency_client.cpp +++ b/test_rclcpp/test/test_client_scope_consistency_client.cpp @@ -35,6 +35,7 @@ using namespace std::chrono_literals; // This test is concerned with the consistency of the two clients' behavior, not necessarily whether // or not they are successful. TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_regression_test) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("client_scope_consistency_regression_test"); // 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 std::cout.flush(); } } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp b/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp index 3d1906f2..cffea5a0 100644 --- a/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp +++ b/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp @@ -17,6 +17,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" +#include "rclcpp/scope_exit.hpp" #include "test_rclcpp/srv/add_two_ints.hpp" #ifdef RMW_IMPLEMENTATION @@ -35,14 +36,14 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) { auto client = node->create_client("wait_for_service_shutdown"); - auto shutdown_thread = std::thread( + std::thread shutdown_thread( []() { std::this_thread::sleep_for(1s); rclcpp::shutdown(); }); + RCLCPP_SCOPE_EXIT({shutdown_thread.join();}); auto start = std::chrono::steady_clock::now(); client->wait_for_service(15s); auto end = std::chrono::steady_clock::now(); ASSERT_LE(end - start, 10s); - shutdown_thread.join(); } diff --git a/test_rclcpp/test/test_executor.cpp b/test_rclcpp/test/test_executor.cpp index 9d5b68ff..fcee2e2b 100644 --- a/test_rclcpp/test/test_executor.cpp +++ b/test_rclcpp/test/test_executor.cpp @@ -40,6 +40,7 @@ using namespace std::chrono_literals; TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} rclcpp::executors::SingleThreadedExecutor executor; auto node = rclcpp::Node::make_shared("recursive_spin_call"); auto timer = node->create_wall_timer( @@ -55,6 +56,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) { } TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} rclcpp::executors::SingleThreadedExecutor executor; auto node = rclcpp::Node::make_shared("spin_some_max_duration"); auto timer = node->create_wall_timer( @@ -73,6 +75,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) { } TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} rclcpp::executors::SingleThreadedExecutor executor; auto node = rclcpp::Node::make_shared("multithreaded_spin_call"); std::mutex m; @@ -105,6 +108,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) { // Try spinning 2 single-threaded executors in two separate threads. TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multiple_executors) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::atomic_uint counter1; counter1 = 0; std::atomic_uint counter2; @@ -165,6 +169,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multiple_executors) { // Check that the executor is notified when a node adds a new timer, publisher, subscription, // service or client. TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), notify) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} rclcpp::executors::SingleThreadedExecutor executor; auto executor_spin_lambda = [&executor]() { executor.spin(); @@ -254,12 +259,3 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), notify) { // test removing a node // test notify with multiple nodes - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_local_parameters.cpp b/test_rclcpp/test/test_local_parameters.cpp index e8c737cc..1dd39f6c 100644 --- a/test_rclcpp/test/test_local_parameters.cpp +++ b/test_rclcpp/test/test_local_parameters.cpp @@ -34,6 +34,7 @@ using namespace std::chrono_literals; #endif TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} rclcpp::Parameter pv("foo", "bar"); rclcpp::Parameter pv2("foo2", "bar2"); std::string json_dict = std::to_string(pv); @@ -65,6 +66,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) { } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous"); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { @@ -75,6 +77,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) { } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated"); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { @@ -88,6 +91,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_rep } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous")); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { @@ -138,6 +142,7 @@ class ParametersAsyncNode : public rclcpp::Node // Regression test for calling parameter client async services, but having the specified callback // go out of scope before it gets called: see https://github.com/ros2/rclcpp/pull/414 TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_callback) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = std::make_shared(); if (!node->parameters_client_->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -150,6 +155,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_call } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { @@ -259,6 +265,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { @@ -322,6 +329,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primiti } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant_type) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); @@ -379,6 +387,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_get_parameter_or"); @@ -415,6 +424,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or) { } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or_set) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_get_parameter_or_set_default"); @@ -447,6 +457,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_parameter_or_set) } TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_set) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} using rclcpp::Parameter; auto node = rclcpp::Node::make_shared("test_parameters_set_parameter_if_not_set"); @@ -482,11 +493,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), set_parameter_if_not_ int main(int argc, char ** argv) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - // NOTE: use custom main to ensure that rclcpp::init is called only once - rclcpp::init(argc, argv); ::testing::InitGoogleTest(&argc, argv); int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); return ret; } diff --git a/test_rclcpp/test/test_multiple_service_calls.cpp b/test_rclcpp/test/test_multiple_service_calls.cpp index e26096b6..aaa10587 100644 --- a/test_rclcpp/test/test_multiple_service_calls.cpp +++ b/test_rclcpp/test/test_multiple_service_calls.cpp @@ -44,6 +44,7 @@ void handle_add_two_ints( } TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_two_service_calls"); auto service = node->create_service( @@ -86,6 +87,7 @@ TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls) { // Regression test for async client not being able to queue another request in a response callback. // See https://github.com/ros2/rclcpp/pull/415 TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_call) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_recursive_service_call"); auto service = node->create_service( @@ -133,6 +135,7 @@ TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_ca } TEST(CLASSNAME(test_multiple_service_calls, RMW_IMPLEMENTATION), multiple_clients) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} const uint32_t n = 5; auto node = rclcpp::Node::make_shared("test_multiple_clients"); @@ -190,12 +193,3 @@ TEST(CLASSNAME(test_multiple_service_calls, RMW_IMPLEMENTATION), multiple_client fflush(stdout); } } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index 558d5155..2c91bf4c 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -137,16 +137,19 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) } TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_single_producer) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} // multiple subscriptions, single publisher multi_consumer_pub_sub_test(false); } TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_intra_process) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} // multiple subscriptions, single publisher, intra-process multi_consumer_pub_sub_test(true); } TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} // multiple clients, single server auto node = rclcpp::Node::make_shared("multi_consumer_clients"); rclcpp::executors::MultiThreadedExecutor executor; @@ -252,6 +255,7 @@ static inline void multi_access_publisher(bool intra_process) { // Try to access the same publisher simultaneously auto context = std::make_shared(); + context->init(0, nullptr); std::string node_topic_name = "multi_access_publisher"; if (intra_process) { node_topic_name += "_intra_process"; @@ -323,20 +327,11 @@ static inline void multi_access_publisher(bool intra_process) } TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} multi_access_publisher(false); } TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher_intra_process) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} multi_access_publisher(true); } - - -int main(int argc, char ** argv) -{ - // use custom main to ensure that rclcpp::init is called only once - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_publisher.cpp b/test_rclcpp/test/test_publisher.cpp index 6ad78ec1..98c5b61c 100644 --- a/test_rclcpp/test/test_publisher.cpp +++ b/test_rclcpp/test/test_publisher.cpp @@ -34,6 +34,7 @@ // Short test for the const reference publish signature. TEST(CLASSNAME(test_publisher, RMW_IMPLEMENTATION), publish_with_const_reference) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} // topic name std::string topic_name = "test_publish_with_const_reference"; // code to create the callback and subscription @@ -67,12 +68,3 @@ TEST(CLASSNAME(test_publisher, RMW_IMPLEMENTATION), publish_with_const_reference single_message_pub_sub_fixture( topic_name, counter, create_subscription_func, publish_func); } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_remote_parameters.cpp b/test_rclcpp/test/test_remote_parameters.cpp index f02fab20..3b06c52f 100644 --- a/test_rclcpp/test/test_remote_parameters.cpp +++ b/test_rclcpp/test/test_remote_parameters.cpp @@ -32,6 +32,7 @@ using namespace std::chrono_literals; TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_async) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string test_server_name = "test_parameters_server"; // TODO(tfoote) make test_server name parameterizable // if (argc >= 2) { @@ -52,6 +53,7 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_async) { } TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_sync) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string test_server_name = "test_parameters_server"; auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_sync")); @@ -68,6 +70,7 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_sync) { } TEST(CLASSNAME(parameters, rmw_implementation), test_set_remote_parameters_atomically_sync) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string test_server_name = "test_parameters_server"; auto node = rclcpp::Node::make_shared(std::string("test_set_remote_parameters_atomically_sync")); @@ -82,12 +85,3 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_set_remote_parameters_atomi verify_test_parameters(parameters_client); } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_services_client.cpp b/test_rclcpp/test/test_services_client.cpp index bfd9830f..19424519 100644 --- a/test_rclcpp/test/test_services_client.cpp +++ b/test_rclcpp/test/test_services_client.cpp @@ -32,6 +32,7 @@ using namespace std::chrono_literals; TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_noreqid) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_services_client_no_reqid"); auto client = node->create_client("add_two_ints_noreqid"); @@ -52,6 +53,7 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_noreqid) { } TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_reqid) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_services_client_add_reqid"); auto client = node->create_client("add_two_ints_reqid"); @@ -72,6 +74,7 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_reqid) { } TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_services_client_return_request"); auto client = node->create_client( @@ -95,12 +98,3 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) { auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. ASSERT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_services_in_constructor.cpp b/test_rclcpp/test/test_services_in_constructor.cpp index dcb98dfc..e60e7e4f 100644 --- a/test_rclcpp/test/test_services_in_constructor.cpp +++ b/test_rclcpp/test/test_services_in_constructor.cpp @@ -54,6 +54,7 @@ class MyNodeWithService : public rclcpp::Node }; TEST(CLASSNAME(test_services_in_constructor, RMW_IMPLEMENTATION), service_in_constructor) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto n = std::make_shared(); } @@ -71,15 +72,6 @@ class MyNodeWithClient : public rclcpp::Node }; TEST(CLASSNAME(test_services_in_constructor, RMW_IMPLEMENTATION), client_in_constructor) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto n = std::make_shared(); } - -int main(int argc, char ** argv) -{ - // NOTE: use custom main to ensure that rclcpp::init is called only once - rclcpp::init(0, nullptr); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_signal_handler_before_shutdown__expected_output.txt b/test_rclcpp/test/test_signal_handler_before_shutdown__expected_output.txt index ea29c6c4..511c8e36 100644 --- a/test_rclcpp/test/test_signal_handler_before_shutdown__expected_output.txt +++ b/test_rclcpp/test/test_signal_handler_before_shutdown__expected_output.txt @@ -1,7 +1,7 @@ Registered custom signal handler. Called rclcpp::init. Waiting to give an opportunity for interrupt... -signal_handler(2) +[INFO] [rclcpp]: signal_handler(signal_value=2) Custom sigint handler called. Calling rclcpp::shutdown... Called rclcpp::shutdown. diff --git a/test_rclcpp/test/test_spin.cpp b/test_rclcpp/test/test_spin.cpp index d1b33a57..d3b7e2ae 100644 --- a/test_rclcpp/test/test_spin.cpp +++ b/test_rclcpp/test/test_spin.cpp @@ -37,6 +37,7 @@ using namespace std::chrono_literals; Ensures that the timeout behavior of spin_until_future_complete is correct. */ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete_timeout) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} using rclcpp::executor::FutureReturnCode; rclcpp::executors::SingleThreadedExecutor executor; @@ -124,6 +125,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete_t } TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -145,6 +147,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { } TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_timeout) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -168,6 +171,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_timeou } TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_interrupted) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -191,6 +195,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_interr } TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), cancel) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("cancel"); rclcpp::executors::SingleThreadedExecutor executor; auto pub = node->create_publisher("cancel", 10); @@ -214,13 +219,3 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), cancel) { executor.add_node(node); executor.spin(); } - -int main(int argc, char ** argv) -{ - // NOTE: use custom main to ensure that rclcpp::init is called only once - rclcpp::init(0, nullptr); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_subscription.cpp b/test_rclcpp/test/test_subscription.cpp index 872402f4..1785df4e 100644 --- a/test_rclcpp/test/test_subscription.cpp +++ b/test_rclcpp/test/test_subscription.cpp @@ -56,6 +56,7 @@ void wait_for_future( } TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_subscription"); rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default; @@ -174,6 +175,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning // Shortened version of the test for the ConstSharedPtr callback signature TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_const) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string topic_name = "test_subscription_subscription_shared_ptr_const"; // create the callback and subscription int counter = 0; @@ -223,7 +225,9 @@ class CallbackHolder // Shortened version of the test for the ConstSharedPtr callback signature in a method TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), - subscription_shared_ptr_const_method_std_function) { + subscription_shared_ptr_const_method_std_function +) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string topic_name = "test_subscription_shared_ptr_const_method_std_function"; // create the callback and subscription CallbackHolder cb_holder; @@ -255,7 +259,9 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), // Shortened version of the test for the ConstSharedPtr callback signature in a method TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), - subscription_shared_ptr_const_method_direct) { + subscription_shared_ptr_const_method_direct +) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string topic_name = "test_subscription_shared_ptr_const_method_direct"; // create the callback and subscription CallbackHolder cb_holder; @@ -287,6 +293,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), // Shortened version of the test for the ConstSharedPtr with info callback signature TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_const_with_info) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string topic_name = "test_subscription_shared_ptr_const_method_direct"; // create the callback and subscription int counter = 0; @@ -322,6 +329,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_shared_ptr_c // Shortened version of the test for subscribing after spinning has started. TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), spin_before_subscription) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} std::string topic_name = "test_spin_before_subscription"; // create the callback and subscription int counter = 0; @@ -366,6 +374,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), spin_before_subscription) // Test of the queue size create_subscription signature. TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), create_subscription_with_queue_size) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_subscription"); auto callback = [](test_rclcpp::msg::UInt32::ConstSharedPtr) -> void {}; @@ -373,12 +382,3 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), create_subscription_with_ auto subscriber = node->create_subscription( "test_subscription", callback, 10); } - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_timer.cpp b/test_rclcpp/test/test_timer.cpp index b32b24c7..908746da 100644 --- a/test_rclcpp/test/test_timer.cpp +++ b/test_rclcpp/test/test_timer.cpp @@ -27,6 +27,7 @@ #endif TEST(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_fire_regularly) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_timer_fire_regularly"); int counter = 0; @@ -81,6 +82,7 @@ TEST(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_fire_regularly) { } TEST(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_during_wait) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("test_timer_during_wait"); int counter = 0; @@ -133,6 +135,7 @@ TEST(CLASSNAME(test_time, RMW_IMPLEMENTATION), timer_during_wait) { TEST(CLASSNAME(test_time, RMW_IMPLEMENTATION), finite_timer) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("finite_timer"); int counter = 0; @@ -164,13 +167,3 @@ TEST(CLASSNAME(test_time, RMW_IMPLEMENTATION), finite_timer) { EXPECT_EQ(counter, 2); } } - -int main(int argc, char ** argv) -{ - // NOTE: use custom main to ensure that rclcpp::init is called only once - rclcpp::init(0, nullptr); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_rclcpp/test/test_waitable.cpp b/test_rclcpp/test/test_waitable.cpp index 9a307758..9da1578f 100644 --- a/test_rclcpp/test/test_waitable.cpp +++ b/test_rclcpp/test/test_waitable.cpp @@ -40,8 +40,13 @@ class WaitableWithTimer : public rclcpp::Waitable timer_.reset(new rcl_timer_t); *timer_ = rcl_get_zero_initialized_timer(); rcl_clock_t * clock_handle = clock->get_clock_handle(); - rcl_ret_t ret = rcl_timer_init(timer_.get(), clock_handle, period_nanoseconds, nullptr, - rcl_get_default_allocator()); + rcl_ret_t ret = rcl_timer_init( + timer_.get(), + clock_handle, + rclcpp::contexts::default_context::get_global_default_context()->get_rcl_context().get(), + period_nanoseconds, + nullptr, + rcl_get_default_allocator()); if (RCL_RET_OK != ret) { throw std::runtime_error("failed to create timer"); } @@ -85,6 +90,7 @@ class WaitableWithTimer : public rclcpp::Waitable }; // class WaitableWithTimer TEST(CLASSNAME(test_waitable, RMW_IMPLEMENTATION), waitable_with_timer) { + if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("waitable_with_timer"); auto waitable = WaitableWithTimer::make_shared(node->get_clock()); auto group = node->create_callback_group(rclcpp::callback_group::CallbackGroupType::Reentrant); @@ -95,12 +101,3 @@ TEST(CLASSNAME(test_waitable, RMW_IMPLEMENTATION), waitable_with_timer) { EXPECT_TRUE(fut.get()); } - -int main(int argc, char ** argv) -{ - rclcpp::init(0, nullptr); - ::testing::InitGoogleTest(&argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} diff --git a/test_security/test/test_invalid_secure_node_creation_c.cpp b/test_security/test/test_invalid_secure_node_creation_c.cpp index c47b8036..3e22ea45 100644 --- a/test_security/test/test_invalid_secure_node_creation_c.cpp +++ b/test_security/test/test_invalid_secure_node_creation_c.cpp @@ -71,6 +71,7 @@ void custom_putenv(const char * name, const char * value) class CLASSNAME (TestInvalidSecureNode, RMW_IMPLEMENTATION) : public ::testing::Test { public: + rcl_context_t context; rcl_node_t * node_ptr; void SetUp() { @@ -80,7 +81,7 @@ class CLASSNAME (TestInvalidSecureNode, RMW_IMPLEMENTATION) : public ::testing:: { rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; - ret = rcl_shutdown(); + ret = rcl_shutdown(&context); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -95,13 +96,17 @@ class CLASSNAME (TestInvalidSecureNode, RMW_IMPLEMENTATION) : public ::testing:: custom_putenv("ROS_SECURITY_ENABLE", ROS_SECURITY_ENABLE); custom_putenv("ROS_SECURITY_STRATEGY", ROS_SECURITY_STRATEGY); rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); // const char * name = "node_name"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, node_name, "", &node_options); + ret = rcl_node_init(this->node_ptr, node_name, "", &context, &node_options); if (should_fail_participant_creation) { ASSERT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; } else {