Skip to content

Commit 523fc90

Browse files
committed
Add fault injection macros and unit tests to rcl_action
Signed-off-by: Stephen Brawner <brawner@gmail.com>
1 parent 9fb197f commit 523fc90

File tree

7 files changed

+265
-2
lines changed

7 files changed

+265
-2
lines changed

rcl_action/CMakeLists.txt

+3-1
Original file line numberDiff line numberDiff line change
@@ -81,6 +81,7 @@ if(BUILD_TESTING)
8181
# Gtests
8282
ament_add_gtest(test_action_client
8383
test/rcl_action/test_action_client.cpp
84+
TIMEOUT 360
8485
)
8586
if(TARGET test_action_client)
8687
target_include_directories(test_action_client PUBLIC
@@ -107,7 +108,7 @@ if(BUILD_TESTING)
107108
function(custom_test_c target)
108109
ament_add_gtest(
109110
"${target}${target_suffix}" ${ARGN}
110-
TIMEOUT 60
111+
TIMEOUT 180
111112
ENV
112113
RCL_ASSERT_RMW_ID_MATCHES=${rmw_implementation}
113114
RMW_IMPLEMENTATION=${rmw_implementation}
@@ -143,6 +144,7 @@ if(BUILD_TESTING)
143144

144145
ament_add_gtest(test_action_server
145146
test/rcl_action/test_action_server.cpp
147+
TIMEOUT 120
146148
)
147149
if(TARGET test_action_server)
148150
target_include_directories(test_action_server PUBLIC

rcl_action/src/rcl_action/goal_handle.c

+10
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,10 @@ rcl_action_goal_handle_init(
4242
const rcl_action_goal_info_t * goal_info,
4343
rcl_allocator_t allocator)
4444
{
45+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
46+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_INIT);
47+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
48+
4549
RCL_CHECK_ARGUMENT_FOR_NULL(goal_handle, RCL_RET_INVALID_ARGUMENT);
4650
RCL_CHECK_ARGUMENT_FOR_NULL(goal_info, RCL_RET_INVALID_ARGUMENT);
4751
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
@@ -103,6 +107,9 @@ rcl_action_goal_handle_get_info(
103107
const rcl_action_goal_handle_t * goal_handle,
104108
rcl_action_goal_info_t * goal_info)
105109
{
110+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ACTION_GOAL_HANDLE_INVALID);
111+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
112+
106113
if (!rcl_action_goal_handle_is_valid(goal_handle)) {
107114
return RCL_RET_ACTION_GOAL_HANDLE_INVALID; // error message is set
108115
}
@@ -117,6 +124,9 @@ rcl_action_goal_handle_get_status(
117124
const rcl_action_goal_handle_t * goal_handle,
118125
rcl_action_goal_state_t * status)
119126
{
127+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ACTION_GOAL_HANDLE_INVALID);
128+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
129+
120130
if (!rcl_action_goal_handle_is_valid(goal_handle)) {
121131
return RCL_RET_ACTION_GOAL_HANDLE_INVALID; // error message is set
122132
}

rcl_action/src/rcl_action/types.c

+5
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ extern "C"
1919
#include "rcl_action/types.h"
2020

2121
#include "rcl/error_handling.h"
22+
#include "rcutils/macros.h"
2223

2324
rcl_action_goal_info_t
2425
rcl_action_get_zero_initialized_goal_info(void)
@@ -96,6 +97,10 @@ rcl_action_cancel_response_init(
9697
const size_t num_goals_canceling,
9798
const rcl_allocator_t allocator)
9899
{
100+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
101+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_INIT);
102+
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
103+
99104
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
100105
RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT);
101106
// Size of array to allocate must be greater than 0

rcl_action/test/rcl_action/test_action_client.cpp

+50-1
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,14 @@
1414

1515
#include <gtest/gtest.h>
1616

17+
#include <string>
18+
1719
#include "rcl_action/action_client.h"
1820
#include "rcl_action/action_client_impl.h"
1921

2022
#include "rcl/error_handling.h"
2123
#include "rcl/rcl.h"
24+
#include "rcutils/testing/fault_injection.h"
2225

2326
#include "osrf_testing_tools_cpp/scope_exit.hpp"
2427
#include "test_msgs/action/fibonacci.h"
@@ -80,7 +83,6 @@ class TestActionClientBaseFixture : public ::testing::Test
8083
rcl_node_t node;
8184
};
8285

83-
8486
TEST_F(TestActionClientBaseFixture, test_action_client_init_fini) {
8587
rcl_ret_t ret = RCL_RET_OK;
8688
rcl_action_client_t invalid_action_client =
@@ -349,3 +351,50 @@ TEST_F(TestActionClientFixture, test_action_client_get_options) {
349351
options = rcl_action_client_get_options(&this->action_client);
350352
ASSERT_NE(options, nullptr) << rcl_get_error_string().str;
351353
}
354+
355+
TEST_F(TestActionClientBaseFixture, test_action_client_init_fini_maybe_fail)
356+
{
357+
RCUTILS_FAULT_INJECTION_TEST(
358+
{
359+
int count = RCUTILS_FAULT_INJECTION_GET_COUNT();
360+
rcl_node_t node = rcl_get_zero_initialized_node();
361+
rcl_node_options_t node_options = rcl_node_get_default_options();
362+
std::string node_name = std::string("test_action_client_node_") + std::to_string(count);
363+
rcl_ret_t ret = rcl_node_init(&node, node_name.c_str(), "", &this->context, &node_options);
364+
if (RCL_RET_OK != ret) {
365+
continue;
366+
}
367+
const rosidl_action_type_support_t * action_typesupport = ROSIDL_GET_ACTION_TYPE_SUPPORT(
368+
test_msgs, Fibonacci);
369+
std::string action_name = std::string("test_action_client_name_") + std::to_string(count);
370+
rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
371+
rcl_action_client_options_t action_client_options = rcl_action_client_get_default_options();
372+
373+
ret = rcl_action_client_init(
374+
&action_client,
375+
&node,
376+
action_typesupport,
377+
action_name.c_str(),
378+
&action_client_options);
379+
380+
if (RCL_RET_OK == ret) {
381+
ret = rcl_action_client_fini(&action_client, &node);
382+
} else {
383+
EXPECT_TRUE(rcl_error_is_set());
384+
rcl_reset_error();
385+
}
386+
EXPECT_EQ(RCL_RET_OK, rcl_node_fini(&node));
387+
});
388+
}
389+
390+
TEST_F(TestActionClientFixture, test_action_server_is_available_maybe_fail)
391+
{
392+
RCUTILS_FAULT_INJECTION_TEST(
393+
{
394+
bool is_available = false;
395+
rcl_ret_t ret = rcl_action_server_is_available(
396+
&this->node, &this->action_client, &is_available);
397+
(void)ret;
398+
rcl_reset_error();
399+
});
400+
}

rcl_action/test/rcl_action/test_action_communication.cpp

+58
Original file line numberDiff line numberDiff line change
@@ -1106,3 +1106,61 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_stat
11061106
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
11071107
action_msgs__msg__GoalStatusArray__fini(&incoming_status_array);
11081108
}
1109+
1110+
TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedback_comm_maybe_fail)
1111+
{
1112+
test_msgs__action__Fibonacci_FeedbackMessage outgoing_feedback;
1113+
test_msgs__action__Fibonacci_FeedbackMessage incoming_feedback;
1114+
test_msgs__action__Fibonacci_FeedbackMessage__init(&outgoing_feedback);
1115+
test_msgs__action__Fibonacci_FeedbackMessage__init(&incoming_feedback);
1116+
1117+
// Initialize feedback
1118+
ASSERT_TRUE(
1119+
rosidl_runtime_c__int32__Sequence__init(
1120+
&outgoing_feedback.feedback.sequence, 3));
1121+
outgoing_feedback.feedback.sequence.data[0] = 0;
1122+
outgoing_feedback.feedback.sequence.data[1] = 1;
1123+
outgoing_feedback.feedback.sequence.data[2] = 2;
1124+
init_test_uuid0(outgoing_feedback.goal_id.uuid);
1125+
1126+
RCUTILS_FAULT_INJECTION_TEST(
1127+
{
1128+
// Publish feedback with valid arguments
1129+
rcl_ret_t ret = rcl_action_publish_feedback(&this->action_server, &outgoing_feedback);
1130+
if (RCL_RET_OK != ret) {
1131+
continue;
1132+
}
1133+
1134+
ret = rcl_action_wait_set_add_action_client(
1135+
&this->wait_set, &this->action_client, NULL, NULL);
1136+
if (RCL_RET_OK != ret) {
1137+
continue;
1138+
}
1139+
1140+
ret = rcl_wait(&this->wait_set, RCL_S_TO_NS(10));
1141+
if (RCL_RET_OK != ret) {
1142+
continue;
1143+
}
1144+
1145+
ret = rcl_action_client_wait_set_get_entities_ready(
1146+
&this->wait_set,
1147+
&this->action_client,
1148+
&this->is_feedback_ready,
1149+
&this->is_status_ready,
1150+
&this->is_goal_response_ready,
1151+
&this->is_cancel_response_ready,
1152+
&this->is_result_response_ready);
1153+
if (RCL_RET_OK != ret) {
1154+
continue;
1155+
}
1156+
1157+
// Take feedback with valid arguments
1158+
ret = rcl_action_take_feedback(&this->action_client, &incoming_feedback);
1159+
if (RCL_RET_OK != ret) {
1160+
continue;
1161+
}
1162+
1163+
test_msgs__action__Fibonacci_FeedbackMessage__fini(&incoming_feedback);
1164+
test_msgs__action__Fibonacci_FeedbackMessage__fini(&outgoing_feedback);
1165+
});
1166+
}

