$search
00001 //================================================================================================= 00002 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #include <hector_pose_estimation/parameters.h> 00030 #include <ros/node_handle.h> 00031 00032 #include <boost/algorithm/string.hpp> 00033 00034 namespace hector_pose_estimation { 00035 00036 template <typename T> 00037 class RegisterParameterImpl { 00038 public: 00039 static bool registerParam(ParameterPtr& parameter, ros::NodeHandle nh) { 00040 try { 00041 TypedParameter<T> p(*parameter); 00042 std::string param_key(boost::algorithm::to_lower_copy(parameter->key)); 00043 if (!nh.getParam(param_key, p.value)) { 00044 nh.setParam(param_key, p.value); 00045 ROS_DEBUG_STREAM("Registered parameter " << param_key << " with new value " << p.value); 00046 } else { 00047 ROS_DEBUG_STREAM("Found parameter " << param_key << " with value " << p.value); 00048 } 00049 return true; 00050 } catch(std::bad_cast&) { 00051 return false; 00052 } 00053 } 00054 }; 00055 00056 static void registerParamRos(ParameterPtr& parameter, ros::NodeHandle nh) { 00057 if (RegisterParameterImpl<std::string>::registerParam(parameter, nh)) return; 00058 if (RegisterParameterImpl<double>::registerParam(parameter, nh)) return; 00059 if (RegisterParameterImpl<int>::registerParam(parameter, nh)) return; 00060 if (RegisterParameterImpl<bool>::registerParam(parameter, nh)) return; 00061 ROS_ERROR("Could not register parameter %s due to unknown type %s!", parameter->key.c_str(), parameter->type()); 00062 } 00063 00064 void ParameterList::registerParamsRos(ros::NodeHandle nh) const { 00065 registerParams(boost::bind(®isterParamRos, _1, nh)); 00066 } 00067 00068 void ParameterList::registerParams(const ParameterRegisterFunc& func) const { 00069 for(const_iterator it = begin(); it != end(); ++it) func(*it); 00070 } 00071 00072 } // namespace hector_pose_estimation