Skip to content

Commit

Permalink
Add fault injection tests to construction/destroy APIs. (#144)
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <[email protected]>
  • Loading branch information
hidmic authored Oct 5, 2020
1 parent 9abac34 commit 4204ed5
Show file tree
Hide file tree
Showing 9 changed files with 331 additions and 33 deletions.
2 changes: 1 addition & 1 deletion test_rmw_implementation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ if(BUILD_TESTING)
ament_add_gtest(test_subscription${target_suffix}
test/test_subscription.cpp
ENV ${rmw_implementation_env_var}
TIMEOUT 80
TIMEOUT 120
)
target_compile_definitions(test_subscription${target_suffix}
PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}")
Expand Down
61 changes: 38 additions & 23 deletions test_rmw_implementation/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,44 @@ TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_with_bad_arguments) {
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}

TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_with_internal_errors) {
constexpr char service_name[] = "/test";
const rosidl_service_type_support_t * ts =
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
RCUTILS_FAULT_INJECTION_TEST(
{
rmw_client_t * client =
rmw_create_client(node, ts, service_name, &rmw_qos_profile_default);
if (client) {
RCUTILS_NO_FAULT_INJECTION(
{
rmw_ret_t ret = rmw_destroy_client(node, client);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});
} else {
rmw_reset_error();
}
});
}

TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), destroy_with_internal_errors) {
constexpr char service_name[] = "/test";
const rosidl_service_type_support_t * ts =
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
RCUTILS_FAULT_INJECTION_TEST(
{
rmw_client_t * client = nullptr;
RCUTILS_NO_FAULT_INJECTION(
{
client = rmw_create_client(node, ts, service_name, &rmw_qos_profile_default);
ASSERT_NE(nullptr, client) << rmw_get_error_string().str;
});
if (RMW_RET_OK != rmw_destroy_client(node, client)) {
rmw_reset_error();
}
});
}

class CLASSNAME (TestClientUse, RMW_IMPLEMENTATION)
: public CLASSNAME(TestClient, RMW_IMPLEMENTATION)
{
Expand Down Expand Up @@ -373,26 +411,3 @@ TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), service_server_is_available
ret = rmw_destroy_service(node, service);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}

TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), create_client_with_internal_errors)
{
RCUTILS_FAULT_INJECTION_TEST(
{
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
test_msgs, srv, BasicTypes);
rmw_client_t * client_fault = rmw_create_client(
node, ts, "/service_name_test",
&rmw_qos_profile_default);

int64_t count = rcutils_fault_injection_get_count();
rcutils_fault_injection_set_count(RCUTILS_FAULT_INJECTION_NEVER_FAIL);

if (client_fault != nullptr) {
rmw_ret_t ret = rmw_destroy_client(node, client_fault);
EXPECT_EQ(ret, RMW_RET_OK) << rcutils_get_error_string().str;
} else {
rmw_reset_error();
}
rcutils_fault_injection_set_count(count);
});
}
43 changes: 43 additions & 0 deletions test_rmw_implementation/test/test_create_destroy_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,16 @@

#include <gtest/gtest.h>

#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp"

#include "rcutils/allocator.h"
#include "rcutils/strdup.h"

#include "rmw/error_handling.h"
#include "rmw/rmw.h"

#include "./testing_macros.hpp"


#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
Expand Down Expand Up @@ -173,3 +177,42 @@ TEST_F(
ASSERT_NE(nullptr, node) << rmw_get_error_string().str;
EXPECT_EQ(RMW_RET_OK, rmw_destroy_node(node)) << rmw_get_error_string().str;
}

TEST_F(
CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION),
create_with_internal_errors) {
RCUTILS_FAULT_INJECTION_TEST(
{
constexpr char node_name[] = "my_node";
constexpr char node_namespace[] = "/my_ns";
rmw_node_t * node = rmw_create_node(&context, node_name, node_namespace);
if (node) {
RCUTILS_NO_FAULT_INJECTION(
{
rmw_ret_t ret = rmw_destroy_node(node);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});
} else {
rmw_reset_error();
}
});
}

