parameters.h
Go to the documentation of this file.
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 #ifndef HECTOR_POSE_ESTIMATION_PARAMETERS_H
00030 #define HECTOR_POSE_ESTIMATION_PARAMETERS_H
00031 
00032 #include <list>
00033 #include <string>
00034 #include <boost/shared_ptr.hpp>
00035 #include <boost/function.hpp>
00036 #include <boost/type_traits.hpp>
00037 
00038 namespace hector_pose_estimation {
00039 
00040   class Parameter;
00041   template <typename T> class TypedParameter;
00042   typedef boost::shared_ptr<Parameter> ParameterPtr;
00043   typedef boost::shared_ptr<const Parameter> ParameterConstPtr;
00044   typedef boost::function<void(ParameterPtr)> ParameterRegisterFunc;
00045 
00046   class Parameter {
00047   public:
00048     std::string key;
00049     Parameter(const std::string& key) : key(key) {}
00050     virtual ParameterPtr clone() = 0;
00051     virtual const char *type() const = 0;
00052 
00053     template <typename T> bool hasType() const {
00054       return dynamic_cast<const TypedParameter<T> *>(this) != 0;
00055     }
00056 
00057     template <typename T> T& as() const {
00058       const TypedParameter<T>& p = dynamic_cast<const TypedParameter<T> &>(*this);
00059       return p.value;
00060     }
00061   };
00062 
00063   template <typename T>
00064   class TypedParameter : public Parameter {
00065   public:
00066     typedef typename boost::remove_reference<typename boost::remove_const<T>::type>::type param_type;
00067 
00068     param_type& value;
00069     TypedParameter(const std::string& key, param_type &value) : Parameter(key), value(value) {}
00070     TypedParameter(const Parameter& other) : Parameter(other), value(dynamic_cast<const TypedParameter<T> &>(other).value) {}
00071 
00072     ParameterPtr clone() { return ParameterPtr(new TypedParameter<T>(*this)); }
00073     const char *type() const { return typeid(param_type).name(); }
00074   };
00075 
00076   class ParameterList : public std::list<ParameterPtr> {
00077   public:
00078     using std::list<ParameterPtr>::iterator;
00079     using std::list<ParameterPtr>::const_iterator;
00080 
00081     ParameterList() {}
00082     ~ParameterList() {}
00083 
00084     template <typename T>
00085     ParameterList& add(const std::string& key, T& value, const T& default_value) {
00086       value = default_value;
00087       return add(key, value);
00088     }
00089 
00090     template <typename T>
00091     ParameterList& add(const std::string& key, T& value) {
00092       erase(key);
00093       push_back(ParameterPtr(new TypedParameter<T>(key, value)));
00094       return *this;
00095     }
00096 
00097     template <typename T>
00098     ParameterList& add(const std::string& key, T* value) {
00099       erase(key);
00100       push_back(ParameterPtr(new TypedParameter<T>(key, *value)));
00101       return *this;
00102     }
00103 
00104     ParameterList& add(ParameterList const& other) {
00105       for(ParameterList::const_iterator it = other.begin(); it != other.end(); ++it) push_back(*it);
00106       return *this;
00107     }
00108 
00109     ParameterList& copy(const std::string& prefix, ParameterList const& parameters) {
00110       for(ParameterList::const_iterator it = parameters.begin(); it != parameters.end(); ++it) {
00111         ParameterPtr copy((*it)->clone());
00112         if (!prefix.empty()) copy->key = prefix + "/" + copy->key;
00113         push_back(copy);
00114       }
00115       return *this;
00116     }
00117 
00118     ParameterList& copy(ParameterList const& parameters) {
00119       copy(std::string(), parameters);
00120       return *this;
00121     }
00122 
00123     template <typename T>
00124     T& get(const std::string& key) const {
00125       for(const_iterator it = begin(); it != end(); ++it) {
00126         if ((*it)->key == key) {
00127           return (*it)->as<T>();
00128         }
00129       }
00130       throw std::bad_cast();
00131     }
00132 
00133     using std::list<ParameterPtr>::erase;
00134     iterator erase(const std::string& key) {
00135       iterator it = begin();
00136       for(; it != end(); ++it) {
00137         if ((*it)->key == key) return erase(it);
00138       }
00139       return it;
00140     }
00141 
00142     void initialize(ParameterRegisterFunc func) const;
00143   };
00144 
00145   static inline ParameterList operator+(ParameterList const& list1, ParameterList const& list2)
00146   {
00147     ParameterList result;
00148     return result.add(list1).add(list2);
00149   }
00150 
00151   struct ParameterRegistry {
00152     virtual void operator()(ParameterPtr) {}
00153   };
00154 
00155 } // namespace hector_pose_estimation
00156 
00157 #endif // HECTOR_POSE_ESTIMATION_PARAMETERS_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Mon Jul 15 2013 16:48:43