29 const ParamHelper
paramHelper(::std::make_shared<::cras::NodeLogHelper>());
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 = {})
78 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
79 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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 = {})
108 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
109 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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 = {})
137 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
138 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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 = {})
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 = {})
188 const ::ros::NodeHandle& node, const ::std::string& name,
189 const char* defaultValue, const ::std::string& unit =
"",
190 const ::cras::GetParamOptions<::std::string>& options = {})
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 = {})
233 const ::ros::NodeHandle& node, const ::std::string& name,
234 const char* defaultValue, const ::std::string& unit =
"",
235 const ::cras::GetParamOptions<std::string>& options = {})
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);
254 result = result->paramsInNamespace(ns);
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...
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
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.
Log helper redirecting the logging calls to ROS_ macros.
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...
INLINE Rall1d< T, V, S > log(const Rall1d< T, V, S > &arg)
A C++11 shim for std::optional. Uses std::optional when used in C++17 mode.
const ParamHelper paramHelper(::std::make_shared<::cras::NodeLogHelper >())
ResultType getParam(const ::cras::GetParamAdapter ¶m, 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...
An adapter that allows getting ROS parameters from a node handle.
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
inline ::cras::GetParamResult< ResultType > getParamVerbose(const ::cras::GetParamAdapter ¶m, 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...
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
Utils for getting node handle parameters, topic diagnostics etc.
An adapter that allows getting ROS parameters from a node handle.
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...
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...
Bound param helper (allows omitting the param adapter in each getParam call).
Wrapper for the result of a getParam() call. It is designed to autoconvert to the result type sometim...