Go to the documentation of this file.
62 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
65 const ::std::string& name, const ::cras::optional<ResultType>& defaultValue = ResultType(),
66 const ::std::string& unit =
"", const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
const
87 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
90 const ::std::string& name,
const ResultType& defaultValue = ResultType(),
91 const ::std::string& unit =
"", const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
const
94 *this->
param, name, ::cras::optional<ResultType>(defaultValue), unit, options);
114 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
117 const ::std::string& name, const ::cras::optional<ResultType>& defaultValue = ResultType(),
118 const ::std::string& unit =
"", const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
const
139 template<typename ResultType, typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type,
142 const ::std::string& name,
const ResultType& defaultValue = ResultType(),
143 const ::std::string& unit =
"", const ::cras::GetParamOptions<ResultType, ParamServerType>& options = {})
const
164 const ::std::string& name, const ::cras::optional<const char *>& defaultValue, const ::std::string& unit =
"",
165 const ::cras::GetParamOptions<::std::string>& options = {})
const
183 const ::std::string& name,
const char* defaultValue, const ::std::string& unit =
"",
184 const ::cras::GetParamOptions<::std::string>& options = {})
const
203 const ::std::string& name, const ::cras::optional<const char *>& defaultValue, const ::std::string& unit =
"",
204 const ::cras::GetParamOptions<::std::string>& options = {})
const
222 const ::std::string& name,
const char* defaultValue, const ::std::string& unit =
"",
223 const ::cras::GetParamOptions<std::string>& options = {})
const
235 inline bool hasParam(const ::std::string& name,
const bool searchNested =
true)
const
237 if (this->
param->hasParam(name))
244 if (parts.size() == 1)
246 const auto& head = parts[0];
247 const auto& tail = parts[1];
248 if (!this->
param->hasParam(head))
251 this->
param->getParam(head, x);
264 return ::std::make_shared<::cras::BoundParamHelper>(this->
log, this->
param->getNamespaced(ns));
273 return this->
param->getNamespace();
276 using ::cras::ParamHelper::getLogger;
inline ::cras::GetParamResult< ResultType > getParamVerbose(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...
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
ResultType getParam(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...
inline ::cras::GetParamResult< std::string > getParamVerbose(const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
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).
An adapter that allows getting ROS parameters from various sources.
inline ::cras::GetParamResult< ResultType > getParamVerbose(const ::std::string &name, const 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,...
~BoundParamHelper() override=default
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...
inline ::cras::GetParamResult<::std::string > getParamVerbose(const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
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...
::std::shared_ptr<::cras::GetParamAdapter > GetParamAdapterPtr
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
::std::vector<::std::string > split(const ::std::string &str, const ::std::string &delimiter, int maxSplits=-1)
Split the given string by the given delimiter.
Wrapper of getParam() call results.
::cras::GetParamAdapterPtr param
The bound parameter adapter.
const Type & getType() const
ResultType getParam(const ::std::string &name, const 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,...
BoundParamHelper(const ::cras::LogHelperPtr &log, const ::cras::GetParamAdapterPtr ¶m)
inline ::std::string getParam(const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions< std::string > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value,...
Options for getParam() calls.
::cras::LogHelper::Ptr LogHelperPtr
Pointer to LogHelper.
::cras::LogHelperPtr log
Log helper.
bool hasParam(const ::std::string &name, const bool searchNested=true) const
Whether a parameter with the given name exists.
inline ::std::string getParam(const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt...
inline ::std::string getNamespace() const
Return the namespace this helper operates in.
inline ::cras::BoundParamHelperPtr paramsInNamespace(const ::std::string &ns) const
Return a parameter helper of a sub-namespace.
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 Tue Nov 26 2024 03:49:03