parameters.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV_2D_UTILS_PARAMETERS_H
36 #define NAV_2D_UTILS_PARAMETERS_H
37 
38 #include <ros/ros.h>
39 #include <string>
40 
41 namespace nav_2d_utils
42 {
43 
55 template<class param_t>
56 param_t searchAndGetParam(const ros::NodeHandle& nh, const std::string& param_name, const param_t& default_value)
57 {
58  std::string resolved_name;
59  if (nh.searchParam(param_name, resolved_name))
60  {
61  param_t value = default_value;
62  nh.param(resolved_name, value, default_value);
63  return value;
64  }
65  return default_value;
66 }
67 
76 template<class param_t>
77 param_t loadParameterWithDeprecation(const ros::NodeHandle& nh, const std::string current_name,
78  const std::string old_name, const param_t& default_value)
79 {
80  param_t value;
81  if (nh.hasParam(current_name))
82  {
83  nh.getParam(current_name, value);
84  return value;
85  }
86  if (nh.hasParam(old_name))
87  {
88  ROS_WARN("Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str());
89  nh.getParam(old_name, value);
90  return value;
91  }
92  return default_value;
93 }
94 
101 template<class param_t>
102 void moveDeprecatedParameter(const ros::NodeHandle& nh, const std::string current_name, const std::string old_name)
103 {
104  if (!nh.hasParam(old_name)) return;
105 
106  param_t value;
107  ROS_WARN("Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str());
108  nh.getParam(old_name, value);
109  nh.setParam(current_name, value);
110 }
111 
125 template<class param_t>
126 void moveParameter(const ros::NodeHandle& nh, std::string old_name,
127  std::string current_name, param_t default_value, bool should_delete = true)
128 {
129  if (nh.hasParam(current_name))
130  {
131  if (should_delete)
132  nh.deleteParam(old_name);
133  return;
134  }
135  XmlRpc::XmlRpcValue value;
136  if (nh.hasParam(old_name))
137  {
138  nh.getParam(old_name, value);
139  if (should_delete) nh.deleteParam(old_name);
140  }
141  else
142  value = default_value;
143 
144  nh.setParam(current_name, value);
145 }
146 
147 
148 } // namespace nav_2d_utils
149 
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.
Definition: parameters.h:102
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
bool deleteParam(const std::string &key) const
#define ROS_WARN(...)
param_t searchAndGetParam(const ros::NodeHandle &nh, const std::string &param_name, const param_t &default_value)
Search for a parameter and load it, or use the default value.
Definition: parameters.h:56
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string &param_name, T &param_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.
Definition: parameters.h:126
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.
Definition: parameters.h:77


nav_2d_utils
Author(s):
autogenerated on Sun Jan 10 2021 04:08:32