ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
parameter_map.cpp
1 // Copyright 2018 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 <string>
16 #include <regex>
17 #include <vector>
18 
19 #include "rcpputils/find_and_replace.hpp"
20 #include "rcpputils/scope_exit.hpp"
21 #include "rclcpp/parameter_map.hpp"
22 
27 
28 static bool is_node_name_matched(const std::string & node_name, const char * node_fqn)
29 {
30  // Update the regular expression ["/*" -> "(/\\w+)" and "/**" -> "(/\\w+)*"]
31  std::string regex = rcpputils::find_and_replace(node_name, "/*", "(/\\w+)");
32  return std::regex_match(node_fqn, std::regex(regex));
33 }
34 
36 rclcpp::parameter_map_from(const rcl_params_t * const c_params, const char * node_fqn)
37 {
38  if (NULL == c_params) {
39  throw InvalidParametersException("parameters struct is NULL");
40  } else if (NULL == c_params->node_names) {
41  throw InvalidParametersException("node names array is NULL");
42  } else if (NULL == c_params->params) {
43  throw InvalidParametersException("node params array is NULL");
44  }
45 
46  // Convert c structs into a list of parameters to set
47  ParameterMap parameters;
48  for (size_t n = 0; n < c_params->num_nodes; ++n) {
49  const char * c_node_name = c_params->node_names[n];
50  if (NULL == c_node_name) {
51  throw InvalidParametersException("Node name at index " + std::to_string(n) + " is NULL");
52  }
53 
55  std::string node_name("/");
56  if ('/' != c_node_name[0]) {
57  node_name += c_node_name;
58  } else {
59  node_name = c_node_name;
60  }
61 
62  if (node_fqn) {
63  if (!is_node_name_matched(node_name, node_fqn)) {
64  // No need to parse the items because the user just care about node_fqn
65  continue;
66  }
67 
68  node_name = node_fqn;
69  }
70 
71  const rcl_node_params_t * const c_params_node = &(c_params->params[n]);
72 
73  std::vector<Parameter> & params_node = parameters[node_name];
74  params_node.reserve(c_params_node->num_params);
75 
76  for (size_t p = 0; p < c_params_node->num_params; ++p) {
77  const char * const c_param_name = c_params_node->parameter_names[p];
78  if (NULL == c_param_name) {
79  std::string message(
80  "At node " + std::to_string(n) + " parameter " + std::to_string(p) + " name is NULL");
81  throw InvalidParametersException(message);
82  }
83  const rcl_variant_t * const c_param_value = &(c_params_node->parameter_values[p]);
84  params_node.emplace_back(c_param_name, parameter_value_from(c_param_value));
85  }
86  }
87 
88  return parameters;
89 }
90 
92 rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value)
93 {
94  if (NULL == c_param_value) {
95  throw InvalidParameterValueException("Passed argument is NULL");
96  }
97  if (c_param_value->bool_value) {
98  return ParameterValue(*(c_param_value->bool_value));
99  } else if (c_param_value->integer_value) {
100  return ParameterValue(*(c_param_value->integer_value));
101  } else if (c_param_value->double_value) {
102  return ParameterValue(*(c_param_value->double_value));
103  } else if (c_param_value->string_value) {
104  return ParameterValue(std::string(c_param_value->string_value));
105  } else if (c_param_value->byte_array_value) {
106  const rcl_byte_array_t * const byte_array = c_param_value->byte_array_value;
107  std::vector<uint8_t> bytes;
108  bytes.reserve(byte_array->size);
109  for (size_t v = 0; v < byte_array->size; ++v) {
110  bytes.push_back(byte_array->values[v]);
111  }
112  return ParameterValue(bytes);
113  } else if (c_param_value->bool_array_value) {
114  const rcl_bool_array_t * const bool_array = c_param_value->bool_array_value;
115  std::vector<bool> bools;
116  bools.reserve(bool_array->size);
117  for (size_t v = 0; v < bool_array->size; ++v) {
118  bools.push_back(bool_array->values[v]);
119  }
120  return ParameterValue(bools);
121  } else if (c_param_value->integer_array_value) {
122  const rcl_int64_array_t * const int_array = c_param_value->integer_array_value;
123  std::vector<int64_t> integers;
124  integers.reserve(int_array->size);
125  for (size_t v = 0; v < int_array->size; ++v) {
126  integers.push_back(int_array->values[v]);
127  }
128  return ParameterValue(integers);
129  } else if (c_param_value->double_array_value) {
130  const rcl_double_array_t * const double_array = c_param_value->double_array_value;
131  std::vector<double> doubles;
132  doubles.reserve(double_array->size);
133  for (size_t v = 0; v < double_array->size; ++v) {
134  doubles.push_back(double_array->values[v]);
135  }
136  return ParameterValue(doubles);
137  } else if (c_param_value->string_array_value) {
138  const rcutils_string_array_t * const string_array = c_param_value->string_array_value;
139  std::vector<std::string> strings;
140  strings.reserve(string_array->size);
141  for (size_t v = 0; v < string_array->size; ++v) {
142  strings.emplace_back(string_array->data[v]);
143  }
144  return ParameterValue(strings);
145  }
146 
147  throw InvalidParameterValueException("No parameter value set");
148 }
149 
150 ParameterMap
151 rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename, const char * node_fqn)
152 {
153  rcutils_allocator_t allocator = rcutils_get_default_allocator();
154  rcl_params_t * rcl_parameters = rcl_yaml_node_struct_init(allocator);
155  RCPPUTILS_SCOPE_EXIT(rcl_yaml_node_struct_fini(rcl_parameters); );
156  const char * path = yaml_filename.c_str();
157  if (!rcl_parse_yaml_file(path, rcl_parameters)) {
158  rclcpp::exceptions::throw_from_rcl_error(RCL_RET_ERROR);
159  }
160 
161  return rclcpp::parameter_map_from(rcl_parameters, node_fqn);
162 }
163 
164 std::vector<rclcpp::Parameter>
165 rclcpp::parameters_from_map(const ParameterMap & parameter_map, const char * node_fqn)
166 {
167  std::vector<rclcpp::Parameter> parameters;
168  std::string node_name_old;
169  for (auto & [node_name, node_parameters] : parameter_map) {
170  if (node_fqn && !is_node_name_matched(node_name, node_fqn)) {
171  // No need to parse the items because the user just care about node_fqn
172  continue;
173  }
174  parameters.insert(parameters.end(), node_parameters.begin(), node_parameters.end());
175  }
176 
177  return parameters;
178 }
Store the type and value of a parameter.
Thrown if passed parameter value is invalid.
Definition: exceptions.hpp:260
Thrown if passed parameters are inconsistent or invalid.
Definition: exceptions.hpp:252
RCLCPP_PUBLIC ParameterMap parameter_map_from_yaml_file(const std::string &yaml_filename, const char *node_fqn=nullptr)
RCLCPP_PUBLIC std::vector< Parameter > parameters_from_map(const ParameterMap &parameter_map, const char *node_fqn=nullptr)
RCLCPP_PUBLIC ParameterMap parameter_map_from(const rcl_params_t *const c_params, const char *node_fqn=nullptr)
RCLCPP_PUBLIC ParameterValue parameter_value_from(const rcl_variant_t *const c_value)
std::unordered_map< std::string, std::vector< Parameter > > ParameterMap
A map of fully qualified node names to a list of parameters.
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:29