nodelet_utils/param_helper.hpp
Go to the documentation of this file.
1 #pragma once
2 
11 #include <functional>
12 #include <memory>
13 #include <string>
14 
15 #include <ros/ros.h>
16 
21 
22 namespace cras
23 {
24 
29 template <typename NodeletType>
30 class NodeletParamHelper : public virtual NodeletType, public ::cras::ParamHelper
31 {
32 public:
34  ~NodeletParamHelper() override;
35 
36 protected:
55  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
57  inline ::cras::GetParamResult<ResultType> getParamVerbose(
58  const ::ros::NodeHandle& node, const ::std::string& name,
59  const ::cras::optional<ResultType>& defaultValue = ResultType(),
60  const ::std::string& unit = "",
61  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
62  {
63  const auto param = ::cras::NodeHandleGetParamAdapter(node);
64  return ::cras::ParamHelper::getParamVerbose(param, name, defaultValue, unit, options);
65  }
66 
84  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
86  inline ::cras::GetParamResult<ResultType> getParamVerbose(
87  const ::ros::NodeHandle& node, const ::std::string& name,
88  const ResultType& defaultValue = ResultType(),
89  const ::std::string& unit = "",
90  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
91  {
92  const auto param = ::cras::NodeHandleGetParamAdapter(node);
93  return ::cras::ParamHelper::getParamVerbose(param, name, defaultValue, unit, options);
94  }
95 
114  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
116  inline ResultType getParam(
117  const ::ros::NodeHandle& node, const ::std::string& name,
118  const ::cras::optional<ResultType>& defaultValue = ResultType(),
119  const ::std::string& unit = "",
120  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
121  {
122  const auto param = ::cras::NodeHandleGetParamAdapter(node);
123  return ::cras::ParamHelper::getParam(param, name, defaultValue, unit, options);
124  }
125 
143  template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
145  inline ResultType getParam(
146  const ::ros::NodeHandle& node, const ::std::string& name,
147  const ResultType& defaultValue = ResultType(),
148  const ::std::string& unit = "",
149  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
150  {
151  const auto param = ::cras::NodeHandleGetParamAdapter(node);
152  return ::cras::ParamHelper::getParam(param, name, defaultValue, unit, options);
153  }
154 
155  // std::string - char interop specializations
156 
171  inline ::cras::GetParamResult<::std::string> getParamVerbose(
172  const ::ros::NodeHandle& node, const ::std::string& name,
173  const ::cras::optional<const char*>& defaultValue, const ::std::string& unit = "",
174  const ::cras::GetParamOptions<::std::string>& options = {})
175  {
176  const auto param = ::cras::NodeHandleGetParamAdapter(node);
177  return ::cras::ParamHelper::getParamVerbose(param, name, defaultValue, unit, options);
178  }
179 
193  inline ::cras::GetParamResult<::std::string> getParamVerbose(
194  const ::ros::NodeHandle& node, const ::std::string& name,
195  const char* defaultValue, const ::std::string& unit = "",
196  const ::cras::GetParamOptions<::std::string>& options = {})
197  {
198  const auto param = ::cras::NodeHandleGetParamAdapter(node);
199  return ::cras::ParamHelper::getParamVerbose(param, name, defaultValue, unit, options);
200  }
201 
216  inline ::std::string getParam(
217  const ::ros::NodeHandle& node, const ::std::string& name,
218  const ::cras::optional<const char*>& defaultValue, const ::std::string& unit = "",
219  const ::cras::GetParamOptions<::std::string>& options = {})
220  {
221  const auto param = ::cras::NodeHandleGetParamAdapter(node);
222  return ::cras::ParamHelper::getParam(param, name, defaultValue, unit, options);
223  }
224 
238  inline ::std::string getParam(
239  const ::ros::NodeHandle& node, const ::std::string& name,
240  const char* defaultValue, const ::std::string& unit = "",
241  const ::cras::GetParamOptions<::std::string>& options = {})
242  {
243  const auto param = ::cras::NodeHandleGetParamAdapter(node);
244  return ::cras::ParamHelper::getParam(param, name, defaultValue, unit, options);
245  }
246 
254  ::cras::BoundParamHelperPtr params(const ::ros::NodeHandle& node, const ::std::string& ns = "") const;
255 
262  ::cras::BoundParamHelperPtr privateParams(const ::std::string& ns = "") const;
263 
270  ::cras::BoundParamHelperPtr publicParams(const ::std::string& ns = "") const;
271 
278  ::cras::BoundParamHelperPtr paramsForNodeHandle(const ::ros::NodeHandle& node) const;
279 
280 protected:
281  using NodeletType::getName;
282 };
283 
284 }
285 
286 #include "impl/param_helper.hpp"
cras::ParamHelper
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
Definition: param_utils/param_helper.hpp:31
cras::NodeletParamHelper::getParamVerbose
inline ::cras::GetParamResult<::std::string > getParamVerbose(const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
Definition: nodelet_utils/param_helper.hpp:171
cras
Definition: any.hpp:15
cras::NodeletParamHelper::getParamVerbose
inline ::cras::GetParamResult< ResultType > getParamVerbose(const ::ros::NodeHandle &node, const ::std::string &name, const 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,...
Definition: nodelet_utils/param_helper.hpp:86
cras::NodeletParamHelper::privateParams
::cras::BoundParamHelperPtr privateParams(const ::std::string &ns="") const
Creates a version of this param helper "bound" to the private nodelet parameters, so that it is not n...
cras::NodeletParamHelper::~NodeletParamHelper
~NodeletParamHelper() override
ros.h
cras::BoundParamHelperPtr
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
Definition: bound_param_helper.hpp:24
cras::NodeletParamHelper::getParamVerbose
inline ::cras::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: nodelet_utils/param_helper.hpp:57
cras::NodeletParamHelper::getParam
inline ::std::string getParam(const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
Get the value of the given ROS parameter, falling back to the specified default value,...
Definition: nodelet_utils/param_helper.hpp:238
bound_param_helper.hpp
Bound param helper (allows omitting the param adapter in each getParam call).
cras::NodeletParamHelper::paramsForNodeHandle
::cras::BoundParamHelperPtr paramsForNodeHandle(const ::ros::NodeHandle &node) const
Creates a version of this param helper "bound" to the given node handle, so that it is not needed to ...
cras::NodeletParamHelper::getParamVerbose
inline ::cras::GetParamResult<::std::string > getParamVerbose(const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
Get the value of the given ROS parameter, falling back to the specified default value,...
Definition: nodelet_utils/param_helper.hpp:193
cras::NodeletParamHelper::getParam
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: nodelet_utils/param_helper.hpp:116
param_utils.hpp
This file provides helper methods easing access to parameters passed to nodes, nodelets and filters.
cras::check_get_param_types
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
cras::getParamVerbose
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
cras::getParam
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
node_handle.hpp
An adapter that allows getting ROS parameters from a node handle.
cras::NodeletParamHelper
This mixin allows calling the getParam() helpers.
Definition: nodelet_utils/param_helper.hpp:30
param_helper.hpp
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
cras::NodeletParamHelper::getParam
ResultType getParam(const ::ros::NodeHandle &node, const ::std::string &name, const 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,...
Definition: nodelet_utils/param_helper.hpp:145
cras::NodeletParamHelper::publicParams
::cras::BoundParamHelperPtr publicParams(const ::std::string &ns="") const
Creates a version of this param helper "bound" to the public nodelet parameters, so that it is not ne...
cras::NodeletParamHelper::NodeletParamHelper
NodeletParamHelper()
cras::NodeletParamHelper::params
::cras::BoundParamHelperPtr params(const ::ros::NodeHandle &node, const ::std::string &ns="") const
Creates a version of this param helper "bound" to the given node handle, so that it is not needed to ...
cras::NodeletParamHelper::getParam
inline ::std::string getParam(const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
Definition: nodelet_utils/param_helper.hpp:216
param
T param(const std::string &param_name, const T &default_val)
cras::NodeHandleGetParamAdapter
An adapter that allows getting ROS parameters from a node handle.
Definition: node_handle.hpp:25


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Mon Jun 17 2024 02:48:57