solver.h
Go to the documentation of this file.
00001 // g2o - General Graph Optimization
00002 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
00003 // 
00004 // g2o is free software: you can redistribute it and/or modify
00005 // it under the terms of the GNU Lesser General Public License as published
00006 // by the Free Software Foundation, either version 3 of the License, or
00007 // (at your option) any later version.
00008 // 
00009 // g2o is distributed in the hope that it will be useful,
00010 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00011 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012 // GNU Lesser General Public License for more details.
00013 // 
00014 // You should have received a copy of the GNU Lesser General Public License
00015 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00016 
00017 #ifndef SOLVER_H
00018 #define SOLVER_H
00019 
00020 #include "hyper_graph.h"
00021 #include "batch_stats.h"
00022 #include "sparse_block_matrix.h"
00023 #include <cstddef>
00024 
00025 namespace g2o {
00026 
00027 
00028   struct SparseOptimizer;
00029 
00033   class Solver
00034   {
00035     public:
00036       explicit Solver(SparseOptimizer* optimizer);
00037       virtual ~Solver();
00038 
00039     public:
00043       virtual bool init(bool online = false) = 0;
00044 
00048       virtual bool buildStructure(bool zeroBlocks = false) = 0;
00052       virtual bool updateStructure(const std::vector<HyperGraph::Vertex*>& vset, const HyperGraph::EdgeSet& edges) = 0;
00056       virtual bool buildSystem() = 0;
00057 
00061       virtual bool solve() = 0;
00062 
00067       virtual bool computeMarginals() = 0;
00068 
00073       virtual bool computeMarginals(SparseBlockMatrix<MatrixXd>& spinv, const std::vector<std::pair<int, int> >& blockIndices) = 0;
00074 
00081       virtual bool setLambda(double lambda) = 0;
00082 
00084       double* x() { return _x;}
00085       const double* x() const { return _x;}
00087       double* b() { return _b;}
00088       const double* b() const { return _b;}
00089 
00091       size_t vectorSize() const { return _xSize;}
00092 
00094       SparseOptimizer* optimizer() const { return _optimizer;}
00095       void setOptimizer(SparseOptimizer* optimizer);
00096 
00098       bool levenberg() const { return _isLevenberg;}
00099       void setLevenberg(bool levenberg);
00100 
00105       virtual bool supportsSchur() {return false;}
00106 
00108       virtual bool schur()=0;
00109       virtual void setSchur(bool s)=0;
00110 
00111       size_t additionalVectorSpace() const { return _additionalVectorSpace;}
00112       void setAdditionalVectorSpace(size_t s);
00113 
00114     protected:
00115       SparseOptimizer* _optimizer;
00116       double* _x;
00117       double* _b;
00118       size_t _xSize, _maxXSize;
00119       bool _isLevenberg; 
00120       size_t _additionalVectorSpace;
00121 
00122       void resizeVector(size_t sx);
00123   };
00124 
00125 } // end namespace
00126 
00127 #endif


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:32:42