sparse_block_matrix_ccs.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_SPARSE_BLOCK_MATRIX_CCS_H
28 #define G2O_SPARSE_BLOCK_MATRIX_CCS_H
29 
30 #include <vector>
31 #include <cassert>
32 #include <Eigen/Core>
33 
34 #include "../../config.h"
35 #include "matrix_operations.h"
36 
37 #ifdef _MSC_VER
38 #include <unordered_map>
39 #else
40 #include <tr1/unordered_map>
41 #endif
42 
43 namespace g2o {
44 
52  template <class MatrixType>
54  {
55  public:
57  typedef MatrixType SparseMatrixBlock;
58 
60  int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;}
62  int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;}
63 
67  struct RowBlock
68  {
69  int row;
70  MatrixType* block;
71  RowBlock() : row(-1), block(0) {}
72  RowBlock(int r, MatrixType* b) : row(r), block(b) {}
73  bool operator<(const RowBlock& other) const { return row < other.row;}
74  };
75  typedef std::vector<RowBlock> SparseColumn;
76 
77  SparseBlockMatrixCCS(const std::vector<int>& rowIndices, const std::vector<int>& colIndices) :
78  _rowBlockIndices(rowIndices), _colBlockIndices(colIndices)
79  {}
80 
82  int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; }
83 
85  int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; }
86 
88  int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; }
89 
91  int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; }
92 
94  const std::vector<SparseColumn>& blockCols() const { return _blockCols;}
95  std::vector<SparseColumn>& blockCols() { return _blockCols;}
96 
98  const std::vector<int>& rowBlockIndices() const { return _rowBlockIndices;}
99 
101  const std::vector<int>& colBlockIndices() const { return _colBlockIndices;}
102 
103  void rightMultiply(double*& dest, const double* src) const
104  {
105  int destSize=cols();
106 
107  if (! dest){
108  dest=new double [ destSize ];
109  memset(dest,0, destSize*sizeof(double));
110  }
111 
112  // map the memory by Eigen
113  Eigen::Map<Eigen::VectorXd> destVec(dest, destSize);
114  Eigen::Map<const Eigen::VectorXd> srcVec(src, rows());
115 
116 # ifdef G2O_OPENMP
117 # pragma omp parallel for default (shared) schedule(dynamic, 10)
118 # endif
119  for (int i=0; i < static_cast<int>(_blockCols.size()); ++i){
120  int destOffset = colBaseOfBlock(i);
121  for (typename SparseColumn::const_iterator it = _blockCols[i].begin(); it!=_blockCols[i].end(); ++it) {
122  const SparseMatrixBlock* a = it->block;
123  int srcOffset = rowBaseOfBlock(it->row);
124  // destVec += *a.transpose() * srcVec (according to the sub-vector parts)
125  internal::atxpy(*a, srcVec, srcOffset, destVec, destOffset);
126  }
127  }
128  }
129 
133  void sortColumns()
134  {
135  for (int i=0; i < static_cast<int>(_blockCols.size()); ++i){
136  std::sort(_blockCols[i].begin(), _blockCols[i].end());
137  }
138  }
139 
143  int fillCCS(int* Cp, int* Ci, double* Cx, bool upperTriangle = false) const
144  {
145  assert(Cp && Ci && Cx && "Target destination is NULL");
146  int nz=0;
147  for (size_t i=0; i<_blockCols.size(); ++i){
148  int cstart=i ? _colBlockIndices[i-1] : 0;
149  int csize=colsOfBlock(i);
150  for (int c=0; c<csize; ++c) {
151  *Cp=nz;
152  for (typename SparseColumn::const_iterator it = _blockCols[i].begin(); it!=_blockCols[i].end(); ++it) {
153  const SparseMatrixBlock* b=it->block;
154  int rstart=it->row ? _rowBlockIndices[it->row-1] : 0;
155 
156  int elemsToCopy = b->rows();
157  if (upperTriangle && rstart == cstart)
158  elemsToCopy = c + 1;
159  for (int r=0; r<elemsToCopy; ++r){
160  *Cx++ = (*b)(r,c);
161  *Ci++ = rstart++;
162  ++nz;
163  }
164  }
165  ++Cp;
166  }
167  }
168  *Cp=nz;
169  return nz;
170  }
171 
176  int fillCCS(double* Cx, bool upperTriangle = false) const
177  {
178  assert(Cx && "Target destination is NULL");
179  double* CxStart = Cx;
180  int cstart = 0;
181  for (size_t i=0; i<_blockCols.size(); ++i){
182  int csize = _colBlockIndices[i] - cstart;
183  for (int c=0; c<csize; ++c) {
184  for (typename SparseColumn::const_iterator it = _blockCols[i].begin(); it!=_blockCols[i].end(); ++it) {
185  const SparseMatrixBlock* b = it->block;
186  int rstart = it->row ? _rowBlockIndices[it->row-1] : 0;
187 
188  int elemsToCopy = b->rows();
189  if (upperTriangle && rstart == cstart)
190  elemsToCopy = c + 1;
191  memcpy(Cx, b->data() + c*b->rows(), elemsToCopy * sizeof(double));
192  Cx += elemsToCopy;
193 
194  }
195  }
196  cstart = _colBlockIndices[i];
197  }
198  return Cx - CxStart;
199  }
200 
201  protected:
202  const std::vector<int>& _rowBlockIndices;
203  const std::vector<int>& _colBlockIndices;
204  std::vector<SparseColumn> _blockCols;
205  };
206 
207 
208 
214  template <class MatrixType>
216  {
217  public:
219  typedef MatrixType SparseMatrixBlock;
220 
222  int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;}
224  int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;}
225 
226  typedef std::tr1::unordered_map<int, MatrixType*> SparseColumn;
227 
228  SparseBlockMatrixHashMap(const std::vector<int>& rowIndices, const std::vector<int>& colIndices) :
229  _rowBlockIndices(rowIndices), _colBlockIndices(colIndices)
230  {}
231 
233  int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; }
234 
236  int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; }
237 
239  int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; }
240 
242  int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; }
243 
245  const std::vector<SparseColumn>& blockCols() const { return _blockCols;}
246  std::vector<SparseColumn>& blockCols() { return _blockCols;}
247 
249  const std::vector<int>& rowBlockIndices() const { return _rowBlockIndices;}
250 
252  const std::vector<int>& colBlockIndices() const { return _colBlockIndices;}
253 
257  MatrixType* addBlock(int r, int c, bool zeroBlock = false)
258  {
259  assert(c <(int)_blockCols.size() && "accessing column which is not available");
260  SparseColumn& sparseColumn = _blockCols[c];
261  typename SparseColumn::iterator foundIt = sparseColumn.find(r);
262  if (foundIt == sparseColumn.end()) {
263  int rb = rowsOfBlock(r);
264  int cb = colsOfBlock(c);
265  MatrixType* m = new MatrixType(rb, cb);
266  if (zeroBlock)
267  m->setZero();
268  sparseColumn[r] = m;
269  return m;
270  }
271  return foundIt->second;
272  }
273 
274  protected:
275  const std::vector<int>& _rowBlockIndices;
276  const std::vector<int>& _colBlockIndices;
277  std::vector<SparseColumn> _blockCols;
278  };
279 
280 } //end namespace
281 
282 #endif
MatrixType SparseMatrixBlock
this is the type of the elementary block, it is an Eigen::Matrix.
int fillCCS(double *Cx, bool upperTriangle=false) const
const std::vector< int > & colBlockIndices() const
indices of the column blocks
const std::vector< int > & rowBlockIndices() const
indices of the row blocks
void rightMultiply(double *&dest, const double *src) const
MatrixType SparseMatrixBlock
this is the type of the elementary block, it is an Eigen::Matrix.
int rows() const
rows of the matrix
int colsOfBlock(int c) const
how many cols does the block at block-col c has?
int rowsOfBlock(int r) const
how many rows does the block at block-row r has?
void atxpy(const MatrixType &A, const Eigen::Map< const Eigen::VectorXd > &x, int xoff, Eigen::Map< Eigen::VectorXd > &y, int yoff)
std::vector< SparseColumn > & blockCols()
int colBaseOfBlock(int c) const
where does the col at block-col r start?
int rowBaseOfBlock(int r) const
where does the row at block-row r start?
const std::vector< int > & _colBlockIndices
vector of the indices of the blocks along the cols
std::vector< RowBlock > SparseColumn
SparseBlockMatrixHashMap(const std::vector< int > &rowIndices, const std::vector< int > &colIndices)
std::vector< SparseColumn > & blockCols()
int fillCCS(int *Cp, int *Ci, double *Cx, bool upperTriangle=false) const
int cols() const
columns of the matrix
MatrixType * addBlock(int r, int c, bool zeroBlock=false)
const std::vector< SparseColumn > & blockCols() const
the block matrices per block-column
Sparse matrix which uses blocks.
int colBaseOfBlock(int c) const
where does the col at block-col r start?
std::vector< SparseColumn > _blockCols
the matrices stored in CCS order
int colsOfBlock(int c) const
how many cols does the block at block-col c has?
int cols() const
columns of the matrix
std::tr1::unordered_map< int, MatrixType * > SparseColumn
const std::vector< int > & _rowBlockIndices
vector of the indices of the blocks along the rows.
SparseBlockMatrixCCS(const std::vector< int > &rowIndices, const std::vector< int > &colIndices)
MatrixType * block
matrix pointer for the block
std::vector< SparseColumn > _blockCols
the matrices stored in CCS order
const std::vector< int > & rowBlockIndices() const
indices of the row blocks
const std::vector< int > & _rowBlockIndices
vector of the indices of the blocks along the rows.
const std::vector< int > & _colBlockIndices
vector of the indices of the blocks along the cols
int rowsOfBlock(int r) const
how many rows does the block at block-row r has?
int rows() const
rows of the matrix
Sparse matrix which uses blocks based on hash structures.
const std::vector< SparseColumn > & blockCols() const
the block matrices per block-column
bool operator<(const RowBlock &other) const
int rowBaseOfBlock(int r) const
where does the row at block-row r start?
const std::vector< int > & colBlockIndices() const
indices of the column blocks


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