Nav2 Navigation Stack - jazzy  jazzy
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_UTIL__NODE_UTILS_HPP_
17 #define NAV2_UTIL__NODE_UTILS_HPP_
18 
19 #include <vector>
20 #include <string>
21 #include "rclcpp/rclcpp.hpp"
22 #include "rcl_interfaces/srv/list_parameters.hpp"
23 
24 namespace nav2_util
25 {
26 
28 
37 std::string sanitize_node_name(const std::string & potential_node_name);
38 
40 
45 std::string add_namespaces(const std::string & top_ns, const std::string & sub_ns = "");
46 
48 
58 std::string generate_internal_node_name(const std::string & prefix = "");
59 
61 
70 rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix = "");
71 
73 
81 std::string time_to_string(size_t len);
82 
83 using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
84 
86 /* Declares static ROS2 parameter and sets it to a given value
87  * if it was not already declared.
88  *
89  * \param[in] node A node in which given parameter to be declared
90  * \param[in] parameter_name The name of parameter
91  * \param[in] default_value Parameter value to initialize with
92  * \param[in] parameter_descriptor Parameter descriptor (optional)
93  */
94 template<typename NodeT>
95 void declare_parameter_if_not_declared(
96  NodeT node,
97  const std::string & parameter_name,
98  const rclcpp::ParameterValue & default_value,
99  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
100 {
101  if (!node->has_parameter(parameter_name)) {
102  node->declare_parameter(parameter_name, default_value, parameter_descriptor);
103  }
104 }
105 
107 /* Declares static ROS2 parameter with given type if it was not already declared.
108  *
109  * \param[in] node A node in which given parameter to be declared
110  * \param[in] parameter_name Name of the parameter
111  * \param[in] param_type The type of parameter
112  * \param[in] parameter_descriptor Parameter descriptor (optional)
113  */
114 template<typename NodeT>
115 void declare_parameter_if_not_declared(
116  NodeT node,
117  const std::string & parameter_name,
118  const rclcpp::ParameterType & param_type,
119  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
120 {
121  if (!node->has_parameter(parameter_name)) {
122  node->declare_parameter(parameter_name, param_type, parameter_descriptor);
123  }
124 }
125 
128 /* Declares a parameter with the specified type if it was not already declared.
129  * If the parameter was overridden, its value is returned, otherwise an
130  * rclcpp::exceptions::InvalidParameterValueException is thrown
131  *
132  * \param[in] node A node in which given parameter to be declared
133  * \param[in] parameter_name Name of the parameter
134  * \param[in] param_type The type of parameter
135  * \param[in] parameter_descriptor Parameter descriptor (optional)
136  * \return The value of the parameter or an exception
137  */
138 template<typename ParameterT, typename NodeT>
139 ParameterT declare_or_get_parameter(
140  NodeT node,
141  const std::string & parameter_name,
142  const rclcpp::ParameterType & param_type,
143  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
144 {
145  if (node->has_parameter(parameter_name)) {
146  return node->get_parameter(parameter_name).template get_value<ParameterT>();
147  }
148  auto parameter = node->declare_parameter(parameter_name, param_type, parameter_descriptor);
149  if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET) {
150  std::string description = "Parameter " + parameter_name + " not in overrides";
151  throw rclcpp::exceptions::InvalidParameterValueException(description.c_str());
152  }
153  return parameter.template get<ParameterT>();
154 }
155 
156 using NodeParamInterfacePtr = rclcpp::node_interfaces::NodeParametersInterface::SharedPtr;
157 
160 
174 template<typename ParamType>
175 ParamType declare_or_get_parameter(
176  const rclcpp::Logger & logger, NodeParamInterfacePtr param_interface,
177  const std::string & parameter_name, const ParamType & default_value,
178  bool warn_if_no_override = false, bool strict_param_loading = false,
179  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
180 {
181  if (param_interface->has_parameter(parameter_name)) {
182  rclcpp::Parameter param(parameter_name, default_value);
183  param_interface->get_parameter(parameter_name, param);
184  return param.get_value<ParamType>();
185  }
186 
187  auto return_value = param_interface
188  ->declare_parameter(parameter_name, rclcpp::ParameterValue{default_value},
189  parameter_descriptor)
190  .get<ParamType>();
191 
192  const bool no_param_override = param_interface->get_parameter_overrides().find(parameter_name) ==
193  param_interface->get_parameter_overrides().end();
194  if (no_param_override) {
195  if (warn_if_no_override) {
196  RCLCPP_WARN_STREAM(
197  logger,
198  "Failed to get param " << parameter_name << " from overrides, using default value.");
199  }
200  if (strict_param_loading) {
201  std::string description = "Parameter " + parameter_name +
202  " not in overrides and strict_param_loading is True";
203  throw rclcpp::exceptions::InvalidParameterValueException(description.c_str());
204  }
205  }
206 
207  return return_value;
208 }
209 
212 
225 template<typename ParamType, typename NodeT>
226 ParamType declare_or_get_parameter(
227  NodeT node, const std::string & parameter_name,
228  const ParamType & default_value,
229  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
230 {
231  declare_parameter_if_not_declared(node, "warn_on_missing_params", rclcpp::ParameterValue(false));
232  bool warn_if_no_override{false};
233  node->get_parameter("warn_on_missing_params", warn_if_no_override);
234  declare_parameter_if_not_declared(node, "strict_param_loading", rclcpp::ParameterValue(false));
235  bool strict_param_loading{false};
236  node->get_parameter("strict_param_loading", strict_param_loading);
237  return declare_or_get_parameter(node->get_logger(), node->get_node_parameters_interface(),
238  parameter_name, default_value, warn_if_no_override, strict_param_loading, parameter_descriptor);
239 }
240 
242 
250 template<typename NodeT>
251 std::string get_plugin_type_param(
252  NodeT node,
253  const std::string & plugin_name)
254 {
255  declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
256  std::string plugin_type;
257  try {
258  if (!node->get_parameter(plugin_name + ".plugin", plugin_type)) {
259  RCLCPP_FATAL(
260  node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
261  throw std::runtime_error("No 'plugin' param for param ns!");
262  }
263  } catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
264  RCLCPP_FATAL(node->get_logger(), "'plugin' param not defined for %s", plugin_name.c_str());
265  throw std::runtime_error("No 'plugin' param for param ns!");
266  }
267 
268  return plugin_type;
269 }
270 
276 void setSoftRealTimePriority();
277 
278 } // namespace nav2_util
279 
280 #endif // NAV2_UTIL__NODE_UTILS_HPP_