marginal_covariance_cholesky.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 MARGINAL_COVARIANCE_CHOLESKY_H
00018 #define MARGINAL_COVARIANCE_CHOLESKY_H
00019 
00020 #include "optimizable_graph.h"
00021 #include "sparse_block_matrix.h"
00022 
00023 #include <cassert>
00024 #include <vector>
00025 
00026 #ifdef _MSC_VER
00027 #include <unordered_map>
00028 #else
00029 #include <tr1/unordered_map>
00030 #endif
00031 
00032 namespace g2o {
00033 
00037   class MarginalCovarianceCholesky {
00038     protected:
00042       typedef std::tr1::unordered_map<int, double>     LookupMap;
00043     
00044     public:
00045       MarginalCovarianceCholesky();
00046       ~MarginalCovarianceCholesky();
00047 
00051       void computeCovariance(const std::vector<OptimizableGraph::Vertex*>& vertices);
00052 
00057       void computeCovariance(double** covBlocks, const std::vector<int>& blockIndices);
00058 
00059 
00063       void computeCovariance(SparseBlockMatrix<MatrixXd>& spinv, const std::vector<int>& rowBlockIndices, const std::vector< std::pair<int, int> >& blockIndices);
00064 
00065 
00070       void setCholeskyFactor(int n, int* Lp, int* Li, double* Lx, int* permInv);
00071 
00072     protected:
00073       // information about the cholesky factor (lower triangle)
00074       int _n;           
00075       int* _Ap;         
00076       int* _Ai;         
00077       double* _Ax;      
00078       int* _perm;       
00079 
00080       LookupMap _map;             
00081       std::vector<double> _diag;  
00082 
00084       int computeIndex(int r, int c) const { /*assert(r <= c);*/ return r*_n + c;}
00089       double computeEntry(int r, int c);
00090   };
00091 
00092 }
00093 
00094 #endif


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