Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
node_utils.hpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_UTIL__NODE_UTILS_HPP_
16 #define NAV2_UTIL__NODE_UTILS_HPP_
17 
18 #include <vector>
19 #include <string>
20 #include "rclcpp/rclcpp.hpp"
21 #include "rcl_interfaces/srv/list_parameters.hpp"
22 
23 namespace nav2_util
24 {
25 
27 
36 std::string sanitize_node_name(const std::string & potential_node_name);
37 
39 
44 std::string add_namespaces(const std::string & top_ns, const std::string & sub_ns = "");
45 
47 
57 std::string generate_internal_node_name(const std::string & prefix = "");
58 
60 
69 rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix = "");
70 
72 
80 std::string time_to_string(size_t len);
81 
83 /* Declares static ROS2 parameter and sets it to a given value
84  * if it was not already declared.
85  *
86  * \param[in] node A node in which given parameter to be declared
87  * \param[in] param_name The name of parameter
88  * \param[in] default_value Parameter value to initialize with
89  * \param[in] parameter_descriptor Parameter descriptor (optional)
90  */
91 template<typename NodeT>
92 void declare_parameter_if_not_declared(
93  NodeT node,
94  const std::string & param_name,
95  const rclcpp::ParameterValue & default_value,
96  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
97  rcl_interfaces::msg::ParameterDescriptor())
98 {
99  if (!node->has_parameter(param_name)) {
100  node->declare_parameter(param_name, default_value, parameter_descriptor);
101  }
102 }
103 
105 /* Declares static ROS2 parameter with given type if it was not already declared.
106  *
107  * \param[in] node A node in which given parameter to be declared
108  * \param[in] param_type The type of parameter
109  * \param[in] default_value Parameter value to initialize with
110  * \param[in] parameter_descriptor Parameter descriptor (optional)
111  */
112 template<typename NodeT>
113 void declare_parameter_if_not_declared(
114  NodeT node,
115  const std::string & param_name,
116  const rclcpp::ParameterType & param_type,
117  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
118  rcl_interfaces::msg::ParameterDescriptor())
119 {
120  if (!node->has_parameter(param_name)) {
121  node->declare_parameter(param_name, param_type, parameter_descriptor);
122  }
123 }
124 
126 
134 template<typename NodeT>
135 std::string get_plugin_type_param(
136  NodeT node,
137  const std::string & plugin_name)
138 {
139  declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
140  std::string plugin_type;
141  try {
142  if (!node->get_parameter(plugin_name + ".plugin", plugin_type)) {
143  RCLCPP_FATAL(
144  node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
145  exit(-1);
146  }
147  } catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
148  RCLCPP_FATAL(node->get_logger(), "'plugin' param not defined for %s", plugin_name.c_str());
149  exit(-1);
150  }
151 
152  return plugin_type;
153 }
154 
161 template<typename NodeT1, typename NodeT2>
162 void copy_all_parameters(const NodeT1 & parent, const NodeT2 & child)
163 {
164  using Parameters = std::vector<rclcpp::Parameter>;
165  std::vector<std::string> param_names = parent->list_parameters({}, 0).names;
166  Parameters params = parent->get_parameters(param_names);
167  for (Parameters::const_iterator iter = params.begin(); iter != params.end(); ++iter) {
168  if (!child->has_parameter(iter->get_name())) {
169  child->declare_parameter(iter->get_name(), iter->get_parameter_value());
170  }
171  }
172 }
173 
174 } // namespace nav2_util
175 
176 #endif // NAV2_UTIL__NODE_UTILS_HPP_