forked from ros2/rcl
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathtest_parser.cpp
457 lines (375 loc) · 18 KB
/
test_parser.cpp
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
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
// Copyright 2020 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 <yaml.h>
#include <string>
#include <vector>
#include "gtest/gtest.h"
#include "osrf_testing_tools_cpp/scope_exit.hpp"
#include "rcl_yaml_param_parser/parser.h"
#include "rcutils/allocator.h"
#include "rcutils/error_handling.h"
#include "rcutils/filesystem.h"
#include "rcutils/testing/fault_injection.h"
#include "rcutils/types/rcutils_ret.h"
#include "rcutils/types/string_array.h"
#include "./mocking_utils/patch.hpp"
#include "./time_bomb_allocator_testing_utils.h"
TEST(RclYamlParamParser, node_init_fini) {
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
EXPECT_NE(params_st, nullptr);
rcl_yaml_node_struct_fini(params_st);
allocator = get_time_bomb_allocator();
// Bad alloc of params_st
set_time_bomb_allocator_calloc_count(allocator, 0);
// This cleans up after itself if it fails so no need to call fini()
EXPECT_EQ(rcl_yaml_node_struct_init(allocator), nullptr);
// Bad alloc of params_st->node_names
set_time_bomb_allocator_calloc_count(allocator, 1);
EXPECT_EQ(rcl_yaml_node_struct_init(allocator), nullptr);
// Bad alloc of params_st->params
set_time_bomb_allocator_calloc_count(allocator, 2);
EXPECT_EQ(rcl_yaml_node_struct_init(allocator), nullptr);
// Check this doesn't die.
rcl_yaml_node_struct_fini(nullptr);
}
TEST(RclYamlParamParser, node_init_with_capacity_fini) {
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init_with_capacity(1024, allocator);
ASSERT_NE(params_st, nullptr);
EXPECT_EQ(0U, params_st->num_nodes);
EXPECT_EQ(1024U, params_st->capacity_nodes);
rcl_yaml_node_struct_fini(params_st);
allocator = get_time_bomb_allocator();
// Bad alloc of params_st
set_time_bomb_allocator_calloc_count(allocator, 0);
// This cleans up after itself if it fails so no need to call fini()
EXPECT_EQ(rcl_yaml_node_struct_init_with_capacity(1024, allocator), nullptr);
// Bad alloc of params_st->node_names
set_time_bomb_allocator_calloc_count(allocator, 1);
EXPECT_EQ(rcl_yaml_node_struct_init_with_capacity(1024, allocator), nullptr);
// Bad alloc of params_st->params
set_time_bomb_allocator_calloc_count(allocator, 2);
EXPECT_EQ(rcl_yaml_node_struct_init_with_capacity(1024, allocator), nullptr);
// Check this doesn't die.
rcl_yaml_node_struct_fini(nullptr);
}
TEST(RclYamlParamParser, reallocate_node_init_with_capacity_fini) {
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init_with_capacity(1024, allocator);
ASSERT_NE(params_st, nullptr);
EXPECT_EQ(0U, params_st->num_nodes);
EXPECT_EQ(1024U, params_st->capacity_nodes);
EXPECT_EQ(RCUTILS_RET_OK, rcl_yaml_node_struct_reallocate(params_st, 2048, allocator));
EXPECT_EQ(0U, params_st->num_nodes);
EXPECT_EQ(2048U, params_st->capacity_nodes);
rcl_yaml_node_struct_fini(params_st);
}
TEST(RclYamlParamParser, node_copy) {
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
EXPECT_NE(params_st, nullptr);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(nullptr));
const char node_name[] = "node name";
const char param_name[] = "param name";
const char yaml_value[] = "true";
EXPECT_TRUE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
rcl_params_t * copy = rcl_yaml_node_struct_copy(params_st);
EXPECT_NE(copy, nullptr);
rcl_yaml_node_struct_fini(copy);
params_st->allocator = get_time_bomb_allocator();
// init of out_params_st fails
set_time_bomb_allocator_calloc_count(params_st->allocator, 0);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
set_time_bomb_allocator_calloc_count(params_st->allocator, 1);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
constexpr int expected_num_calloc_calls = 5;
for (int i = 0; i < expected_num_calloc_calls; ++i) {
// Check various locations for allocation failures
set_time_bomb_allocator_calloc_count(params_st->allocator, i);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
}
// Check that the expected number of calloc calls occur
set_time_bomb_allocator_calloc_count(params_st->allocator, expected_num_calloc_calls);
copy = rcl_yaml_node_struct_copy(params_st);
EXPECT_NE(nullptr, copy);
rcl_yaml_node_struct_fini(copy);
// Reset calloc countdown
set_time_bomb_allocator_calloc_count(params_st->allocator, -1);
constexpr int expected_num_malloc_calls = 3;
for (int i = 0; i < expected_num_malloc_calls; ++i) {
set_time_bomb_allocator_malloc_count(params_st->allocator, i);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
}
// Check that the expected number of malloc calls occur
set_time_bomb_allocator_malloc_count(params_st->allocator, expected_num_malloc_calls);
copy = rcl_yaml_node_struct_copy(params_st);
EXPECT_NE(nullptr, copy);
rcl_yaml_node_struct_fini(copy);
constexpr int num_malloc_calls_until_copy_param = 2;
// Check integer value
int64_t temp_int = 42;
if (params_st->params->parameter_values[0].bool_value != nullptr) {
// Since this bool was allocated above in rcl_parse_yaml_value, it needs to be freed.
params_st->allocator.deallocate(
params_st->params->parameter_values[0].bool_value, params_st->allocator.state);
params_st->params->parameter_values[0].bool_value = nullptr;
}
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
params_st->params->parameter_values[0].integer_value = &temp_int;
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
params_st->params->parameter_values[0].integer_value = nullptr;
// Check double value
double temp_double = 42.0;
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
params_st->params->parameter_values[0].double_value = &temp_double;
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
params_st->params->parameter_values[0].double_value = nullptr;
// Check string value
char temp_string[] = "stringy string";
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
params_st->params->parameter_values[0].string_value = temp_string;
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
params_st->params->parameter_values[0].string_value = nullptr;
// Check bool_array_value array pointer is allocated
bool bool_array[] = {true};
rcl_bool_array_s temp_bool_array = {bool_array, 1};
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
params_st->params->parameter_values[0].bool_array_value = &temp_bool_array;
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
// Check bool_array_value->values is allocated
set_time_bomb_allocator_malloc_count(
params_st->allocator, num_malloc_calls_until_copy_param + 1);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
// Check bool_array_value->values is set to null if size is 0
set_time_bomb_allocator_malloc_count(params_st->allocator, -1);
params_st->params->parameter_values[0].bool_array_value->size = 0u;
copy = rcl_yaml_node_struct_copy(params_st);
EXPECT_NE(nullptr, copy);
EXPECT_EQ(nullptr, copy->params->parameter_values[0].bool_array_value->values);
rcl_yaml_node_struct_fini(copy);
params_st->params->parameter_values[0].bool_array_value = nullptr;
// Check integer_array array pointer is allocated
int64_t integer_array[] = {42};
rcl_int64_array_s temp_integer_array = {integer_array, 1};
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
params_st->params->parameter_values[0].integer_array_value = &temp_integer_array;
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
// Check integer_array->values is allocated
set_time_bomb_allocator_malloc_count(
params_st->allocator, num_malloc_calls_until_copy_param + 1);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
// Check integer_array->values is set to null if size is 0
params_st->params->parameter_values[0].integer_array_value->size = 0u;
copy = rcl_yaml_node_struct_copy(params_st);
EXPECT_NE(nullptr, copy);
EXPECT_EQ(nullptr, copy->params->parameter_values[0].integer_array_value->values);
rcl_yaml_node_struct_fini(copy);
params_st->params->parameter_values[0].integer_array_value = nullptr;
double double_array[] = {42.0};
rcl_double_array_s temp_double_array = {double_array, 1};
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
params_st->params->parameter_values[0].double_array_value = &temp_double_array;
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
set_time_bomb_allocator_malloc_count(
params_st->allocator, num_malloc_calls_until_copy_param + 1);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
params_st->params->parameter_values[0].double_array_value->size = 0u;
copy = rcl_yaml_node_struct_copy(params_st);
EXPECT_NE(nullptr, copy);
EXPECT_EQ(nullptr, copy->params->parameter_values[0].double_array_value->values);
rcl_yaml_node_struct_fini(copy);
params_st->params->parameter_values[0].double_array_value = nullptr;
char s[] = "stringy string";
char * string_array[] = {s};
rcutils_string_array_t temp_string_array = {1, string_array, allocator};
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
params_st->params->parameter_values[0].string_array_value = &temp_string_array;
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
params_st->params->parameter_values[0].string_array_value = nullptr;
for (int i = 0; i < 5; ++i) {
set_time_bomb_allocator_calloc_count(params_st->allocator, i);
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
}
rcl_yaml_node_struct_fini(params_st);
}
// // This just tests a couple of basic failures that test_parse_yaml.cpp misses.
// // See that file for more thorough testing of bad yaml files
TEST(RclYamlParamParser, test_file) {
// file path is null
EXPECT_FALSE(rcl_parse_yaml_file(nullptr, nullptr));
const char bad_file_path[] = "not_a_file.yaml";
// params_st is null
EXPECT_FALSE(rcl_parse_yaml_file(bad_file_path, nullptr));
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(rcl_parse_yaml_file(bad_file_path, params_st));
rcl_yaml_node_struct_fini(params_st);
}
TEST(RclYamlParamParser, test_parse_yaml_value) {
const char node_name[] = "node name";
const char param_name[] = "param name";
const char yaml_value[] = "true";
const char empty_string[] = "\0";
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
EXPECT_NE(params_st, nullptr);
// Check null arguments
EXPECT_FALSE(rcl_parse_yaml_value(nullptr, param_name, yaml_value, params_st));
EXPECT_FALSE(rcl_parse_yaml_value(node_name, nullptr, yaml_value, params_st));
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, nullptr, params_st));
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, nullptr));
// Check strings are empty
EXPECT_FALSE(rcl_parse_yaml_value(empty_string, param_name, yaml_value, params_st));
EXPECT_FALSE(rcl_parse_yaml_value(node_name, empty_string, yaml_value, params_st));
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, empty_string, params_st));
// Check allocating params_st->node_names[*node_idx] fails
params_st->allocator = get_time_bomb_allocator();
set_time_bomb_allocator_malloc_count(params_st->allocator, 0);
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
// Check allocating node_params->parameter_names fails
allocator = get_time_bomb_allocator();
set_time_bomb_allocator_calloc_count(params_st->allocator, 0);
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
// Check allocating node_params->parameter_values fails
allocator = get_time_bomb_allocator();
set_time_bomb_allocator_calloc_count(params_st->allocator, 1);
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
allocator = rcutils_get_default_allocator();
EXPECT_TRUE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
rcl_yaml_node_struct_fini(params_st);
}
TEST(RclYamlParamParser, test_yaml_node_struct_get) {
const char node_name[] = "node name";
const char param_name[] = "param name";
const char yaml_value[] = "true";
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
ASSERT_NE(params_st, nullptr);
EXPECT_TRUE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
// Check null arguments
EXPECT_EQ(nullptr, rcl_yaml_node_struct_get(nullptr, param_name, params_st));
EXPECT_EQ(nullptr, rcl_yaml_node_struct_get(node_name, nullptr, params_st));
EXPECT_EQ(nullptr, rcl_yaml_node_struct_get(node_name, param_name, nullptr));
rcl_variant_t * result = rcl_yaml_node_struct_get(node_name, param_name, params_st);
ASSERT_NE(nullptr, result->bool_value);
EXPECT_TRUE(*result->bool_value);
EXPECT_EQ(nullptr, result->integer_value);
EXPECT_EQ(nullptr, result->double_value);
EXPECT_EQ(nullptr, result->string_value);
EXPECT_EQ(nullptr, result->byte_array_value);
EXPECT_EQ(nullptr, result->bool_array_value);
EXPECT_EQ(nullptr, result->integer_array_value);
EXPECT_EQ(nullptr, result->double_array_value);
EXPECT_EQ(nullptr, result->string_array_value);
rcl_yaml_node_struct_fini(params_st);
}
// Just testing basic parameters, this is exercised more in test_parse_yaml.cpp
TEST(RclYamlParamParser, test_yaml_node_struct_print) {
rcl_yaml_node_struct_print(nullptr);
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
rcl_yaml_node_struct_print(params_st);
rcl_yaml_node_struct_fini(params_st);
}
TEST(RclYamlParamParser, test_parse_file_with_bad_allocator) {
char cur_dir[1024];
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)) << rcutils_get_error_string().str;
rcutils_allocator_t allocator = rcutils_get_default_allocator();
char * test_path = rcutils_join_path(cur_dir, "test", allocator);
ASSERT_TRUE(NULL != test_path) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
allocator.deallocate(test_path, allocator.state);
});
const std::vector<std::string> filenames = {
"correct_config.yaml",
"empty_string.yaml",
"indented_name_space.yaml",
"multi_ns_correct.yaml",
"no_alias_support.yaml",
"no_value1.yaml",
"overlay.yaml",
"params_with_no_node.yaml",
"root_ns.yaml",
"seq_map1.yaml",
"seq_map2.yaml",
"string_array_with_quoted_number.yaml"
};
for (auto & filename : filenames) {
SCOPED_TRACE(filename);
char * path = rcutils_join_path(test_path, filename.c_str(), allocator);
ASSERT_TRUE(NULL != path) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
allocator.deallocate(path, allocator.state);
});
ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path;
RCUTILS_FAULT_INJECTION_TEST(
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
if (NULL == params_hdl) {
continue;
}
bool res = rcl_parse_yaml_file(path, params_hdl);
// Not verifying res is true or false here, because eventually it will come back with an ok
// result. We're just trying to make sure that bad allocations are properly handled
(void)res;
// If `rcutils_string_array_fini` fails, there will be a small memory leak here.
// However, it's necessary for coverage
rcl_yaml_node_struct_fini(params_hdl);
params_hdl = NULL;
});
}
}
TEST(RclYamlParamParser, test_parse_yaml_initialize_mock) {
char cur_dir[1024];
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)) << rcutils_get_error_string().str;
rcutils_allocator_t allocator = rcutils_get_default_allocator();
char * test_path = rcutils_join_path(cur_dir, "test", allocator);
char * path = rcutils_join_path(test_path, "correct_config.yaml", allocator);
ASSERT_TRUE(NULL != path) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
});
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
ASSERT_NE(nullptr, params_hdl);
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcl_yaml_node_struct_fini(params_hdl);
});
auto mock = mocking_utils::patch_and_return(
"lib:rcl_yaml_param_parser", yaml_parser_initialize, false);
EXPECT_FALSE(rcl_parse_yaml_file(path, params_hdl));
constexpr char node_name[] = "node name";
constexpr char param_name[] = "param name";
constexpr char yaml_value[] = "true";
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
ASSERT_NE(params_st, nullptr);
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcl_yaml_node_struct_fini(params_st);
});
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
}
int32_t main(int32_t argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}