-
Notifications
You must be signed in to change notification settings - Fork 134
/
Copy pathu16string_functions.c
242 lines (226 loc) · 5.79 KB
/
u16string_functions.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
// Copyright 2015-2018 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 "rosidl_runtime_c/u16string_functions.h"
#include <assert.h>
#include <stdlib.h>
#include <string.h>
#include <stdio.h>
#include "rcutils/macros.h"
bool
rosidl_runtime_c__U16String__init(rosidl_runtime_c__U16String * str)
{
RCUTILS_CAN_RETURN_WITH_ERROR_OF(false);
if (!str) {
return false;
}
str->data = malloc(sizeof(uint16_t));
if (!str->data) {
return false;
}
str->data[0] = 0;
str->size = 0;
str->capacity = 1;
return true;
}
void
rosidl_runtime_c__U16String__fini(rosidl_runtime_c__U16String * str)
{
if (!str) {
return;
}
if (str->data) {
/* ensure that data and capacity values are consistent */
if (str->capacity <= 0) {
fprintf(
stderr, "Unexpected condition: string capacity was zero for allocated data! "
"Exiting.\n");
exit(-1);
}
free(str->data);
str->data = NULL;
str->size = 0;
str->capacity = 0;
} else {
/* ensure that data, size, and capacity values are consistent */
if (0 != str->size) {
fprintf(
stderr, "Unexpected condition: string size was non-zero for deallocated data! "
"Exiting.\n");
exit(-1);
}
if (0 != str->capacity) {
fprintf(
stderr, "Unexpected behavior: string capacity was non-zero for deallocated data! "
"Exiting.\n");
exit(-1);
}
}
}
bool
rosidl_runtime_c__U16String__assignn(
rosidl_runtime_c__U16String * str, const uint16_t * value, size_t n)
{
if (!str) {
return false;
}
// a NULL value is not valid
if (!value) {
return false;
}
// since n + 1 bytes are being allocated n can't be the maximum value
if (n == SIZE_MAX) {
return false;
}
uint16_t * data = realloc(str->data, (n + 1) * sizeof(uint16_t));
if (!data) {
return false;
}
memcpy(data, value, n * sizeof(uint16_t));
data[n] = 0;
str->data = data;
str->size = n;
str->capacity = n + 1;
return true;
}
bool
rosidl_runtime_c__U16String__assignn_from_char(
rosidl_runtime_c__U16String * str, const char * value, size_t n)
{
// since n represents the number of 8-bit characters it must be an even number
if (n % 2 != 0) {
return false;
}
return rosidl_runtime_c__U16String__assignn(
str, (const uint16_t *)value, n / 2);
}
bool
rosidl_runtime_c__U16String__assign(
rosidl_runtime_c__U16String * str, const uint16_t * value)
{
return rosidl_runtime_c__U16String__assignn(
str, value, rosidl_runtime_c__U16String__len(value));
}
size_t
rosidl_runtime_c__U16String__len(const uint16_t * value)
{
if (!value) {
return 0;
}
size_t len = 0;
while (value[len]) {
len++;
}
return len;
}
bool
rosidl_runtime_c__U16String__resize(
rosidl_runtime_c__U16String * str, size_t n)
{
if (!str) {
return false;
}
// check valid range of n before allocating n + 1 characters
if (n > SIZE_MAX / sizeof(uint16_t) - 1) {
return false;
}
uint16_t * data = realloc(str->data, (n + 1) * sizeof(uint16_t));
if (!data) {
return false;
}
data[n] = 0;
str->data = data;
str->size = n;
str->capacity = n + 1;
return true;
}
bool
rosidl_runtime_c__U16String__Sequence__init(
rosidl_runtime_c__U16String__Sequence * sequence, size_t size)
{
RCUTILS_CAN_RETURN_WITH_ERROR_OF(false);
if (!sequence) {
return false;
}
rosidl_runtime_c__U16String * data = NULL;
if (size) {
data = (rosidl_runtime_c__U16String *)malloc(size * sizeof(rosidl_runtime_c__U16String));
if (!data) {
return false;
}
// initialize all sequence elements
for (size_t i = 0; i < size; ++i) {
if (!rosidl_runtime_c__U16String__init(&data[i])) {
/* free currently allocated and return false */
for (; i-- > 0; ) {
rosidl_runtime_c__U16String__fini(&data[i]);
}
free(data);
return false;
}
}
}
sequence->data = data;
sequence->size = size;
sequence->capacity = size;
return true;
}
void
rosidl_runtime_c__U16String__Sequence__fini(
rosidl_runtime_c__U16String__Sequence * sequence)
{
if (!sequence) {
return;
}
if (sequence->data) {
// ensure that data and capacity values are consistent
assert(sequence->capacity > 0);
// finalize all sequence elements
for (size_t i = 0; i < sequence->capacity; ++i) {
rosidl_runtime_c__U16String__fini(&sequence->data[i]);
}
free(sequence->data);
sequence->data = NULL;
sequence->size = 0;
sequence->capacity = 0;
} else {
// ensure that data, size, and capacity values are consistent
assert(0 == sequence->size);
assert(0 == sequence->capacity);
}
}
rosidl_runtime_c__U16String__Sequence *
rosidl_runtime_c__U16String__Sequence__create(size_t size)
{
rosidl_runtime_c__U16String__Sequence * sequence =
(rosidl_runtime_c__U16String__Sequence *)malloc(
sizeof(rosidl_runtime_c__U16String__Sequence));
if (!sequence) {
return NULL;
}
bool success = rosidl_runtime_c__U16String__Sequence__init(sequence, size);
if (!success) {
free(sequence);
return NULL;
}
return sequence;
}
void
rosidl_runtime_c__U16String__Sequence__destroy(
rosidl_runtime_c__U16String__Sequence * sequence)
{
if (sequence) {
rosidl_runtime_c__U16String__Sequence__fini(sequence);
}
free(sequence);
}