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"
29 using std::chrono::high_resolution_clock;
32 using std::replace_if;
48 inline std::string sanitize_node_name(
const std::string & potential_node_name)
50 string node_name(potential_node_name);
54 begin(node_name), end(node_name),
55 [](
auto c) {
return !isalnum(c);},
66 inline std::string add_namespaces(
const std::string & top_ns,
const std::string & sub_ns =
"")
68 if (!top_ns.empty() && top_ns.back() ==
'/') {
69 if (top_ns.front() ==
'/') {
70 return top_ns + sub_ns;
72 return "/" + top_ns + sub_ns;
76 return top_ns +
"/" + sub_ns;
88 inline std::string time_to_string(
size_t len)
90 string output(len,
'0');
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) {
99 timestring.length() - len, len);
103 len - timestring.length(), timestring.length(),
105 0, timestring.length());
121 inline std::string generate_internal_node_name(
const std::string & prefix =
"")
123 return sanitize_node_name(prefix) +
"_" + time_to_string(8);
136 inline rclcpp::Node::SharedPtr generate_internal_node(
const std::string & prefix =
"")
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);
146 using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
157 template<
typename NodeT>
158 inline void declare_parameter_if_not_declared(
160 const std::string & parameter_name,
161 const rclcpp::ParameterValue & default_value,
162 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
164 if (!node->has_parameter(parameter_name)) {
165 node->declare_parameter(parameter_name, default_value, parameter_descriptor);
177 template<
typename NodeT>
178 inline void declare_parameter_if_not_declared(
180 const std::string & parameter_name,
181 const rclcpp::ParameterType & param_type,
182 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
184 if (!node->has_parameter(parameter_name)) {
185 node->declare_parameter(parameter_name, param_type, parameter_descriptor);
200 template<
typename ParameterT,
typename NodeT>
201 inline ParameterT declare_or_get_parameter(
203 const std::string & parameter_name,
204 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
206 if (node->has_parameter(parameter_name)) {
207 return node->get_parameter(parameter_name).template get_value<ParameterT>();
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());
215 return parameter.template get<ParameterT>();
218 using NodeParamInterfacePtr = rclcpp::node_interfaces::NodeParametersInterface::SharedPtr;
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())
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>();
249 auto return_value = param_interface
250 ->declare_parameter(parameter_name, rclcpp::ParameterValue{default_value},
251 parameter_descriptor)
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) {
260 "Failed to get param " << parameter_name <<
" from overrides, using default value.");
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());
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())
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);
312 template<
typename NodeT>
313 inline std::string get_plugin_type_param(
315 const std::string & plugin_name)
317 declare_parameter_if_not_declared(node, plugin_name +
".plugin", rclcpp::PARAMETER_STRING);
318 std::string plugin_type;
320 if (!node->get_parameter(plugin_name +
".plugin", plugin_type)) {
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!");
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!");
338 inline void setSoftRealTimePriority()
341 sch.sched_priority = 49;
342 if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
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));
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)
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"));
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;
371 ros_interface->configure_introspection(clock, rclcpp::ServicesQoS(), introspection_state);
374 (void)node_parameters_interface;
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)
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;
393 arguments.push_back(
"--ros-args");
394 arguments.push_back(option);
395 arguments.push_back(new_argument);