From 72389f872b0eba33897158ba8b8d73c04afa2165 Mon Sep 17 00:00:00 2001 From: Stephen Brawner Date: Tue, 28 Jul 2020 16:58:08 -0700 Subject: [PATCH] Add fault injection macros and unit tests to rcl_action Signed-off-by: Stephen Brawner --- rcl_action/CMakeLists.txt | 4 +- rcl_action/src/rcl_action/goal_handle.c | 10 +++ rcl_action/src/rcl_action/types.c | 5 ++ .../test/rcl_action/test_action_client.cpp | 52 ++++++++++++- .../rcl_action/test_action_communication.cpp | 58 +++++++++++++++ .../test/rcl_action/test_action_server.cpp | 66 +++++++++++++++++ rcl_action/test/rcl_action/test_graph.cpp | 73 +++++++++++++++++++ 7 files changed, 266 insertions(+), 2 deletions(-) diff --git a/rcl_action/CMakeLists.txt b/rcl_action/CMakeLists.txt index 783ee737de..9465202e6a 100644 --- a/rcl_action/CMakeLists.txt +++ b/rcl_action/CMakeLists.txt @@ -81,6 +81,7 @@ if(BUILD_TESTING) # Gtests ament_add_gtest(test_action_client test/rcl_action/test_action_client.cpp + TIMEOUT 360 ) if(TARGET test_action_client) target_include_directories(test_action_client PUBLIC @@ -107,7 +108,7 @@ if(BUILD_TESTING) function(custom_test_c target) ament_add_gtest( "${target}${target_suffix}" ${ARGN} - TIMEOUT 60 + TIMEOUT 180 ENV RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation} RMW_IMPLEMENTATION=${rmw_implementation} @@ -143,6 +144,7 @@ if(BUILD_TESTING) ament_add_gtest(test_action_server test/rcl_action/test_action_server.cpp + TIMEOUT 120 ) if(TARGET test_action_server) target_include_directories(test_action_server PUBLIC diff --git a/rcl_action/src/rcl_action/goal_handle.c b/rcl_action/src/rcl_action/goal_handle.c index f86f96cba3..4dab6f679c 100644 --- a/rcl_action/src/rcl_action/goal_handle.c +++ b/rcl_action/src/rcl_action/goal_handle.c @@ -42,6 +42,10 @@ rcl_action_goal_handle_init( const rcl_action_goal_info_t * goal_info, rcl_allocator_t allocator) { + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT); + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_INIT); + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC); + RCL_CHECK_ARGUMENT_FOR_NULL(goal_handle, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(goal_info, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); @@ -103,6 +107,9 @@ rcl_action_goal_handle_get_info( const rcl_action_goal_handle_t * goal_handle, rcl_action_goal_info_t * goal_info) { + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ACTION_GOAL_HANDLE_INVALID); + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT); + if (!rcl_action_goal_handle_is_valid(goal_handle)) { return RCL_RET_ACTION_GOAL_HANDLE_INVALID; // error message is set } @@ -117,6 +124,9 @@ rcl_action_goal_handle_get_status( const rcl_action_goal_handle_t * goal_handle, rcl_action_goal_state_t * status) { + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ACTION_GOAL_HANDLE_INVALID); + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT); + if (!rcl_action_goal_handle_is_valid(goal_handle)) { return RCL_RET_ACTION_GOAL_HANDLE_INVALID; // error message is set } diff --git a/rcl_action/src/rcl_action/types.c b/rcl_action/src/rcl_action/types.c index 03c9cbeef0..e6df168057 100644 --- a/rcl_action/src/rcl_action/types.c +++ b/rcl_action/src/rcl_action/types.c @@ -19,6 +19,7 @@ extern "C" #include "rcl_action/types.h" #include "rcl/error_handling.h" +#include "rcutils/macros.h" rcl_action_goal_info_t rcl_action_get_zero_initialized_goal_info(void) @@ -96,6 +97,10 @@ rcl_action_cancel_response_init( const size_t num_goals_canceling, const rcl_allocator_t allocator) { + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT); + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_INIT); + RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC); + RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT); // Size of array to allocate must be greater than 0 diff --git a/rcl_action/test/rcl_action/test_action_client.cpp b/rcl_action/test/rcl_action/test_action_client.cpp index 5970cfe77a..b6c6f9cf6c 100644 --- a/rcl_action/test/rcl_action/test_action_client.cpp +++ b/rcl_action/test/rcl_action/test_action_client.cpp @@ -14,11 +14,14 @@ #include +#include + #include "rcl_action/action_client.h" #include "rcl_action/action_client_impl.h" #include "rcl/error_handling.h" #include "rcl/rcl.h" +#include "rcutils/testing/fault_injection.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "test_msgs/action/fibonacci.h" @@ -80,7 +83,6 @@ class TestActionClientBaseFixture : public ::testing::Test rcl_node_t node; }; - TEST_F(TestActionClientBaseFixture, test_action_client_init_fini) { rcl_ret_t ret = RCL_RET_OK; rcl_action_client_t invalid_action_client = @@ -349,3 +351,51 @@ TEST_F(TestActionClientFixture, test_action_client_get_options) { options = rcl_action_client_get_options(&this->action_client); ASSERT_NE(options, nullptr) << rcl_get_error_string().str; } + + +TEST_F(TestActionClientBaseFixture, test_action_client_init_fini_maybe_fail) +{ + RCUTILS_FAULT_INJECTION_TEST( + { + int count = RCUTILS_FAULT_INJECTION_GET_COUNT(); + rcl_node_t node = rcl_get_zero_initialized_node(); + rcl_node_options_t node_options = rcl_node_get_default_options(); + std::string node_name = std::string("test_action_client_node_") + std::to_string(count); + rcl_ret_t ret = rcl_node_init(&node, node_name.c_str(), "", &this->context, &node_options); + if (RCL_RET_OK != ret) { + continue; + } + const rosidl_action_type_support_t * action_typesupport = ROSIDL_GET_ACTION_TYPE_SUPPORT( + test_msgs, Fibonacci); + std::string action_name = std::string("test_action_client_name_") + std::to_string(count); + rcl_action_client_t action_client = rcl_action_get_zero_initialized_client(); + rcl_action_client_options_t action_client_options = rcl_action_client_get_default_options(); + + ret = rcl_action_client_init( + &action_client, + &node, + action_typesupport, + action_name.c_str(), + &action_client_options); + + if (RCL_RET_OK == ret) { + ret = rcl_action_client_fini(&action_client, &node); + } else { + EXPECT_TRUE(rcl_error_is_set()); + rcl_reset_error(); + } + EXPECT_EQ(RCL_RET_OK, rcl_node_fini(&node)); + }); +} + +TEST_F(TestActionClientFixture, test_action_server_is_available_maybe_fail) +{ + RCUTILS_FAULT_INJECTION_TEST( + { + bool is_available = false; + rcl_ret_t ret = rcl_action_server_is_available( + &this->node, &this->action_client, &is_available); + (void)ret; + rcl_reset_error(); + }); +} diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index d91d691858..c652c54dd5 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -1106,3 +1106,61 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_stat ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; action_msgs__msg__GoalStatusArray__fini(&incoming_status_array); } + +TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedback_comm_maybe_fail) +{ + test_msgs__action__Fibonacci_FeedbackMessage outgoing_feedback; + test_msgs__action__Fibonacci_FeedbackMessage incoming_feedback; + test_msgs__action__Fibonacci_FeedbackMessage__init(&outgoing_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__init(&incoming_feedback); + + // Initialize feedback + ASSERT_TRUE( + rosidl_runtime_c__int32__Sequence__init( + &outgoing_feedback.feedback.sequence, 3)); + outgoing_feedback.feedback.sequence.data[0] = 0; + outgoing_feedback.feedback.sequence.data[1] = 1; + outgoing_feedback.feedback.sequence.data[2] = 2; + init_test_uuid0(outgoing_feedback.goal_id.uuid); + + RCUTILS_FAULT_INJECTION_TEST( + { + // Publish feedback with valid arguments + rcl_ret_t ret = rcl_action_publish_feedback(&this->action_server, &outgoing_feedback); + if (RCL_RET_OK != ret) { + continue; + } + + ret = rcl_action_wait_set_add_action_client( + &this->wait_set, &this->action_client, NULL, NULL); + if (RCL_RET_OK != ret) { + continue; + } + + ret = rcl_wait(&this->wait_set, RCL_S_TO_NS(10)); + if (RCL_RET_OK != ret) { + continue; + } + + ret = rcl_action_client_wait_set_get_entities_ready( + &this->wait_set, + &this->action_client, + &this->is_feedback_ready, + &this->is_status_ready, + &this->is_goal_response_ready, + &this->is_cancel_response_ready, + &this->is_result_response_ready); + if (RCL_RET_OK != ret) { + continue; + } + + // Take feedback with valid arguments + ret = rcl_action_take_feedback(&this->action_client, &incoming_feedback); + if (RCL_RET_OK != ret) { + continue; + } + + test_msgs__action__Fibonacci_FeedbackMessage__fini(&incoming_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__fini(&outgoing_feedback); + }); +} diff --git a/rcl_action/test/rcl_action/test_action_server.cpp b/rcl_action/test/rcl_action/test_action_server.cpp index b116e3a4a3..5a076cd55e 100644 --- a/rcl_action/test/rcl_action/test_action_server.cpp +++ b/rcl_action/test/rcl_action/test_action_server.cpp @@ -965,3 +965,69 @@ TEST_F(TestActionServerCancelPolicy, test_action_process_cancel_request_by_time_ EXPECT_TRUE(uuidcmp(goal_info_out->goal_id.uuid, cancel_request.goal_info.goal_id.uuid)); EXPECT_EQ(RCL_RET_OK, rcl_action_cancel_response_fini(&cancel_response)); } + +TEST_F(TestActionServer, action_server_init_fini_maybe_fail) +{ + rcl_allocator_t allocator = rcl_get_default_allocator(); + rcl_ret_t ret; + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, allocator); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_context_t 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; + + rcl_node_t node = rcl_get_zero_initialized_node(); + rcl_node_options_t node_options = rcl_node_get_default_options(); + ret = rcl_node_init(&node, "test_action_server_node", "", &context, &node_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_clock_t clock; + ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + const rosidl_action_type_support_t * ts = ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci); + const rcl_action_server_options_t options = rcl_action_server_get_default_options(); + const char * action_name = "test_action_server_name"; + + RCUTILS_FAULT_INJECTION_TEST( + { + rcl_action_server_t action_server = rcl_action_get_zero_initialized_server(); + rcl_ret_t ret = rcl_action_server_init( + &action_server, &node, &clock, ts, action_name, &options); + + if (RCL_RET_OK == ret) { + ret = rcl_action_server_fini(&action_server, &node); + } + }); +} + +TEST_F(TestActionServerCancelPolicy, test_action_process_cancel_request_maybe_fail) +{ + // Request to cancel all goals + rcl_action_cancel_request_t cancel_request = rcl_action_get_zero_initialized_cancel_request(); + cancel_request.goal_info.stamp.sec = 0; + cancel_request.goal_info.stamp.nanosec = 0u; + rcl_action_cancel_response_t cancel_response = rcl_action_get_zero_initialized_cancel_response(); + + RCUTILS_FAULT_INJECTION_TEST( + { + rcl_ret_t ret = rcl_action_process_cancel_request( + &this->action_server, &cancel_request, &cancel_response); + (void)ret; + EXPECT_EQ(RCL_RET_OK, rcl_action_cancel_response_fini(&cancel_response)); + }); +} + +TEST_F(TestActionServerCancelPolicy, test_action_expire_goals_maybe_fail) +{ + const size_t capacity = 10u; + rcl_action_goal_info_t expired_goals[10u]; + size_t num_expired = 42u; + + RCUTILS_FAULT_INJECTION_TEST( + { + rcl_ret_t ret = rcl_action_expire_goals( + &this->action_server, expired_goals, capacity, &num_expired); + (void)ret; + rcl_reset_error(); + }); +} diff --git a/rcl_action/test/rcl_action/test_graph.cpp b/rcl_action/test/rcl_action/test_graph.cpp index 95fb64baf0..b7a2b57205 100644 --- a/rcl_action/test/rcl_action/test_graph.cpp +++ b/rcl_action/test/rcl_action/test_graph.cpp @@ -24,6 +24,7 @@ #include "rcl/error_handling.h" #include "rcl/rcl.h" +#include "rcutils/testing/fault_injection.h" #include "osrf_testing_tools_cpp/scope_exit.hpp" @@ -593,3 +594,75 @@ TEST_F(TestActionGraphMultiNodeFixture, test_action_get_client_names_and_types_b ret = rcl_names_and_types_fini(&nat); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } + +TEST_F(TestActionGraphMultiNodeFixture, get_names_and_types_maybe_fail) +{ + RCUTILS_FAULT_INJECTION_TEST( + { + rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); + rcl_ret_t ret = rcl_action_get_names_and_types(&this->node, &this->allocator, &nat); + if (RCL_RET_OK == ret) { + ret = rcl_names_and_types_fini(&nat); + if (ret != RCL_RET_OK) { + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + } + } + }); +} + +TEST_F(TestActionGraphMultiNodeFixture, action_client_init_maybe_fail) +{ + RCUTILS_FAULT_INJECTION_TEST( + { + const rosidl_action_type_support_t * action_typesupport = ROSIDL_GET_ACTION_TYPE_SUPPORT( + test_msgs, Fibonacci); + + rcl_action_client_t action_client = rcl_action_get_zero_initialized_client(); + rcl_action_client_options_t action_client_options = rcl_action_client_get_default_options(); + rcl_ret_t ret = rcl_action_client_init( + &action_client, + &this->remote_node, + action_typesupport, + this->action_name, + &action_client_options); + + if (RCL_RET_OK == ret) { + ret = rcl_action_client_fini(&action_client, &this->remote_node); + } + }); +} + +TEST_F(TestActionGraphMultiNodeFixture, rcl_get_client_names_and_types_by_node_maybe_fail) +{ + RCUTILS_FAULT_INJECTION_TEST( + { + rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); + rcl_ret_t ret = rcl_action_get_client_names_and_types_by_node( + &this->node, &this->allocator, this->test_graph_node_name, "", &nat); + if (RCL_RET_OK == ret) { + ret = rcl_names_and_types_fini(&nat); + if (ret != RCL_RET_OK) { + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + } + } + }); +} + +TEST_F(TestActionGraphMultiNodeFixture, rcl_get_server_names_and_types_by_node_maybe_fail) +{ + RCUTILS_FAULT_INJECTION_TEST( + { + rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); + rcl_ret_t ret = rcl_action_get_server_names_and_types_by_node( + &this->node, &this->allocator, this->test_graph_node_name, "", &nat); + if (RCL_RET_OK == ret) { + ret = rcl_names_and_types_fini(&nat); + if (ret != RCL_RET_OK) { + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + } + } + }); +}