parameters.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #ifndef NAV_2D_UTILS_PARAMETERS_H
00036 #define NAV_2D_UTILS_PARAMETERS_H
00037 
00038 #include <ros/ros.h>
00039 #include <string>
00040 
00041 namespace nav_2d_utils
00042 {
00043 
00055 template<class param_t>
00056 param_t searchAndGetParam(const ros::NodeHandle& nh, const std::string& param_name, const param_t& default_value)
00057 {
00058   std::string resolved_name;
00059   if (nh.searchParam(param_name, resolved_name))
00060   {
00061     param_t value = default_value;
00062     nh.param(resolved_name, value, default_value);
00063     return value;
00064   }
00065   return default_value;
00066 }
00067 
00076 template<class param_t>
00077 param_t loadParameterWithDeprecation(const ros::NodeHandle& nh, const std::string current_name,
00078                                      const std::string old_name, const param_t& default_value)
00079 {
00080   param_t value;
00081   if (nh.hasParam(current_name))
00082   {
00083     nh.getParam(current_name, value);
00084     return value;
00085   }
00086   if (nh.hasParam(old_name))
00087   {
00088     ROS_WARN("Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str());
00089     nh.getParam(old_name, value);
00090     return value;
00091   }
00092   return default_value;
00093 }
00094 
00101 template<class param_t>
00102 void moveDeprecatedParameter(const ros::NodeHandle& nh, const std::string current_name, const std::string old_name)
00103 {
00104   if (!nh.hasParam(old_name)) return;
00105 
00106   param_t value;
00107   ROS_WARN("Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str());
00108   nh.getParam(old_name, value);
00109   nh.setParam(current_name, value);
00110 }
00111 
00125 template<class param_t>
00126 void moveParameter(const ros::NodeHandle& nh, std::string old_name,
00127                    std::string current_name, param_t default_value, bool should_delete = true)
00128 {
00129   if (nh.hasParam(current_name))
00130   {
00131     if (should_delete)
00132       nh.deleteParam(old_name);
00133     return;
00134   }
00135   XmlRpc::XmlRpcValue value;
00136   if (nh.hasParam(old_name))
00137   {
00138     nh.getParam(old_name, value);
00139     if (should_delete) nh.deleteParam(old_name);
00140   }
00141   else
00142     value = default_value;
00143 
00144   nh.setParam(current_name, value);
00145 }
00146 
00147 
00148 }  // namespace nav_2d_utils
00149 
00150 #endif  // NAV_2D_UTILS_PARAMETERS_H


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:09:36