From a8df5b5a5e1d1277cff9fa10d637c923c937cdd7 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Sat, 24 Nov 2018 09:10:14 -0800 Subject: [PATCH 1/8] update test to IDL-based action generation --- .../rcl_action/test_action_communication.cpp | 48 +++++++++---------- 1 file changed, 24 insertions(+), 24 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index 8b6b86390..4cded9f6e 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -629,10 +629,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal_request_opts) { - test_msgs__action__Fibonacci_Goal_Request outgoing_goal_request; - test_msgs__action__Fibonacci_Goal_Request incoming_goal_request; - test_msgs__action__Fibonacci_Goal_Request__init(&outgoing_goal_request); - test_msgs__action__Fibonacci_Goal_Request__init(&incoming_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request outgoing_goal_request; + test_msgs__action__Fibonacci_Action_Goal_Request incoming_goal_request; + test_msgs__action__Fibonacci_Action_Goal_Request__init(&outgoing_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__init(&incoming_goal_request); // Initialize goal request init_test_uuid0(outgoing_goal_request.action_goal_id.uuid); @@ -680,16 +680,16 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Goal_Request__fini(&outgoing_goal_request); - test_msgs__action__Fibonacci_Goal_Request__fini(&incoming_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&outgoing_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&incoming_goal_request); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal_response_opts) { - test_msgs__action__Fibonacci_Goal_Response outgoing_goal_response; - test_msgs__action__Fibonacci_Goal_Response incoming_goal_response; - test_msgs__action__Fibonacci_Goal_Response__init(&outgoing_goal_response); - test_msgs__action__Fibonacci_Goal_Response__init(&incoming_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response outgoing_goal_response; + test_msgs__action__Fibonacci_Action_Goal_Response incoming_goal_response; + test_msgs__action__Fibonacci_Action_Goal_Response__init(&outgoing_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__init(&incoming_goal_response); // Initialize goal response outgoing_goal_response.accepted = true; @@ -741,8 +741,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal EXPECT_EQ(ret, RCL_RET_ACTION_CLIENT_INVALID) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Goal_Response__fini(&incoming_goal_response); - test_msgs__action__Fibonacci_Goal_Response__fini(&outgoing_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&incoming_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&outgoing_goal_response); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_cancel_request_opts) @@ -868,10 +868,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_canc TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_result_request_opts) { - test_msgs__action__Fibonacci_Result_Request outgoing_result_request; - test_msgs__action__Fibonacci_Result_Request incoming_result_request; - test_msgs__action__Fibonacci_Result_Request__init(&outgoing_result_request); - test_msgs__action__Fibonacci_Result_Request__init(&incoming_result_request); + test_msgs__action__Fibonacci_Action_Result_Request outgoing_result_request; + test_msgs__action__Fibonacci_Action_Result_Request incoming_result_request; + test_msgs__action__Fibonacci_Action_Result_Request__init(&outgoing_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__init(&incoming_result_request); // Initialize result request init_test_uuid0(outgoing_result_request.action_goal_id.uuid); @@ -918,16 +918,16 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Result_Request__fini(&incoming_result_request); - test_msgs__action__Fibonacci_Result_Request__fini(&outgoing_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__fini(&incoming_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__fini(&outgoing_result_request); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_result_response_opts) { - test_msgs__action__Fibonacci_Result_Response outgoing_result_response; - test_msgs__action__Fibonacci_Result_Response incoming_result_response; - test_msgs__action__Fibonacci_Result_Response__init(&outgoing_result_response); - test_msgs__action__Fibonacci_Result_Response__init(&incoming_result_response); + test_msgs__action__Fibonacci_Action_Result_Response outgoing_result_response; + test_msgs__action__Fibonacci_Action_Result_Response incoming_result_response; + test_msgs__action__Fibonacci_Action_Result_Response__init(&outgoing_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__init(&incoming_result_response); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( @@ -980,8 +980,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu EXPECT_EQ(ret, RCL_RET_ACTION_CLIENT_INVALID) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Result_Response__fini(&incoming_result_response); - test_msgs__action__Fibonacci_Result_Response__fini(&outgoing_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&incoming_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&outgoing_result_response); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feedback_opts) From 82d0f0af766c52bf2fcbf3b4f14b5df7feb68cbb Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 27 Nov 2018 21:57:56 -0800 Subject: [PATCH 2/8] update test to IDL-based action generation --- .../rcl_action/test_action_communication.cpp | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index 4cded9f6e..34917c002 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -986,10 +986,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feedback_opts) { - test_msgs__action__Fibonacci_Feedback outgoing_feedback; - test_msgs__action__Fibonacci_Feedback incoming_feedback; - test_msgs__action__Fibonacci_Feedback__init(&outgoing_feedback); - test_msgs__action__Fibonacci_Feedback__init(&incoming_feedback); + test_msgs__action__Fibonacci_Action_Feedback outgoing_feedback; + test_msgs__action__Fibonacci_Action_Feedback incoming_feedback; + test_msgs__action__Fibonacci_Action_Feedback__init(&outgoing_feedback); + test_msgs__action__Fibonacci_Action_Feedback__init(&incoming_feedback); // Initialize feedback ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( @@ -1031,8 +1031,12 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Feedback__fini(&incoming_feedback); - test_msgs__action__Fibonacci_Feedback__fini(&outgoing_feedback); +<<<<<<< HEAD + test_msgs__action__Fibonacci_Action_Feedback__fini(&incoming_feedback); + test_msgs__action__Fibonacci_Action_Feedback__fini(&outgoing_feedback); +======= + test_msgs__action__Fibonacci_Action_Feedback__fini(&feedback); +>>>>>>> update test to IDL-based action generation } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_status_opts) From 4ce3dc05956875f6aaa630b25dd12b9809fc924a Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Fri, 30 Nov 2018 11:09:35 -0800 Subject: [PATCH 3/8] fix merge conflict --- rcl_action/test/rcl_action/test_action_communication.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index 34917c002..38c46b5c1 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -1031,12 +1031,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str; rcl_reset_error(); -<<<<<<< HEAD test_msgs__action__Fibonacci_Action_Feedback__fini(&incoming_feedback); test_msgs__action__Fibonacci_Action_Feedback__fini(&outgoing_feedback); -======= - test_msgs__action__Fibonacci_Action_Feedback__fini(&feedback); ->>>>>>> update test to IDL-based action generation } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_status_opts) From 9b8aea9e00251176dac99d7b7a92e2cfb21ce8af Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Fri, 30 Nov 2018 11:33:27 -0800 Subject: [PATCH 4/8] update new tests --- .../rcl_action/test_action_communication.cpp | 74 +++++++++---------- 1 file changed, 37 insertions(+), 37 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index 38c46b5c1..62a14e98d 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -156,14 +156,14 @@ class CLASSNAME (TestActionCommunication, RMW_IMPLEMENTATION) : public ::testing TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_comm) { - test_msgs__action__Fibonacci_Goal_Request outgoing_goal_request; - test_msgs__action__Fibonacci_Goal_Request incoming_goal_request; - test_msgs__action__Fibonacci_Goal_Response outgoing_goal_response; - test_msgs__action__Fibonacci_Goal_Response incoming_goal_response; - test_msgs__action__Fibonacci_Goal_Request__init(&outgoing_goal_request); - test_msgs__action__Fibonacci_Goal_Request__init(&incoming_goal_request); - test_msgs__action__Fibonacci_Goal_Response__init(&outgoing_goal_response); - test_msgs__action__Fibonacci_Goal_Response__init(&incoming_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Request outgoing_goal_request; + test_msgs__action__Fibonacci_Action_Goal_Request incoming_goal_request; + test_msgs__action__Fibonacci_Action_Goal_Response outgoing_goal_response; + test_msgs__action__Fibonacci_Action_Goal_Response incoming_goal_response; + test_msgs__action__Fibonacci_Action_Goal_Request__init(&outgoing_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__init(&incoming_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Response__init(&outgoing_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__init(&incoming_goal_response); // Initialize goal request init_test_uuid0(outgoing_goal_request.action_goal_id.uuid); @@ -252,10 +252,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c EXPECT_EQ(outgoing_goal_response.stamp.sec, incoming_goal_response.stamp.sec); EXPECT_EQ(outgoing_goal_response.stamp.nanosec, incoming_goal_response.stamp.nanosec); - test_msgs__action__Fibonacci_Goal_Request__fini(&outgoing_goal_request); - test_msgs__action__Fibonacci_Goal_Request__fini(&incoming_goal_request); - test_msgs__action__Fibonacci_Goal_Response__fini(&incoming_goal_response); - test_msgs__action__Fibonacci_Goal_Response__fini(&outgoing_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&outgoing_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&incoming_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&incoming_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&outgoing_goal_response); } @@ -385,14 +385,14 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_cancel TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result_comm) { - test_msgs__action__Fibonacci_Result_Request outgoing_result_request; - test_msgs__action__Fibonacci_Result_Request incoming_result_request; - test_msgs__action__Fibonacci_Result_Response outgoing_result_response; - test_msgs__action__Fibonacci_Result_Response incoming_result_response; - test_msgs__action__Fibonacci_Result_Request__init(&outgoing_result_request); - test_msgs__action__Fibonacci_Result_Request__init(&incoming_result_request); - test_msgs__action__Fibonacci_Result_Response__init(&outgoing_result_response); - test_msgs__action__Fibonacci_Result_Response__init(&incoming_result_response); + test_msgs__action__Fibonacci_Action_Result_Request outgoing_result_request; + test_msgs__action__Fibonacci_Action_Result_Request incoming_result_request; + test_msgs__action__Fibonacci_Action_Result_Response outgoing_result_response; + test_msgs__action__Fibonacci_Action_Result_Response incoming_result_response; + test_msgs__action__Fibonacci_Action_Result_Request__init(&outgoing_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__init(&incoming_result_request); + test_msgs__action__Fibonacci_Action_Result_Response__init(&outgoing_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__init(&incoming_result_response); // Initialize result request init_test_uuid0(outgoing_result_request.action_goal_id.uuid); @@ -482,14 +482,14 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result EXPECT_EQ(outgoing_result_response.action_status, incoming_result_response.action_status); ASSERT_EQ(outgoing_result_response.sequence.size, incoming_result_response.sequence.size); EXPECT_TRUE(!memcmp( - outgoing_result_response.sequence.data, - incoming_result_response.sequence.data, - outgoing_result_response.sequence.size)); - - test_msgs__action__Fibonacci_Result_Request__fini(&incoming_result_request); - test_msgs__action__Fibonacci_Result_Request__fini(&outgoing_result_request); - test_msgs__action__Fibonacci_Result_Response__fini(&incoming_result_response); - test_msgs__action__Fibonacci_Result_Response__fini(&outgoing_result_response); + outgoing_result_response.response.sequence.data, + incoming_result_response.response.sequence.data, + outgoing_result_response.response.sequence.size)); + + test_msgs__action__Fibonacci_Action_Result_Request__fini(&incoming_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__fini(&outgoing_result_request); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&incoming_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&outgoing_result_response); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_status_comm) @@ -569,10 +569,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_status TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedback_comm) { - test_msgs__action__Fibonacci_Feedback outgoing_feedback; - test_msgs__action__Fibonacci_Feedback incoming_feedback; - test_msgs__action__Fibonacci_Feedback__init(&outgoing_feedback); - test_msgs__action__Fibonacci_Feedback__init(&incoming_feedback); + test_msgs__action__Fibonacci_Action_Feedback outgoing_feedback; + test_msgs__action__Fibonacci_Action_Feedback incoming_feedback; + test_msgs__action__Fibonacci_Action_Feedback__init(&outgoing_feedback); + test_msgs__action__Fibonacci_Action_Feedback__init(&incoming_feedback); // Initialize feedback ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( @@ -619,12 +619,12 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba incoming_feedback.action_goal_id.uuid)); ASSERT_EQ(outgoing_feedback.sequence.size, incoming_feedback.sequence.size); EXPECT_TRUE(!memcmp( - outgoing_feedback.sequence.data, - incoming_feedback.sequence.data, - outgoing_feedback.sequence.size)); + outgoing_feedback.feedback.sequence.data, + incoming_feedback.feedback.sequence.data, + outgoing_feedback.feedback.sequence.size)); - test_msgs__action__Fibonacci_Feedback__fini(&incoming_feedback); - test_msgs__action__Fibonacci_Feedback__fini(&outgoing_feedback); + test_msgs__action__Fibonacci_Action_Feedback__fini(&incoming_feedback); + test_msgs__action__Fibonacci_Action_Feedback__fini(&outgoing_feedback); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal_request_opts) From a6ed604be6196d7cc96f373f6411520c34887c76 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Mon, 11 Feb 2019 10:47:30 -0800 Subject: [PATCH 5/8] update action types --- .../rcl_action/test_action_communication.cpp | 76 +++---- .../rcl_action/test_action_interaction.cpp | 202 +++++++++--------- 2 files changed, 139 insertions(+), 139 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index 62a14e98d..7beab2a58 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -166,8 +166,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c test_msgs__action__Fibonacci_Action_Goal_Response__init(&incoming_goal_response); // Initialize goal request - init_test_uuid0(outgoing_goal_request.action_goal_id.uuid); - outgoing_goal_request.order = 10; + init_test_uuid0(outgoing_goal_request.uuid); + outgoing_goal_request.request.order = 10; // Send goal request with valid arguments int64_t sequence_number; @@ -201,10 +201,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; // Check that the goal request was received correctly - EXPECT_EQ(outgoing_goal_request.order, incoming_goal_request.order); + EXPECT_EQ(outgoing_goal_request.request.order, incoming_goal_request.request.order); EXPECT_TRUE(uuidcmp( - outgoing_goal_request.action_goal_id.uuid, - incoming_goal_request.action_goal_id.uuid)); + outgoing_goal_request.uuid, + incoming_goal_request.uuid)); // Initialize goal response outgoing_goal_response.accepted = true; @@ -395,7 +395,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result test_msgs__action__Fibonacci_Action_Result_Response__init(&incoming_result_response); // Initialize result request - init_test_uuid0(outgoing_result_request.action_goal_id.uuid); + init_test_uuid0(outgoing_result_request.uuid); // Send result request with valid arguments int64_t sequence_number; @@ -430,17 +430,17 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - outgoing_result_request.action_goal_id.uuid, - incoming_result_request.action_goal_id.uuid)); + outgoing_result_request.uuid, + incoming_result_request.uuid)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &outgoing_result_response.sequence, 4)); - outgoing_result_response.sequence.data[0] = 0; - outgoing_result_response.sequence.data[1] = 1; - outgoing_result_response.sequence.data[2] = 2; - outgoing_result_response.sequence.data[3] = 6; - outgoing_result_response.action_status = + &outgoing_result_response.response.sequence, 4)); + outgoing_result_response.response.sequence.data[0] = 0; + outgoing_result_response.response.sequence.data[1] = 1; + outgoing_result_response.response.sequence.data[2] = 2; + outgoing_result_response.response.sequence.data[3] = 6; + outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; // Send result response with valid arguments @@ -479,8 +479,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; // Check that the result response was received correctly - EXPECT_EQ(outgoing_result_response.action_status, incoming_result_response.action_status); - ASSERT_EQ(outgoing_result_response.sequence.size, incoming_result_response.sequence.size); + EXPECT_EQ(outgoing_result_response.status, incoming_result_response.status); + ASSERT_EQ(outgoing_result_response.response.sequence.size, incoming_result_response.response.sequence.size); EXPECT_TRUE(!memcmp( outgoing_result_response.response.sequence.data, incoming_result_response.response.sequence.data, @@ -576,11 +576,11 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba // Initialize feedback ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &outgoing_feedback.sequence, 3)); - outgoing_feedback.sequence.data[0] = 0; - outgoing_feedback.sequence.data[1] = 1; - outgoing_feedback.sequence.data[2] = 2; - init_test_uuid0(outgoing_feedback.action_goal_id.uuid); + &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.uuid); // Publish feedback with valid arguments rcl_ret_t ret = rcl_action_publish_feedback(&this->action_server, &outgoing_feedback); @@ -615,9 +615,9 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - outgoing_feedback.action_goal_id.uuid, - incoming_feedback.action_goal_id.uuid)); - ASSERT_EQ(outgoing_feedback.sequence.size, incoming_feedback.sequence.size); + outgoing_feedback.uuid, + incoming_feedback.uuid)); + ASSERT_EQ(outgoing_feedback.feedback.sequence.size, incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( outgoing_feedback.feedback.sequence.data, incoming_feedback.feedback.sequence.data, @@ -635,8 +635,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal test_msgs__action__Fibonacci_Action_Goal_Request__init(&incoming_goal_request); // Initialize goal request - init_test_uuid0(outgoing_goal_request.action_goal_id.uuid); - outgoing_goal_request.order = 10; + init_test_uuid0(outgoing_goal_request.uuid); + outgoing_goal_request.request.order = 10; int64_t sequence_number = 1234; rcl_ret_t ret = 0; @@ -874,7 +874,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu test_msgs__action__Fibonacci_Action_Result_Request__init(&incoming_result_request); // Initialize result request - init_test_uuid0(outgoing_result_request.action_goal_id.uuid); + init_test_uuid0(outgoing_result_request.uuid); // Send result request with null action client int64_t sequence_number = 1324; @@ -931,12 +931,12 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &outgoing_result_response.sequence, 4)); - outgoing_result_response.sequence.data[0] = 0; - outgoing_result_response.sequence.data[1] = 1; - outgoing_result_response.sequence.data[2] = 2; - outgoing_result_response.sequence.data[3] = 6; - outgoing_result_response.action_status = + &outgoing_result_response.response.sequence, 4)); + outgoing_result_response.response.sequence.data[0] = 0; + outgoing_result_response.response.sequence.data[1] = 1; + outgoing_result_response.response.sequence.data[2] = 2; + outgoing_result_response.response.sequence.data[3] = 6; + outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; // Send result response with null action client @@ -993,11 +993,11 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed // Initialize feedback ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &outgoing_feedback.sequence, 3)); - outgoing_feedback.sequence.data[0] = 0; - outgoing_feedback.sequence.data[1] = 1; - outgoing_feedback.sequence.data[2] = 2; - init_test_uuid0(outgoing_feedback.action_goal_id.uuid); + &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.uuid); // Publish feedback with null action server rcl_ret_t ret = rcl_action_publish_feedback(nullptr, &outgoing_feedback); diff --git a/rcl_action/test/rcl_action/test_action_interaction.cpp b/rcl_action/test/rcl_action/test_action_interaction.cpp index f1ce85de2..7f79a92f3 100644 --- a/rcl_action/test/rcl_action/test_action_interaction.cpp +++ b/rcl_action/test/rcl_action/test_action_interaction.cpp @@ -36,16 +36,16 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public protected: void SetUp() override { - test_msgs__action__Fibonacci_Goal_Request__init(&this->outgoing_goal_request); - test_msgs__action__Fibonacci_Goal_Request__init(&this->incoming_goal_request); - test_msgs__action__Fibonacci_Goal_Response__init(&this->outgoing_goal_response); - test_msgs__action__Fibonacci_Goal_Response__init(&this->incoming_goal_response); - test_msgs__action__Fibonacci_Result_Request__init(&this->outgoing_result_request); - test_msgs__action__Fibonacci_Result_Request__init(&this->incoming_result_request); - test_msgs__action__Fibonacci_Result_Response__init(&this->outgoing_result_response); - test_msgs__action__Fibonacci_Result_Response__init(&this->incoming_result_response); - test_msgs__action__Fibonacci_Feedback__init(&this->outgoing_feedback); - test_msgs__action__Fibonacci_Feedback__init(&this->incoming_feedback); + test_msgs__action__Fibonacci_Action_Goal_Request__init(&this->outgoing_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__init(&this->incoming_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Response__init(&this->outgoing_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__init(&this->incoming_goal_response); + test_msgs__action__Fibonacci_Action_Result_Request__init(&this->outgoing_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__init(&this->incoming_result_request); + test_msgs__action__Fibonacci_Action_Result_Response__init(&this->outgoing_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__init(&this->incoming_result_response); + test_msgs__action__Fibonacci_Action_Feedback__init(&this->outgoing_feedback); + test_msgs__action__Fibonacci_Action_Feedback__init(&this->incoming_feedback); rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -118,16 +118,16 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public void TearDown() override { // Finalize - test_msgs__action__Fibonacci_Goal_Request__fini(&this->outgoing_goal_request); - test_msgs__action__Fibonacci_Goal_Request__fini(&this->incoming_goal_request); - test_msgs__action__Fibonacci_Goal_Response__fini(&this->incoming_goal_response); - test_msgs__action__Fibonacci_Goal_Response__fini(&this->outgoing_goal_response); - test_msgs__action__Fibonacci_Result_Request__fini(&this->incoming_result_request); - test_msgs__action__Fibonacci_Result_Request__fini(&this->outgoing_result_request); - test_msgs__action__Fibonacci_Result_Response__fini(&this->incoming_result_response); - test_msgs__action__Fibonacci_Result_Response__fini(&this->outgoing_result_response); - test_msgs__action__Fibonacci_Feedback__fini(&this->outgoing_feedback); - test_msgs__action__Fibonacci_Feedback__fini(&this->incoming_feedback); + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->outgoing_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->incoming_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->incoming_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->outgoing_goal_response); + test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->incoming_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->outgoing_result_request); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->incoming_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->outgoing_result_response); + test_msgs__action__Fibonacci_Action_Feedback__fini(&this->outgoing_feedback); + test_msgs__action__Fibonacci_Action_Feedback__fini(&this->incoming_feedback); rcl_ret_t ret = rcl_action_server_fini(&this->action_server, &this->node); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; ret = rcl_clock_fini(&this->clock); @@ -156,16 +156,16 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public } } - test_msgs__action__Fibonacci_Goal_Request outgoing_goal_request; - test_msgs__action__Fibonacci_Goal_Request incoming_goal_request; - test_msgs__action__Fibonacci_Goal_Response outgoing_goal_response; - test_msgs__action__Fibonacci_Goal_Response incoming_goal_response; - test_msgs__action__Fibonacci_Result_Request outgoing_result_request; - test_msgs__action__Fibonacci_Result_Request incoming_result_request; - test_msgs__action__Fibonacci_Result_Response outgoing_result_response; - test_msgs__action__Fibonacci_Result_Response incoming_result_response; - test_msgs__action__Fibonacci_Feedback outgoing_feedback; - test_msgs__action__Fibonacci_Feedback incoming_feedback; + test_msgs__action__Fibonacci_Action_Goal_Request outgoing_goal_request; + test_msgs__action__Fibonacci_Action_Goal_Request incoming_goal_request; + test_msgs__action__Fibonacci_Action_Goal_Response outgoing_goal_response; + test_msgs__action__Fibonacci_Action_Goal_Response incoming_goal_response; + test_msgs__action__Fibonacci_Action_Result_Request outgoing_result_request; + test_msgs__action__Fibonacci_Action_Result_Request incoming_result_request; + test_msgs__action__Fibonacci_Action_Result_Response outgoing_result_response; + test_msgs__action__Fibonacci_Action_Result_Response incoming_result_response; + test_msgs__action__Fibonacci_Action_Feedback outgoing_feedback; + test_msgs__action__Fibonacci_Action_Feedback incoming_feedback; rcl_action_client_t action_client; rcl_action_server_t action_server; @@ -197,8 +197,8 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_interaction) { // Initialize goal request - init_test_uuid0(this->outgoing_goal_request.action_goal_id.uuid); - this->outgoing_goal_request.order = 10; + init_test_uuid0(this->outgoing_goal_request.uuid); + this->outgoing_goal_request.request.order = 10; // Send goal request with valid arguments int64_t sequence_number; @@ -235,10 +235,10 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; // Check that the goal request was received correctly - EXPECT_EQ(this->outgoing_goal_request.order, this->incoming_goal_request.order); + EXPECT_EQ(this->outgoing_goal_request.request.order, this->incoming_goal_request.request.order); EXPECT_TRUE(uuidcmp( - this->outgoing_goal_request.action_goal_id.uuid, - this->incoming_goal_request.action_goal_id.uuid)); + this->outgoing_goal_request.uuid, + this->incoming_goal_request.uuid)); // Initialize goal response this->outgoing_goal_response.accepted = true; @@ -288,7 +288,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in EXPECT_EQ(this->outgoing_goal_response.stamp.nanosec, this->incoming_goal_response.stamp.nanosec); // Initialize result request - init_test_uuid0(this->outgoing_result_request.action_goal_id.uuid); + init_test_uuid0(this->outgoing_result_request.uuid); // Send result request with valid arguments ret = rcl_action_send_result_request( @@ -297,11 +297,11 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Initialize feedback ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &this->outgoing_feedback.sequence, 3)); - this->outgoing_feedback.sequence.data[0] = 0; - this->outgoing_feedback.sequence.data[1] = 1; - this->outgoing_feedback.sequence.data[2] = 2; - init_test_uuid0(this->outgoing_feedback.action_goal_id.uuid); + &this->outgoing_feedback.feedback.sequence, 3)); + this->outgoing_feedback.feedback.sequence.data[0] = 0; + this->outgoing_feedback.feedback.sequence.data[1] = 1; + this->outgoing_feedback.feedback.sequence.data[2] = 2; + init_test_uuid0(this->outgoing_feedback.uuid); // Publish feedback with valid arguments ret = rcl_action_publish_feedback(&this->action_server, &this->outgoing_feedback); @@ -339,13 +339,13 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_feedback.action_goal_id.uuid, - this->incoming_feedback.action_goal_id.uuid)); - ASSERT_EQ(this->outgoing_feedback.sequence.size, this->incoming_feedback.sequence.size); + this->outgoing_feedback.uuid, + this->incoming_feedback.uuid)); + ASSERT_EQ(this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( - this->outgoing_feedback.sequence.data, - this->incoming_feedback.sequence.data, - this->outgoing_feedback.sequence.size)); + this->outgoing_feedback.feedback.sequence.data, + this->incoming_feedback.feedback.sequence.data, + this->outgoing_feedback.feedback.sequence.size)); ret = rcl_wait_set_clear(&this->wait_set); @@ -377,17 +377,17 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_result_request.action_goal_id.uuid, - this->incoming_result_request.action_goal_id.uuid)); + this->outgoing_result_request.uuid, + this->incoming_result_request.uuid)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &this->outgoing_result_response.sequence, 4)); - this->outgoing_result_response.sequence.data[0] = 0; - this->outgoing_result_response.sequence.data[1] = 1; - this->outgoing_result_response.sequence.data[2] = 2; - this->outgoing_result_response.sequence.data[3] = 6; - this->outgoing_result_response.action_status = + &this->outgoing_result_response.response.sequence, 4)); + this->outgoing_result_response.response.sequence.data[0] = 0; + this->outgoing_result_response.response.sequence.data[1] = 1; + this->outgoing_result_response.response.sequence.data[2] = 2; + this->outgoing_result_response.response.sequence.data[3] = 6; + this->outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; // Send result response with valid arguments @@ -428,14 +428,14 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that the result response was received correctly EXPECT_EQ( - this->outgoing_result_response.action_status, - this->incoming_result_response.action_status); + this->outgoing_result_response.status, + this->incoming_result_response.status); ASSERT_EQ( - this->outgoing_result_response.sequence.size, this->incoming_result_response.sequence.size); + this->outgoing_result_response.response.sequence.size, this->incoming_result_response.response.sequence.size); EXPECT_TRUE(!memcmp( - this->outgoing_result_response.sequence.data, - this->incoming_result_response.sequence.data, - this->outgoing_result_response.sequence.size)); + this->outgoing_result_response.response.sequence.data, + this->incoming_result_response.response.sequence.data, + this->outgoing_result_response.response.sequence.size)); } // Exercises the "Example 2" sequence diagram found in the actions_proposal document. @@ -455,8 +455,8 @@ TEST_F( action_msgs__srv__CancelGoal_Response__init(&incoming_cancel_response); // Initialize goal request - init_test_uuid0(this->outgoing_goal_request.action_goal_id.uuid); - this->outgoing_goal_request.order = 10; + init_test_uuid0(this->outgoing_goal_request.uuid); + this->outgoing_goal_request.request.order = 10; // Send goal request with valid arguments int64_t sequence_number; @@ -493,10 +493,10 @@ TEST_F( EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; // Check that the goal request was received correctly - EXPECT_EQ(this->outgoing_goal_request.order, this->incoming_goal_request.order); + EXPECT_EQ(this->outgoing_goal_request.request.order, this->incoming_goal_request.request.order); EXPECT_TRUE(uuidcmp( - this->outgoing_goal_request.action_goal_id.uuid, - this->incoming_goal_request.action_goal_id.uuid)); + this->outgoing_goal_request.uuid, + this->incoming_goal_request.uuid)); // Initialize goal response this->outgoing_goal_response.accepted = true; @@ -546,7 +546,7 @@ TEST_F( EXPECT_EQ(this->outgoing_goal_response.stamp.nanosec, this->incoming_goal_response.stamp.nanosec); // Initialize result request - init_test_uuid0(this->outgoing_result_request.action_goal_id.uuid); + init_test_uuid0(this->outgoing_result_request.uuid); // Send result request with valid arguments ret = rcl_action_send_result_request( @@ -555,11 +555,11 @@ TEST_F( // Initialize feedback ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &this->outgoing_feedback.sequence, 3)); - this->outgoing_feedback.sequence.data[0] = 0; - this->outgoing_feedback.sequence.data[1] = 1; - this->outgoing_feedback.sequence.data[2] = 2; - init_test_uuid0(this->outgoing_feedback.action_goal_id.uuid); + &this->outgoing_feedback.feedback.sequence, 3)); + this->outgoing_feedback.feedback.sequence.data[0] = 0; + this->outgoing_feedback.feedback.sequence.data[1] = 1; + this->outgoing_feedback.feedback.sequence.data[2] = 2; + init_test_uuid0(this->outgoing_feedback.uuid); // Publish feedback with valid arguments ret = rcl_action_publish_feedback(&this->action_server, &this->outgoing_feedback); @@ -597,13 +597,13 @@ TEST_F( // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_feedback.action_goal_id.uuid, - this->incoming_feedback.action_goal_id.uuid)); - ASSERT_EQ(this->outgoing_feedback.sequence.size, this->incoming_feedback.sequence.size); + this->outgoing_feedback.uuid, + this->incoming_feedback.uuid)); + ASSERT_EQ(this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( - this->outgoing_feedback.sequence.data, - this->incoming_feedback.sequence.data, - this->outgoing_feedback.sequence.size)); + this->outgoing_feedback.feedback.sequence.data, + this->incoming_feedback.feedback.sequence.data, + this->outgoing_feedback.feedback.sequence.size)); ret = rcl_wait_set_clear(&this->wait_set); @@ -635,17 +635,17 @@ TEST_F( // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_result_request.action_goal_id.uuid, - this->incoming_result_request.action_goal_id.uuid)); + this->outgoing_result_request.uuid, + this->incoming_result_request.uuid)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &this->outgoing_result_response.sequence, 4)); - this->outgoing_result_response.sequence.data[0] = 0; - this->outgoing_result_response.sequence.data[1] = 1; - this->outgoing_result_response.sequence.data[2] = 2; - this->outgoing_result_response.sequence.data[3] = 6; - this->outgoing_result_response.action_status = + &this->outgoing_result_response.response.sequence, 4)); + this->outgoing_result_response.response.sequence.data[0] = 0; + this->outgoing_result_response.response.sequence.data[1] = 1; + this->outgoing_result_response.response.sequence.data[2] = 2; + this->outgoing_result_response.response.sequence.data[3] = 6; + this->outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; // Initialize cancel request @@ -790,23 +790,23 @@ TEST_F( // Check that the result response was received correctly EXPECT_EQ( - this->outgoing_result_response.action_status, - this->incoming_result_response.action_status); + this->outgoing_result_response.status, + this->incoming_result_response.status); ASSERT_EQ( - this->outgoing_result_response.sequence.size, this->incoming_result_response.sequence.size); + this->outgoing_result_response.response.sequence.size, this->incoming_result_response.response.sequence.size); EXPECT_TRUE(!memcmp( - this->outgoing_result_response.sequence.data, - this->incoming_result_response.sequence.data, - this->outgoing_result_response.sequence.size)); - - test_msgs__action__Fibonacci_Goal_Request__fini(&this->outgoing_goal_request); - test_msgs__action__Fibonacci_Goal_Request__fini(&this->incoming_goal_request); - test_msgs__action__Fibonacci_Goal_Response__fini(&this->incoming_goal_response); - test_msgs__action__Fibonacci_Goal_Response__fini(&this->outgoing_goal_response); - test_msgs__action__Fibonacci_Result_Request__fini(&this->incoming_result_request); - test_msgs__action__Fibonacci_Result_Request__fini(&this->outgoing_result_request); - test_msgs__action__Fibonacci_Result_Response__fini(&this->incoming_result_response); - test_msgs__action__Fibonacci_Result_Response__fini(&this->outgoing_result_response); + this->outgoing_result_response.response.sequence.data, + this->incoming_result_response.response.sequence.data, + this->outgoing_result_response.response.sequence.size)); + + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->outgoing_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->incoming_goal_request); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->incoming_goal_response); + test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->outgoing_goal_response); + test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->incoming_result_request); + test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->outgoing_result_request); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->incoming_result_response); + test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->outgoing_result_response); action_msgs__srv__CancelGoal_Request__fini(&incoming_cancel_request); action_msgs__srv__CancelGoal_Request__fini(&outgoing_cancel_request); action_msgs__srv__CancelGoal_Response__fini(&incoming_cancel_response); From 41eb88fea2b42ee503e32dc0179e916b50dcf85a Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 12 Feb 2019 11:50:56 -0800 Subject: [PATCH 6/8] match renamed action types --- .../rcl_action/test_action_communication.cpp | 180 +++++++++--------- .../rcl_action/test_action_interaction.cpp | 158 +++++++-------- 2 files changed, 169 insertions(+), 169 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index 7beab2a58..c80ad83bb 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -156,18 +156,18 @@ class CLASSNAME (TestActionCommunication, RMW_IMPLEMENTATION) : public ::testing TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_comm) { - test_msgs__action__Fibonacci_Action_Goal_Request outgoing_goal_request; - test_msgs__action__Fibonacci_Action_Goal_Request incoming_goal_request; - test_msgs__action__Fibonacci_Action_Goal_Response outgoing_goal_response; - test_msgs__action__Fibonacci_Action_Goal_Response incoming_goal_response; - test_msgs__action__Fibonacci_Action_Goal_Request__init(&outgoing_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Request__init(&incoming_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Response__init(&outgoing_goal_response); - test_msgs__action__Fibonacci_Action_Goal_Response__init(&incoming_goal_response); + test_msgs__action__Fibonacci_SendGoal_Request outgoing_goal_request; + test_msgs__action__Fibonacci_SendGoal_Request incoming_goal_request; + test_msgs__action__Fibonacci_SendGoal_Response outgoing_goal_response; + test_msgs__action__Fibonacci_SendGoal_Response incoming_goal_response; + test_msgs__action__Fibonacci_SendGoal_Request__init(&outgoing_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__init(&incoming_goal_request); + test_msgs__action__Fibonacci_SendGoal_Response__init(&outgoing_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__init(&incoming_goal_response); // Initialize goal request - init_test_uuid0(outgoing_goal_request.uuid); - outgoing_goal_request.request.order = 10; + init_test_uuid0(outgoing_goal_request.goal_id); + outgoing_goal_request.goal.order = 10; // Send goal request with valid arguments int64_t sequence_number; @@ -201,10 +201,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; // Check that the goal request was received correctly - EXPECT_EQ(outgoing_goal_request.request.order, incoming_goal_request.request.order); + EXPECT_EQ(outgoing_goal_request.goal.order, incoming_goal_request.goal.order); EXPECT_TRUE(uuidcmp( - outgoing_goal_request.uuid, - incoming_goal_request.uuid)); + outgoing_goal_request.goal_id, + incoming_goal_request.goal_id)); // Initialize goal response outgoing_goal_response.accepted = true; @@ -252,10 +252,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c EXPECT_EQ(outgoing_goal_response.stamp.sec, incoming_goal_response.stamp.sec); EXPECT_EQ(outgoing_goal_response.stamp.nanosec, incoming_goal_response.stamp.nanosec); - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&outgoing_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&incoming_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&incoming_goal_response); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&outgoing_goal_response); + test_msgs__action__Fibonacci_SendGoal_Request__fini(&outgoing_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__fini(&incoming_goal_request); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&incoming_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&outgoing_goal_response); } @@ -385,17 +385,17 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_cancel TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result_comm) { - test_msgs__action__Fibonacci_Action_Result_Request outgoing_result_request; - test_msgs__action__Fibonacci_Action_Result_Request incoming_result_request; - test_msgs__action__Fibonacci_Action_Result_Response outgoing_result_response; - test_msgs__action__Fibonacci_Action_Result_Response incoming_result_response; - test_msgs__action__Fibonacci_Action_Result_Request__init(&outgoing_result_request); - test_msgs__action__Fibonacci_Action_Result_Request__init(&incoming_result_request); - test_msgs__action__Fibonacci_Action_Result_Response__init(&outgoing_result_response); - test_msgs__action__Fibonacci_Action_Result_Response__init(&incoming_result_response); + test_msgs__action__Fibonacci_GetResult_Request outgoing_result_request; + test_msgs__action__Fibonacci_GetResult_Request incoming_result_request; + test_msgs__action__Fibonacci_GetResult_Response outgoing_result_response; + test_msgs__action__Fibonacci_GetResult_Response incoming_result_response; + test_msgs__action__Fibonacci_GetResult_Request__init(&outgoing_result_request); + test_msgs__action__Fibonacci_GetResult_Request__init(&incoming_result_request); + test_msgs__action__Fibonacci_GetResult_Response__init(&outgoing_result_response); + test_msgs__action__Fibonacci_GetResult_Response__init(&incoming_result_response); // Initialize result request - init_test_uuid0(outgoing_result_request.uuid); + init_test_uuid0(outgoing_result_request.goal_id); // Send result request with valid arguments int64_t sequence_number; @@ -430,16 +430,16 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - outgoing_result_request.uuid, - incoming_result_request.uuid)); + outgoing_result_request.goal_id, + incoming_result_request.goal_id)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &outgoing_result_response.response.sequence, 4)); - outgoing_result_response.response.sequence.data[0] = 0; - outgoing_result_response.response.sequence.data[1] = 1; - outgoing_result_response.response.sequence.data[2] = 2; - outgoing_result_response.response.sequence.data[3] = 6; + &outgoing_result_response.result.sequence, 4)); + outgoing_result_response.result.sequence.data[0] = 0; + outgoing_result_response.result.sequence.data[1] = 1; + outgoing_result_response.result.sequence.data[2] = 2; + outgoing_result_response.result.sequence.data[3] = 6; outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; @@ -480,16 +480,16 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result // Check that the result response was received correctly EXPECT_EQ(outgoing_result_response.status, incoming_result_response.status); - ASSERT_EQ(outgoing_result_response.response.sequence.size, incoming_result_response.response.sequence.size); + ASSERT_EQ(outgoing_result_response.result.sequence.size, incoming_result_response.result.sequence.size); EXPECT_TRUE(!memcmp( - outgoing_result_response.response.sequence.data, - incoming_result_response.response.sequence.data, - outgoing_result_response.response.sequence.size)); - - test_msgs__action__Fibonacci_Action_Result_Request__fini(&incoming_result_request); - test_msgs__action__Fibonacci_Action_Result_Request__fini(&outgoing_result_request); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&incoming_result_response); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&outgoing_result_response); + outgoing_result_response.result.sequence.data, + incoming_result_response.result.sequence.data, + outgoing_result_response.result.sequence.size)); + + test_msgs__action__Fibonacci_GetResult_Request__fini(&incoming_result_request); + test_msgs__action__Fibonacci_GetResult_Request__fini(&outgoing_result_request); + test_msgs__action__Fibonacci_GetResult_Response__fini(&incoming_result_response); + test_msgs__action__Fibonacci_GetResult_Response__fini(&outgoing_result_response); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_status_comm) @@ -569,10 +569,10 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_status TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedback_comm) { - test_msgs__action__Fibonacci_Action_Feedback outgoing_feedback; - test_msgs__action__Fibonacci_Action_Feedback incoming_feedback; - test_msgs__action__Fibonacci_Action_Feedback__init(&outgoing_feedback); - test_msgs__action__Fibonacci_Action_Feedback__init(&incoming_feedback); + 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_generator_c__int32__Sequence__init( @@ -580,7 +580,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba 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.uuid); + init_test_uuid0(outgoing_feedback.goal_id); // Publish feedback with valid arguments rcl_ret_t ret = rcl_action_publish_feedback(&this->action_server, &outgoing_feedback); @@ -615,28 +615,28 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - outgoing_feedback.uuid, - incoming_feedback.uuid)); + outgoing_feedback.goal_id, + incoming_feedback.goal_id)); ASSERT_EQ(outgoing_feedback.feedback.sequence.size, incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( outgoing_feedback.feedback.sequence.data, incoming_feedback.feedback.sequence.data, outgoing_feedback.feedback.sequence.size)); - test_msgs__action__Fibonacci_Action_Feedback__fini(&incoming_feedback); - test_msgs__action__Fibonacci_Action_Feedback__fini(&outgoing_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__fini(&incoming_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__fini(&outgoing_feedback); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal_request_opts) { - test_msgs__action__Fibonacci_Action_Goal_Request outgoing_goal_request; - test_msgs__action__Fibonacci_Action_Goal_Request incoming_goal_request; - test_msgs__action__Fibonacci_Action_Goal_Request__init(&outgoing_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Request__init(&incoming_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request outgoing_goal_request; + test_msgs__action__Fibonacci_SendGoal_Request incoming_goal_request; + test_msgs__action__Fibonacci_SendGoal_Request__init(&outgoing_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__init(&incoming_goal_request); // Initialize goal request - init_test_uuid0(outgoing_goal_request.uuid); - outgoing_goal_request.request.order = 10; + init_test_uuid0(outgoing_goal_request.goal_id); + outgoing_goal_request.goal.order = 10; int64_t sequence_number = 1234; rcl_ret_t ret = 0; @@ -680,16 +680,16 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal EXPECT_EQ(ret, RCL_RET_ACTION_SERVER_INVALID) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&outgoing_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&incoming_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__fini(&outgoing_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__fini(&incoming_goal_request); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal_response_opts) { - test_msgs__action__Fibonacci_Action_Goal_Response outgoing_goal_response; - test_msgs__action__Fibonacci_Action_Goal_Response incoming_goal_response; - test_msgs__action__Fibonacci_Action_Goal_Response__init(&outgoing_goal_response); - test_msgs__action__Fibonacci_Action_Goal_Response__init(&incoming_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response outgoing_goal_response; + test_msgs__action__Fibonacci_SendGoal_Response incoming_goal_response; + test_msgs__action__Fibonacci_SendGoal_Response__init(&outgoing_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__init(&incoming_goal_response); // Initialize goal response outgoing_goal_response.accepted = true; @@ -741,8 +741,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal EXPECT_EQ(ret, RCL_RET_ACTION_CLIENT_INVALID) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&incoming_goal_response); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&outgoing_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&incoming_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&outgoing_goal_response); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_cancel_request_opts) @@ -868,13 +868,13 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_canc TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_result_request_opts) { - test_msgs__action__Fibonacci_Action_Result_Request outgoing_result_request; - test_msgs__action__Fibonacci_Action_Result_Request incoming_result_request; - test_msgs__action__Fibonacci_Action_Result_Request__init(&outgoing_result_request); - test_msgs__action__Fibonacci_Action_Result_Request__init(&incoming_result_request); + test_msgs__action__Fibonacci_GetResult_Request outgoing_result_request; + test_msgs__action__Fibonacci_GetResult_Request incoming_result_request; + test_msgs__action__Fibonacci_GetResult_Request__init(&outgoing_result_request); + test_msgs__action__Fibonacci_GetResult_Request__init(&incoming_result_request); // Initialize result request - init_test_uuid0(outgoing_result_request.uuid); + init_test_uuid0(outgoing_result_request.goal_id); // Send result request with null action client int64_t sequence_number = 1324; @@ -918,24 +918,24 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Action_Result_Request__fini(&incoming_result_request); - test_msgs__action__Fibonacci_Action_Result_Request__fini(&outgoing_result_request); + test_msgs__action__Fibonacci_GetResult_Request__fini(&incoming_result_request); + test_msgs__action__Fibonacci_GetResult_Request__fini(&outgoing_result_request); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_result_response_opts) { - test_msgs__action__Fibonacci_Action_Result_Response outgoing_result_response; - test_msgs__action__Fibonacci_Action_Result_Response incoming_result_response; - test_msgs__action__Fibonacci_Action_Result_Response__init(&outgoing_result_response); - test_msgs__action__Fibonacci_Action_Result_Response__init(&incoming_result_response); + test_msgs__action__Fibonacci_GetResult_Response outgoing_result_response; + test_msgs__action__Fibonacci_GetResult_Response incoming_result_response; + test_msgs__action__Fibonacci_GetResult_Response__init(&outgoing_result_response); + test_msgs__action__Fibonacci_GetResult_Response__init(&incoming_result_response); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &outgoing_result_response.response.sequence, 4)); - outgoing_result_response.response.sequence.data[0] = 0; - outgoing_result_response.response.sequence.data[1] = 1; - outgoing_result_response.response.sequence.data[2] = 2; - outgoing_result_response.response.sequence.data[3] = 6; + &outgoing_result_response.result.sequence, 4)); + outgoing_result_response.result.sequence.data[0] = 0; + outgoing_result_response.result.sequence.data[1] = 1; + outgoing_result_response.result.sequence.data[2] = 2; + outgoing_result_response.result.sequence.data[3] = 6; outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; @@ -980,16 +980,16 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu EXPECT_EQ(ret, RCL_RET_ACTION_CLIENT_INVALID) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&incoming_result_response); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&outgoing_result_response); + test_msgs__action__Fibonacci_GetResult_Response__fini(&incoming_result_response); + test_msgs__action__Fibonacci_GetResult_Response__fini(&outgoing_result_response); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feedback_opts) { - test_msgs__action__Fibonacci_Action_Feedback outgoing_feedback; - test_msgs__action__Fibonacci_Action_Feedback incoming_feedback; - test_msgs__action__Fibonacci_Action_Feedback__init(&outgoing_feedback); - test_msgs__action__Fibonacci_Action_Feedback__init(&incoming_feedback); + 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_generator_c__int32__Sequence__init( @@ -997,7 +997,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed 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.uuid); + init_test_uuid0(outgoing_feedback.goal_id); // Publish feedback with null action server rcl_ret_t ret = rcl_action_publish_feedback(nullptr, &outgoing_feedback); @@ -1031,8 +1031,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str; rcl_reset_error(); - test_msgs__action__Fibonacci_Action_Feedback__fini(&incoming_feedback); - test_msgs__action__Fibonacci_Action_Feedback__fini(&outgoing_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__fini(&incoming_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__fini(&outgoing_feedback); } TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_status_opts) diff --git a/rcl_action/test/rcl_action/test_action_interaction.cpp b/rcl_action/test/rcl_action/test_action_interaction.cpp index 7f79a92f3..83dc311c9 100644 --- a/rcl_action/test/rcl_action/test_action_interaction.cpp +++ b/rcl_action/test/rcl_action/test_action_interaction.cpp @@ -36,16 +36,16 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public protected: void SetUp() override { - test_msgs__action__Fibonacci_Action_Goal_Request__init(&this->outgoing_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Request__init(&this->incoming_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Response__init(&this->outgoing_goal_response); - test_msgs__action__Fibonacci_Action_Goal_Response__init(&this->incoming_goal_response); - test_msgs__action__Fibonacci_Action_Result_Request__init(&this->outgoing_result_request); - test_msgs__action__Fibonacci_Action_Result_Request__init(&this->incoming_result_request); - test_msgs__action__Fibonacci_Action_Result_Response__init(&this->outgoing_result_response); - test_msgs__action__Fibonacci_Action_Result_Response__init(&this->incoming_result_response); - test_msgs__action__Fibonacci_Action_Feedback__init(&this->outgoing_feedback); - test_msgs__action__Fibonacci_Action_Feedback__init(&this->incoming_feedback); + test_msgs__action__Fibonacci_SendGoal_Request__init(&this->outgoing_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__init(&this->incoming_goal_request); + test_msgs__action__Fibonacci_SendGoal_Response__init(&this->outgoing_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__init(&this->incoming_goal_response); + test_msgs__action__Fibonacci_GetResult_Request__init(&this->outgoing_result_request); + test_msgs__action__Fibonacci_GetResult_Request__init(&this->incoming_result_request); + test_msgs__action__Fibonacci_GetResult_Response__init(&this->outgoing_result_response); + test_msgs__action__Fibonacci_GetResult_Response__init(&this->incoming_result_response); + test_msgs__action__Fibonacci_FeedbackMessage__init(&this->outgoing_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__init(&this->incoming_feedback); rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -118,16 +118,16 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public void TearDown() override { // Finalize - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->outgoing_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->incoming_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->incoming_goal_response); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->outgoing_goal_response); - test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->incoming_result_request); - test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->outgoing_result_request); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->incoming_result_response); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->outgoing_result_response); - test_msgs__action__Fibonacci_Action_Feedback__fini(&this->outgoing_feedback); - test_msgs__action__Fibonacci_Action_Feedback__fini(&this->incoming_feedback); + test_msgs__action__Fibonacci_SendGoal_Request__fini(&this->outgoing_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__fini(&this->incoming_goal_request); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&this->incoming_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&this->outgoing_goal_response); + test_msgs__action__Fibonacci_GetResult_Request__fini(&this->incoming_result_request); + test_msgs__action__Fibonacci_GetResult_Request__fini(&this->outgoing_result_request); + test_msgs__action__Fibonacci_GetResult_Response__fini(&this->incoming_result_response); + test_msgs__action__Fibonacci_GetResult_Response__fini(&this->outgoing_result_response); + test_msgs__action__Fibonacci_FeedbackMessage__fini(&this->outgoing_feedback); + test_msgs__action__Fibonacci_FeedbackMessage__fini(&this->incoming_feedback); rcl_ret_t ret = rcl_action_server_fini(&this->action_server, &this->node); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; ret = rcl_clock_fini(&this->clock); @@ -156,16 +156,16 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public } } - test_msgs__action__Fibonacci_Action_Goal_Request outgoing_goal_request; - test_msgs__action__Fibonacci_Action_Goal_Request incoming_goal_request; - test_msgs__action__Fibonacci_Action_Goal_Response outgoing_goal_response; - test_msgs__action__Fibonacci_Action_Goal_Response incoming_goal_response; - test_msgs__action__Fibonacci_Action_Result_Request outgoing_result_request; - test_msgs__action__Fibonacci_Action_Result_Request incoming_result_request; - test_msgs__action__Fibonacci_Action_Result_Response outgoing_result_response; - test_msgs__action__Fibonacci_Action_Result_Response incoming_result_response; - test_msgs__action__Fibonacci_Action_Feedback outgoing_feedback; - test_msgs__action__Fibonacci_Action_Feedback incoming_feedback; + test_msgs__action__Fibonacci_SendGoal_Request outgoing_goal_request; + test_msgs__action__Fibonacci_SendGoal_Request incoming_goal_request; + test_msgs__action__Fibonacci_SendGoal_Response outgoing_goal_response; + test_msgs__action__Fibonacci_SendGoal_Response incoming_goal_response; + test_msgs__action__Fibonacci_GetResult_Request outgoing_result_request; + test_msgs__action__Fibonacci_GetResult_Request incoming_result_request; + test_msgs__action__Fibonacci_GetResult_Response outgoing_result_response; + test_msgs__action__Fibonacci_GetResult_Response incoming_result_response; + test_msgs__action__Fibonacci_FeedbackMessage outgoing_feedback; + test_msgs__action__Fibonacci_FeedbackMessage incoming_feedback; rcl_action_client_t action_client; rcl_action_server_t action_server; @@ -197,8 +197,8 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_interaction) { // Initialize goal request - init_test_uuid0(this->outgoing_goal_request.uuid); - this->outgoing_goal_request.request.order = 10; + init_test_uuid0(this->outgoing_goal_request.goal_id); + this->outgoing_goal_request.goal.order = 10; // Send goal request with valid arguments int64_t sequence_number; @@ -235,10 +235,10 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; // Check that the goal request was received correctly - EXPECT_EQ(this->outgoing_goal_request.request.order, this->incoming_goal_request.request.order); + EXPECT_EQ(this->outgoing_goal_request.goal.order, this->incoming_goal_request.goal.order); EXPECT_TRUE(uuidcmp( - this->outgoing_goal_request.uuid, - this->incoming_goal_request.uuid)); + this->outgoing_goal_request.goal_id, + this->incoming_goal_request.goal_id)); // Initialize goal response this->outgoing_goal_response.accepted = true; @@ -288,7 +288,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in EXPECT_EQ(this->outgoing_goal_response.stamp.nanosec, this->incoming_goal_response.stamp.nanosec); // Initialize result request - init_test_uuid0(this->outgoing_result_request.uuid); + init_test_uuid0(this->outgoing_result_request.goal_id); // Send result request with valid arguments ret = rcl_action_send_result_request( @@ -301,7 +301,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in this->outgoing_feedback.feedback.sequence.data[0] = 0; this->outgoing_feedback.feedback.sequence.data[1] = 1; this->outgoing_feedback.feedback.sequence.data[2] = 2; - init_test_uuid0(this->outgoing_feedback.uuid); + init_test_uuid0(this->outgoing_feedback.goal_id); // Publish feedback with valid arguments ret = rcl_action_publish_feedback(&this->action_server, &this->outgoing_feedback); @@ -339,8 +339,8 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_feedback.uuid, - this->incoming_feedback.uuid)); + this->outgoing_feedback.goal_id, + this->incoming_feedback.goal_id)); ASSERT_EQ(this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( this->outgoing_feedback.feedback.sequence.data, @@ -377,16 +377,16 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_result_request.uuid, - this->incoming_result_request.uuid)); + this->outgoing_result_request.goal_id, + this->incoming_result_request.goal_id)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &this->outgoing_result_response.response.sequence, 4)); - this->outgoing_result_response.response.sequence.data[0] = 0; - this->outgoing_result_response.response.sequence.data[1] = 1; - this->outgoing_result_response.response.sequence.data[2] = 2; - this->outgoing_result_response.response.sequence.data[3] = 6; + &this->outgoing_result_response.result.sequence, 4)); + this->outgoing_result_response.result.sequence.data[0] = 0; + this->outgoing_result_response.result.sequence.data[1] = 1; + this->outgoing_result_response.result.sequence.data[2] = 2; + this->outgoing_result_response.result.sequence.data[3] = 6; this->outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; @@ -431,11 +431,11 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in this->outgoing_result_response.status, this->incoming_result_response.status); ASSERT_EQ( - this->outgoing_result_response.response.sequence.size, this->incoming_result_response.response.sequence.size); + this->outgoing_result_response.result.sequence.size, this->incoming_result_response.result.sequence.size); EXPECT_TRUE(!memcmp( - this->outgoing_result_response.response.sequence.data, - this->incoming_result_response.response.sequence.data, - this->outgoing_result_response.response.sequence.size)); + this->outgoing_result_response.result.sequence.data, + this->incoming_result_response.result.sequence.data, + this->outgoing_result_response.result.sequence.size)); } // Exercises the "Example 2" sequence diagram found in the actions_proposal document. @@ -455,8 +455,8 @@ TEST_F( action_msgs__srv__CancelGoal_Response__init(&incoming_cancel_response); // Initialize goal request - init_test_uuid0(this->outgoing_goal_request.uuid); - this->outgoing_goal_request.request.order = 10; + init_test_uuid0(this->outgoing_goal_request.goal_id); + this->outgoing_goal_request.goal.order = 10; // Send goal request with valid arguments int64_t sequence_number; @@ -493,10 +493,10 @@ TEST_F( EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; // Check that the goal request was received correctly - EXPECT_EQ(this->outgoing_goal_request.request.order, this->incoming_goal_request.request.order); + EXPECT_EQ(this->outgoing_goal_request.goal.order, this->incoming_goal_request.goal.order); EXPECT_TRUE(uuidcmp( - this->outgoing_goal_request.uuid, - this->incoming_goal_request.uuid)); + this->outgoing_goal_request.goal_id, + this->incoming_goal_request.goal_id)); // Initialize goal response this->outgoing_goal_response.accepted = true; @@ -546,7 +546,7 @@ TEST_F( EXPECT_EQ(this->outgoing_goal_response.stamp.nanosec, this->incoming_goal_response.stamp.nanosec); // Initialize result request - init_test_uuid0(this->outgoing_result_request.uuid); + init_test_uuid0(this->outgoing_result_request.goal_id); // Send result request with valid arguments ret = rcl_action_send_result_request( @@ -559,7 +559,7 @@ TEST_F( this->outgoing_feedback.feedback.sequence.data[0] = 0; this->outgoing_feedback.feedback.sequence.data[1] = 1; this->outgoing_feedback.feedback.sequence.data[2] = 2; - init_test_uuid0(this->outgoing_feedback.uuid); + init_test_uuid0(this->outgoing_feedback.goal_id); // Publish feedback with valid arguments ret = rcl_action_publish_feedback(&this->action_server, &this->outgoing_feedback); @@ -597,8 +597,8 @@ TEST_F( // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_feedback.uuid, - this->incoming_feedback.uuid)); + this->outgoing_feedback.goal_id, + this->incoming_feedback.goal_id)); ASSERT_EQ(this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( this->outgoing_feedback.feedback.sequence.data, @@ -635,16 +635,16 @@ TEST_F( // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_result_request.uuid, - this->incoming_result_request.uuid)); + this->outgoing_result_request.goal_id, + this->incoming_result_request.goal_id)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( - &this->outgoing_result_response.response.sequence, 4)); - this->outgoing_result_response.response.sequence.data[0] = 0; - this->outgoing_result_response.response.sequence.data[1] = 1; - this->outgoing_result_response.response.sequence.data[2] = 2; - this->outgoing_result_response.response.sequence.data[3] = 6; + &this->outgoing_result_response.result.sequence, 4)); + this->outgoing_result_response.result.sequence.data[0] = 0; + this->outgoing_result_response.result.sequence.data[1] = 1; + this->outgoing_result_response.result.sequence.data[2] = 2; + this->outgoing_result_response.result.sequence.data[3] = 6; this->outgoing_result_response.status = action_msgs__msg__GoalStatus__STATUS_SUCCEEDED; @@ -793,20 +793,20 @@ TEST_F( this->outgoing_result_response.status, this->incoming_result_response.status); ASSERT_EQ( - this->outgoing_result_response.response.sequence.size, this->incoming_result_response.response.sequence.size); + this->outgoing_result_response.result.sequence.size, this->incoming_result_response.result.sequence.size); EXPECT_TRUE(!memcmp( - this->outgoing_result_response.response.sequence.data, - this->incoming_result_response.response.sequence.data, - this->outgoing_result_response.response.sequence.size)); - - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->outgoing_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Request__fini(&this->incoming_goal_request); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->incoming_goal_response); - test_msgs__action__Fibonacci_Action_Goal_Response__fini(&this->outgoing_goal_response); - test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->incoming_result_request); - test_msgs__action__Fibonacci_Action_Result_Request__fini(&this->outgoing_result_request); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->incoming_result_response); - test_msgs__action__Fibonacci_Action_Result_Response__fini(&this->outgoing_result_response); + this->outgoing_result_response.result.sequence.data, + this->incoming_result_response.result.sequence.data, + this->outgoing_result_response.result.sequence.size)); + + test_msgs__action__Fibonacci_SendGoal_Request__fini(&this->outgoing_goal_request); + test_msgs__action__Fibonacci_SendGoal_Request__fini(&this->incoming_goal_request); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&this->incoming_goal_response); + test_msgs__action__Fibonacci_SendGoal_Response__fini(&this->outgoing_goal_response); + test_msgs__action__Fibonacci_GetResult_Request__fini(&this->incoming_result_request); + test_msgs__action__Fibonacci_GetResult_Request__fini(&this->outgoing_result_request); + test_msgs__action__Fibonacci_GetResult_Response__fini(&this->incoming_result_response); + test_msgs__action__Fibonacci_GetResult_Response__fini(&this->outgoing_result_response); action_msgs__srv__CancelGoal_Request__fini(&incoming_cancel_request); action_msgs__srv__CancelGoal_Request__fini(&outgoing_cancel_request); action_msgs__srv__CancelGoal_Response__fini(&incoming_cancel_response); From cc4822b3bd981a41276eda6deaab28fb19de7867 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Thu, 14 Feb 2019 12:53:30 -0800 Subject: [PATCH 7/8] style fix --- .../test/rcl_action/test_action_communication.cpp | 4 +++- .../test/rcl_action/test_action_interaction.cpp | 14 ++++++++++---- 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index c80ad83bb..a5ed5a1ca 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -480,7 +480,9 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result // Check that the result response was received correctly EXPECT_EQ(outgoing_result_response.status, incoming_result_response.status); - ASSERT_EQ(outgoing_result_response.result.sequence.size, incoming_result_response.result.sequence.size); + ASSERT_EQ( + outgoing_result_response.result.sequence.size, + incoming_result_response.result.sequence.size); EXPECT_TRUE(!memcmp( outgoing_result_response.result.sequence.data, incoming_result_response.result.sequence.data, diff --git a/rcl_action/test/rcl_action/test_action_interaction.cpp b/rcl_action/test/rcl_action/test_action_interaction.cpp index 83dc311c9..214f261f9 100644 --- a/rcl_action/test/rcl_action/test_action_interaction.cpp +++ b/rcl_action/test/rcl_action/test_action_interaction.cpp @@ -341,7 +341,9 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in EXPECT_TRUE(uuidcmp( this->outgoing_feedback.goal_id, this->incoming_feedback.goal_id)); - ASSERT_EQ(this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); + ASSERT_EQ( + this->outgoing_feedback.feedback.sequence.size, + this->incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( this->outgoing_feedback.feedback.sequence.data, this->incoming_feedback.feedback.sequence.data, @@ -431,7 +433,8 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in this->outgoing_result_response.status, this->incoming_result_response.status); ASSERT_EQ( - this->outgoing_result_response.result.sequence.size, this->incoming_result_response.result.sequence.size); + this->outgoing_result_response.result.sequence.size, + this->incoming_result_response.result.sequence.size); EXPECT_TRUE(!memcmp( this->outgoing_result_response.result.sequence.data, this->incoming_result_response.result.sequence.data, @@ -599,7 +602,9 @@ TEST_F( EXPECT_TRUE(uuidcmp( this->outgoing_feedback.goal_id, this->incoming_feedback.goal_id)); - ASSERT_EQ(this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); + ASSERT_EQ( + this->outgoing_feedback.feedback.sequence.size, + this->incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( this->outgoing_feedback.feedback.sequence.data, this->incoming_feedback.feedback.sequence.data, @@ -793,7 +798,8 @@ TEST_F( this->outgoing_result_response.status, this->incoming_result_response.status); ASSERT_EQ( - this->outgoing_result_response.result.sequence.size, this->incoming_result_response.result.sequence.size); + this->outgoing_result_response.result.sequence.size, + this->incoming_result_response.result.sequence.size); EXPECT_TRUE(!memcmp( this->outgoing_result_response.result.sequence.data, this->incoming_result_response.result.sequence.data, From 73f2a5b7027e9259b33850702d67842d7fc141fb Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Sun, 17 Feb 2019 21:20:52 -0800 Subject: [PATCH 8/8] update types using unique_identifier_msgs --- .../rcl_action/test_action_communication.cpp | 24 ++++++------- .../rcl_action/test_action_interaction.cpp | 36 +++++++++---------- 2 files changed, 30 insertions(+), 30 deletions(-) diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index a5ed5a1ca..07af43f43 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -166,7 +166,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c test_msgs__action__Fibonacci_SendGoal_Response__init(&incoming_goal_response); // Initialize goal request - init_test_uuid0(outgoing_goal_request.goal_id); + init_test_uuid0(outgoing_goal_request.goal_id.uuid); outgoing_goal_request.goal.order = 10; // Send goal request with valid arguments @@ -203,8 +203,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_goal_c // Check that the goal request was received correctly EXPECT_EQ(outgoing_goal_request.goal.order, incoming_goal_request.goal.order); EXPECT_TRUE(uuidcmp( - outgoing_goal_request.goal_id, - incoming_goal_request.goal_id)); + outgoing_goal_request.goal_id.uuid, + incoming_goal_request.goal_id.uuid)); // Initialize goal response outgoing_goal_response.accepted = true; @@ -395,7 +395,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result test_msgs__action__Fibonacci_GetResult_Response__init(&incoming_result_response); // Initialize result request - init_test_uuid0(outgoing_result_request.goal_id); + init_test_uuid0(outgoing_result_request.goal_id.uuid); // Send result request with valid arguments int64_t sequence_number; @@ -430,8 +430,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_result // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - outgoing_result_request.goal_id, - incoming_result_request.goal_id)); + outgoing_result_request.goal_id.uuid, + incoming_result_request.goal_id.uuid)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( @@ -582,7 +582,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba 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); + init_test_uuid0(outgoing_feedback.goal_id.uuid); // Publish feedback with valid arguments rcl_ret_t ret = rcl_action_publish_feedback(&this->action_server, &outgoing_feedback); @@ -617,8 +617,8 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_valid_feedba // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - outgoing_feedback.goal_id, - incoming_feedback.goal_id)); + outgoing_feedback.goal_id.uuid, + incoming_feedback.goal_id.uuid)); ASSERT_EQ(outgoing_feedback.feedback.sequence.size, incoming_feedback.feedback.sequence.size); EXPECT_TRUE(!memcmp( outgoing_feedback.feedback.sequence.data, @@ -637,7 +637,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_goal test_msgs__action__Fibonacci_SendGoal_Request__init(&incoming_goal_request); // Initialize goal request - init_test_uuid0(outgoing_goal_request.goal_id); + init_test_uuid0(outgoing_goal_request.goal_id.uuid); outgoing_goal_request.goal.order = 10; int64_t sequence_number = 1234; rcl_ret_t ret = 0; @@ -876,7 +876,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_resu test_msgs__action__Fibonacci_GetResult_Request__init(&incoming_result_request); // Initialize result request - init_test_uuid0(outgoing_result_request.goal_id); + init_test_uuid0(outgoing_result_request.goal_id.uuid); // Send result request with null action client int64_t sequence_number = 1324; @@ -999,7 +999,7 @@ TEST_F(CLASSNAME(TestActionCommunication, RMW_IMPLEMENTATION), test_invalid_feed 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); + init_test_uuid0(outgoing_feedback.goal_id.uuid); // Publish feedback with null action server rcl_ret_t ret = rcl_action_publish_feedback(nullptr, &outgoing_feedback); diff --git a/rcl_action/test/rcl_action/test_action_interaction.cpp b/rcl_action/test/rcl_action/test_action_interaction.cpp index 214f261f9..60c0d694b 100644 --- a/rcl_action/test/rcl_action/test_action_interaction.cpp +++ b/rcl_action/test/rcl_action/test_action_interaction.cpp @@ -197,7 +197,7 @@ class CLASSNAME (TestActionClientServerInteraction, RMW_IMPLEMENTATION) : public TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_interaction) { // Initialize goal request - init_test_uuid0(this->outgoing_goal_request.goal_id); + init_test_uuid0(this->outgoing_goal_request.goal_id.uuid); this->outgoing_goal_request.goal.order = 10; // Send goal request with valid arguments @@ -237,8 +237,8 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that the goal request was received correctly EXPECT_EQ(this->outgoing_goal_request.goal.order, this->incoming_goal_request.goal.order); EXPECT_TRUE(uuidcmp( - this->outgoing_goal_request.goal_id, - this->incoming_goal_request.goal_id)); + this->outgoing_goal_request.goal_id.uuid, + this->incoming_goal_request.goal_id.uuid)); // Initialize goal response this->outgoing_goal_response.accepted = true; @@ -288,7 +288,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in EXPECT_EQ(this->outgoing_goal_response.stamp.nanosec, this->incoming_goal_response.stamp.nanosec); // Initialize result request - init_test_uuid0(this->outgoing_result_request.goal_id); + init_test_uuid0(this->outgoing_result_request.goal_id.uuid); // Send result request with valid arguments ret = rcl_action_send_result_request( @@ -301,7 +301,7 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in this->outgoing_feedback.feedback.sequence.data[0] = 0; this->outgoing_feedback.feedback.sequence.data[1] = 1; this->outgoing_feedback.feedback.sequence.data[2] = 2; - init_test_uuid0(this->outgoing_feedback.goal_id); + init_test_uuid0(this->outgoing_feedback.goal_id.uuid); // Publish feedback with valid arguments ret = rcl_action_publish_feedback(&this->action_server, &this->outgoing_feedback); @@ -339,8 +339,8 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_feedback.goal_id, - this->incoming_feedback.goal_id)); + this->outgoing_feedback.goal_id.uuid, + this->incoming_feedback.goal_id.uuid)); ASSERT_EQ( this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); @@ -379,8 +379,8 @@ TEST_F(CLASSNAME(TestActionClientServerInteraction, RMW_IMPLEMENTATION), test_in // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_result_request.goal_id, - this->incoming_result_request.goal_id)); + this->outgoing_result_request.goal_id.uuid, + this->incoming_result_request.goal_id.uuid)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init( @@ -458,7 +458,7 @@ TEST_F( action_msgs__srv__CancelGoal_Response__init(&incoming_cancel_response); // Initialize goal request - init_test_uuid0(this->outgoing_goal_request.goal_id); + init_test_uuid0(this->outgoing_goal_request.goal_id.uuid); this->outgoing_goal_request.goal.order = 10; // Send goal request with valid arguments @@ -498,8 +498,8 @@ TEST_F( // Check that the goal request was received correctly EXPECT_EQ(this->outgoing_goal_request.goal.order, this->incoming_goal_request.goal.order); EXPECT_TRUE(uuidcmp( - this->outgoing_goal_request.goal_id, - this->incoming_goal_request.goal_id)); + this->outgoing_goal_request.goal_id.uuid, + this->incoming_goal_request.goal_id.uuid)); // Initialize goal response this->outgoing_goal_response.accepted = true; @@ -549,7 +549,7 @@ TEST_F( EXPECT_EQ(this->outgoing_goal_response.stamp.nanosec, this->incoming_goal_response.stamp.nanosec); // Initialize result request - init_test_uuid0(this->outgoing_result_request.goal_id); + init_test_uuid0(this->outgoing_result_request.goal_id.uuid); // Send result request with valid arguments ret = rcl_action_send_result_request( @@ -562,7 +562,7 @@ TEST_F( this->outgoing_feedback.feedback.sequence.data[0] = 0; this->outgoing_feedback.feedback.sequence.data[1] = 1; this->outgoing_feedback.feedback.sequence.data[2] = 2; - init_test_uuid0(this->outgoing_feedback.goal_id); + init_test_uuid0(this->outgoing_feedback.goal_id.uuid); // Publish feedback with valid arguments ret = rcl_action_publish_feedback(&this->action_server, &this->outgoing_feedback); @@ -600,8 +600,8 @@ TEST_F( // Check that feedback was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_feedback.goal_id, - this->incoming_feedback.goal_id)); + this->outgoing_feedback.goal_id.uuid, + this->incoming_feedback.goal_id.uuid)); ASSERT_EQ( this->outgoing_feedback.feedback.sequence.size, this->incoming_feedback.feedback.sequence.size); @@ -640,8 +640,8 @@ TEST_F( // Check that the result request was received correctly EXPECT_TRUE(uuidcmp( - this->outgoing_result_request.goal_id, - this->incoming_result_request.goal_id)); + this->outgoing_result_request.goal_id.uuid, + this->incoming_result_request.goal_id.uuid)); // Initialize result response ASSERT_TRUE(rosidl_generator_c__int32__Sequence__init(