Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Call rclcpp::init and rclcpp::shutdown in each test for test_rclcpp #454

Merged
merged 3 commits into from
Dec 1, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 12 additions & 2 deletions test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,22 @@
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

class CLASSNAME (test_avoid_ros_namespace_conventions_qos, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

// Test communciation works with the avoid_ros_namespace_conventions QoS enabled.
TEST(
TEST_F(
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
14 changes: 12 additions & 2 deletions test_rclcpp/test/test_client_scope_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,18 @@

using namespace std::chrono_literals;

TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test) {
auto node = rclcpp::Node::make_shared("client_scope_regression_test");

// Extra scope so the first client will be deleted afterwards
Expand Down
14 changes: 12 additions & 2 deletions test_rclcpp/test/test_client_scope_consistency_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,20 @@

using namespace std::chrono_literals;

class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

// 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);}
TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_regression_test) {
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
14 changes: 12 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 @@ -29,9 +29,19 @@

using namespace std::chrono_literals;

class CLASSNAME (service_client, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

// rclcpp::shutdown() should wake up wait_for_service, even without spin.
TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) {
rclcpp::init(0, nullptr);
TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) {
auto node = rclcpp::Node::make_shared("wait_for_service_shutdown");

auto client = node->create_client<test_rclcpp::srv::AddTwoInts>("wait_for_service_shutdown");
Expand Down
26 changes: 16 additions & 10 deletions test_rclcpp/test/test_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,18 @@

using namespace std::chrono_literals;

TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
class CLASSNAME (test_executor, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) {
rclcpp::executors::SingleThreadedExecutor executor;
auto node = rclcpp::Node::make_shared("recursive_spin_call");
auto timer = node->create_wall_timer(
Expand All @@ -56,8 +66,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), recursive_spin_call) {
executor.spin();
}

TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) {
rclcpp::executors::SingleThreadedExecutor executor;
auto node = rclcpp::Node::make_shared("spin_some_max_duration");
auto lambda = []() {
Expand All @@ -80,8 +89,7 @@ TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), spin_some_max_duration) {
ASSERT_GT(max_duration + 500ms, end - start);
}

TEST(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multithreaded_spin_call) {
rclcpp::executors::SingleThreadedExecutor executor;
auto node = rclcpp::Node::make_shared("multithreaded_spin_call");
std::mutex m;
Expand Down Expand Up @@ -113,8 +121,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);}
TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), multiple_executors) {
std::atomic_uint counter1;
counter1 = 0;
std::atomic_uint counter2;
Expand Down Expand Up @@ -174,8 +181,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);}
TEST_F(CLASSNAME(test_executor, RMW_IMPLEMENTATION), notify) {
rclcpp::executors::SingleThreadedExecutor executor;
auto executor_spin_lambda = [&executor]() {
executor.spin();
Expand Down
14 changes: 11 additions & 3 deletions test_rclcpp/test/test_intra_process.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,18 @@
static const std::chrono::milliseconds sleep_per_loop(10);
static const int max_loops = 200;

TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_usage) {
rclcpp::init(0, nullptr);
class CLASSNAME (test_intra_process_within_one_node, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

TEST_F(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_usage) {
// use intra process = true
auto node = rclcpp::Node::make_shared(
"test_intra_process",
Expand Down Expand Up @@ -164,5 +173,4 @@ TEST(CLASSNAME(test_intra_process_within_one_node, RMW_IMPLEMENTATION), nominal_
printf("spin_node_some() - no callbacks expected\n");
executor.spin_node_some(node);
ASSERT_EQ(5, counter);
rclcpp::shutdown();
}
35 changes: 19 additions & 16 deletions test_rclcpp/test/test_local_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,18 @@ using namespace std::chrono_literals;
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
class CLASSNAME (test_local_parameters, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
rclcpp::Parameter pv("foo", "bar");
rclcpp::Parameter pv2("foo2", "bar2");
std::string json_dict = std::to_string(pv);
Expand Down Expand Up @@ -65,8 +75,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
std::to_string(pv).c_str());
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous");
declare_test_parameters(node);
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
Expand All @@ -77,8 +86,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
test_get_parameters_sync(parameters_client);
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) {
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated");
declare_test_parameters(node);
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
Expand All @@ -92,8 +100,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);}
TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) {
auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous"));
declare_test_parameters(node);
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
Expand Down Expand Up @@ -153,8 +160,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);}
TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_callback) {
auto node = std::make_shared<ParametersAsyncNode>();
if (!node->parameters_client_->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
Expand All @@ -166,8 +172,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_call
executor.spin();
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
node->declare_parameter("foo");
node->declare_parameter("bar");
Expand Down Expand Up @@ -290,8 +295,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
EXPECT_EQ(barfoo[2], 5);
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) {
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
node->declare_parameter("foo");
node->declare_parameter("bar");
Expand Down Expand Up @@ -364,8 +368,7 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primiti
EXPECT_EQ(barfoo[2], 5);
}

TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant_type) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant_type) {
using rclcpp::Parameter;

auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
Expand Down
31 changes: 25 additions & 6 deletions test_rclcpp/test/test_multiple_service_calls.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,18 @@ void handle_add_two_ints(
response->sum = request->a + request->b;
}

TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
class CLASSNAME (test_two_service_calls, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls) {
auto node = rclcpp::Node::make_shared("test_two_service_calls");

auto service = node->create_service<test_rclcpp::srv::AddTwoInts>(
Expand Down Expand Up @@ -86,8 +96,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);}
TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_call) {
auto node = rclcpp::Node::make_shared("test_recursive_service_call");

auto service = node->create_service<test_rclcpp::srv::AddTwoInts>(
Expand Down Expand Up @@ -134,8 +143,18 @@ TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_ca
EXPECT_TRUE(second_result_received);
}

TEST(CLASSNAME(test_multiple_service_calls, RMW_IMPLEMENTATION), multiple_clients) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
class CLASSNAME (test_multiple_service_calls, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

TEST_F(CLASSNAME(test_multiple_service_calls, RMW_IMPLEMENTATION), multiple_clients) {
const uint32_t n = 5;

auto node = rclcpp::Node::make_shared("test_multiple_clients");
Expand Down
26 changes: 16 additions & 10 deletions test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,17 @@

using namespace std::chrono_literals;

class CLASSNAME (test_multithreaded, RMW_IMPLEMENTATION) : public ::testing::Test {
public:
static void SetUpTestCase() {
rclcpp::init(0, nullptr);
}

static void TearDownTestCase() {
rclcpp::shutdown();
}
};

static inline void multi_consumer_pub_sub_test(bool intra_process)
{
std::string node_topic_name = "multi_consumer";
Expand Down Expand Up @@ -139,20 +150,17 @@ static inline void multi_consumer_pub_sub_test(bool intra_process)
EXPECT_EQ(expected_count, counter.load());
}

TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_single_producer) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_single_producer) {
// 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);}
TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_intra_process) {
// 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);}
TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) {
// multiple clients, single server
auto node = rclcpp::Node::make_shared("multi_consumer_clients");
rclcpp::executors::MultiThreadedExecutor executor;
Expand Down Expand Up @@ -330,12 +338,10 @@ static inline void multi_access_publisher(bool intra_process)
ASSERT_EQ(subscription_counter, timer_counter.load());
}

TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher) {
multi_access_publisher(false);
}

TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher_intra_process) {
if (!rclcpp::ok()) {rclcpp::init(0, nullptr);}
TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_access_publisher_intra_process) {
multi_access_publisher(true);
}
Loading