TEST_F(
CLASSNAME(TestNodeConstructionDestruction, RMW_IMPLEMENTATION),
destroy_with_internal_errors) {
RCUTILS_FAULT_INJECTION_TEST(
{
constexpr char node_name[] = "my_node";
constexpr char node_namespace[] = "/my_ns";
rmw_node_t * node = nullptr;
RCUTILS_NO_FAULT_INJECTION(
{
node = rmw_create_node(&context, node_name, node_namespace);
ASSERT_NE(nullptr, node) << rmw_get_error_string().str;
});
if (RMW_RET_OK != rmw_destroy_node(node)) {
rmw_reset_error();
}
});
}
72 changes: 72 additions & 0 deletions test_rmw_implementation/test/test_init_shutdown.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,18 @@

#include <gtest/gtest.h>

#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp"

#include "rcutils/allocator.h"
#include "rcutils/error_handling.h"
#include "rcutils/macros.h"
#include "rcutils/strdup.h"

#include "rmw/error_handling.h"
#include "rmw/rmw.h"

#include "./testing_macros.hpp"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
Expand Down Expand Up @@ -170,3 +176,69 @@ TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_shutdown) {
ret = rmw_context_fini(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
}

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_with_internal_errors) {
RCUTILS_FAULT_INJECTION_TEST(
{
rmw_context_t context = rmw_get_zero_initialized_context();
rmw_ret_t ret = rmw_init(&options, &context);

RCUTILS_NO_FAULT_INJECTION(
{
if (RMW_RET_OK == ret) {
ret = rmw_shutdown(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
ret = rmw_context_fini(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
} else {
rmw_reset_error();
}
});
});
}

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), shutdown_with_internal_errors) {
RCUTILS_FAULT_INJECTION_TEST(
{
rmw_ret_t ret = RMW_RET_OK;
rmw_context_t context = rmw_get_zero_initialized_context();

RCUTILS_NO_FAULT_INJECTION(
{
ret = rmw_init(&options, &context);
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});

ret = rmw_shutdown(&context);

RCUTILS_NO_FAULT_INJECTION(
{
if (RMW_RET_OK != ret) {
rmw_reset_error();

ret = rmw_shutdown(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}
ret = rmw_context_fini(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});
});
}

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), context_fini_with_internal_errors) {
RCUTILS_FAULT_INJECTION_TEST(
{
rmw_context_t context = rmw_get_zero_initialized_context();
RCUTILS_NO_FAULT_INJECTION(
{
rmw_ret_t ret = rmw_init(&options, &context);
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
ret = rmw_shutdown(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});

if (RMW_RET_OK != rmw_context_fini(&context)) {
rmw_reset_error();
}
});
}
85 changes: 85 additions & 0 deletions test_rmw_implementation/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,10 @@
#include <gtest/gtest.h>

#include "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp"
#include "osrf_testing_tools_cpp/scope_exit.hpp"

#include "rcutils/allocator.h"
#include "rcutils/macros.h"
#include "rcutils/strdup.h"

#include "rmw/rmw.h"
Expand Down Expand Up @@ -82,6 +84,28 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_and_destroy) {
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}

TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_with_internal_errors) {
constexpr char topic_name[] = "/test";
const rosidl_message_type_support_t * ts =
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes);

RCUTILS_FAULT_INJECTION_TEST(
{
rmw_publisher_t * pub = nullptr;
rmw_publisher_options_t options = rmw_get_default_publisher_options();
pub = rmw_create_publisher(node, ts, topic_name, &rmw_qos_profile_default, &options);
if (pub) {
RCUTILS_NO_FAULT_INJECTION(
{
rmw_ret_t ret = rmw_destroy_publisher(node, pub);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});
} else {
rmw_reset_error();
}
});
}

TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), create_and_destroy_native) {
rmw_publisher_options_t options = rmw_get_default_publisher_options();
constexpr char topic_name[] = "test";
Expand Down Expand Up @@ -194,6 +218,26 @@ TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_bad_arguments)
rmw_reset_error();
}

TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), destroy_with_internal_errors) {
constexpr char topic_name[] = "/test";
const rosidl_message_type_support_t * ts =
ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes);

