ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
type_hash.c
1 // Copyright 2023 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <stdio.h>
16 
17 #include <yaml.h>
18 
19 #include "rcl/allocator.h"
20 #include "rcl/error_handling.h"
21 #include "rcl/type_hash.h"
22 #include "rcutils/types/char_array.h"
23 #include "rcutils/sha256.h"
24 #include "type_description_interfaces/msg/type_description.h"
25 
26 #include "./common.h"
27 
28 static int yaml_write_handler(void * ext, uint8_t * buffer, size_t size)
29 {
30  rcutils_char_array_t * repr = (rcutils_char_array_t *)ext;
31  rcutils_ret_t res = rcutils_char_array_strncat(repr, (char *)buffer, size);
32  return res == RCL_RET_OK ? 1 : 0;
33 }
34 
35 static inline int start_sequence(yaml_emitter_t * emitter)
36 {
37  yaml_event_t event;
38  return
39  yaml_sequence_start_event_initialize(&event, NULL, NULL, 1, YAML_FLOW_SEQUENCE_STYLE) &&
40  yaml_emitter_emit(emitter, &event);
41 }
42 
43 static inline int end_sequence(yaml_emitter_t * emitter)
44 {
45  yaml_event_t event;
46  return
47  yaml_sequence_end_event_initialize(&event) &&
48  yaml_emitter_emit(emitter, &event);
49 }
50 
51 static inline int start_mapping(yaml_emitter_t * emitter)
52 {
53  yaml_event_t event;
54  return
55  yaml_mapping_start_event_initialize(&event, NULL, NULL, 1, YAML_FLOW_MAPPING_STYLE) &&
56  yaml_emitter_emit(emitter, &event);
57 }
58 
59 static inline int end_mapping(yaml_emitter_t * emitter)
60 {
61  yaml_event_t event;
62  return
63  yaml_mapping_end_event_initialize(&event) &&
64  yaml_emitter_emit(emitter, &event);
65 }
66 
67 static int emit_key(yaml_emitter_t * emitter, const char * key)
68 {
69  yaml_event_t event;
70  return
71  yaml_scalar_event_initialize(
72  &event, NULL, NULL,
73  (yaml_char_t *)key, (int)strlen(key),
74  0, 1, YAML_DOUBLE_QUOTED_SCALAR_STYLE) &&
75  yaml_emitter_emit(emitter, &event);
76 }
77 
78 static int emit_int(yaml_emitter_t * emitter, size_t val, const char * fmt)
79 {
80  // longest uint64 is 20 decimal digits, plus one byte for trailing \0
81  char decimal_buf[21];
82  yaml_event_t event;
83  int ret = snprintf(decimal_buf, sizeof(decimal_buf), fmt, val);
84  if (ret < 0) {
85  emitter->problem = "Failed expanding integer";
86  return 0;
87  }
88  if ((size_t)ret >= sizeof(decimal_buf)) {
89  emitter->problem = "Decimal buffer overflow";
90  return 0;
91  }
92  return
93  yaml_scalar_event_initialize(
94  &event, NULL, NULL,
95  (yaml_char_t *)decimal_buf, (int)strlen(decimal_buf),
96  1, 0, YAML_PLAIN_SCALAR_STYLE) &&
97  yaml_emitter_emit(emitter, &event);
98 }
99 
100 static int emit_str(yaml_emitter_t * emitter, const rosidl_runtime_c__String * val)
101 {
102  yaml_event_t event;
103  return
104  yaml_scalar_event_initialize(
105  &event, NULL, NULL,
106  (yaml_char_t *)val->data, (int)val->size,
107  0, 1, YAML_DOUBLE_QUOTED_SCALAR_STYLE) &&
108  yaml_emitter_emit(emitter, &event);
109 }
110 
111 static int emit_field_type(
112  yaml_emitter_t * emitter,
113  const type_description_interfaces__msg__FieldType * field_type)
114 {
115  return
116  start_mapping(emitter) &&
117 
118  emit_key(emitter, "type_id") &&
119  emit_int(emitter, field_type->type_id, "%d") &&
120 
121  emit_key(emitter, "capacity") &&
122  emit_int(emitter, field_type->capacity, "%zu") &&
123 
124  emit_key(emitter, "string_capacity") &&
125  emit_int(emitter, field_type->string_capacity, "%zu") &&
126 
127  emit_key(emitter, "nested_type_name") &&
128  emit_str(emitter, &field_type->nested_type_name) &&
129 
130  end_mapping(emitter);
131 }
132 
133 static int emit_field(
134  yaml_emitter_t * emitter,
135  const type_description_interfaces__msg__Field * field)
136 {
137  return
138  start_mapping(emitter) &&
139 
140  emit_key(emitter, "name") &&
141  emit_str(emitter, &field->name) &&
142 
143  emit_key(emitter, "type") &&
144  emit_field_type(emitter, &field->type) &&
145 
146  end_mapping(emitter);
147 }
148 
149 static int emit_individual_type_description(
150  yaml_emitter_t * emitter,
151  const type_description_interfaces__msg__IndividualTypeDescription * individual_type_description)
152 {
153  if (!(
154  start_mapping(emitter) &&
155 
156  emit_key(emitter, "type_name") &&
157  emit_str(emitter, &individual_type_description->type_name) &&
158 
159  emit_key(emitter, "fields") &&
160  start_sequence(emitter)))
161  {
162  return 0;
163  }
164  for (size_t i = 0; i < individual_type_description->fields.size; i++) {
165  if (!emit_field(emitter, &individual_type_description->fields.data[i])) {
166  return 0;
167  }
168  }
169  return end_sequence(emitter) && end_mapping(emitter);
170 }
171 
172 static int emit_type_description(
173  yaml_emitter_t * emitter,
174  const type_description_interfaces__msg__TypeDescription * type_description)
175 {
176  if (!(
177  start_mapping(emitter) &&
178 
179  emit_key(emitter, "type_description") &&
180  emit_individual_type_description(emitter, &type_description->type_description) &&
181 
182  emit_key(emitter, "referenced_type_descriptions") &&
183  start_sequence(emitter)))
184  {
185  return 0;
186  }
187  for (size_t i = 0; i < type_description->referenced_type_descriptions.size; i++) {
188  if (!emit_individual_type_description(
189  emitter, &type_description->referenced_type_descriptions.data[i]))
190  {
191  return 0;
192  }
193  }
194  return end_sequence(emitter) && end_mapping(emitter);
195 }
196 
197 rcl_ret_t
198 rcl_type_description_to_hashable_json(
199  const type_description_interfaces__msg__TypeDescription * type_description,
200  rcutils_char_array_t * output_repr)
201 {
202  RCL_CHECK_ARGUMENT_FOR_NULL(type_description, RCL_RET_INVALID_ARGUMENT);
203  RCL_CHECK_ARGUMENT_FOR_NULL(output_repr, RCL_RET_INVALID_ARGUMENT);
204 
205  yaml_emitter_t emitter;
206  yaml_event_t event;
207 
208  if (!yaml_emitter_initialize(&emitter)) {
209  goto error;
210  }
211 
212  // Disable line breaks based on line length
213  yaml_emitter_set_width(&emitter, -1);
214  // Circumvent EOF line break by providing invalid break style
215  yaml_emitter_set_break(&emitter, -1);
216  yaml_emitter_set_output(&emitter, yaml_write_handler, output_repr);
217 
218  if (!(
219  yaml_stream_start_event_initialize(&event, YAML_UTF8_ENCODING) &&
220  yaml_emitter_emit(&emitter, &event) &&
221 
222  yaml_document_start_event_initialize(&event, NULL, NULL, NULL, 1) &&
223  yaml_emitter_emit(&emitter, &event) &&
224 
225  emit_type_description(&emitter, type_description) &&
226 
227  yaml_document_end_event_initialize(&event, 1) &&
228  yaml_emitter_emit(&emitter, &event) &&
229 
230  yaml_stream_end_event_initialize(&event) &&
231  yaml_emitter_emit(&emitter, &event)))
232  {
233  goto error;
234  }
235 
236  yaml_emitter_delete(&emitter);
237  return RCL_RET_OK;
238 
239 error:
240  rcl_set_error_state(emitter.problem, __FILE__, __LINE__);
241  yaml_emitter_delete(&emitter);
242  return RCL_RET_ERROR;
243 }
244 
245 rcl_ret_t
246 rcl_calculate_type_hash(
247  const type_description_interfaces__msg__TypeDescription * type_description,
248  rosidl_type_hash_t * output_hash)
249 {
250  RCL_CHECK_ARGUMENT_FOR_NULL(type_description, RCL_RET_INVALID_ARGUMENT);
251  RCL_CHECK_ARGUMENT_FOR_NULL(output_hash, RCL_RET_INVALID_ARGUMENT);
252 
253  rcl_ret_t result = RCL_RET_OK;
255  rcutils_char_array_t msg_repr = rcutils_get_zero_initialized_char_array();
256  rcutils_ret_t rcutils_result = rcutils_char_array_init(&msg_repr, 0, &allocator);
257  if (rcutils_result != RCL_RET_OK) {
258  // rcutils_char_array_init already set the error
259  return rcl_convert_rcutils_ret_to_rcl_ret(rcutils_result);
260  }
261 
262  output_hash->version = 1;
263  result = rcl_type_description_to_hashable_json(type_description, &msg_repr);
264  if (result == RCL_RET_OK) {
265  rcutils_sha256_ctx_t sha_ctx;
266  rcutils_sha256_init(&sha_ctx);
267  // Last item in char_array is null terminator, which should not be hashed.
268  rcutils_sha256_update(&sha_ctx, (const uint8_t *)msg_repr.buffer, msg_repr.buffer_length - 1);
269  rcutils_sha256_final(&sha_ctx, output_hash->value);
270  }
271  result = rcutils_char_array_fini(&msg_repr);
272  return result;
273 }
#define rcl_get_default_allocator
Return a properly initialized rcl_allocator_t with default values.
Definition: allocator.h:37
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
Definition: allocator.h:31
#define RCL_RET_OK
Success return code.
Definition: types.h:27
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:35
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:29
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24