Go to the documentation of this file.
29 template <
typename NodeletType>
55 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
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 = {})
84 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
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 = {})
114 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
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 = {})
143 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
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 = {})
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 = {})
194 const ::ros::NodeHandle& node, const ::std::string& name,
195 const char* defaultValue, const ::std::string& unit =
"",
196 const ::cras::GetParamOptions<::std::string>& options = {})
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 = {})
239 const ::ros::NodeHandle& node, const ::std::string& name,
240 const char* defaultValue, const ::std::string& unit =
"",
241 const ::cras::GetParamOptions<::std::string>& options = {})
281 using NodeletType::getName;
286 #include "impl/param_helper.hpp"
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
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...
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,...
::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...
~NodeletParamHelper() override
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
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...
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,...
Bound param helper (allows omitting the param adapter in each getParam call).
::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 ...
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,...
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...
This file provides helper methods easing access to parameters passed to nodes, nodelets and filters.
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.
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...
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...
An adapter that allows getting ROS parameters from a node handle.
This mixin allows calling the getParam() helpers.
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
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,...
::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::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 ::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...
T param(const std::string ¶m_name, const T &default_val)
An adapter that allows getting ROS parameters from a node handle.
cras_cpp_common
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:04