diff --git a/include/ccf/util/NodeUtil.h b/include/ccf/util/NodeUtil.h index 200d33ef873f8272393bdfd2271ff34a4ed5e699..845a8a3e72e8feb03e179c912d7f1d67192418e7 100644 --- a/include/ccf/util/NodeUtil.h +++ b/include/ccf/util/NodeUtil.h @@ -44,6 +44,34 @@ namespace CetiRosToolbox { return fallback; } + /// Gets a private parameter from the parameter server. If the parameter does not exist, the fallback is used. + /// If no fallback value is specified, an empty string is returned. + /// + /// If the parameter is \a not on the parameter server, a warning is issued at \c ROS_WARN. + /// + /// Usually, when using the method, the template parameter can be omitted if a fallback value is provided. This does + /// \a not work when providing \c const \c char* as fallback (i.e., string constants). In this case, the template + /// parameter must be provided: + /// \code{.cpp} + /// auto intValue1 = getParameter<int>(n, "foo"); // no fallback means no automatic matching + /// auto intValue2 = getParameter(n, "foo", 42); // the compiler matches T with int, this is okay + /// auto stringValue = getParameter<std::string>(n, "bar", "fourtytwo"); // const char* requires the std::string template parameter + /// \endcode + /// \tparam T a type supported by the parameter server. + /// The parameter server supports \c std::string double \c float \c int \c bool + /// and \c std::vector and \std::map of these types. + /// Additionally, also \c XmlRpc::XmlRpcValue is supported, though not as a vector or map. + /// \param key the name of the parameter + /// \param fallback the default value + /// \return the parameter (if it exists), otherwise the fallback value (if it exists), otherwise the default + /// instance of the respective object + /// \warning Currently, this is a header-only library, but this might change in the future + template<class T> + T getPrivateParameter(const std::string &key, T fallback = T()) { + ros::NodeHandle n("~"); // a private node handle + return getParameter(n, key, fallback); + } + /** @cond */ // the specializations are required to print the warning correctly template<> XmlRpc::XmlRpcValue getParameter(const ros::NodeHandle &n, const std::string &key, XmlRpc::XmlRpcValue fallback) {