35 #ifndef NAV_2D_UTILS_PARAMETERS_H 36 #define NAV_2D_UTILS_PARAMETERS_H 55 template<
class param_t>
58 std::string resolved_name;
61 param_t value = default_value;
62 nh.
param(resolved_name, value, default_value);
76 template<
class param_t>
78 const std::string old_name,
const param_t& default_value)
88 ROS_WARN(
"Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str());
101 template<
class param_t>
107 ROS_WARN(
"Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str());
125 template<
class param_t>
127 std::string current_name, param_t default_value,
bool should_delete =
true)
142 value = default_value;
150 #endif // NAV_2D_UTILS_PARAMETERS_H void moveDeprecatedParameter(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name)
If a deprecated parameter exists, complain and move to its new location.
bool deleteParam(const std::string &key) const
param_t searchAndGetParam(const ros::NodeHandle &nh, const std::string ¶m_name, const param_t &default_value)
Search for a parameter and load it, or use the default value.
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void moveParameter(const ros::NodeHandle &nh, std::string old_name, std::string current_name, param_t default_value, bool should_delete=true)
Move a parameter from one place to another.
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
param_t loadParameterWithDeprecation(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name, const param_t &default_value)
Load a parameter from one of two namespaces. Complain if it uses the old name.