optimization_algorithm_factory.h
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #ifndef G2O_OPTMIZATION_ALGORITHM_PROPERTY_H
28 #define G2O_OPTMIZATION_ALGORITHM_PROPERTY_H
29 
30 #include "../../config.h"
31 #include "../stuff/misc.h"
33 
34 #include <list>
35 #include <iostream>
36 #include <typeinfo>
37 
38 
39 // define to get some verbose output
40 //#define G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY
41 
42 namespace g2o {
43 
44  // forward decl
45  class OptimizationAlgorithm;
46  class SparseOptimizer;
47 
55  {
56  public:
60  virtual OptimizationAlgorithm* construct() = 0;
63  protected:
65  };
66 
75  {
76  public:
77  typedef std::list<AbstractOptimizationAlgorithmCreator*> CreatorList;
78 
80  static OptimizationAlgorithmFactory* instance();
81 
83  static void destroy();
84 
88  void registerSolver(AbstractOptimizationAlgorithmCreator* c);
89 
93  void unregisterSolver(AbstractOptimizationAlgorithmCreator* c);
94 
98  OptimizationAlgorithm* construct(const std::string& tag, OptimizationAlgorithmProperty& solverProperty) const;
99 
101  void listSolvers(std::ostream& os) const;
102 
104  const CreatorList& creatorList() const { return _creator;}
105 
106  protected:
109 
110  CreatorList _creator;
111 
112  CreatorList::const_iterator findSolver(const std::string& name) const;
113  CreatorList::iterator findSolver(const std::string& name);
114 
115  private:
117  };
118 
120  {
121  public:
123  {
124  _creator = c;
125 #ifdef G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY
126  std::cout << __FUNCTION__ << ": Registering " << _creator->property().name << " of type " << typeid(*_creator).name() << std::endl;
127 #endif
129  }
130 
132  {
133 #ifdef G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY
134  std::cout << __FUNCTION__ << ": Unregistering " << _creator->property().name << std::endl;
135 #endif
137  }
138  private:
140  };
141 
142 }
143 
144 #if defined _MSC_VER && defined G2O_SHARED_LIBS
145 # define G2O_OAF_EXPORT __declspec(dllexport)
146 # define G2O_OAF_IMPORT __declspec(dllimport)
147 #else
148 # define G2O_OAF_EXPORT
149 # define G2O_OAF_IMPORT
150 #endif
151 
152 #define G2O_REGISTER_OPTIMIZATION_LIBRARY(libraryname) \
153  extern "C" void G2O_OAF_EXPORT g2o_optimization_library_##libraryname(void) {}
154 
155 #define G2O_USE_OPTIMIZATION_LIBRARY(libraryname) \
156  extern "C" void G2O_OAF_IMPORT g2o_optimization_library_##libraryname(void); \
157  static g2o::ForceLinker g2o_force_optimization_algorithm_library_##libraryname(g2o_optimization_library_##libraryname);
158 
159 #define G2O_REGISTER_OPTIMIZATION_ALGORITHM(optimizername, instance) \
160  extern "C" void G2O_OAF_EXPORT g2o_optimization_algorithm_##optimizername(void) {} \
161  static g2o::RegisterOptimizationAlgorithmProxy g_optimization_algorithm_proxy_##optimizername(instance);
162 
163 #define G2O_USE_OPTIMIZATION_ALGORITHM(optimizername) \
164  extern "C" void G2O_OAF_IMPORT g2o_optimization_algorithm_##optimizername(void); \
165  static g2o::ForceLinker g2o_force_optimization_algorithm_link_##optimizername(g2o_optimization_algorithm_##optimizername);
166 
167 #endif
std::string name
name of the solver, e.g., var
describe the properties of a solver
const OptimizationAlgorithmProperty & property() const
return the properties of the solver
static OptimizationAlgorithmFactory * factoryInstance
create solvers based on their short name
const CreatorList & creatorList() const
return the underlying list of creators
base for allocating an optimization algorithm
RegisterOptimizationAlgorithmProxy(AbstractOptimizationAlgorithmCreator *c)
void registerSolver(AbstractOptimizationAlgorithmCreator *c)
static OptimizationAlgorithmFactory * instance()
return the instance
AbstractOptimizationAlgorithmCreator * _creator
virtual OptimizationAlgorithm * construct()=0
allocate a solver operating on optimizer, re-implement for your creator
void unregisterSolver(AbstractOptimizationAlgorithmCreator *c)
std::list< AbstractOptimizationAlgorithmCreator * > CreatorList
AbstractOptimizationAlgorithmCreator(const OptimizationAlgorithmProperty &p)
Generic interface for a non-linear solver operating on a graph.


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05