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 #include "nav2_ros_common/node_utils.hpp"
29 
30 using std::chrono::high_resolution_clock;
31 using std::to_string;
32 using std::string;
33 using std::replace_if;
34 using std::isalnum;
35 
36 namespace nav2
37 {
38 
40 
49 inline std::string sanitize_node_name(const std::string & potential_node_name)
50 {
51  string node_name(potential_node_name);
52  // read this as `replace` characters in `node_name` `if` not alphanumeric.
53  // replace with '_'
54  replace_if(
55  begin(node_name), end(node_name),
56  [](auto c) {return !isalnum(c);},
57  '_');
58  return node_name;
59 }
60 
62 
67 inline std::string add_namespaces(const std::string & top_ns, const std::string & sub_ns = "")
68 {
69  if (!top_ns.empty() && top_ns.back() == '/') {
70  if (top_ns.front() == '/') {
71  return top_ns + sub_ns;
72  } else {
73  return "/" + top_ns + sub_ns;
74  }
75  }
76 
77  return top_ns + "/" + sub_ns;
78 }
79 
81 
89 inline std::string time_to_string(size_t len)
90 {
91  string output(len, '0'); // prefill the string with zeros
92  auto timepoint = high_resolution_clock::now();
93  auto timecount = timepoint.time_since_epoch().count();
94  auto timestring = to_string(timecount);
95  if (timestring.length() >= len) {
96  // if `timestring` is shorter, put it at the end of `output`
97  output.replace(
98  0, len,
99  timestring,
100  timestring.length() - len, len);
101  } else {
102  // if `output` is shorter, just copy in the end of `timestring`
103  output.replace(
104  len - timestring.length(), timestring.length(),
105  timestring,
106  0, timestring.length());
107  }
108  return output;
109 }
110 
112 
122 inline std::string generate_internal_node_name(const std::string & prefix = "")
123 {
124  return sanitize_node_name(prefix) + "_" + time_to_string(8);
125 }
126 
128 
137 inline rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix = "")
138 {
139  auto options =
140  rclcpp::NodeOptions()
141  .start_parameter_services(false)
142  .start_parameter_event_publisher(false)
143  .arguments({"--ros-args", "-r", "__node:=" + generate_internal_node_name(prefix), "--"});
144  return rclcpp::Node::make_shared("_", options);
145 }
146 
147 using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
148 
150 /* Declares static ROS2 parameter and sets it to a given value
151  * if it was not already declared.
152  *
153  * \param[in] node A node in which given parameter to be declared
154  * \param[in] parameter_name The name of parameter
155  * \param[in] default_value Parameter value to initialize with
156  * \param[in] parameter_descriptor Parameter descriptor (optional)
157  */
158 template<typename NodeT>
159 inline void declare_parameter_if_not_declared(
160  NodeT node,
161  const std::string & parameter_name,
162  const rclcpp::ParameterValue & default_value,
163  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
164 {
165  if (!node->has_parameter(parameter_name)) {
166  node->declare_parameter(parameter_name, default_value, parameter_descriptor);
167  }
168 }
169 
171 /* Declares static ROS2 parameter with given type if it was not already declared.
172  *
173  * \param[in] node A node in which given parameter to be declared
174  * \param[in] parameter_name Name of the parameter
175  * \param[in] param_type The type of parameter
176  * \param[in] parameter_descriptor Parameter descriptor (optional)
177  */
178 template<typename NodeT>
179 inline void declare_parameter_if_not_declared(
180  NodeT node,
181  const std::string & parameter_name,
182  const rclcpp::ParameterType & param_type,
183  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
184 {
185  if (!node->has_parameter(parameter_name)) {
186  node->declare_parameter(parameter_name, param_type, parameter_descriptor);
187  }
188 }
189 
192 /* Declares a parameter with the specified type if it was not already declared.
193  * If the parameter was overridden, its value is returned, otherwise an
194  * rclcpp::exceptions::InvalidParameterValueException is thrown
195  *
196  * \param[in] node A node in which given parameter to be declared
197  * \param[in] parameter_name Name of the parameter
198  * \param[in] param_type The type of parameter
199  * \param[in] parameter_descriptor Parameter descriptor (optional)
200  * \return The value of the parameter or an exception
201  */
202 template<typename ParameterT, typename NodeT>
203 inline ParameterT declare_or_get_parameter(
204  NodeT node,
205  const std::string & parameter_name,
206  const rclcpp::ParameterType & param_type,
207  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
208 {
209  if (node->has_parameter(parameter_name)) {
210  return node->get_parameter(parameter_name).template get_value<ParameterT>();
211  }
212  auto parameter = node->declare_parameter(parameter_name, param_type, parameter_descriptor);
213  if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET) {
214  std::string description = "Parameter " + parameter_name + " not in overrides";
215  throw rclcpp::exceptions::InvalidParameterValueException(description.c_str());
216  }
217  return parameter.template get<ParameterT>();
218 }
219 
220 using NodeParamInterfacePtr = rclcpp::node_interfaces::NodeParametersInterface::SharedPtr;
221 
224 
238 template<typename ParamType>
239 inline ParamType declare_or_get_parameter(
240  const rclcpp::Logger & logger, NodeParamInterfacePtr param_interface,
241  const std::string & parameter_name, const ParamType & default_value,
242  bool warn_if_no_override = false, bool strict_param_loading = false,
243  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
244 {
245  if (param_interface->has_parameter(parameter_name)) {
246  rclcpp::Parameter param(parameter_name, default_value);
247  param_interface->get_parameter(parameter_name, param);
248  return param.get_value<ParamType>();
249  }
250 
251  auto return_value = param_interface
252  ->declare_parameter(parameter_name, rclcpp::ParameterValue{default_value},
253  parameter_descriptor)
254  .get<ParamType>();
255 
256  const bool no_param_override = param_interface->get_parameter_overrides().find(parameter_name) ==
257  param_interface->get_parameter_overrides().end();
258  if (no_param_override) {
259  if (warn_if_no_override) {
260  RCLCPP_WARN_STREAM(
261  logger,
262  "Failed to get param " << parameter_name << " from overrides, using default value.");
263  }
264  if (strict_param_loading) {
265  std::string description = "Parameter " + parameter_name +
266  " not in overrides and strict_param_loading is True";
267  throw rclcpp::exceptions::InvalidParameterValueException(description.c_str());
268  }
269  }
270 
271  return return_value;
272 }
273 
276 
289 template<typename ParamType, typename NodeT>
290 inline ParamType declare_or_get_parameter(
291  NodeT node, const std::string & parameter_name,
292  const ParamType & default_value,
293  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
294 {
295  declare_parameter_if_not_declared(node, "warn_on_missing_params", rclcpp::ParameterValue(false));
296  bool warn_if_no_override{false};
297  node->get_parameter("warn_on_missing_params", warn_if_no_override);
298  declare_parameter_if_not_declared(node, "strict_param_loading", rclcpp::ParameterValue(false));
299  bool strict_param_loading{false};
300  node->get_parameter("strict_param_loading", strict_param_loading);
301  return declare_or_get_parameter(node->get_logger(), node->get_node_parameters_interface(),
302  parameter_name, default_value, warn_if_no_override, strict_param_loading, parameter_descriptor);
303 }
304 
306 
314 template<typename NodeT>
315 inline std::string get_plugin_type_param(
316  NodeT node,
317  const std::string & plugin_name)
318 {
319  declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
320  std::string plugin_type;
321  try {
322  if (!node->get_parameter(plugin_name + ".plugin", plugin_type)) {
323  RCLCPP_FATAL(
324  node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
325  throw pluginlib::PluginlibException("No 'plugin' param for param ns!");
326  }
327  } catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
328  RCLCPP_FATAL(node->get_logger(), "'plugin' param not defined for %s", plugin_name.c_str());
329  throw pluginlib::PluginlibException("No 'plugin' param for param ns!");
330  }
331 
332  return plugin_type;
333 }
334 
340 inline void setSoftRealTimePriority()
341 {
342  sched_param sch;
343  sch.sched_priority = 49;
344  if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
345  std::string errmsg(
346  "Cannot set as real-time thread. Users must set: <username> hard rtprio 99 and "
347  "<username> soft rtprio 99 in /etc/security/limits.conf to enable "
348  "realtime prioritization! Error: ");
349  throw std::runtime_error(errmsg + std::strerror(errno));
350  }
351 }
352 
353 template<typename InterfaceT>
354 inline void setIntrospectionMode(
355  InterfaceT & ros_interface,
356  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface,
357  rclcpp::Clock::SharedPtr clock)
358 {
359  #if RCLCPP_VERSION_GTE(29, 0, 0)
360  rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
361  if (!node_parameters_interface->has_parameter("introspection_mode")) {
362  node_parameters_interface->declare_parameter(
363  "introspection_mode", rclcpp::ParameterValue("disabled"));
364  }
365  std::string introspection_mode =
366  node_parameters_interface->get_parameter("introspection_mode").as_string();
367  if (introspection_mode == "metadata") {
368  introspection_state = RCL_SERVICE_INTROSPECTION_METADATA;
369  } else if (introspection_mode == "contents") {
370  introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS;
371  }
372 
373  ros_interface->configure_introspection(clock, rclcpp::ServicesQoS(), introspection_state);
374  #else
375  (void)ros_interface;
376  (void)node_parameters_interface;
377  (void)clock;
378  #endif
379 }
380 
386 inline void replaceOrAddArgument(
387  std::vector<std::string> & arguments, const std::string & option,
388  const std::string & arg_name, const std::string & new_argument)
389 {
390  auto argument = std::find_if(arguments.begin(), arguments.end(),
391  [arg_name](const std::string & value){return value.find(arg_name) != std::string::npos;});
392  if (argument != arguments.end()) {
393  *argument = new_argument;
394  } else {
395  arguments.push_back("--ros-args");
396  arguments.push_back(option);
397  arguments.push_back(new_argument);
398  }
399 }
400 
401 } // namespace nav2
402 
403 #endif // NAV2_ROS_COMMON__NODE_UTILS_HPP_