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,
85  ::cras::check_get_param_types<ResultType, ParamServerType>* = nullptr>
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,
115  ::cras::check_get_param_types<ResultType, ParamServerType>* = nullptr>
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,
144  ::cras::check_get_param_types<ResultType, ParamServerType>* = nullptr>
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"
bool param(const std::string &param_name, T &param_val, const T &default_val)
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...
::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...
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
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::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 ...
An adapter that allows getting ROS parameters from a node handle.
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...
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
options
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, and print out a ROS log message with the loaded values (if specified).
An adapter that allows getting ROS parameters from a node handle.
Definition: node_handle.hpp:25
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
This mixin allows calling the getParam() helpers.
~NodeletParamHelper() override
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...
This file provides helper methods easing access to parameters passed to nodes, nodelets and filters...
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, and print out a ROS log message with the loaded values (if specified).
Definition: any.hpp:15
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, and print out a ROS log message with the loaded values (if specified).
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, and print out a ROS log message with the loaded values (if specified).
::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 ...
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...
Bound param helper (allows omitting the param adapter in each getParam call).
::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_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:32:53