@@ -983,54 +983,6 @@ TEST_F(TestServer, deferred_execution)
983983 EXPECT_TRUE (received_handle->is_executing ());
984984}
985985
986- class TestValidServer : public TestServer
987- {
988- public:
989- TestValidServer ()
990- : node_(nullptr ), action_server_(nullptr ), current_goal_handle_(nullptr ) {}
991-
992- void SetUp ()
993- {
994- node_ = std::make_shared<rclcpp::Node>(" is_ready_error" , " /rclcpp_action/construct" );
995- using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
996- action_server_ = rclcpp_action::create_server<Fibonacci>(
997- node_, " fibonacci" ,
998- [](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
999- return rclcpp_action::GoalResponse::ACCEPT_AND_DEFER;
1000- },
1001- [](std::shared_ptr<GoalHandle>) {
1002- return rclcpp_action::CancelResponse::REJECT;
1003- },
1004- [this ](std::shared_ptr<GoalHandle> handle) {
1005- current_goal_handle_ = handle;
1006- });
1007- }
1008-
1009- protected:
1010- std::shared_ptr<rclcpp::Node> node_;
1011- std::shared_ptr<rclcpp_action::Server<Fibonacci>> action_server_;
1012- std::shared_ptr<rclcpp_action::ServerGoalHandle<Fibonacci>> current_goal_handle_;
1013- };
1014-
1015- TEST_F (TestValidServer, is_ready_rcl_error) {
1016- rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set ();
1017- rcutils_allocator_t allocator = rcutils_get_default_allocator ();
1018- auto rcl_context = node_->get_node_base_interface ()->get_context ()->get_rcl_context ().get ();
1019- ASSERT_EQ (
1020- RCL_RET_OK,
1021- rcl_wait_set_init (&wait_set, 10 , 10 , 10 , 10 , 10 , 10 , rcl_context, allocator));
1022- RCLCPP_SCOPE_EXIT (
1023- {
1024- EXPECT_EQ (RCL_RET_OK, rcl_wait_set_fini (&wait_set));
1025- });
1026- ASSERT_TRUE (action_server_->add_to_wait_set (&wait_set));
1027-
1028- EXPECT_TRUE (action_server_->is_ready (&wait_set));
1029- auto mock = mocking_utils::patch_and_return (
1030- " lib:rclcpp_action" , rcl_action_server_wait_set_get_entities_ready, RCL_RET_ERROR);
1031- EXPECT_THROW (action_server_->is_ready (&wait_set), rclcpp::exceptions::RCLError);
1032- }
1033-
1034986class TestBasicServer : public TestServer
1035987{
1036988public:
@@ -1044,15 +996,52 @@ class TestBasicServer : public TestServer
1044996 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
1045997 },
1046998 [](std::shared_ptr<GoalHandle>) {
1047- return rclcpp_action::CancelResponse::REJECT ;
999+ return rclcpp_action::CancelResponse::ACCEPT ;
10481000 },
10491001 [this ](std::shared_ptr<GoalHandle> handle) {
10501002 goal_handle_ = handle;
10511003 });
10521004 }
10531005
1054- virtual void SendClientRequest (
1055- std::chrono::milliseconds timeout = std::chrono::milliseconds(-1 )) = 0;
1006+ void SendClientGoalRequest (
1007+ std::chrono::milliseconds timeout = std::chrono::milliseconds(-1 ))
1008+ {
1009+ send_goal_request (node_, uuid_, timeout);
1010+ auto result_client = node_->create_client <Fibonacci::Impl::GetResultService>(
1011+ " fibonacci/_action/get_result" );
1012+ if (!result_client->wait_for_service (std::chrono::seconds (20 ))) {
1013+ throw std::runtime_error (" get result service didn't become available" );
1014+ }
1015+ auto request = std::make_shared<Fibonacci::Impl::GetResultService::Request>();
1016+ request->goal_id .uuid = uuid_;
1017+ auto future = result_client->async_send_request (request);
1018+
1019+ // Send a result
1020+ auto result = std::make_shared<Fibonacci::Result>();
1021+ result->sequence = {5 , 8 , 13 , 21 };
1022+ goal_handle_->succeed (result);
1023+
1024+ // Wait for the result request to be received
1025+ ASSERT_EQ (
1026+ rclcpp::FutureReturnCode::SUCCESS,
1027+ rclcpp::spin_until_future_complete (node_, future));
1028+
1029+ auto response = future.get ();
1030+ EXPECT_EQ (action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status );
1031+ EXPECT_EQ (result->sequence , response->result .sequence );
1032+
1033+ // Wait for goal expiration
1034+ rclcpp::sleep_for (std::chrono::milliseconds (100 ));
1035+
1036+ // Allow for expiration to take place
1037+ rclcpp::spin_some (node_);
1038+
1039+ // Send and wait for another result request
1040+ future = result_client->async_send_request (request);
1041+ ASSERT_EQ (
1042+ rclcpp::FutureReturnCode::SUCCESS,
1043+ rclcpp::spin_until_future_complete (node_, future));
1044+ }
10561045
10571046protected:
10581047 GoalUUID uuid_;
@@ -1063,97 +1052,110 @@ class TestBasicServer : public TestServer
10631052 std::shared_ptr<GoalHandle> goal_handle_;
10641053};
10651054
1066- class TestGoalRequestServer : public TestBasicServer
1055+ class TestGoalRequestServer : public TestBasicServer {};
1056+
1057+ TEST_F (TestGoalRequestServer, execute_goal_request_received_take_goal)
10671058{
1068- public:
1069- void SendClientRequest (
1070- std::chrono::milliseconds timeout = std::chrono::milliseconds(-1 )) override
1071- {
1072- send_goal_request (node_, uuid_, timeout);
1073- goal_handle_->execute ();
1074- auto result = std::make_shared<Fibonacci::Result>();
1075- result->sequence = {5 , 8 , 13 , 21 };
1076- goal_handle_->succeed (result);
1077- }
1078- };
1059+ EXPECT_NO_THROW (SendClientGoalRequest ());
1060+ }
10791061
10801062class TestCancelRequestServer : public TestBasicServer
10811063{
10821064public:
1083- void SendClientRequest (
1084- std::chrono::milliseconds timeout = std::chrono::milliseconds(-1 )) override
1065+ void SendClientCancelRequest (
1066+ std::chrono::milliseconds timeout = std::chrono::milliseconds(-1 ))
10851067 {
1068+ send_goal_request (node_, uuid_, timeout);
10861069 send_cancel_request (node_, uuid_, timeout);
10871070 }
10881071};
10891072
1073+ TEST_F (TestCancelRequestServer, execute_goal_request_received_take_goal)
1074+ {
1075+ EXPECT_NO_THROW (SendClientCancelRequest ());
1076+ }
1077+
1078+ TEST_F (TestGoalRequestServer, is_ready_rcl_error) {
1079+ rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set ();
1080+ rcutils_allocator_t allocator = rcutils_get_default_allocator ();
1081+ auto rcl_context = node_->get_node_base_interface ()->get_context ()->get_rcl_context ().get ();
1082+ ASSERT_EQ (
1083+ RCL_RET_OK,
1084+ rcl_wait_set_init (&wait_set, 10 , 10 , 10 , 10 , 10 , 10 , rcl_context, allocator));
1085+ RCLCPP_SCOPE_EXIT (
1086+ {
1087+ EXPECT_EQ (RCL_RET_OK, rcl_wait_set_fini (&wait_set));
1088+ });
1089+ ASSERT_TRUE (action_server_->add_to_wait_set (&wait_set));
1090+
1091+ EXPECT_TRUE (action_server_->is_ready (&wait_set));
1092+ auto mock = mocking_utils::patch_and_return (
1093+ " lib:rclcpp_action" , rcl_action_server_wait_set_get_entities_ready, RCL_RET_ERROR);
1094+ EXPECT_THROW (action_server_->is_ready (&wait_set), rclcpp::exceptions::RCLError);
1095+ }
1096+
10901097TEST_F (TestGoalRequestServer, execute_goal_request_received_take_goal_request_errors)
10911098{
10921099 auto mock = mocking_utils::patch_and_return (
10931100 " lib:rclcpp_action" , rcl_action_take_goal_request, RCL_RET_ERROR);
10941101
1095- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1102+ EXPECT_THROW (SendClientGoalRequest (), rclcpp::exceptions::RCLError);
10961103}
1104+
10971105TEST_F (TestGoalRequestServer, execute_goal_request_received_send_goal_response_errors)
10981106{
10991107 auto mock = mocking_utils::patch_and_return (
11001108 " lib:rclcpp_action" , rcl_action_send_goal_response, RCL_RET_ERROR);
11011109
1102- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1110+ EXPECT_THROW (SendClientGoalRequest (), rclcpp::exceptions::RCLError);
11031111}
1112+
11041113TEST_F (TestGoalRequestServer, execute_goal_request_received_accept_new_goal_errors)
11051114{
11061115 auto mock = mocking_utils::patch_and_return (
11071116 " lib:rclcpp_action" , rcl_action_accept_new_goal, nullptr );
11081117
1109- EXPECT_THROW (SendClientRequest (), std::runtime_error);
1118+ EXPECT_THROW (SendClientGoalRequest (), std::runtime_error);
11101119}
1120+
11111121TEST_F (TestGoalRequestServer, execute_goal_request_received_update_goal_state_errors)
11121122{
11131123 auto mock = mocking_utils::patch_and_return (
11141124 " lib:rclcpp_action" , rcl_action_update_goal_state, RCL_RET_ERROR);
11151125
1116- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1126+ EXPECT_THROW (SendClientGoalRequest (), rclcpp::exceptions::RCLError);
11171127}
11181128
11191129TEST_F (TestGoalRequestServer, publish_status_server_get_goal_handles_errors)
11201130{
11211131 auto mock = mocking_utils::patch_and_return (
11221132 " lib:rclcpp_action" , rcl_action_server_get_goal_handles, RCL_RET_ERROR);
11231133
1124- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1134+ EXPECT_THROW (SendClientGoalRequest (), rclcpp::exceptions::RCLError);
11251135}
11261136
11271137TEST_F (TestGoalRequestServer, publish_status_get_goal_status_array_errors)
11281138{
11291139 auto mock = mocking_utils::patch_and_return (
11301140 " lib:rclcpp_action" , rcl_action_get_goal_status_array, RCL_RET_ERROR);
11311141
1132- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1142+ EXPECT_THROW (SendClientGoalRequest (), rclcpp::exceptions::RCLError);
11331143}
11341144
11351145TEST_F (TestGoalRequestServer, publish_status_publish_status_errors)
11361146{
11371147 auto mock = mocking_utils::patch_and_return (
11381148 " lib:rclcpp_action" , rcl_action_publish_status, RCL_RET_ERROR);
11391149
1140- EXPECT_THROW (SendClientRequest (), std::runtime_error);
1141- }
1142-
1143- TEST_F (TestGoalRequestServer, publish_result_send_result_response_errors)
1144- {
1145- auto mock = mocking_utils::patch_and_return (
1146- " lib:rclcpp_action" , rcl_action_send_result_response, RCL_RET_ERROR);
1147-
1148- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1150+ EXPECT_THROW (SendClientGoalRequest (), std::runtime_error);
11491151}
11501152
11511153TEST_F (TestGoalRequestServer, execute_goal_request_received_take_failed)
11521154{
11531155 auto mock = mocking_utils::inject_on_return (
11541156 " lib:rclcpp_action" , rcl_action_take_goal_request, RCL_RET_ACTION_SERVER_TAKE_FAILED);
11551157 try {
1156- SendClientRequest (std::chrono::milliseconds (100 ));
1158+ SendClientGoalRequest (std::chrono::milliseconds (100 ));
11571159 ADD_FAILURE () << " SetupActionServerAndSpin did not throw, but was expected to" ;
11581160 } catch (const std::runtime_error & e) {
11591161 EXPECT_STREQ (" send goal future timed out" , e.what ());
@@ -1162,35 +1164,36 @@ TEST_F(TestGoalRequestServer, execute_goal_request_received_take_failed)
11621164 }
11631165}
11641166
1165- TEST_F (TestCancelRequestServer, execute_cancel_request_received_take_cancel_request_errors )
1167+ TEST_F (TestGoalRequestServer, get_result_rcl_errors )
11661168{
11671169 auto mock = mocking_utils::patch_and_return (
1168- " lib:rclcpp_action" , rcl_action_take_cancel_request , RCL_RET_ERROR);
1170+ " lib:rclcpp_action" , rcl_action_take_result_request , RCL_RET_ERROR);
11691171
1170- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1172+ EXPECT_THROW (SendClientGoalRequest (), rclcpp::exceptions::RCLError);
11711173}
11721174
1173- TEST_F (TestGoalRequestServer, publish_status_rcl_errors )
1175+ TEST_F (TestGoalRequestServer, send_result_rcl_errors )
11741176{
11751177 auto mock = mocking_utils::patch_and_return (
1176- " lib:rclcpp_action" , rcl_action_process_cancel_request , RCL_RET_ERROR);
1178+ " lib:rclcpp_action" , rcl_action_send_result_response , RCL_RET_ERROR);
11771179
1178- EXPECT_THROW (SendClientRequest (), rclcpp::exceptions::RCLError);
1180+ EXPECT_THROW (SendClientGoalRequest (), rclcpp::exceptions::RCLError);
11791181}
1180- TEST_F (TestGoalRequestServer, publish_status_send_cancel_response_errors)
1182+
1183+ TEST_F (TestCancelRequestServer, execute_cancel_request_received_take_cancel_request_errors)
11811184{
11821185 auto mock = mocking_utils::patch_and_return (
1183- " lib:rclcpp_action" , rcl_action_send_cancel_response , RCL_RET_ERROR);
1186+ " lib:rclcpp_action" , rcl_action_take_cancel_request , RCL_RET_ERROR);
11841187
1185- EXPECT_THROW (SendClientRequest (), std::runtime_error );
1188+ EXPECT_THROW (SendClientCancelRequest (), rclcpp::exceptions::RCLError );
11861189}
11871190
11881191TEST_F (TestCancelRequestServer, execute_cancel_request_received_take_failed)
11891192{
11901193 auto mock = mocking_utils::patch_and_return (
11911194 " lib:rclcpp_action" , rcl_action_take_cancel_request, RCL_RET_ACTION_SERVER_TAKE_FAILED);
11921195 try {
1193- SendClientRequest (std::chrono::milliseconds (100 ));
1196+ SendClientCancelRequest (std::chrono::milliseconds (100 ));
11941197 ADD_FAILURE () << " SetupActionServerAndSpin did not throw, but it was expected to" ;
11951198 } catch (const std::runtime_error & e) {
11961199 EXPECT_STREQ (" cancel request future timed out" , e.what ());
@@ -1199,42 +1202,18 @@ TEST_F(TestCancelRequestServer, execute_cancel_request_received_take_failed)
11991202 }
12001203}
12011204
1202- TEST_F (TestGoalRequestServer, get_result_rcl_errors )
1205+ TEST_F (TestCancelRequestServer, publish_status_rcl_errors )
12031206{
1204- auto take_result_request_error = [this ]() {
1205- this ->SendClientRequest ();
1206- // Send result request
1207- auto result_client = node_->create_client <Fibonacci::Impl::GetResultService>(
1208- " fibonacci/_action/get_result" );
1209- if (!result_client->wait_for_service (std::chrono::seconds (20 ))) {
1210- throw std::runtime_error (" get result service didn't become available" );
1211- }
1212- auto request = std::make_shared<Fibonacci::Impl::GetResultService::Request>();
1213- request->goal_id .uuid = uuid_;
1214- auto mock = mocking_utils::patch_and_return (
1215- " lib:rclcpp_action" , rcl_action_take_result_request, RCL_RET_ERROR);
1216- auto future = result_client->async_send_request (request);
1217- };
1207+ auto mock = mocking_utils::patch_and_return (
1208+ " lib:rclcpp_action" , rcl_action_process_cancel_request, RCL_RET_ERROR);
12181209
1219- EXPECT_THROW (take_result_request_error (), rclcpp::exceptions::RCLError);
1210+ EXPECT_THROW (SendClientCancelRequest (), rclcpp::exceptions::RCLError);
12201211}
12211212
1222- TEST_F (TestGoalRequestServer, send_result_rcl_errors )
1213+ TEST_F (TestCancelRequestServer, publish_status_send_cancel_response_errors )
12231214{
1224- auto send_result_error = [this ]() {
1225- this ->SendClientRequest ();
1226- // Send result request
1227- auto result_client = node_->create_client <Fibonacci::Impl::GetResultService>(
1228- " fibonacci/_action/get_result" );
1229- if (!result_client->wait_for_service (std::chrono::seconds (20 ))) {
1230- throw std::runtime_error (" get result service didn't become available" );
1231- }
1232- auto request = std::make_shared<Fibonacci::Impl::GetResultService::Request>();
1233- request->goal_id .uuid = uuid_;
1234- auto mock = mocking_utils::patch_and_return (
1235- " lib:rclcpp_action" , rcl_action_send_result_response, RCL_RET_ERROR);
1236- auto future = result_client->async_send_request (request);
1237- };
1215+ auto mock = mocking_utils::patch_and_return (
1216+ " lib:rclcpp_action" , rcl_action_send_cancel_response, RCL_RET_ERROR);
12381217
1239- EXPECT_THROW (send_result_error (), rclcpp::exceptions::RCLError );
1218+ EXPECT_THROW (SendClientCancelRequest (), std::runtime_error );
12401219}
0 commit comments