.. _program_listing_file__tmp_ws_src_grid_map_grid_map_cv_include_grid_map_cv_utilities.hpp: Program Listing for File utilities.hpp ====================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/grid_map/grid_map_cv/include/grid_map_cv/utilities.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef GRID_MAP_CV__UTILITIES_HPP_ #define GRID_MAP_CV__UTILITIES_HPP_ #include #include #include namespace grid_map { class ParameterReader { public: ParameterReader( std::string param_prefix, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr params_interface) : param_prefix_(param_prefix), params_interface_(params_interface) {} template bool get_template(const std::string & name, T & value_out, rclcpp::ParameterType param_type) { rclcpp::Parameter param; params_interface_->declare_parameter(param_prefix_ + name, param_type); params_interface_->get_parameter(param_prefix_ + name, param); if (param.get_type() != param_type) { return false; } else { value_out = param.get_value(); return true; } } bool get(const std::string & name, int & value_out) { return get_template(name, value_out, rclcpp::PARAMETER_INTEGER); } bool get(const std::string & name, double & value_out) { return get_template(name, value_out, rclcpp::PARAMETER_DOUBLE); } bool get(const std::string & name, std::string & value_out) { return get_template(name, value_out, rclcpp::PARAMETER_STRING); } bool get(const std::string & name, bool & value_out) { return get_template(name, value_out, rclcpp::PARAMETER_BOOL); } bool get(const std::string & name, std::vector & value_out) { return get_template(name, value_out, rclcpp::PARAMETER_DOUBLE_ARRAY); } bool get(const std::string & name, std::vector & value_out) { return get_template>(name, value_out, rclcpp::PARAMETER_STRING_ARRAY); } private: std::string param_prefix_; rclcpp::node_interfaces::NodeParametersInterface::SharedPtr params_interface_; }; } // namespace grid_map #endif // GRID_MAP_CV__UTILITIES_HPP_