RCUTILS_FAULT_INJECTION_TEST(
{
rmw_publisher_t * pub = nullptr;
RCUTILS_NO_FAULT_INJECTION(
{
rmw_publisher_options_t options = rmw_get_default_publisher_options();
pub = rmw_create_publisher(node, ts, topic_name, &rmw_qos_profile_default, &options);
ASSERT_NE(nullptr, pub) << rmw_get_error_string().str;
});
if (RMW_RET_OK != rmw_destroy_publisher(node, pub)) {
rmw_reset_error();
}
});
}

TEST_F(CLASSNAME(TestPublisher, RMW_IMPLEMENTATION), get_actual_qos_from_system_defaults) {
rmw_publisher_options_t options = rmw_get_default_publisher_options();
constexpr char topic_name[] = "/test";
Expand Down Expand Up @@ -414,6 +458,20 @@ TEST_F(
test_msgs__msg__BasicTypes__fini(&input_message);
}

TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), publish_with_internal_errors) {
test_msgs__msg__BasicTypes message{};
ASSERT_TRUE(test_msgs__msg__BasicTypes__init(&message));
rmw_publisher_allocation_t * null_allocation{nullptr}; // still a valid allocation

RCUTILS_FAULT_INJECTION_TEST(
{
rmw_ret_t ret = rmw_publish(pub, &message, null_allocation);
if (RMW_RET_OK != ret) {
rmw_reset_error();
}
});
}

TEST_F(
CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION),
publish_serialized_message_with_bad_arguments) {
Expand Down Expand Up @@ -443,6 +501,33 @@ TEST_F(
RMW_RET_OK, rmw_serialized_message_fini(&serialized_message)) << rmw_get_error_string().str;
}

TEST_F(CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION), publish_serialized_with_internal_errors) {
test_msgs__msg__BasicTypes message{};
ASSERT_TRUE(test_msgs__msg__BasicTypes__init(&message));
rcutils_allocator_t default_allocator = rcutils_get_default_allocator();
rmw_serialized_message_t serialized_message = rmw_get_zero_initialized_serialized_message();
rmw_ret_t ret = rmw_serialized_message_init(&serialized_message, 0lu, &default_allocator);
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rmw_ret_t ret = rmw_serialized_message_fini(&serialized_message);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});
ret = rmw_serialize(&message, ts, &serialized_message);
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
rmw_publisher_allocation_t * null_allocation{nullptr}; // still a valid allocation

RCUTILS_FAULT_INJECTION_TEST(
{
ret = rmw_publish_serialized_message(
pub, &serialized_message, null_allocation);
if (RMW_RET_OK != ret) {
rmw_reset_error();
}
});
}


class CLASSNAME (TestPublisherUseLoan, RMW_IMPLEMENTATION)
: public CLASSNAME(TestPublisherUse, RMW_IMPLEMENTATION)
{
Expand Down
38 changes: 38 additions & 0 deletions test_rmw_implementation/test/test_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,44 @@ TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_with_bad_arguments) {
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}


TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), create_with_internal_errors) {
constexpr char service_name[] = "/test";
const rosidl_service_type_support_t * ts =
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
RCUTILS_FAULT_INJECTION_TEST(
{
rmw_service_t * srv = rmw_create_service(node, ts, service_name, &rmw_qos_profile_default);
if (srv) {
RCUTILS_NO_FAULT_INJECTION(
{
rmw_ret_t ret = rmw_destroy_service(node, srv);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
});
} else {
rmw_reset_error();
}
});
}

TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), destroy_with_internal_errors) {
constexpr char service_name[] = "/test";
const rosidl_service_type_support_t * ts =
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
RCUTILS_FAULT_INJECTION_TEST(
{
rmw_service_t * srv = nullptr;
RCUTILS_NO_FAULT_INJECTION(
{
srv = rmw_create_service(node, ts, service_name, &rmw_qos_profile_default);
ASSERT_NE(nullptr, srv) << rmw_get_error_string().str;
});
if (RMW_RET_OK != rmw_destroy_service(node, srv)) {
rmw_reset_error();
}
});
}

class CLASSNAME (TestServiceUse, RMW_IMPLEMENTATION)
: public CLASSNAME(TestService, RMW_IMPLEMENTATION)
{
Expand Down
Loading

0 comments on commit 4204ed5

Please sign in to comment.