rcl_action/test/rcl_action/test_action_server.cpp

+66
Original file line numberDiff line numberDiff line change
@@ -965,3 +965,69 @@ TEST_F(TestActionServerCancelPolicy, test_action_process_cancel_request_by_time_
965965
EXPECT_TRUE(uuidcmp(goal_info_out->goal_id.uuid, cancel_request.goal_info.goal_id.uuid));
966966
EXPECT_EQ(RCL_RET_OK, rcl_action_cancel_response_fini(&cancel_response));
967967
}
968+
969+
TEST_F(TestActionServer, action_server_init_fini_maybe_fail)
970+
{
971+
rcl_allocator_t allocator = rcl_get_default_allocator();
972+
rcl_ret_t ret;
973+
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
974+
ret = rcl_init_options_init(&init_options, allocator);
975+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
976+
rcl_context_t context = rcl_get_zero_initialized_context();
977+
ret = rcl_init(0, nullptr, &init_options, &context);
978+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
979+
980+
rcl_node_t node = rcl_get_zero_initialized_node();
981+
rcl_node_options_t node_options = rcl_node_get_default_options();
982+
ret = rcl_node_init(&node, "test_action_server_node", "", &context, &node_options);
983+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
984+
rcl_clock_t clock;
985+
ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator);
986+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
987+
const rosidl_action_type_support_t * ts = ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci);
988+
const rcl_action_server_options_t options = rcl_action_server_get_default_options();
989+
constexpr char action_name[] = "test_action_server_name";
990+
991+
RCUTILS_FAULT_INJECTION_TEST(
992+
{
993+
rcl_action_server_t action_server = rcl_action_get_zero_initialized_server();
994+
rcl_ret_t ret = rcl_action_server_init(
995+
&action_server, &node, &clock, ts, action_name, &options);
996+
997+
if (RCL_RET_OK == ret) {
998+
ret = rcl_action_server_fini(&action_server, &node);
999+
}
1000+
});
1001+
}
1002+
1003+
TEST_F(TestActionServerCancelPolicy, test_action_process_cancel_request_maybe_fail)
1004+
{
1005+
// Request to cancel all goals
1006+
rcl_action_cancel_request_t cancel_request = rcl_action_get_zero_initialized_cancel_request();
1007+
cancel_request.goal_info.stamp.sec = 0;
1008+
cancel_request.goal_info.stamp.nanosec = 0u;
1009+
rcl_action_cancel_response_t cancel_response = rcl_action_get_zero_initialized_cancel_response();
1010+
1011+
RCUTILS_FAULT_INJECTION_TEST(
1012+
{
1013+
rcl_ret_t ret = rcl_action_process_cancel_request(
1014+
&this->action_server, &cancel_request, &cancel_response);
1015+
(void)ret;
1016+
EXPECT_EQ(RCL_RET_OK, rcl_action_cancel_response_fini(&cancel_response));
1017+
});
1018+
}
1019+
1020+
TEST_F(TestActionServerCancelPolicy, test_action_expire_goals_maybe_fail)
1021+
{
1022+
const size_t capacity = 10u;
1023+
rcl_action_goal_info_t expired_goals[10u];
1024+
size_t num_expired = 42u;
1025+
1026+
RCUTILS_FAULT_INJECTION_TEST(
1027+
{
1028+
rcl_ret_t ret = rcl_action_expire_goals(
1029+
&this->action_server, expired_goals, capacity, &num_expired);
1030+
(void)ret;
1031+
rcl_reset_error();
1032+
});
1033+
}

