param_utils/param_helper.hpp
Go to the documentation of this file.
1 #pragma once
2 
11 #include <memory>
12 #include <string>
13 #include <utility>
14 
21 
22 namespace cras
23 {
24 
32 {
33 public:
39  virtual ~ParamHelper() = default;
40 
63  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
65  inline ::cras::GetParamResult<ResultType> getParamVerbose(
66  const ::cras::GetParamAdapter& param, const ::std::string& name,
67  const ::cras::optional<ResultType>& defaultValue = ResultType(),
68  const ::std::string& unit = "",
69  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {}) const
70  {
71  return ::cras::getParamVerbose(param, name, defaultValue, unit, options, this->log.get());
72  }
73 
91  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
92  ::cras::check_get_param_types<ResultType, ParamServerType>* = nullptr>
93  inline ::cras::GetParamResult<ResultType> getParamVerbose(
94  const ::cras::GetParamAdapter& param, const ::std::string& name,
95  const ResultType& defaultValue = ResultType(),
96  const ::std::string& unit = "",
97  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {}) const
98  {
99  return ::cras::getParamVerbose(param, name, defaultValue, unit, options, this->log.get());
100  }
101 
120  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
121  ::cras::check_get_param_types<ResultType, ParamServerType>* = nullptr>
122  inline ResultType getParam(
123  const ::cras::GetParamAdapter& param, const ::std::string& name,
124  const ::cras::optional<ResultType>& defaultValue = ResultType(),
125  const ::std::string& unit = "",
126  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {}) const
127  {
128  return ::cras::getParam(param, name, defaultValue, unit, options, this->log.get());
129  }
130 
148  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
149  ::cras::check_get_param_types<ResultType, ParamServerType>* = nullptr>
150  inline ResultType getParam(
151  const ::cras::GetParamAdapter& param, const ::std::string& name,
152  const ResultType& defaultValue = ResultType(),
153  const ::std::string& unit = "",
154  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {}) const
155  {
156  return ::cras::getParam(param, name, defaultValue, unit, options, this->log.get());
157  }
158 
159  // std::string - char interop specializations
160 
175  inline ::cras::GetParamResult<::std::string> getParamVerbose(
176  const ::cras::GetParamAdapter& param, const ::std::string& name,
177  const ::cras::optional<const char *>& defaultValue, const ::std::string& unit = "",
178  const ::cras::GetParamOptions<::std::string>& options = {}) const
179  {
180  return ::cras::getParamVerbose(param, name, defaultValue, unit, options, this->log.get());
181  }
182 
196  inline ::cras::GetParamResult<::std::string> getParamVerbose(
197  const ::cras::GetParamAdapter& param, const ::std::string &name,
198  const char* defaultValue, const ::std::string &unit = "",
199  const ::cras::GetParamOptions<::std::string>& options = {}) const
200  {
201  return ::cras::getParamVerbose(param, name, defaultValue, unit, options, this->log.get());
202  }
203 
218  inline ::std::string getParam(
219  const ::cras::GetParamAdapter& param, const ::std::string &name,
220  const ::cras::optional<const char *>& defaultValue, const ::std::string &unit = "",
221  const ::cras::GetParamOptions<::std::string>& options = {}) const
222  {
223  return ::cras::getParam(param, name, defaultValue, unit, options, this->log.get());
224  }
225 
239  inline ::std::string getParam(
240  const ::cras::GetParamAdapter& param, const ::std::string &name,
241  const char* defaultValue, const ::std::string &unit = "",
242  const ::cras::GetParamOptions<::std::string>& options = {}) const
243  {
244  return ::cras::getParam(param, name, defaultValue, unit, options, this->log.get());
245  }
246 
252  {
253  return this->log;
254  }
255 
261  {
262  this->log = logger;
263  }
264 };
265 
266 typedef ::std::shared_ptr<::cras::ParamHelper> ParamHelperPtr;
267 
268 }
inline ::std::string getParam(const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).
inline ::cras::GetParamResult<::std::string > getParamVerbose(const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char *> &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
typename std::enable_if_t< !::cras::is_optional< ResultType >::value &&!::cras::is_c_string< ResultType >::value &&!::cras::is_c_string< ParamServerType >::value > check_get_param_types
This type is a TrueType if the combination of ResultType and ParamServerType is valid.
Definition: param_utils.hpp:67
inline ::cras::GetParamResult<::std::string > getParamVerbose(const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).
::cras::LogHelperPtr getLogger() const
Return the log helper used for logging.
GetParamResult< ResultType > getParamVerbose(const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
Definition: node_utils.hpp:51
A C++11 shim for std::optional. Uses std::optional when used in C++17 mode.
ParamHelper(const ::cras::LogHelperPtr &log)
Options for getParam() calls.
inline ::std::string getParam(const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char *> &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
ResultType getParam(const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
::cras::LogHelperPtr log
Log helper.
Definition: log_utils.h:252
ResultType getParam(const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
void setLogger(const ::cras::LogHelperPtr &logger)
Set the log helper used for logging.
inline ::cras::GetParamResult< ResultType > getParamVerbose(const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified).
inline ::cras::GetParamResult< ResultType > getParamVerbose(const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
options
ResultType getParam(const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
Definition: node_utils.hpp:110
::std::shared_ptr<::cras::ParamHelper > ParamHelperPtr
Wrapper of getParam() call results.
This file provides helper methods easing access to parameters passed to nodes, nodelets and filters...
Definition: any.hpp:15
virtual ~ParamHelper()=default
Convenience base class for providing this->log and getCrasLogger(). Just add it as a base to your cla...
Definition: log_utils.h:229
An adapter that allows getting ROS parameters from various sources.
ROS logging helpers.
::cras::LogHelper::Ptr LogHelperPtr
Pointer to LogHelper.
Definition: log_utils.h:202


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:32:53