From 1a8d86135e788501b500cb9ce003e8108ccce3a7 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 25 Jan 2023 17:58:27 +0000 Subject: [PATCH] Switch to using the client_gid. It should not be a UUID. Signed-off-by: Chris Lalancette --- .../resource/srv__type_support.cpp.em | 1 - .../test_service_typesupport.cpp | 12 ++++++------ .../test_service_typesupport.cpp | 12 ++++++------ 3 files changed, 12 insertions(+), 13 deletions(-) diff --git a/rosidl_typesupport_c/resource/srv__type_support.cpp.em b/rosidl_typesupport_c/resource/srv__type_support.cpp.em index b23a7156..e0de2141 100644 --- a/rosidl_typesupport_c/resource/srv__type_support.cpp.em +++ b/rosidl_typesupport_c/resource/srv__type_support.cpp.em @@ -43,7 +43,6 @@ if len(type_supports) != 1: header_files.append('rosidl_typesupport_interface/macros.h') header_files.append('service_msgs/msg/service_event_info.h') header_files.append('builtin_interfaces/msg/time.h') -header_files.append('unique_identifier_msgs/msg/uuid.h') }@ @[for header_file in header_files]@ @[ if header_file in include_directives]@ diff --git a/rosidl_typesupport_tests/test/rosidl_typesupport_c/test_service_typesupport.cpp b/rosidl_typesupport_tests/test/rosidl_typesupport_c/test_service_typesupport.cpp index 07c57fec..e41f880f 100644 --- a/rosidl_typesupport_tests/test/rosidl_typesupport_c/test_service_typesupport.cpp +++ b/rosidl_typesupport_tests/test/rosidl_typesupport_c/test_service_typesupport.cpp @@ -61,8 +61,8 @@ TEST(test_service_typesupport, basic_types_event_message_create) expected_info.event_type = 2; expected_info.stamp_nanosec = 123; expected_info.stamp_sec = 123; - auto uuid = std::array{0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; - std::copy(uuid.begin(), uuid.end(), expected_info.client_id); + auto gid = std::array{0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; + std::copy(gid.begin(), gid.end(), expected_info.client_gid); rosidl_typesupport_tests__srv__BasicTypes_Request expected_request; rosidl_typesupport_tests__srv__BasicTypes_Request__init(&expected_request); @@ -83,7 +83,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } EXPECT_EQ(event->request.size, 0U); EXPECT_EQ(event->response.size, 0U); @@ -105,7 +105,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } ASSERT_EQ(event->request.size, 1U); EXPECT_EQ(event->response.size, 0U); @@ -129,7 +129,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } EXPECT_EQ(event->request.size, 0U); ASSERT_EQ(event->response.size, 1U); @@ -155,7 +155,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } ASSERT_EQ(event->request.size, 1U); EXPECT_EQ(event->request.data[0].int16_value, expected_request.int16_value); diff --git a/rosidl_typesupport_tests/test/rosidl_typesupport_cpp/test_service_typesupport.cpp b/rosidl_typesupport_tests/test/rosidl_typesupport_cpp/test_service_typesupport.cpp index ba7c92be..ba028aee 100644 --- a/rosidl_typesupport_tests/test/rosidl_typesupport_cpp/test_service_typesupport.cpp +++ b/rosidl_typesupport_tests/test/rosidl_typesupport_cpp/test_service_typesupport.cpp @@ -68,8 +68,8 @@ TEST(test_service_typesupport, basic_types_event_message_create) expected_info.event_type = 2; expected_info.stamp_nanosec = 123; expected_info.stamp_sec = 123; - auto uuid = std::array{0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; - std::copy(uuid.begin(), uuid.end(), expected_info.client_id); + auto gid = std::array{0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; + std::copy(gid.begin(), gid.end(), expected_info.client_gid); auto expected_request = rosidl_typesupport_tests::srv::BasicTypes_Request(); expected_request.int16_value = -1; @@ -88,7 +88,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } EXPECT_EQ(event->request.size(), 0U); EXPECT_EQ(event->response.size(), 0U); @@ -111,7 +111,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } ASSERT_EQ(event->request.size(), 1U); EXPECT_EQ(event->response.size(), 0U); @@ -135,7 +135,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } EXPECT_EQ(event->request.size(), 0U); ASSERT_EQ(event->response.size(), 1U); @@ -159,7 +159,7 @@ TEST(test_service_typesupport, basic_types_event_message_create) EXPECT_EQ(event->info.stamp.nanosec, expected_info.stamp_nanosec); EXPECT_EQ(event->info.stamp.sec, expected_info.stamp_sec); for (int i = 0; i < 16; ++i) { - EXPECT_EQ(event->info.client_id.uuid[i], expected_info.client_id[i]); + EXPECT_EQ(event->info.client_gid[i], expected_info.client_gid[i]); } ASSERT_EQ(event->request.size(), 1U); EXPECT_EQ(event->request[0].int16_value, expected_request.int16_value);