35 #ifndef NAV_2D_UTILS__PARAMETERS_HPP_
36 #define NAV_2D_UTILS__PARAMETERS_HPP_
41 #include "rclcpp/rclcpp.hpp"
42 #include "nav2_util/lifecycle_node.hpp"
43 #include "nav2_util/node_utils.hpp"
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Wunused-parameter"
48 namespace nav_2d_utils
62 template<
class param_t>
63 param_t searchAndGetParam(
64 const nav2_util::LifecycleNode::SharedPtr & nh,
const std::string & param_name,
65 const param_t & default_value)
67 nav2_util::declare_parameter_if_not_declared(
69 rclcpp::ParameterValue(default_value));
70 return nh->get_parameter(param_name).get_value<param_t>();
74 #pragma GCC diagnostic pop