node_utils.hpp
Go to the documentation of this file.
1 #pragma once
2 
13 #include <memory>
14 #include <string>
15 
16 #include <ros/ros.h>
17 
24 
25 namespace cras
26 {
27 
29 const ParamHelper paramHelper(::std::make_shared<::cras::NodeLogHelper>());
30 
49 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
52  const ::ros::NodeHandle& node, const ::std::string& name,
53  const ::cras::optional<ResultType>& defaultValue = ResultType(),
54  const ::std::string& unit = "",
55  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
56 {
57  const auto param = ::cras::NodeHandleGetParamAdapter(node);
58  return paramHelper.getParamVerbose(param, name, defaultValue, unit, options);
59 }
60 
78 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
81  const ::ros::NodeHandle& node, const ::std::string& name,
82  const ResultType& defaultValue = ResultType(),
83  const ::std::string& unit = "",
84  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
85 {
86  const auto param = ::cras::NodeHandleGetParamAdapter(node);
87  return paramHelper.getParamVerbose(param, name, defaultValue, unit, options);
88 }
89 
108 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
110 inline ResultType getParam(
111  const ::ros::NodeHandle& node, const ::std::string& name,
112  const ::cras::optional<ResultType>& defaultValue = ResultType(),
113  const ::std::string& unit = "",
114  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
115 {
116  const auto param = ::cras::NodeHandleGetParamAdapter(node);
117  return paramHelper.getParam(param, name, defaultValue, unit, options);
118 }
119 
137 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
139 inline ResultType getParam(
140  const ::ros::NodeHandle& node, const ::std::string& name,
141  const ResultType& defaultValue = ResultType(),
142  const ::std::string& unit = "",
143  const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
144 {
145  const auto param = ::cras::NodeHandleGetParamAdapter(node);
146  return paramHelper.getParam(param, name, defaultValue, unit, options);
147 }
148 
149 // std::string - char interop specializations
150 
166  const ::ros::NodeHandle& node, const ::std::string& name,
167  const ::cras::optional<const char*>& defaultValue, const ::std::string& unit = "",
168  const ::cras::GetParamOptions<::std::string>& options = {})
169 {
170  const auto param = ::cras::NodeHandleGetParamAdapter(node);
171  return paramHelper.getParamVerbose(param, name, defaultValue, unit, options);
172 }
173 
188  const ::ros::NodeHandle& node, const ::std::string& name,
189  const char* defaultValue, const ::std::string& unit = "",
190  const ::cras::GetParamOptions<::std::string>& options = {})
191 {
192  const auto param = ::cras::NodeHandleGetParamAdapter(node);
193  return paramHelper.getParamVerbose(param, name, defaultValue, unit, options);
194 }
195 
210 inline ::std::string getParam(
211  const ::ros::NodeHandle& node, const ::std::string& name,
212  const ::cras::optional<const char*>& defaultValue, const ::std::string& unit = "",
213  const ::cras::GetParamOptions<::std::string>& options = {})
214 {
215  const auto param = ::cras::NodeHandleGetParamAdapter(node);
216  return paramHelper.getParam(param, name, defaultValue, unit, options);
217 }
218 
232 inline ::std::string getParam(
233  const ::ros::NodeHandle& node, const ::std::string& name,
234  const char* defaultValue, const ::std::string& unit = "",
235  const ::cras::GetParamOptions<std::string>& options = {})
236 {
237  const auto param = ::cras::NodeHandleGetParamAdapter(node);
238  return paramHelper.getParam(param, name, defaultValue, unit, options);
239 }
240 
248 inline ::cras::BoundParamHelperPtr nodeParams(const ::ros::NodeHandle& node, const ::std::string& ns = "")
249 {
250  const auto log = ::std::make_shared<NodeLogHelper>();
251  const auto param = ::std::make_shared<NodeHandleGetParamAdapter>(node);
252  auto result = ::std::make_shared<BoundParamHelper>(log, param);
253  if (!ns.empty())
254  result = result->paramsInNamespace(ns);
255  return result;
256 }
257 
265 {
267 }
268 
269 }
cras::paramHelper
const ParamHelper paramHelper(::std::make_shared<::cras::NodeLogHelper >())
cras
Definition: any.hpp:15
cras::GetParamResult
Wrapper for the result of a getParam() call. It is designed to autoconvert to the result type sometim...
Definition: get_param_result.hpp:45
ros.h
cras::BoundParamHelperPtr
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
Definition: bound_param_helper.hpp:24
cras::ParamHelper::getParam
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...
Definition: param_utils/param_helper.hpp:122
bound_param_helper.hpp
Bound param helper (allows omitting the param adapter in each getParam call).
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.h
Log helper redirecting the logging calls to ROS_ macros.
node_handle.hpp
An adapter that allows getting ROS parameters from a node handle.
param_helper.hpp
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
cras::ParamHelper::getParamVerbose
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...
Definition: param_utils/param_helper.hpp:65
cras::nodeParams
inline ::cras::BoundParamHelperPtr nodeParams(const ::ros::NodeHandle &node, const ::std::string &ns="")
Returns a param helper structure "bound" to the given node handle, so that it is not needed to specif...
Definition: node_utils.hpp:248
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
node_handle.h
Utils for getting node handle parameters, topic diagnostics etc.
cras::paramsForNodeHandle
inline ::cras::BoundParamHelperPtr paramsForNodeHandle(const ::ros::NodeHandle &node)
Returns a param helper structure "bound" to the given node handle, so that it is not needed to specif...
Definition: node_utils.hpp:264
optional.hpp
A C++11 shim for std::optional. Uses std::optional when used in C++17 mode.


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14