rcl_action/test/rcl_action/test_graph.cpp

+73
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424

2525
#include "rcl/error_handling.h"
2626
#include "rcl/rcl.h"
27+
#include "rcutils/testing/fault_injection.h"
2728

2829
#include "osrf_testing_tools_cpp/scope_exit.hpp"
2930

@@ -593,3 +594,75 @@ TEST_F(TestActionGraphMultiNodeFixture, test_action_get_client_names_and_types_b
593594
ret = rcl_names_and_types_fini(&nat);
594595
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
595596
}
597+
598+
TEST_F(TestActionGraphMultiNodeFixture, get_names_and_types_maybe_fail)
599+
{
600+
RCUTILS_FAULT_INJECTION_TEST(
601+
{
602+
rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
603+
rcl_ret_t ret = rcl_action_get_names_and_types(&this->node, &this->allocator, &nat);
604+
if (RCL_RET_OK == ret) {
605+
ret = rcl_names_and_types_fini(&nat);
606+
if (ret != RCL_RET_OK) {
607+
EXPECT_TRUE(rcutils_error_is_set());
608+
rcutils_reset_error();
609+
}
610+
}
611+
});
612+
}
613+
614+
TEST_F(TestActionGraphMultiNodeFixture, action_client_init_maybe_fail)
615+
{
616+
RCUTILS_FAULT_INJECTION_TEST(
617+
{
618+
const rosidl_action_type_support_t * action_typesupport = ROSIDL_GET_ACTION_TYPE_SUPPORT(
619+
test_msgs, Fibonacci);
620+
621+
rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
622+
rcl_action_client_options_t action_client_options = rcl_action_client_get_default_options();
623+
rcl_ret_t ret = rcl_action_client_init(
624+
&action_client,
625+
&this->remote_node,
626+
action_typesupport,
627+
this->action_name,
628+
&action_client_options);
629+
630+
if (RCL_RET_OK == ret) {
631+
ret = rcl_action_client_fini(&action_client, &this->remote_node);
632+
}
633+
});
634+
}
635+
636+
TEST_F(TestActionGraphMultiNodeFixture, rcl_get_client_names_and_types_by_node_maybe_fail)
637+
{
638+
RCUTILS_FAULT_INJECTION_TEST(
639+
{
640+
rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
641+
rcl_ret_t ret = rcl_action_get_client_names_and_types_by_node(
642+
&this->node, &this->allocator, this->test_graph_node_name, "", &nat);
643+
if (RCL_RET_OK == ret) {
644+
ret = rcl_names_and_types_fini(&nat);
645+
if (ret != RCL_RET_OK) {
646+
EXPECT_TRUE(rcutils_error_is_set());
647+
rcutils_reset_error();
648+
}
649+
}
650+
});
651+
}
652+
653+
TEST_F(TestActionGraphMultiNodeFixture, rcl_get_server_names_and_types_by_node_maybe_fail)
654+
{
655+
RCUTILS_FAULT_INJECTION_TEST(
656+
{
657+
rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types();
658+
rcl_ret_t ret = rcl_action_get_server_names_and_types_by_node(
659+
&this->node, &this->allocator, this->test_graph_node_name, "", &nat);
660+
if (RCL_RET_OK == ret) {
661+
ret = rcl_names_and_types_fini(&nat);
662+
if (ret != RCL_RET_OK) {
663+
EXPECT_TRUE(rcutils_error_is_set());
664+
rcutils_reset_error();
665+
}
666+
}
667+
});
668+
}

0 commit comments

Comments
 (0)