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,
85 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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,
115 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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,
144 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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" bool param(const std::string ¶m_name, T ¶m_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.
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...
::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...
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.
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 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).
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...