marginal_covariance_cholesky.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_MARGINAL_COVARIANCE_CHOLESKY_H
28 #define G2O_MARGINAL_COVARIANCE_CHOLESKY_H
29 
30 #include "optimizable_graph.h"
31 #include "sparse_block_matrix.h"
32 
33 #include <cassert>
34 #include <vector>
35 
36 #ifdef _MSC_VER
37 #include <unordered_map>
38 #else
39 #include <tr1/unordered_map>
40 #endif
41 
42 
43 namespace g2o {
44 
49  protected:
53  typedef std::tr1::unordered_map<int, double> LookupMap;
54 
55  public:
58 
63  void computeCovariance(double** covBlocks, const std::vector<int>& blockIndices);
64 
65 
69  void computeCovariance(SparseBlockMatrix<MatrixXd>& spinv, const std::vector<int>& rowBlockIndices, const std::vector< std::pair<int, int> >& blockIndices);
70 
71 
79  void setCholeskyFactor(int n, int* Lp, int* Li, double* Lx, int* permInv);
80 
81  protected:
82  // information about the cholesky factor (lower triangle)
83  int _n;
84  int* _Ap;
85  int* _Ai;
86  double* _Ax;
87  int* _perm;
88 
89  LookupMap _map;
90  std::vector<double> _diag;
91 
93  int computeIndex(int r, int c) const { /*assert(r <= c);*/ return r*_n + c;}
98  double computeEntry(int r, int c);
99  };
100 
101 }
102 
103 #endif
LookupMap _map
hash look up table for the already computed entries
std::tr1::unordered_map< int, double > LookupMap
void setCholeskyFactor(int n, int *Lp, int *Li, double *Lx, int *permInv)
computing the marginal covariance given a cholesky factor (lower triangle of the factor) ...
int * _Ai
row indices of the CCS storage
int * _Ap
column pointer of the CCS storage
void computeCovariance(double **covBlocks, const std::vector< int > &blockIndices)
double * _Ax
values of the cholesky factor
int * _perm
permutation of the cholesky factor. Variable re-ordering for better fill-in
std::vector< double > _diag
cache 1 / H_ii to avoid recalculations
Sparse matrix which uses blocks.
int computeIndex(int r, int c) const
compute the index used for hashing


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