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 ParameterT;
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), parameter_(this) {}
00050     Parameter(Parameter& other) : key(other.key), parameter_(&other) {}
00051     virtual ~Parameter() {}
00052 
00053     virtual ParameterPtr clone() { return parameter_ ? parameter_->clone() : ParameterPtr(); }
00054     virtual const char *type() const { return parameter_ ? parameter_->type() : 0; }
00055 
00056     virtual bool empty() const { return !parameter_; }
00057     virtual bool isAlias() const { return false; }
00058 
00059     template <typename T> bool hasType() const {
00060       return dynamic_cast<const ParameterT<T> *>(parameter_) != 0;
00061     }
00062 
00063     template <typename T> const T& as() const {
00064       const ParameterT<T>& p = dynamic_cast<const ParameterT<T> &>(*parameter_);
00065       return p.value();
00066     }
00067 
00068     template <typename T> T& as() {
00069       ParameterT<T>& p = dynamic_cast<ParameterT<T> &>(*parameter_);
00070       return p.value();
00071     }
00072 
00073     operator void*() const { return reinterpret_cast<void *>(!empty()); }
00074 
00075     template <typename T> Parameter& operator =(const T& value) {
00076       ParameterT<T>& p = dynamic_cast<ParameterT<T>&>(*parameter_);
00077       p.set(value);
00078       return *this;
00079     }
00080 
00081   protected:
00082     Parameter *parameter_;
00083   };
00084 
00085   template <typename T>
00086   class ParameterT : public Parameter {
00087   public:
00088     typedef typename boost::remove_reference<typename boost::remove_const<T>::type>::type param_type;
00089 
00090     ParameterT(const std::string& key, param_type &value) : Parameter(key), value_(value) {}
00091     ParameterT(Parameter& other) : Parameter(other), value_(other.as<T>()) {}
00092     virtual ~ParameterT() {}
00093 
00094     ParameterPtr clone() { return ParameterPtr(new ParameterT<T>(*this)); }
00095     const char *type() const { return typeid(param_type).name(); }
00096 
00097     operator param_type&() const { return value_; }
00098     param_type& value() { return value_; }
00099     const param_type& value() const { return value_; }
00100     void set(const param_type& value) { value_ = value; }
00101 
00102   protected:
00103     param_type& value_;
00104   };
00105 
00106   class Alias : public Parameter {
00107   public:
00108     Alias() : Parameter(std::string()) { parameter_ = 0; }
00109     Alias(const ParameterPtr& other) : Parameter(other->key) { *this = parameter_; }
00110     Alias(const ParameterPtr& other, const std::string& key) : Parameter(key) { *this = parameter_; }
00111     virtual ~Alias() {}
00112 
00113     virtual bool isAlias() const { return true; }
00114 
00115     using Parameter::operator =;
00116     Alias& operator =(const ParameterPtr& other) {
00117       parameter_ = other.get();
00118       if (key.empty()) key = other->key;
00119       return *this;
00120     }
00121   };
00122 
00123   template <typename T>
00124   class AliasT : public Alias {
00125   public:
00126     typedef typename boost::remove_reference<typename boost::remove_const<T>::type>::type param_type;
00127 
00128     AliasT() {}
00129     AliasT(const ParameterPtr& other) : Alias(other) {}
00130     AliasT(const ParameterPtr& other, const std::string& key) : Alias(other, key) {}
00131     virtual ~AliasT() {}
00132 
00133     operator param_type&() const { return dynamic_cast<ParameterT<T> &>(*parameter_).value(); }
00134     param_type& value() { return dynamic_cast<ParameterT<T> &>(*parameter_).value(); }
00135     const param_type& value() const { return dynamic_cast<const ParameterT<T> &>(*parameter_).value(); }
00136     void set(const param_type& value) { dynamic_cast<ParameterT<T> &>(*parameter_).set(value); }
00137 
00138     using Alias::operator =;
00139   };
00140 
00141   class ParameterList : public std::list<ParameterPtr> {
00142   public:
00143     using std::list<ParameterPtr>::iterator;
00144     using std::list<ParameterPtr>::const_iterator;
00145 
00146     ~ParameterList() {}
00147 
00148     template <typename T> ParameterList& add(const std::string& key, T& value, const T& default_value) {
00149       value = default_value;
00150       return add(key, value);
00151     }
00152 
00153     template <typename T> ParameterList& add(const std::string& key, T* value) {
00154       return add(key, *value);
00155     }
00156 
00157     template <typename T> ParameterList& add(const std::string& key, T& value);
00158 
00159     ParameterList& add(ParameterPtr const& parameter);
00160     ParameterList& add(ParameterList const& other);
00161     ParameterList& add(Parameter& alias, const std::string& key = std::string());
00162     ParameterList& addAlias(const std::string& key, Alias& alias) { return add(alias, key); }
00163 
00164     ParameterList& copy(const std::string& prefix, ParameterList const& parameters);
00165     ParameterList& copy(ParameterList const& parameters);
00166 
00167     ParameterPtr const& get(const std::string& key) const;
00168     template <typename T> T& getAs(const std::string& key) const {
00169       return get(key)->as<T>();
00170     }
00171 
00172     using std::list<ParameterPtr>::erase;
00173     iterator erase(const std::string& key);
00174 
00175     void initialize(ParameterRegisterFunc func) const;
00176   };
00177 
00178   template <typename T> inline ParameterList& ParameterList::add(const std::string& key, T& value) {
00179     return add(ParameterPtr(new ParameterT<T>(key, value)));
00180   }
00181 
00182   static inline ParameterList operator+(ParameterList const& list1, ParameterList const& list2)
00183   {
00184     ParameterList result;
00185     return result.add(list1).add(list2);
00186   }
00187 
00188   struct ParameterRegistry {
00189     virtual void operator()(ParameterPtr) {}
00190   };
00191 
00192 } // namespace hector_pose_estimation
00193 
00194 #endif // HECTOR_POSE_ESTIMATION_PARAMETERS_H


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Fri Aug 28 2015 10:59:54