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,
88 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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,
115 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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,
140 ::cras::check_get_param_types<ResultType, ParamServerType>* =
nullptr>
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 ::std::string getNamespace() const
Return the namespace this helper operates in.
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.
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...
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...
~BoundParamHelper() override=default
A C++11 shim for std::optional. Uses std::optional when used in C++17 mode.
Options for getParam() calls.
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, and print out a ROS log message with the loaded values (if specified).
::std::shared_ptr<::cras::GetParamAdapter > GetParamAdapterPtr
::cras::LogHelperPtr log
Log helper.
inline ::cras::BoundParamHelperPtr paramsInNamespace(const ::std::string &ns) const
Return a parameter helper of a sub-namespace.
This class provides a unified experience for nodes, nodelets and filters for getting ROS parameter va...
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 ::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, and print out a ROS log message with the loaded values (if specified).
Type const & getType() const
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
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...
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, and print out a ROS log message with the loaded values (if specified).
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...
Bound param helper (allows omitting the param adapter in each getParam call).
bool hasParam(const ::std::string &name, const bool searchNested=true) const
Whether a parameter with the given name exists.
Wrapper of getParam() call results.
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, and print out a ROS log message with the loaded values (if specified).
::std::vector<::std::string > split(const ::std::string &str, const ::std::string &delimiter, int maxSplits=-1)
Split the given string by the given delimiter.
An adapter that allows getting ROS parameters from various sources.
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...
BoundParamHelper(const ::cras::LogHelperPtr &log, const ::cras::GetParamAdapterPtr ¶m)
::cras::GetParamAdapterPtr param
The bound parameter adapter.
::cras::LogHelper::Ptr LogHelperPtr
Pointer to LogHelper.