16 #ifndef NAV2_UTIL__NODE_UTILS_HPP_
17 #define NAV2_UTIL__NODE_UTILS_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "rcl_interfaces/srv/list_parameters.hpp"
37 std::string sanitize_node_name(
const std::string & potential_node_name);
45 std::string add_namespaces(
const std::string & top_ns,
const std::string & sub_ns =
"");
58 std::string generate_internal_node_name(
const std::string & prefix =
"");
70 rclcpp::Node::SharedPtr generate_internal_node(
const std::string & prefix =
"");
81 std::string time_to_string(
size_t len);
83 using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor;
94 template<
typename NodeT>
95 void declare_parameter_if_not_declared(
97 const std::string & parameter_name,
98 const rclcpp::ParameterValue & default_value,
99 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
101 if (!node->has_parameter(parameter_name)) {
102 node->declare_parameter(parameter_name, default_value, parameter_descriptor);
114 template<
typename NodeT>
115 void declare_parameter_if_not_declared(
117 const std::string & parameter_name,
118 const rclcpp::ParameterType & param_type,
119 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
121 if (!node->has_parameter(parameter_name)) {
122 node->declare_parameter(parameter_name, param_type, parameter_descriptor);
138 template<
typename ParameterT,
typename NodeT>
139 ParameterT declare_or_get_parameter(
141 const std::string & parameter_name,
142 const rclcpp::ParameterType & param_type,
143 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
145 if (node->has_parameter(parameter_name)) {
146 return node->get_parameter(parameter_name).template get_value<ParameterT>();
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());
153 return parameter.template get<ParameterT>();
156 using NodeParamInterfacePtr = rclcpp::node_interfaces::NodeParametersInterface::SharedPtr;
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())
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>();
187 auto return_value = param_interface
188 ->declare_parameter(parameter_name, rclcpp::ParameterValue{default_value},
189 parameter_descriptor)
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) {
198 "Failed to get param " << parameter_name <<
" from overrides, using default value.");
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());
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())
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);
250 template<
typename NodeT>
251 std::string get_plugin_type_param(
253 const std::string & plugin_name)
255 declare_parameter_if_not_declared(node, plugin_name +
".plugin", rclcpp::PARAMETER_STRING);
256 std::string plugin_type;
258 if (!node->get_parameter(plugin_name +
".plugin", plugin_type)) {
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!");
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!");
276 void setSoftRealTimePriority();