-
Notifications
You must be signed in to change notification settings - Fork 527
Expand file tree
/
Copy pathparameter_map.cpp
More file actions
188 lines (169 loc) · 6.9 KB
/
parameter_map.cpp
File metadata and controls
188 lines (169 loc) · 6.9 KB
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
// Copyright 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 <string>
#include <regex>
#include <vector>
#include "rcpputils/find_and_replace.hpp"
#include "rcpputils/scope_exit.hpp"
#include "rclcpp/parameter_map.hpp"
using rclcpp::exceptions::InvalidParametersException;
using rclcpp::exceptions::InvalidParameterValueException;
using rclcpp::ParameterMap;
using rclcpp::ParameterValue;
static bool is_node_name_matched(const std::string & node_name, const char * node_fqn)
{
// Update the regular expression ["/*" -> "(/\\w+)" and "/**" -> "(/\\w+)*"]
std::string regex = rcpputils::find_and_replace(node_name, "/*", "(/\\w+)");
return std::regex_match(node_fqn, std::regex(regex));
}
ParameterMap
rclcpp::parameter_map_from(const rcl_params_t * const c_params, const char * node_fqn)
{
if (NULL == c_params) {
throw InvalidParametersException("parameters struct is NULL");
} else if (NULL == c_params->node_names) {
throw InvalidParametersException("node names array is NULL");
} else if (NULL == c_params->params) {
throw InvalidParametersException("node params array is NULL");
}
// Convert c structs into a list of parameters to set
ParameterMap parameters;
for (size_t n = 0; n < c_params->num_nodes; ++n) {
const char * c_node_name = c_params->node_names[n];
if (NULL == c_node_name) {
throw InvalidParametersException("Node name at index " + std::to_string(n) + " is NULL");
}
/// make sure there is a leading slash on the fully qualified node name
std::string node_name("/");
if ('/' != c_node_name[0]) {
node_name += c_node_name;
} else {
node_name = c_node_name;
}
if (node_fqn) {
if (!is_node_name_matched(node_name, node_fqn)) {
// No need to parse the items because the user just care about node_fqn
continue;
}
node_name = node_fqn;
}
const rcl_node_params_t * const c_params_node = &(c_params->params[n]);
std::vector<Parameter> & params_node = parameters[node_name];
params_node.reserve(c_params_node->num_params);
for (size_t p = 0; p < c_params_node->num_params; ++p) {
const char * const c_param_name = c_params_node->parameter_names[p];
if (NULL == c_param_name) {
std::string message(
"At node " + std::to_string(n) + " parameter " + std::to_string(p) + " name is NULL");
throw InvalidParametersException(message);
}
const rcl_variant_t * const c_param_value = &(c_params_node->parameter_values[p]);
ParameterValue value;
try {
value = parameter_value_from(c_param_value);
} catch (const InvalidParameterValueException & e) {
throw InvalidParameterValueException(
std::string("parameter_value_from failed for parameter '") +
c_param_name + "': " + e.what());
}
params_node.emplace_back(c_param_name, value);
}
}
return parameters;
}
ParameterValue
rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value)
{
if (NULL == c_param_value) {
throw InvalidParameterValueException("Passed argument is NULL");
}
if (c_param_value->bool_value) {
return ParameterValue(*(c_param_value->bool_value));
} else if (c_param_value->integer_value) {
return ParameterValue(*(c_param_value->integer_value));
} else if (c_param_value->double_value) {
return ParameterValue(*(c_param_value->double_value));
} else if (c_param_value->string_value) {
return ParameterValue(std::string(c_param_value->string_value));
} else if (c_param_value->byte_array_value) {
const rcl_byte_array_t * const byte_array = c_param_value->byte_array_value;
std::vector<uint8_t> bytes;
bytes.reserve(byte_array->size);
for (size_t v = 0; v < byte_array->size; ++v) {
bytes.push_back(byte_array->values[v]);
}
return ParameterValue(bytes);
} else if (c_param_value->bool_array_value) {
const rcl_bool_array_t * const bool_array = c_param_value->bool_array_value;
std::vector<bool> bools;
bools.reserve(bool_array->size);
for (size_t v = 0; v < bool_array->size; ++v) {
bools.push_back(bool_array->values[v]);
}
return ParameterValue(bools);
} else if (c_param_value->integer_array_value) {
const rcl_int64_array_t * const int_array = c_param_value->integer_array_value;
std::vector<int64_t> integers;
integers.reserve(int_array->size);
for (size_t v = 0; v < int_array->size; ++v) {
integers.push_back(int_array->values[v]);
}
return ParameterValue(integers);
} else if (c_param_value->double_array_value) {
const rcl_double_array_t * const double_array = c_param_value->double_array_value;
std::vector<double> doubles;
doubles.reserve(double_array->size);
for (size_t v = 0; v < double_array->size; ++v) {
doubles.push_back(double_array->values[v]);
}
return ParameterValue(doubles);
} else if (c_param_value->string_array_value) {
const rcutils_string_array_t * const string_array = c_param_value->string_array_value;
std::vector<std::string> strings;
strings.reserve(string_array->size);
for (size_t v = 0; v < string_array->size; ++v) {
strings.emplace_back(string_array->data[v]);
}
return ParameterValue(strings);
}
throw InvalidParameterValueException(
"Invalid parameter value: rcl parameter structure"
"Contains no value");
}
ParameterMap
rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename, const char * node_fqn)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_params_t * rcl_parameters = rcl_yaml_node_struct_init(allocator);
RCPPUTILS_SCOPE_EXIT(rcl_yaml_node_struct_fini(rcl_parameters); );
const char * path = yaml_filename.c_str();
if (!rcl_parse_yaml_file(path, rcl_parameters)) {
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_ERROR);
}
return rclcpp::parameter_map_from(rcl_parameters, node_fqn);
}
std::vector<rclcpp::Parameter>
rclcpp::parameters_from_map(const ParameterMap & parameter_map, const char * node_fqn)
{
std::vector<rclcpp::Parameter> parameters;
std::string node_name_old;
for (auto & [node_name, node_parameters] : parameter_map) {
if (node_fqn && !is_node_name_matched(node_name, node_fqn)) {
// No need to parse the items because the user just care about node_fqn
continue;
}
parameters.insert(parameters.end(), node_parameters.begin(), node_parameters.end());
}
return parameters;
}