From 973951dd7da96a7c680a2e34770f7955c20b8f01 Mon Sep 17 00:00:00 2001 From: Emerson Knapp <537409+emersonknapp@users.noreply.github.com> Date: Wed, 29 Mar 2023 06:55:31 -0700 Subject: [PATCH] Calculate type hash from TypeDescription (rep2011) (#1027) * Convert TypeDescription to YAML and hash Signed-off-by: Emerson Knapp --- rcl/CMakeLists.txt | 8 + rcl/include/rcl/type_hash.h | 79 ++++++++++ rcl/package.xml | 3 + rcl/src/rcl/type_hash.c | 266 ++++++++++++++++++++++++++++++++ rcl/test/CMakeLists.txt | 6 + rcl/test/rcl/test_type_hash.cpp | 223 ++++++++++++++++++++++++++ 6 files changed, 585 insertions(+) create mode 100644 rcl/include/rcl/type_hash.h create mode 100644 rcl/src/rcl/type_hash.c create mode 100644 rcl/test/rcl/test_type_hash.cpp diff --git a/rcl/CMakeLists.txt b/rcl/CMakeLists.txt index a2aa1d65a..d09ad1122 100644 --- a/rcl/CMakeLists.txt +++ b/rcl/CMakeLists.txt @@ -4,6 +4,7 @@ project(rcl) find_package(ament_cmake_ros REQUIRED) +find_package(libyaml_vendor REQUIRED) find_package(rcl_interfaces REQUIRED) find_package(rcl_logging_interface REQUIRED) find_package(rcl_yaml_param_parser REQUIRED) @@ -13,6 +14,8 @@ find_package(rmw_implementation REQUIRED) find_package(rosidl_runtime_c REQUIRED) find_package(service_msgs REQUIRED) find_package(tracetools REQUIRED) +find_package(type_description_interfaces REQUIRED) +find_package(yaml REQUIRED) include(cmake/rcl_set_symbol_visibility_hidden.cmake) include(cmake/get_default_rcl_logging_implementation.cmake) @@ -64,6 +67,7 @@ set(${PROJECT_NAME}_sources src/rcl/subscription.c src/rcl/time.c src/rcl/timer.c + src/rcl/type_hash.c src/rcl/validate_enclave_name.c src/rcl/validate_topic_name.c src/rcl/wait.c @@ -76,6 +80,7 @@ target_include_directories(${PROJECT_NAME} PUBLIC "$") # specific order: dependents before dependencies ament_target_dependencies(${PROJECT_NAME} + "libyaml_vendor" "rcl_interfaces" "rcl_logging_interface" "rcl_yaml_param_parser" @@ -86,6 +91,7 @@ ament_target_dependencies(${PROJECT_NAME} "rosidl_runtime_c" "service_msgs" "tracetools" + "type_description_interfaces" ) # Causes the visibility macros to use dllexport rather than dllimport, @@ -127,6 +133,8 @@ ament_export_dependencies(${RCL_LOGGING_IMPL}) ament_export_dependencies(rosidl_runtime_c) ament_export_dependencies(service_msgs) ament_export_dependencies(tracetools) +ament_export_dependencies(type_description_interfaces) +ament_export_dependencies(libyaml_vendor) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) diff --git a/rcl/include/rcl/type_hash.h b/rcl/include/rcl/type_hash.h new file mode 100644 index 000000000..08ac509ce --- /dev/null +++ b/rcl/include/rcl/type_hash.h @@ -0,0 +1,79 @@ +// Copyright 2023 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCL__TYPE_HASH_H_ +#define RCL__TYPE_HASH_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rcl/types.h" +#include "rcl/visibility_control.h" +#include "rcutils/sha256.h" +#include "rosidl_runtime_c/type_hash.h" +#include "type_description_interfaces/msg/type_description.h" + +/// Given a TypeDescription, output a string of the hashable JSON representation of that data. +/** + * The output here is generally hashed via rcl_calculate_type_hash() below. + * Compare this reference implementation with the .json output files from + * `rosidl_generator_type_description.generate_type_hash`. + * Both must produce the same output for the same types, providing a stable reference for + * external implementations of the ROS 2 Type Version Hash. + * + * The JSON representation contains all types and fields of the original message, but excludes: + * - Default values + * - Comments + * - The input plaintext files that generated the TypeDescription + * + * \param[in] type_description Prefilled TypeDescription message to be translated + * \param[out] output_repr An initialized empty char array that will be filled with + * the JSON representation of type_description. Note that output_repr will have a + * terminating null character, which should be omitted from hashing. To do so, use + * (output_repr.buffer_length - 1) or strlen(output_repr.buffer) for the size of data to hash. + * \return #RCL_RET_OK on success, or + * \return #RCL_RET_ERROR if any problems occur in translation. + */ +RCL_PUBLIC +rcl_ret_t +rcl_type_description_to_hashable_json( + const type_description_interfaces__msg__TypeDescription * type_description, + rcutils_char_array_t * output_repr); + +/// Calculate the Type Version Hash for a given TypeDescription. +/** + * This function produces a stable hash value for a ROS communication interface type. + * For design motivations leading to this implementation, see REP-2011. + * + * This convenience wrapper calls rcl_type_description_to_hashable_json, + * then runs sha256 hash on the result. + * + * \param[in] msg Prefilled TypeDescription message describing the type to be hashed + * \param[out] message_digest Preallocated buffer, to be filled with calculated checksum + * \return #RCL_RET_OK on success, or + * \return #RCL_RET_ERROR if any problems occur while hashing. + */ +RCL_PUBLIC +rcl_ret_t +rcl_calculate_type_hash( + const type_description_interfaces__msg__TypeDescription * type_description, + rosidl_type_hash_t * out_type_hash); + +#ifdef __cplusplus +} +#endif + +#endif // RCL__TYPE_HASH_H_ diff --git a/rcl/package.xml b/rcl/package.xml index 41adb55d0..e0c065563 100644 --- a/rcl/package.xml +++ b/rcl/package.xml @@ -19,6 +19,7 @@ rmw + libyaml_vendor rcl_interfaces rcl_logging_interface rcl_logging_spdlog @@ -28,6 +29,8 @@ rosidl_runtime_c service_msgs tracetools + type_description_interfaces + yaml ament_cmake_gtest ament_lint_auto diff --git a/rcl/src/rcl/type_hash.c b/rcl/src/rcl/type_hash.c new file mode 100644 index 000000000..f05dd9851 --- /dev/null +++ b/rcl/src/rcl/type_hash.c @@ -0,0 +1,266 @@ +// Copyright 2023 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include "rcl/allocator.h" +#include "rcl/error_handling.h" +#include "rcl/type_hash.h" +#include "rcutils/types/char_array.h" +#include "rcutils/sha256.h" +#include "type_description_interfaces/msg/type_description.h" + +static int yaml_write_handler(void * ext, uint8_t * buffer, size_t size) +{ + rcutils_char_array_t * repr = (rcutils_char_array_t *)ext; + rcutils_ret_t res = rcutils_char_array_strncat(repr, (char *)buffer, size); + return res == RCL_RET_OK ? 1 : 0; +} + +static inline int start_sequence(yaml_emitter_t * emitter) +{ + yaml_event_t event; + return + yaml_sequence_start_event_initialize(&event, NULL, NULL, 1, YAML_FLOW_SEQUENCE_STYLE) && + yaml_emitter_emit(emitter, &event); +} + +static inline int end_sequence(yaml_emitter_t * emitter) +{ + yaml_event_t event; + return + yaml_sequence_end_event_initialize(&event) && + yaml_emitter_emit(emitter, &event); +} + +static inline int start_mapping(yaml_emitter_t * emitter) +{ + yaml_event_t event; + return + yaml_mapping_start_event_initialize(&event, NULL, NULL, 1, YAML_FLOW_MAPPING_STYLE) && + yaml_emitter_emit(emitter, &event); +} + +static inline int end_mapping(yaml_emitter_t * emitter) +{ + yaml_event_t event; + return + yaml_mapping_end_event_initialize(&event) && + yaml_emitter_emit(emitter, &event); +} + +static int emit_key(yaml_emitter_t * emitter, const char * key) +{ + yaml_event_t event; + return + yaml_scalar_event_initialize( + &event, NULL, NULL, + (yaml_char_t *)key, (int)strlen(key), + 0, 1, YAML_DOUBLE_QUOTED_SCALAR_STYLE) && + yaml_emitter_emit(emitter, &event); +} + +static int emit_int(yaml_emitter_t * emitter, size_t val, const char * fmt) +{ + // longest uint64 is 20 decimal digits, plus one byte for trailing \0 + char decimal_buf[21]; + yaml_event_t event; + int ret = snprintf(decimal_buf, sizeof(decimal_buf), fmt, val); + if (ret < 0) { + emitter->problem = "Failed expanding integer"; + return 0; + } + if ((size_t)ret >= sizeof(decimal_buf)) { + emitter->problem = "Decimal buffer overflow"; + return 0; + } + return + yaml_scalar_event_initialize( + &event, NULL, NULL, + (yaml_char_t *)decimal_buf, (int)strlen(decimal_buf), + 1, 0, YAML_PLAIN_SCALAR_STYLE) && + yaml_emitter_emit(emitter, &event); +} + +static int emit_str(yaml_emitter_t * emitter, const rosidl_runtime_c__String * val) +{ + yaml_event_t event; + return + yaml_scalar_event_initialize( + &event, NULL, NULL, + (yaml_char_t *)val->data, (int)val->size, + 0, 1, YAML_DOUBLE_QUOTED_SCALAR_STYLE) && + yaml_emitter_emit(emitter, &event); +} + +static int emit_field_type( + yaml_emitter_t * emitter, + const type_description_interfaces__msg__FieldType * field_type) +{ + return + start_mapping(emitter) && + + emit_key(emitter, "type_id") && + emit_int(emitter, field_type->type_id, "%d") && + + emit_key(emitter, "capacity") && + emit_int(emitter, field_type->capacity, "%zu") && + + emit_key(emitter, "string_capacity") && + emit_int(emitter, field_type->string_capacity, "%zu") && + + emit_key(emitter, "nested_type_name") && + emit_str(emitter, &field_type->nested_type_name) && + + end_mapping(emitter); +} + +static int emit_field( + yaml_emitter_t * emitter, + const type_description_interfaces__msg__Field * field) +{ + return + start_mapping(emitter) && + + emit_key(emitter, "name") && + emit_str(emitter, &field->name) && + + emit_key(emitter, "type") && + emit_field_type(emitter, &field->type) && + + end_mapping(emitter); +} + +static int emit_individual_type_description( + yaml_emitter_t * emitter, + const type_description_interfaces__msg__IndividualTypeDescription * individual_type_description) +{ + if (!( + start_mapping(emitter) && + + emit_key(emitter, "type_name") && + emit_str(emitter, &individual_type_description->type_name) && + + emit_key(emitter, "fields") && + start_sequence(emitter))) + { + return 0; + } + for (size_t i = 0; i < individual_type_description->fields.size; i++) { + if (!emit_field(emitter, &individual_type_description->fields.data[i])) { + return 0; + } + } + return end_sequence(emitter) && end_mapping(emitter); +} + +static int emit_type_description( + yaml_emitter_t * emitter, + const type_description_interfaces__msg__TypeDescription * type_description) +{ + if (!( + start_mapping(emitter) && + + emit_key(emitter, "type_description") && + emit_individual_type_description(emitter, &type_description->type_description) && + + emit_key(emitter, "referenced_type_descriptions") && + start_sequence(emitter))) + { + return 0; + } + for (size_t i = 0; i < type_description->referenced_type_descriptions.size; i++) { + if (!emit_individual_type_description( + emitter, &type_description->referenced_type_descriptions.data[i])) + { + return 0; + } + } + return end_sequence(emitter) && end_mapping(emitter); +} + +rcl_ret_t +rcl_type_description_to_hashable_json( + const type_description_interfaces__msg__TypeDescription * type_description, + rcutils_char_array_t * output_repr) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(type_description, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(output_repr, RCL_RET_INVALID_ARGUMENT); + + yaml_emitter_t emitter; + yaml_event_t event; + + if (!yaml_emitter_initialize(&emitter)) { + goto error; + } + + // Disable line breaks based on line length + yaml_emitter_set_width(&emitter, -1); + // Circumvent EOF line break by providing invalid break style + yaml_emitter_set_break(&emitter, -1); + yaml_emitter_set_output(&emitter, yaml_write_handler, output_repr); + + if (!( + yaml_stream_start_event_initialize(&event, YAML_UTF8_ENCODING) && + yaml_emitter_emit(&emitter, &event) && + + yaml_document_start_event_initialize(&event, NULL, NULL, NULL, 1) && + yaml_emitter_emit(&emitter, &event) && + + emit_type_description(&emitter, type_description) && + + yaml_document_end_event_initialize(&event, 1) && + yaml_emitter_emit(&emitter, &event) && + + yaml_stream_end_event_initialize(&event) && + yaml_emitter_emit(&emitter, &event))) + { + goto error; + } + + yaml_emitter_delete(&emitter); + return RCL_RET_OK; + +error: + rcl_set_error_state(emitter.problem, __FILE__, __LINE__); + yaml_emitter_delete(&emitter); + return RCL_RET_ERROR; +} + +rcl_ret_t +rcl_calculate_type_hash( + const type_description_interfaces__msg__TypeDescription * type_description, + rosidl_type_hash_t * output_hash) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(type_description, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(output_hash, RCL_RET_INVALID_ARGUMENT); + + rcl_ret_t result = RCL_RET_OK; + rcutils_char_array_t msg_repr = rcutils_get_zero_initialized_char_array(); + msg_repr.allocator = rcl_get_default_allocator(); + + output_hash->version = 1; + result = rcl_type_description_to_hashable_json(type_description, &msg_repr); + if (result == RCL_RET_OK) { + rcutils_sha256_ctx_t sha_ctx; + rcutils_sha256_init(&sha_ctx); + // Last item in char_array is null terminator, which should not be hashed. + rcutils_sha256_update(&sha_ctx, (const uint8_t *)msg_repr.buffer, msg_repr.buffer_length - 1); + rcutils_sha256_final(&sha_ctx, output_hash->value); + } + result = rcutils_char_array_fini(&msg_repr); + return result; +} diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 743270fda..560f0540d 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -456,3 +456,9 @@ rcl_add_custom_gtest(test_subscription_content_filter_options LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES "osrf_testing_tools_cpp" "test_msgs" ) + +rcl_add_custom_gtest(test_type_hash + SRCS rcl/test_type_hash.cpp + APPEND_LIBRARY_DIRS ${extra_lib_dirs} + LIBRARIES ${PROJECT_NAME} +) diff --git a/rcl/test/rcl/test_type_hash.cpp b/rcl/test/rcl/test_type_hash.cpp new file mode 100644 index 000000000..f9b4df78c --- /dev/null +++ b/rcl/test/rcl/test_type_hash.cpp @@ -0,0 +1,223 @@ +// Copyright 2023 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include + +#include "type_description_interfaces/msg/type_description.h" +#include "type_description_interfaces/msg/individual_type_description.h" +#include "type_description_interfaces/msg/field.h" +#include "rosidl_runtime_c/string_functions.h" +#include "rcl/allocator.h" +#include "rcl/type_hash.h" +#include "rcutils/sha256.h" + +// Copied directly from generated code +static const rosidl_type_hash_t sensor_msgs__msg__PointCloud2__TYPE_HASH__copy = {1, { + 0x91, 0x98, 0xca, 0xbf, 0x7d, 0xa3, 0x79, 0x6a, + 0xe6, 0xfe, 0x19, 0xc4, 0xcb, 0x3b, 0xdd, 0x35, + 0x25, 0x49, 0x29, 0x88, 0xc7, 0x05, 0x22, 0x62, + 0x8a, 0xf5, 0xda, 0xa1, 0x24, 0xba, 0xe2, 0xb5, + }}; + + +static void init_individual_type_description( + type_description_interfaces__msg__IndividualTypeDescription * itd, + const char * name, + const std::vector> & fields) +{ + rosidl_runtime_c__String__assign( + &itd->type_name, name); + type_description_interfaces__msg__Field__Sequence__init(&itd->fields, fields.size()); + for (size_t i = 0; i < fields.size(); i++) { + auto * field = &itd->fields.data[i]; + const char * name = std::get<0>(fields[i]); + + rosidl_runtime_c__String__assign(&field->name, name); + field->type.type_id = std::get<1>(fields[i]); + const char * nested_type = std::get<2>(fields[i]); + if (nested_type != NULL) { + rosidl_runtime_c__String__assign(&field->type.nested_type_name, nested_type); + } + } +} + +TEST(TestTypeVersionHash, field_type_from_install) { + rcl_ret_t res = RCL_RET_OK; + type_description_interfaces__msg__TypeDescription * td_msg = + type_description_interfaces__msg__TypeDescription__create(); + + init_individual_type_description( + &td_msg->type_description, + "type_description_interfaces/msg/FieldType", { + {"type_id", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT8, NULL}, + {"capacity", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT64, NULL}, + {"string_capacity", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT64, NULL}, + { + "nested_type_name", + type_description_interfaces__msg__FieldType__FIELD_TYPE_BOUNDED_STRING, + NULL}} + ); + td_msg->type_description.fields.data[3].type.string_capacity = 255; + + rosidl_type_hash_t direct_hash; + res = rcl_calculate_type_hash(td_msg, &direct_hash); + ASSERT_EQ(res, RCL_RET_OK); + + rosidl_type_hash_t hash_from_repr; + hash_from_repr.version = 1; + { + rcutils_sha256_ctx_t sha; + rcutils_char_array_t msg_repr = rcutils_get_zero_initialized_char_array(); + msg_repr.allocator = rcl_get_default_allocator(); + + res = rcl_type_description_to_hashable_json(td_msg, &msg_repr); + ASSERT_EQ(res, RCL_RET_OK); + + rcutils_sha256_init(&sha); + rcutils_sha256_update(&sha, (const uint8_t *)msg_repr.buffer, msg_repr.buffer_length - 1); + rcutils_sha256_final(&sha, hash_from_repr.value); + + res = rcutils_char_array_fini(&msg_repr); + ASSERT_EQ(res, RCL_RET_OK); + } + + // NOTE: testing this against the actual installed one, forces an up to date test + auto validation_hash = type_description_interfaces__msg__FieldType__TYPE_HASH; + ASSERT_EQ(direct_hash.version, hash_from_repr.version); + ASSERT_EQ(direct_hash.version, validation_hash.version); + ASSERT_EQ(0, memcmp(direct_hash.value, hash_from_repr.value, ROSIDL_TYPE_HASH_SIZE)); + ASSERT_EQ(0, memcmp(direct_hash.value, validation_hash.value, ROSIDL_TYPE_HASH_SIZE)); +} + + +TEST(TestTypeVersionHash, nested_real_type) { + rcl_ret_t res = RCL_RET_OK; + type_description_interfaces__msg__TypeDescription * td_msg = + type_description_interfaces__msg__TypeDescription__create(); + // 3 referenced types: std_msgs/Header, builtin_interfaces/Time, sensor_msgs/PointField + type_description_interfaces__msg__IndividualTypeDescription__Sequence__init( + &td_msg->referenced_type_descriptions, 3); + + // PointCloud2.msg + // + // std_msgs/Header header + // uint32 height + // uint32 width + // PointField[] fields + // bool is_bigendian + // uint32 point_step + // uint32 row_step + // uint8[] data + // bool is_dense + init_individual_type_description( + &td_msg->type_description, + "sensor_msgs/msg/PointCloud2", { + { + "header", + type_description_interfaces__msg__FieldType__FIELD_TYPE_NESTED_TYPE, + "std_msgs/msg/Header"}, + {"height", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT32, NULL}, + {"width", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT32, NULL}, + { + "fields", + type_description_interfaces__msg__FieldType__FIELD_TYPE_NESTED_TYPE_UNBOUNDED_SEQUENCE, + "sensor_msgs/msg/PointField"}, + {"is_bigendian", type_description_interfaces__msg__FieldType__FIELD_TYPE_BOOLEAN, NULL}, + {"point_step", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT32, NULL}, + {"row_step", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT32, NULL}, + { + "data", + type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT8_UNBOUNDED_SEQUENCE, + NULL}, + {"is_dense", type_description_interfaces__msg__FieldType__FIELD_TYPE_BOOLEAN, NULL}} + ); + + // add referenced types in alphabetical order + size_t nested_field_index = 0; + + // builtin_interfaces/msg/Time.msg + // + // int32 sec + // uint32 nanosec + init_individual_type_description( + &td_msg->referenced_type_descriptions.data[nested_field_index++], + "builtin_interfaces/msg/Time", { + {"sec", type_description_interfaces__msg__FieldType__FIELD_TYPE_INT32, NULL}, + {"nanosec", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT32, NULL}} + ); + + // sensor_msgs/msg/PointField.msg + // + // string name + // uint32 offset + // uint8 datatype + // uint32 count + init_individual_type_description( + &td_msg->referenced_type_descriptions.data[nested_field_index++], + "sensor_msgs/msg/PointField", { + {"name", type_description_interfaces__msg__FieldType__FIELD_TYPE_STRING, NULL}, + {"offset", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT32, NULL}, + {"datatype", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT8, NULL}, + {"count", type_description_interfaces__msg__FieldType__FIELD_TYPE_UINT32, NULL}} + ); + + // std_msgs/msg/Header.msg + // + // builtin_interfaces/Time stamp + // string frame_id + init_individual_type_description( + &td_msg->referenced_type_descriptions.data[nested_field_index++], + "std_msgs/msg/Header", { + { + "stamp", + type_description_interfaces__msg__FieldType__FIELD_TYPE_NESTED_TYPE, + "builtin_interfaces/msg/Time"}, + { + "frame_id", + type_description_interfaces__msg__FieldType__FIELD_TYPE_STRING, + NULL}} + ); + + rosidl_type_hash_t direct_hash; + res = rcl_calculate_type_hash(td_msg, &direct_hash); + ASSERT_EQ(res, RCL_RET_OK); + + rosidl_type_hash_t hash_from_repr; + hash_from_repr.version = 1; + { + rcutils_sha256_ctx_t sha; + rcutils_char_array_t msg_repr = rcutils_get_zero_initialized_char_array(); + msg_repr.allocator = rcl_get_default_allocator(); + + res = rcl_type_description_to_hashable_json(td_msg, &msg_repr); + ASSERT_EQ(res, RCL_RET_OK); + + rcutils_sha256_init(&sha); + rcutils_sha256_update(&sha, (const uint8_t *)msg_repr.buffer, msg_repr.buffer_length - 1); + rcutils_sha256_final(&sha, hash_from_repr.value); + + res = rcutils_char_array_fini(&msg_repr); + ASSERT_EQ(res, RCL_RET_OK); + } + + auto validation_hash = sensor_msgs__msg__PointCloud2__TYPE_HASH__copy; + ASSERT_EQ(direct_hash.version, hash_from_repr.version); + ASSERT_EQ(direct_hash.version, validation_hash.version); + ASSERT_EQ(0, memcmp(direct_hash.value, hash_from_repr.value, ROSIDL_TYPE_HASH_SIZE)); + ASSERT_EQ(0, memcmp(direct_hash.value, validation_hash.value, ROSIDL_TYPE_HASH_SIZE)); +}