Skip to content

Commit

Permalink
refactor to support init options and context (#313)
Browse files Browse the repository at this point in the history
* refactor to support init options and context

Signed-off-by: William Woodall <william@osrfoundation.org>

* fix security tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* pass context to timer api

Signed-off-by: William Woodall <william@osrfoundation.org>

* avoid custom main just for init/shutdown

Signed-off-by: William Woodall <william@osrfoundation.org>

* avoid terminate in ~thread on exceptions

Signed-off-by: William Woodall <william@osrfoundation.org>

* update expected output

Signed-off-by: William Woodall <william@osrfoundation.org>

* add missing fini in test fixture

Signed-off-by: William Woodall <william@osrfoundation.org>

* fixup pub/sub test fixture

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood authored Nov 30, 2018
1 parent 394f326 commit 2fb8a20
Show file tree
Hide file tree
Showing 23 changed files with 123 additions and 158 deletions.
4 changes: 4 additions & 0 deletions test_communication/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}")
Expand Down Expand Up @@ -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})
Expand Down
1 change: 1 addition & 0 deletions test_communication/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>launch</test_depend>
<test_depend>osrf_testing_tools_cpp</test_depend>
<test_depend>rcl</test_depend>
<test_depend>rclcpp</test_depend>
<test_depend>rclpy</test_depend>
Expand Down
27 changes: 22 additions & 5 deletions test_communication/test/test_messages_c.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <string>
#include <thread>

#include "osrf_testing_tools_cpp/scope_exit.hpp"

#include "rcl/subscription.h"
#include "rcl/publisher.h"

Expand Down Expand Up @@ -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;
}

Expand All @@ -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<typename MessageT>
void test_message_type(const char * topic_name, const rosidl_message_type_support_t * ts)
{
Expand Down
10 changes: 6 additions & 4 deletions test_communication/test/test_publisher_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <chrono>
#include <string>
#include <thread>
#include <vector>

#include "rclcpp/rclcpp.hpp"
Expand Down Expand Up @@ -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);
}
}

Expand Down Expand Up @@ -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<test_msgs::msg::Empty>(
node, message, messages_empty, received_messages);
Expand Down Expand Up @@ -202,11 +205,10 @@ int main(int argc, char ** argv)
publish<test_msgs::msg::Builtins>(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<float> diff = (end - start);
Expand Down
18 changes: 14 additions & 4 deletions test_rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}")
Expand Down Expand Up @@ -270,29 +280,29 @@ 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
${GTEST_LIBRARIES})

# 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
Expand Down
10 changes: 1 addition & 9 deletions test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -72,12 +73,3 @@ TEST(
single_message_pub_sub_fixture<test_rclcpp::msg::UInt32>(
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;
}
10 changes: 1 addition & 9 deletions test_rclcpp/test/test_client_scope_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
}
10 changes: 1 addition & 9 deletions test_rclcpp/test/test_client_scope_consistency_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
}
5 changes: 3 additions & 2 deletions test_rclcpp/test/test_client_wait_for_service_shutdown.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -35,14 +36,14 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) {

auto client = node->create_client<test_rclcpp::srv::AddTwoInts>("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();
}
14 changes: 5 additions & 9 deletions test_rclcpp/test/test_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand All @@ -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(
Expand All @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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;
}
Loading

0 comments on commit 2fb8a20

Please sign in to comment.