Program Listing for File node_utils.hpp
↰ Return to documentation for file (include/nav2_util/node_utils.hpp
)
// Copyright (c) 2019 Intel Corporation
// Copyright (c) 2023 Open Navigation LLC
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_UTIL__NODE_UTILS_HPP_
#define NAV2_UTIL__NODE_UTILS_HPP_
#include <vector>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "rcl_interfaces/srv/list_parameters.hpp"
namespace nav2_util
{
std::string sanitize_node_name(const std::string & potential_node_name);
std::string add_namespaces(const std::string & top_ns, const std::string & sub_ns = "");
std::string generate_internal_node_name(const std::string & prefix = "");
rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix = "");
std::string time_to_string(size_t len);
/* Declares static ROS2 parameter and sets it to a given value
* if it was not already declared.
*
* \param[in] node A node in which given parameter to be declared
* \param[in] param_name The name of parameter
* \param[in] default_value Parameter value to initialize with
* \param[in] parameter_descriptor Parameter descriptor (optional)
*/
template<typename NodeT>
void declare_parameter_if_not_declared(
NodeT node,
const std::string & param_name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor())
{
if (!node->has_parameter(param_name)) {
node->declare_parameter(param_name, default_value, parameter_descriptor);
}
}
/* Declares static ROS2 parameter with given type if it was not already declared.
*
* \param[in] node A node in which given parameter to be declared
* \param[in] param_type The type of parameter
* \param[in] default_value Parameter value to initialize with
* \param[in] parameter_descriptor Parameter descriptor (optional)
*/
template<typename NodeT>
void declare_parameter_if_not_declared(
NodeT node,
const std::string & param_name,
const rclcpp::ParameterType & param_type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor())
{
if (!node->has_parameter(param_name)) {
node->declare_parameter(param_name, param_type, parameter_descriptor);
}
}
template<typename NodeT>
std::string get_plugin_type_param(
NodeT node,
const std::string & plugin_name)
{
declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
std::string plugin_type;
try {
if (!node->get_parameter(plugin_name + ".plugin", plugin_type)) {
RCLCPP_FATAL(
node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
throw std::runtime_error("No 'plugin' param for param ns!");
}
} catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
RCLCPP_FATAL(node->get_logger(), "'plugin' param not defined for %s", plugin_name.c_str());
throw std::runtime_error("No 'plugin' param for param ns!");
}
return plugin_type;
}
void setSoftRealTimePriority();
} // namespace nav2_util
#endif // NAV2_UTIL__NODE_UTILS_HPP_