mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
param_provider.hpp
Go to the documentation of this file.
1// clang: MatousFormat
7#pragma once
8
10
11namespace mrs_lib
12{
13
14 template <typename T>
15 std::ostream& operator<<(std::ostream& os, const std::vector<T>& var)
16 {
17 for (size_t it = 0; it < var.size(); it++)
18 {
19 os << var.at(it);
20 if (it < var.size() - 1)
21 os << ", ";
22 }
23 return os;
24 }
25
26 template <typename Key, typename Value>
27 std::ostream& operator<<(std::ostream& os, const std::map<Key, Value>& var)
28 {
29 size_t it = 0;
30 for (const auto& pair : var)
31 {
32 os << pair.first << ": " << pair.second;
33 if (it < var.size() - 1)
34 os << std::endl;
35 it++;
36 }
37 return os;
38 }
39
40 /* ParamProvider::resolved_name_t //{ */
41
43 {
44 std::string str;
45
46 resolved_name_t() = default;
47 resolved_name_t(std::string&& s) : str(s)
48 {
49 }
50 resolved_name_t(const std::string& s) : str(s)
51 {
52 }
53
54 // Explicit conversion
55 explicit operator std::string() const
56 {
57 return str;
58 }
59
60 friend std::ostream& operator<<(std::ostream& os, const resolved_name_t& r)
61 {
62 return os << r.str;
63 }
64
65 friend bool operator==(const resolved_name_t& lhs, const resolved_name_t& rhs)
66 {
67 return lhs.str == rhs.str;
68 }
69 };
70
71 //}
72
73 /* to_param_type() method //{ */
74 template <typename T>
75 rclcpp::ParameterType to_param_type()
76 {
77 return rclcpp::ParameterValue{T{}}.get_type();
78 }
79 //}
80
81 /* getParam() method and overloads //{ */
82 template <typename T>
83 bool ParamProvider::getParam(const std::string& param_name, T& value_out) const
84 {
85 return getParam(resolveName(param_name), value_out, {});
86 }
87
88 template <typename T>
89 bool ParamProvider::getParam(const resolved_name_t& resolved_name, T& value_out, const get_options_t<T>& opts) const
90 {
91 bool use_rosparam = m_use_rosparam;
92 // the options structure always has precedence if the parameter is set
93 if (opts.use_rosparam.has_value())
94 use_rosparam = opts.use_rosparam.value();
95
96 // first, try to load from YAML, if enabled
97 if (opts.use_yaml && loadFromYaml(resolved_name, value_out, opts))
98 return true;
99
100 // then, try to load from ROS, if enabled
101 if (use_rosparam && loadFromROS(resolved_name, value_out, opts))
102 return true;
103
104 // if both fail, check for a default value
105 if (opts.declare_options.default_value.has_value())
106 {
107 const auto& default_value = opts.declare_options.default_value.value();
108
109 if (opts.always_declare && !declareParam<T>(resolved_name, opts.declare_options))
110 {
111 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Failed to declare parameter \"" << resolved_name << "\".");
112 return false;
113 }
114
115 value_out = default_value;
116 return true;
117 }
118
119 // if all options fail, return false
120 std::stringstream ss;
121 ss << "Param '" << resolved_name << "' not found:";
122 if (opts.use_yaml)
123 ss << " in YAML files,";
124 if (use_rosparam)
125 ss << " in ROS,";
126 ss << " no default value provided.";
127 RCLCPP_ERROR_STREAM(m_node->get_logger(), ss.str());
128 return false;
129 }
130 //}
131
132 /* setParam() method //{ */
133 template <typename T>
134 bool ParamProvider::setParam(const std::string& param_name, const T& value) const
135 {
136 return setParam(resolveName(param_name), value);
137 }
138
139 template <typename T>
140 bool ParamProvider::setParam(const resolved_name_t& resolved_name, const T& value, const set_options_t<T>& opts) const
141 {
142 // if the parameter is not yet declared, declare and set it together
143 if (!m_node->has_parameter(resolved_name.str))
144 {
145 auto declare_opts_local = opts.declare_options;
146 declare_opts_local.default_value = value;
147 const auto result = declareParam<T>(resolved_name, declare_opts_local);
148 if (!result)
149 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Could not declare and set param '" << resolved_name << "'!");
150 return result;
151 }
152
153 // otherwise, try setting it
154 try
155 {
156 /* RCLCPP_INFO_STREAM(m_node->get_logger(), "Setting param '" << resolved_name << "'"); */
157 rcl_interfaces::msg::SetParametersResult res = m_node->set_parameter({resolved_name.str, value});
158 if (!res.successful)
159 {
160 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Could not set param '" << resolved_name << "': " << res.reason);
161 return false;
162 }
163 }
164 // if the parameter has a wrong value, return failure
165 catch (const rclcpp::exceptions::ParameterNotDeclaredException& e)
166 {
167 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Could not set param '" << resolved_name << "': " << e.what());
168 return false;
169 }
170 return true;
171 }
172 //}
173
174 /* declareParam() method and overloads //{ */
175 template <typename T>
176 bool ParamProvider::declareParam(const std::string& param_name) const
177 {
178 return declareParam<T>(resolveName(param_name), {});
179 }
180
181 template <typename T>
182 bool ParamProvider::declareParam(const std::string& param_name, const T& default_value) const
183 {
184 return declareParam<T>(resolveName(param_name), {.default_value = default_value});
185 }
186
187 template <typename T>
188 bool ParamProvider::declareParam(const resolved_name_t& resolved_name, const declare_options_t<T>& opts) const
189 {
190 try
191 {
192 rcl_interfaces::msg::ParameterDescriptor descriptor;
193 descriptor.read_only = !opts.reconfigurable;
194
195 // if the parameter range is specified, set it if applicable
196 if (opts.range.has_value())
197 {
198 const auto& opt_range = opts.range.value();
199 // set the range approprately according to the parameter type
200 if constexpr (!numeric<T>)
201 {
202 // if the type is not numerical, print an error to let the user know and fail
203 RCLCPP_ERROR_STREAM(m_node->get_logger(),
204 "Error when declaring parameter \"" << resolved_name << "\": Range cannot be set for non-numerical values! Ignoring range.");
205 return false;
206 } else if constexpr (std::integral<T>)
207 {
208 // integer range for integral types
209 rcl_interfaces::msg::IntegerRange range;
210 range.from_value = opt_range.minimum;
211 range.to_value = opt_range.maximum;
212 descriptor.integer_range.push_back(range);
213 } else if constexpr (std::floating_point<T>)
214 {
215 // floating-point range for floating-point types
216 rcl_interfaces::msg::FloatingPointRange range;
217 range.from_value = opt_range.minimum;
218 range.to_value = opt_range.maximum;
219 descriptor.floating_point_range.push_back(range);
220 }
221 }
222
223 // actually declare the parameter
224 if (opts.default_value.has_value())
225 {
226 m_node->declare_parameter(resolved_name.str, opts.default_value.value(), descriptor);
227 } else
228 {
229 // a hack to allow declaring a strong-typed parameter without a default value
230 // because ROS2 apparently fell on its head when it was a litle baby
231 // this is actually not documented in the API documentation, so see https://github.com/ros2/rclcpp/issues/1691
232 const rclcpp::ParameterType type = to_param_type<T>();
233 descriptor.type = type;
234 m_node->declare_parameter(resolved_name.str, type, descriptor);
235 }
236 }
237 catch (const std::exception& e)
238 {
239 // this can happen if (see
240 // http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Node.html#_CPPv4N6rclcpp4Node17declare_parameterERKNSt6stringERKN6rclcpp14ParameterValueERKN14rcl_interfaces3msg19ParameterDescriptorEb):
241 // * parameter has already been declared (rclcpp::exceptions::ParameterAlreadyDeclaredException)
242 // * parameter name is invalid (rclcpp::exceptions::InvalidParametersException)
243 // * initial value fails to be set (rclcpp::exceptions::InvalidParameterValueException, not sure what exactly this means)
244 // * type of the default value or override is wrong (rclcpp::exceptions::InvalidParameterTypeException, the most common one)
245 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Could not declare param '" << resolved_name << "': " << e.what());
246
247 return false;
248 }
249 return true;
250 }
251 //}
252
253 /* loadFromYaml() method //{ */
254 template <typename T>
255 bool ParamProvider::loadFromYaml(const resolved_name_t& resolved_name, T& value_out, const get_options_t<T>& opts) const
256 {
257 T loaded_value;
258
259 const auto found_node_opt = findYamlNode(resolved_name);
260 if (!found_node_opt.has_value())
261 {
262 return false;
263 }
264
265 const auto& found_node = found_node_opt.value();
266 try
267 {
268 // try catch is the only type-generic option...
269 loaded_value = applyTag<T>(found_node);
270 }
271 catch (const YAML::BadConversion& e)
272 {
273 RCLCPP_ERROR_STREAM(m_node->get_logger(), "[" << m_node_name << "]: The YAML-loaded parameter has a wrong type: " << e.what());
274 return false;
275 }
276 catch (const YAML::Exception& e)
277 {
278 RCLCPP_ERROR_STREAM(m_node->get_logger(), "[" << m_node_name << "]: YAML-CPP threw an unknown exception: " << e.what());
279 return false;
280 }
281
282 // declare the parameter if the options specify to always define it
283 if (opts.always_declare)
284 {
285 auto declare_opts_local = opts.declare_options;
286 declare_opts_local.default_value = loaded_value;
287
288 // see https://docs.ros.org/en/jazzy/Concepts/Basic/About-Parameters.html#parameters
289 if (!m_node->has_parameter(resolved_name.str) && !declareParam<T>(resolved_name, declare_opts_local))
290 {
291 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Failed to declare parameter \"" << resolved_name << "\".");
292 return false;
293 }
294 }
295
296 // if all is OK, set the output value
297 value_out = loaded_value;
298 // the parameter value was successfully loaded and the parameter was declared if required, everything is done, return true
299 return true;
300 }
301 //}
302
303 /* degrees2radians() method //{ */
304 template <typename T>
305 inline T ParamProvider::degrees2radians(const T degrees)
306 {
307 return degrees / T(180) * T(M_PI);
308 }
309 //}
310
311 /* applyTag() method //{ */
312 template <typename T>
313 T ParamProvider::applyTag(const YAML::Node& node) const
314 {
315 if constexpr (std::is_floating_point_v<T>)
316 {
317 if (node.Tag() == "!degrees")
318 return degrees2radians(node.as<T>());
319 }
320 return node.as<T>();
321 }
322 //}
323
324 /* ranges_match() method //{ */
325 template <typename T>
326 bool ParamProvider::ranges_match(const rcl_interfaces::msg::ParameterDescriptor& descriptor, const range_t<T>& declare_range) const
327 {
328 if constexpr (numeric<T>)
329 {
330 if (!descriptor.floating_point_range.empty())
331 {
332 const auto& desc_range = descriptor.floating_point_range.front();
333 if (desc_range.from_value != declare_range.minimum || desc_range.to_value != declare_range.maximum)
334 return false;
335 }
336
337 if (!descriptor.integer_range.empty())
338 {
339 const auto& desc_range = descriptor.integer_range.front();
340 if (desc_range.from_value != declare_range.minimum || desc_range.to_value != declare_range.maximum)
341 return false;
342 }
343 }
344
345 // trying to specify a range for a non-numeric type...
346 return false;
347 }
348
349 //}
350
351 /* loadFromROS() method //{ */
352 template <typename T>
353 bool ParamProvider::loadFromROS(const resolved_name_t& resolved_name, T& value_out, const get_options_t<T>& opts) const
354 {
355 std::optional<T> loaded_value;
356 const bool was_declared = m_node->has_parameter(resolved_name.str);
357
358 // check if the current declaration is compatible with the desired declaration
359 if (was_declared)
360 {
361 const auto descriptor = m_node->describe_parameter(resolved_name.str);
362 if (descriptor.read_only && opts.declare_options.reconfigurable)
363 {
364 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Parameter \"" << resolved_name << "\" already declared as read-only, cannot re-declare as reconfigurable!");
365 return false;
366 }
367
368 if (opts.declare_options.range.has_value() && !ranges_match(descriptor, opts.declare_options.range.value()))
369 {
370 RCLCPP_ERROR_STREAM(m_node->get_logger(),
371 "Parameter \"" << resolved_name << "\" already declared with a range, cannot re-declare with a different one!");
372 return false;
373 }
374 }
375
376 // if the parameter is not declared yet, check if it is available in ROS by declaring it as dynamically-typed and read-writable
377 if (!was_declared)
378 {
379 rcl_interfaces::msg::ParameterDescriptor descriptor;
380 descriptor.read_only = false;
381 descriptor.dynamic_typing = true;
382 try
383 {
384 m_node->declare_parameter(resolved_name.str, rclcpp::ParameterValue(), descriptor);
385 }
386 catch (const std::exception& e)
387 {
388 // if the declaration already fails, something is wrong
389 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Failed to declare parameter \"" << resolved_name << "\": " << e.what());
390 return false;
391 }
392 }
393
394 // now try loading the parameter
395 try
396 {
397 /* RCLCPP_INFO_STREAM(m_node->get_logger(), "Getting param '" << resolved_name << "'"); */
398 rclcpp::Parameter param;
399 if (m_node->get_parameter(resolved_name.str, param))
400 loaded_value = param.get_value<T>();
401 }
402 // if the parameter has a wrong value, return failure
403 catch (const rclcpp::exceptions::InvalidParameterTypeException& e)
404 {
405 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Could not get param '" << resolved_name << "' from ROS: " << e.what());
406 }
407
408 // if the parameter was not declared before, undecalre it:
409 // 1. either it was loaded successfully and has to be re-declared with the correct options
410 // 2. or it was not loaded and has to be un-declared
411 if (!was_declared)
412 m_node->undeclare_parameter(resolved_name.str);
413
414 // loading from ROS was not successful, just return false
415 if (!loaded_value.has_value())
416 return false;
417
418 // if the parameter was not declared before, redeclare it with the correct parameters
419 if (!was_declared)
420 {
421 auto declare_opts_local = opts.declare_options;
422 declare_opts_local.default_value = value_out;
423 if (!declareParam<T>(resolved_name, declare_opts_local))
424 {
425 RCLCPP_ERROR_STREAM(m_node->get_logger(), "Failed to declare parameter \"" << resolved_name << "\".");
426 return false;
427 }
428 }
429
430 // if all went good, set the value and return true
431 value_out = std::move(loaded_value.value());
432 return true;
433 }
434 //}
435
436} // namespace mrs_lib
437
438namespace std
439{
440 template <>
441 struct hash<mrs_lib::ParamProvider::resolved_name_t>
442 {
443 std::size_t operator()(const mrs_lib::ParamProvider::resolved_name_t& r) const noexcept
444 {
445 return std::hash<std::string>{}(r.str);
446 }
447 };
448} // namespace std
resolved_name_t resolveName(const std::string &param_name) const
Returns the parameter name with prefixes and subnode namespaces.
Definition param_provider.cpp:160
bool getParam(const std::string &param_name, T &value_out) const
Gets the value of a parameter.
Definition param_provider.hpp:83
bool declareParam(const std::string &param_name) const
Defines a parameter.
Definition param_provider.hpp:176
bool setParam(const std::string &param_name, const T &value) const
Sets the value of a parameter to ROS.
Definition param_provider.hpp:134
Convenience concept of a numeric value (i.e. either integral or floating point, and not bool).
Definition param_provider.h:58
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
std::ostream & operator<<(std::ostream &os, const Eigen::MatrixX< T > &var)
Helper overload for printing of Eigen matrices.
Definition param_loader.hpp:21
rclcpp::ParameterType to_param_type()
Convenince function to get the corresponding rclcpp::ParamType from a C++ type.
Definition param_provider.hpp:75
Defines ParamProvider - a convenience class for seamlessly loading parameters from YAML or ROS.
Definition cyclic_example.cpp:23
Struct of options when declaring a parameter to ROS.
Definition param_provider.h:102
bool reconfigurable
If true, the parameter will be dynamically reconfigurable, otherwise it will be declared as read-only...
Definition param_provider.h:104
std::optional< T > default_value
An optional default value to initialize the parameter with.
Definition param_provider.h:106
std::optional< range_t< T > > range
An optional range of valid values of the parameter (only for numerical types).
Definition param_provider.h:108
Struct of options when getting a parameter from ROS.
Definition param_provider.h:118
declare_options_t< T > declare_options
Options when declaring a parameter to ROS (see the declare_options_t<T> documentation).
Definition param_provider.h:128
std::optional< bool > use_rosparam
Specifies whether the parameter should be attempted to be loaded from ROS if it cannot be loaded from...
Definition param_provider.h:124
bool always_declare
Iff true, the parameter will be declared to ROS even if it's value was loaded from a YAML.
Definition param_provider.h:120
bool use_yaml
Iff false, loading from YAML will be skipped even if some YAML files were specified.
Definition param_provider.h:122
Helper struct for a numeric range with named members to make the code a bit more readable.
Definition param_provider.h:87
T maximum
Maximal value of a parameter.
Definition param_provider.h:91
T minimum
Minimal value of a parameter.
Definition param_provider.h:89
Definition param_provider.hpp:43
Struct of options when setting a parameter to ROS.
Definition param_provider.h:138
declare_options_t< T > declare_options
Options when declaring a parameter to ROS (see the declare_options_t<T> documentation).
Definition param_provider.h:142