16 #ifndef NAV2_ROS_COMMON__NODE_UTILS_HPP_
17 #define NAV2_ROS_COMMON__NODE_UTILS_HPP_
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"
30 using std::chrono::high_resolution_clock;
33 using std::replace_if;
49 inline std::string sanitize_node_name(
const std::string & potential_node_name)
51 string node_name(potential_node_name);
55 begin(node_name), end(node_name),
56 [](
auto c) {
return !isalnum(c);},
67 inline std::string add_namespaces(
const std::string & top_ns,
const std::string & sub_ns =
"")
69 if (!top_ns.empty() && top_ns.back() ==
'/') {
70 if (top_ns.front() ==
'/') {
71 return top_ns + sub_ns;
73 return "/" + top_ns + sub_ns;
77 return top_ns +
"/" + sub_ns;
89 inline std::string time_to_string(
size_t len)
91 string output(len,
'0');
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) {
100 timestring.length() - len, len);
104 len - timestring.length(), timestring.length(),
106 0, timestring.length());
122 inline std::string generate_internal_node_name(
const std::string & prefix =
"")
124 return sanitize_node_name(prefix) +
"_" + time_to_string(8);
137 inline rclcpp::Node::SharedPtr generate_internal_node(
const std::string & prefix =
"")
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);
147 using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
158 template<
typename NodeT>
159 inline void declare_parameter_if_not_declared(
161 const std::string & parameter_name,
162 const rclcpp::ParameterValue & default_value,
163 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
165 if (!node->has_parameter(parameter_name)) {
166 node->declare_parameter(parameter_name, default_value, parameter_descriptor);
178 template<
typename NodeT>
179 inline void declare_parameter_if_not_declared(
181 const std::string & parameter_name,
182 const rclcpp::ParameterType & param_type,
183 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
185 if (!node->has_parameter(parameter_name)) {
186 node->declare_parameter(parameter_name, param_type, parameter_descriptor);
202 template<
typename ParameterT,
typename NodeT>
203 inline ParameterT declare_or_get_parameter(
205 const std::string & parameter_name,
206 const rclcpp::ParameterType & param_type,
207 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
209 if (node->has_parameter(parameter_name)) {
210 return node->get_parameter(parameter_name).template get_value<ParameterT>();
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());
217 return parameter.template get<ParameterT>();
220 using NodeParamInterfacePtr = rclcpp::node_interfaces::NodeParametersInterface::SharedPtr;
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())
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>();
251 auto return_value = param_interface
252 ->declare_parameter(parameter_name, rclcpp::ParameterValue{default_value},
253 parameter_descriptor)
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) {
262 "Failed to get param " << parameter_name <<
" from overrides, using default value.");
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());
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())
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);
314 template<
typename NodeT>
315 inline std::string get_plugin_type_param(
317 const std::string & plugin_name)
319 declare_parameter_if_not_declared(node, plugin_name +
".plugin", rclcpp::PARAMETER_STRING);
320 std::string plugin_type;
322 if (!node->get_parameter(plugin_name +
".plugin", plugin_type)) {
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!");
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!");
340 inline void setSoftRealTimePriority()
343 sch.sched_priority = 49;
344 if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
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));
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)
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"));
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;
373 ros_interface->configure_introspection(clock, rclcpp::ServicesQoS(), introspection_state);
376 (void)node_parameters_interface;
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)
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;
395 arguments.push_back(
"--ros-args");
396 arguments.push_back(option);
397 arguments.push_back(new_argument);