Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
node_utils.hpp
1 // Copyright (c) 2019 Intel Corporation
2 // Copyright (c) 2023 Open Navigation LLC
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_ROS_COMMON__NODE_UTILS_HPP_
17 #define NAV2_ROS_COMMON__NODE_UTILS_HPP_
18 
19 #include <vector>
20 #include <string>
21 #include <chrono>
22 #include <algorithm>
23 #include <cctype>
24 #include "rclcpp/version.h"
25 #include "rclcpp/rclcpp.hpp"
26 #include "rcl_interfaces/srv/list_parameters.hpp"
27 #include "pluginlib/exceptions.hpp"
28 
29 using std::chrono::high_resolution_clock;
30 using std::to_string;
31 using std::string;
32 using std::replace_if;
33 using std::isalnum;
34 
35 namespace nav2
36 {
37 
39 
48 inline std::string sanitize_node_name(const std::string & potential_node_name)
49 {
50  string node_name(potential_node_name);
51  // read this as `replace` characters in `node_name` `if` not alphanumeric.
52  // replace with '_'
53  replace_if(
54  begin(node_name), end(node_name),
55  [](auto c) {return !isalnum(c);},
56  '_');
57  return node_name;
58 }
59 
61 
66 inline std::string add_namespaces(const std::string & top_ns, const std::string & sub_ns = "")
67 {
68  if (!top_ns.empty() && top_ns.back() == '/') {
69  if (top_ns.front() == '/') {
70  return top_ns + sub_ns;
71  } else {
72  return "/" + top_ns + sub_ns;
73  }
74  }
75 
76  return top_ns + "/" + sub_ns;
77 }
78 
80 
88 inline std::string time_to_string(size_t len)
89 {
90  string output(len, '0'); // prefill the string with zeros
91  auto timepoint = high_resolution_clock::now();
92  auto timecount = timepoint.time_since_epoch().count();
93  auto timestring = to_string(timecount);
94  if (timestring.length() >= len) {
95  // if `timestring` is shorter, put it at the end of `output`
96  output.replace(
97  0, len,
98  timestring,
99  timestring.length() - len, len);
100  } else {
101  // if `output` is shorter, just copy in the end of `timestring`
102  output.replace(
103  len - timestring.length(), timestring.length(),
104  timestring,
105  0, timestring.length());
106  }
107  return output;
108 }
109 
111 
121 inline std::string generate_internal_node_name(const std::string & prefix = "")
122 {
123  return sanitize_node_name(prefix) + "_" + time_to_string(8);
124 }
125 
127 
136 inline rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix = "")
137 {
138  auto options =
139  rclcpp::NodeOptions()
140  .start_parameter_services(false)
141  .start_parameter_event_publisher(false)
142  .arguments({"--ros-args", "-r", "__node:=" + generate_internal_node_name(prefix), "--"});
143  return rclcpp::Node::make_shared("_", options);
144 }
145 
146 using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
147 
149 /* Declares static ROS2 parameter and sets it to a given value
150  * if it was not already declared.
151  *
152  * \param[in] node A node in which given parameter to be declared
153  * \param[in] parameter_name The name of parameter
154  * \param[in] default_value Parameter value to initialize with
155  * \param[in] parameter_descriptor Parameter descriptor (optional)
156  */
157 template<typename NodeT>
158 inline void declare_parameter_if_not_declared(
159  NodeT node,
160  const std::string & parameter_name,
161  const rclcpp::ParameterValue & default_value,
162  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
163 {
164  if (!node->has_parameter(parameter_name)) {
165  node->declare_parameter(parameter_name, default_value, parameter_descriptor);
166  }
167 }
168 
170 /* Declares static ROS2 parameter with given type if it was not already declared.
171  *
172  * \param[in] node A node in which given parameter to be declared
173  * \param[in] parameter_name Name of the parameter
174  * \param[in] param_type The type of parameter
175  * \param[in] parameter_descriptor Parameter descriptor (optional)
176  */
177 template<typename NodeT>
178 inline void declare_parameter_if_not_declared(
179  NodeT node,
180  const std::string & parameter_name,
181  const rclcpp::ParameterType & param_type,
182  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
183 {
184  if (!node->has_parameter(parameter_name)) {
185  node->declare_parameter(parameter_name, param_type, parameter_descriptor);
186  }
187 }
188 
191 /* Declares a parameter with the specified type if it was not already declared.
192  * If the parameter was overridden, its value is returned, otherwise an
193  * rclcpp::exceptions::InvalidParameterValueException is thrown
194  *
195  * \param[in] node A node in which given parameter to be declared
196  * \param[in] parameter_name Name of the parameter
197  * \param[in] parameter_descriptor Parameter descriptor (optional)
198  * \return The value of the parameter or an exception
199  */
200 template<typename ParameterT, typename NodeT>
201 inline ParameterT declare_or_get_parameter(
202  NodeT node,
203  const std::string & parameter_name,
204  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
205 {
206  if (node->has_parameter(parameter_name)) {
207  return node->get_parameter(parameter_name).template get_value<ParameterT>();
208  }
209  auto param_type = rclcpp::ParameterValue{ParameterT{}}.get_type();
210  auto parameter = node->declare_parameter(parameter_name, param_type, parameter_descriptor);
211  if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET) {
212  std::string description = "Parameter " + parameter_name + " not in overrides";
213  throw rclcpp::exceptions::InvalidParameterValueException(description.c_str());
214  }
215  return parameter.template get<ParameterT>();
216 }
217 
218 using NodeParamInterfacePtr = rclcpp::node_interfaces::NodeParametersInterface::SharedPtr;
219 
222 
236 template<typename ParamType>
237 inline ParamType declare_or_get_parameter(
238  const rclcpp::Logger & logger, NodeParamInterfacePtr param_interface,
239  const std::string & parameter_name, const ParamType & default_value,
240  bool warn_if_no_override = false, bool strict_param_loading = false,
241  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
242 {
243  if (param_interface->has_parameter(parameter_name)) {
244  rclcpp::Parameter param(parameter_name, default_value);
245  param_interface->get_parameter(parameter_name, param);
246  return param.get_value<ParamType>();
247  }
248 
249  auto return_value = param_interface
250  ->declare_parameter(parameter_name, rclcpp::ParameterValue{default_value},
251  parameter_descriptor)
252  .get<ParamType>();
253 
254  const bool no_param_override = param_interface->get_parameter_overrides().find(parameter_name) ==
255  param_interface->get_parameter_overrides().end();
256  if (no_param_override) {
257  if (warn_if_no_override) {
258  RCLCPP_WARN_STREAM(
259  logger,
260  "Failed to get param " << parameter_name << " from overrides, using default value.");
261  }
262  if (strict_param_loading) {
263  std::string description = "Parameter " + parameter_name +
264  " not in overrides and strict_param_loading is True";
265  throw rclcpp::exceptions::InvalidParameterValueException(description.c_str());
266  }
267  }
268 
269  return return_value;
270 }
271 
274 
287 template<typename ParamType, typename NodeT>
288 inline ParamType declare_or_get_parameter(
289  NodeT node, const std::string & parameter_name,
290  const ParamType & default_value,
291  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
292 {
293  declare_parameter_if_not_declared(node, "warn_on_missing_params", rclcpp::ParameterValue(false));
294  bool warn_if_no_override{false};
295  node->get_parameter("warn_on_missing_params", warn_if_no_override);
296  declare_parameter_if_not_declared(node, "strict_param_loading", rclcpp::ParameterValue(false));
297  bool strict_param_loading{false};
298  node->get_parameter("strict_param_loading", strict_param_loading);
299  return declare_or_get_parameter(node->get_logger(), node->get_node_parameters_interface(),
300  parameter_name, default_value, warn_if_no_override, strict_param_loading, parameter_descriptor);
301 }
302 
304 
312 template<typename NodeT>
313 inline std::string get_plugin_type_param(
314  NodeT node,
315  const std::string & plugin_name)
316 {
317  declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
318  std::string plugin_type;
319  try {
320  if (!node->get_parameter(plugin_name + ".plugin", plugin_type)) {
321  RCLCPP_FATAL(
322  node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
323  throw pluginlib::PluginlibException("No 'plugin' param for param ns!");
324  }
325  } catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
326  RCLCPP_FATAL(node->get_logger(), "'plugin' param not defined for %s", plugin_name.c_str());
327  throw pluginlib::PluginlibException("No 'plugin' param for param ns!");
328  }
329 
330  return plugin_type;
331 }
332 
338 inline void setSoftRealTimePriority()
339 {
340  sched_param sch;
341  sch.sched_priority = 49;
342  if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
343  std::string errmsg(
344  "Cannot set as real-time thread. Users must set: <username> hard rtprio 99 and "
345  "<username> soft rtprio 99 in /etc/security/limits.conf to enable "
346  "realtime prioritization! Error: ");
347  throw std::runtime_error(errmsg + std::strerror(errno));
348  }
349 }
350 
351 template<typename InterfaceT>
352 inline void setIntrospectionMode(
353  InterfaceT & ros_interface,
354  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface,
355  rclcpp::Clock::SharedPtr clock)
356 {
357  #if RCLCPP_VERSION_GTE(29, 0, 0)
358  rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
359  if (!node_parameters_interface->has_parameter("introspection_mode")) {
360  node_parameters_interface->declare_parameter(
361  "introspection_mode", rclcpp::ParameterValue("disabled"));
362  }
363  std::string introspection_mode =
364  node_parameters_interface->get_parameter("introspection_mode").as_string();
365  if (introspection_mode == "metadata") {
366  introspection_state = RCL_SERVICE_INTROSPECTION_METADATA;
367  } else if (introspection_mode == "contents") {
368  introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS;
369  }
370 
371  ros_interface->configure_introspection(clock, rclcpp::ServicesQoS(), introspection_state);
372  #else
373  (void)ros_interface;
374  (void)node_parameters_interface;
375  (void)clock;
376  #endif
377 }
378 
384 inline void replaceOrAddArgument(
385  std::vector<std::string> & arguments, const std::string & option,
386  const std::string & arg_name, const std::string & new_argument)
387 {
388  auto argument = std::find_if(arguments.begin(), arguments.end(),
389  [arg_name](const std::string & value){return value.find(arg_name) != std::string::npos;});
390  if (argument != arguments.end()) {
391  *argument = new_argument;
392  } else {
393  arguments.push_back("--ros-args");
394  arguments.push_back(option);
395  arguments.push_back(new_argument);
396  }
397 }
398 
399 } // namespace nav2
400 
401 #endif // NAV2_ROS_COMMON__NODE_UTILS_HPP_