Registrar.h
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2012,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014     * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016     * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00033 
00034 */
00035 
00036 #ifndef __POINTMATCHER_REGISTRAR_H
00037 #define __POINTMATCHER_REGISTRAR_H
00038 
00039 #include "Parametrizable.h"
00040 #include "PointMatcher.h"
00041 #include <boost/format.hpp>
00042 #include <boost/typeof/typeof.hpp>
00043 
00044 
00045 #ifdef SYSTEM_YAML_CPP
00046         namespace YAML
00047         {
00048                 class Node;
00049         }
00050 #else
00051         namespace YAML_PM
00052         {
00053                 class Node;
00054         }
00055 #endif // HAVE_YAML_CPP
00056 
00057 namespace PointMatcherSupport
00058 {
00059 #ifdef SYSTEM_YAML_CPP
00060         namespace YAML = ::YAML;
00061 #else
00062         namespace YAML = ::YAML_PM;
00063 #endif
00064 
00066         void getNameParamsFromYAML(const YAML::Node& module, std::string& name, Parametrizable::Parameters& params);
00067 
00069         struct InvalidElement: std::runtime_error
00070         {
00071                 InvalidElement(const std::string& reason);
00072         };
00073         
00075         template<typename Interface>
00076         struct Registrar
00077         {
00078         public:
00079                 typedef Interface TargetType; 
00080                 
00082                 struct ClassDescriptor
00083                 {
00085                         virtual ~ClassDescriptor() {}
00087                         virtual std::shared_ptr<Interface> createInstance(const std::string& className, const Parametrizable::Parameters& params) const = 0;
00089                         virtual const std::string description() const = 0;
00091                         virtual const Parametrizable::ParametersDoc availableParameters() const = 0;
00092                 };
00093                 
00095                 template<typename C>
00096                 struct GenericClassDescriptor: public ClassDescriptor
00097                 {
00098                         virtual std::shared_ptr<Interface> createInstance(const std::string& className, const Parametrizable::Parameters& params) const
00099                         {
00100                                 std::shared_ptr<C> instance = std::make_shared<C>(params);
00101                                 
00102                                 // check that all parameters were set
00103                                 for (BOOST_AUTO(it, params.begin()); it != params.end() ;++it)
00104                                 {
00105                                         if (instance->parametersUsed.find(it->first) == instance->parametersUsed.end()){
00106                                                 throw Parametrizable::InvalidParameter(
00107                                                         (boost::format("Parameter %1% for module %2% was set but is not used") % it->first % className).str()
00108                                                 );
00109                                         }
00110                                 }
00111                                 
00112                                 return instance;
00113                         }
00114                         virtual const std::string description() const
00115                         {
00116                                 return C::description();
00117                         }
00118                         virtual const Parametrizable::ParametersDoc availableParameters() const
00119                         {
00120                                 return C::availableParameters();
00121                         }
00122                 };
00123                 
00125                 template<typename C>
00126                 struct GenericClassDescriptorNoParam: public ClassDescriptor
00127                 {
00128                         virtual std::shared_ptr<Interface> createInstance(const std::string& className, const Parametrizable::Parameters& params) const
00129                         {
00130                                 for (BOOST_AUTO(it, params.begin()); it != params.end() ;++it)
00131                                         throw Parametrizable::InvalidParameter(
00132                                                         (boost::format("Parameter %1% was set but module %2% dos not use any parameter") % it->first % className).str()
00133                                                 );
00134                                 return std::make_shared<C>();
00135                         }
00136                         virtual const std::string description() const
00137                         {
00138                                 return C::description();
00139                         }
00140                         virtual const Parametrizable::ParametersDoc availableParameters() const
00141                         {
00142                                 return Parametrizable::ParametersDoc();
00143                         }
00144                 };
00145                 
00146         protected:
00147                 typedef std::map<std::string, ClassDescriptor*> DescriptorMap; 
00148                 DescriptorMap classes; 
00149                 
00150         public:
00152                 ~Registrar()
00153                 {
00154                         for (BOOST_AUTO(it, classes.begin()); it != classes.end(); ++it)
00155                                 delete it->second;
00156                 }
00158                 void reg(const std::string &name, ClassDescriptor* descriptor)
00159                 {
00160                         classes[name] = descriptor;
00161                 }
00162                 
00164                 const ClassDescriptor* getDescriptor(const std::string& name) const
00165                 {
00166                         BOOST_AUTO(it, classes.find(name));
00167                         if (it == classes.end())
00168                         {
00169                                 std::cerr << "No element named " << name << " is registered. Known ones are:\n";
00170                                 dump(std::cerr);
00171                                 throw InvalidElement(
00172                                         (boost::format("Trying to instanciate unknown element %1% from registrar") % name).str()
00173                                 );
00174                         }
00175                         return it->second;
00176                 }
00177                 
00179                 std::shared_ptr<Interface> create(const std::string& name, const Parametrizable::Parameters& params = Parametrizable::Parameters()) const
00180                 {
00181                         return getDescriptor(name)->createInstance(name, params);
00182                 }
00183                                 
00185                 std::shared_ptr<Interface> createFromYAML(const YAML::Node& module) const
00186                 {
00187                         std::string name;
00188                         Parametrizable::Parameters params;
00189 
00190                         getNameParamsFromYAML(module, name, params);
00191                         
00192                         return create(name, params);
00193                 }
00194                                 
00196                 const std::string getDescription(const std::string& name) const
00197                 {
00198                         return getDescriptor(name)->description();
00199                 }
00200                 
00202                 void dump(std::ostream &stream) const
00203                 {
00204                         for (BOOST_AUTO(it, classes.begin()); it != classes.end(); ++it)
00205                                 stream << "- " << it->first << "\n";
00206                 }
00207                 
00209                 typename DescriptorMap::const_iterator begin() const
00210                 {       
00211                         return classes.begin();
00212                 }
00214                 typename DescriptorMap::const_iterator end() const
00215                 {
00216                         return classes.end();
00217                 }
00218         };
00219 
00220         #define REG(name) name##Registrar
00221         #define DEF_REGISTRAR(name) PointMatcherSupport::Registrar< name > name##Registrar;
00222         #define DEF_REGISTRAR_IFACE(name, ifaceName) PointMatcherSupport::Registrar< ifaceName > name##Registrar;
00223         #define ADD_TO_REGISTRAR(name, elementName, element) { \
00224                 typedef typename PointMatcherSupport::Registrar< name >::template GenericClassDescriptor< element > Desc; \
00225                 name##Registrar.reg(# elementName, new Desc() ); \
00226         }
00227         #define ADD_TO_REGISTRAR_NO_PARAM(name, elementName, element) { \
00228                 typedef typename PointMatcherSupport::Registrar< name >::template GenericClassDescriptorNoParam< element > Desc; \
00229                 name##Registrar.reg(# elementName, new Desc() ); \
00230         }
00231 } // namespace PointMatcherSupport
00232 
00233 #endif // __POINTMATCHER_REGISTRAR_H


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:32