Public Types | Public Member Functions | Protected Attributes | List of all members
g2o::SparseBlockMatrix< MatrixType > Class Template Reference

Sparse matrix which uses blocks. More...

#include <sparse_block_matrix.h>

Public Types

typedef std::map< int, SparseMatrixBlock * > IntBlockMap
 
typedef MatrixType SparseMatrixBlock
 this is the type of the elementary block, it is an Eigen::Matrix. More...
 

Public Member Functions

bool add (SparseBlockMatrix< MatrixType > *&dest) const
 adds the current matrix to the destination More...
 
SparseMatrixBlockblock (int r, int c, bool alloc=false)
 returns the block at location r,c. if alloc=true he block is created if it does not exist More...
 
const SparseMatrixBlockblock (int r, int c) const
 returns the block at location r,c More...
 
const std::vector< IntBlockMap > & blockCols () const
 the block matrices per block-column More...
 
std::vector< IntBlockMap > & blockCols ()
 
void clear (bool dealloc=false)
 this zeroes all the blocks. If dealloc=true the blocks are removed from memory More...
 
SparseBlockMatrixclone () const
 deep copy of a sparse-block-matrix; More...
 
int colBaseOfBlock (int c) const
 where does the col at block-col r starts? More...
 
const std::vector< int > & colBlockIndices () const
 indices of the column blocks More...
 
std::vector< int > & colBlockIndices ()
 
int cols () const
 columns of the matrix More...
 
int colsOfBlock (int c) const
 how many cols does the block at block-col c has? More...
 
void fillBlockStructure (MatrixStructure &ms) const
 exports the non zero blocks in the structure matrix ms More...
 
int fillCCS (int *Cp, int *Ci, double *Cx, bool upperTriangle=false) const
 
int fillCCS (double *Cx, bool upperTriangle=false) const
 
int fillSparseBlockMatrixCCS (SparseBlockMatrixCCS< MatrixType > &blockCCS) const
 
int fillSparseBlockMatrixCCSTransposed (SparseBlockMatrixCCS< MatrixType > &blockCCS) const
 
template<class MatrixResultType , class MatrixFactorType >
bool multiply (SparseBlockMatrix< MatrixResultType > *&dest, const SparseBlockMatrix< MatrixFactorType > *M) const
 dest = (*this) * M More...
 
void multiply (double *&dest, const double *src) const
 dest = (*this) * src More...
 
void multiplySymmetricUpperTriangle (double *&dest, const double *src) const
 
size_t nonZeroBlocks () const
 number of allocated blocks More...
 
size_t nonZeros () const
 number of non-zero elements More...
 
void rightMultiply (double *&dest, const double *src) const
 dest = M * (*this) More...
 
int rowBaseOfBlock (int r) const
 where does the row at block-row r starts? More...
 
const std::vector< int > & rowBlockIndices () const
 indices of the row blocks More...
 
std::vector< int > & rowBlockIndices ()
 
int rows () const
 rows of the matrix More...
 
int rowsOfBlock (int r) const
 how many rows does the block at block-row r has? More...
 
void scale (double a)
 *this *= a More...
 
SparseBlockMatrixslice (int rmin, int rmax, int cmin, int cmax, bool alloc=true) const
 
 SparseBlockMatrix (const int *rbi, const int *cbi, int rb, int cb, bool hasStorage=true)
 
 SparseBlockMatrix ()
 
bool symmPermutation (SparseBlockMatrix< MatrixType > *&dest, const int *pinv, bool onlyUpper=false) const
 
void takePatternFromHash (SparseBlockMatrixHashMap< MatrixType > &hashMatrix)
 
template<class MatrixTransposedType >
bool transpose (SparseBlockMatrix< MatrixTransposedType > *&dest) const
 transposes a block matrix, The transposed type should match the argument false on failure More...
 
bool writeOctave (const char *filename, bool upperTriangle=true) const
 
 ~SparseBlockMatrix ()
 

Protected Attributes

std::vector< IntBlockMap_blockCols
 
std::vector< int > _colBlockIndices
 
bool _hasStorage
 
std::vector< int > _rowBlockIndices
 vector of the indices of the blocks along the rows. More...
 

Detailed Description

template<class MatrixType = MatrixXd>
class g2o::SparseBlockMatrix< MatrixType >

Sparse matrix which uses blocks.

Template class that specifies a sparse block matrix. A block matrix is a sparse matrix made of dense blocks. These blocks cannot have a random pattern, but follow a (variable) grid structure. This structure is specified by a partition of the rows and the columns of the matrix. The blocks are represented by the Eigen::Matrix structure, thus they can be statically or dynamically allocated. For efficiency reasons it is convenient to allocate them statically, when possible. A static block matrix has all blocks of the same size, and the size of the block is specified by the template argument. If this is not the case, and you have different block sizes than you have to use a dynamic-block matrix (default template argument).

Definition at line 62 of file sparse_block_matrix.h.

Member Typedef Documentation

template<class MatrixType = MatrixXd>
typedef std::map<int, SparseMatrixBlock*> g2o::SparseBlockMatrix< MatrixType >::IntBlockMap

Definition at line 73 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
typedef MatrixType g2o::SparseBlockMatrix< MatrixType >::SparseMatrixBlock

this is the type of the elementary block, it is an Eigen::Matrix.

Definition at line 66 of file sparse_block_matrix.h.

Constructor & Destructor Documentation

template<class MatrixType >
g2o::SparseBlockMatrix< MatrixType >::SparseBlockMatrix ( const int *  rbi,
const int *  cbi,
int  rb,
int  cb,
bool  hasStorage = true 
)

constructs a sparse block matrix having a specific layout

Parameters
rbiarray of int containing the row layout of the blocks. the component i of the array should contain the index of the first row of the block i+1.
rbiarray of int containing the column layout of the blocks. the component i of the array should contain the index of the first col of the block i+1.
rbnumber of row blocks
cbnumber of col blocks
hasStorageset it to true if the matrix "owns" the blocks, thus it deletes it on destruction. if false the matrix is only a "view" over an existing structure.

Definition at line 54 of file sparse_block_matrix.hpp.

template<class MatrixType >
g2o::SparseBlockMatrix< MatrixType >::SparseBlockMatrix ( )

Definition at line 62 of file sparse_block_matrix.hpp.

template<class MatrixType >
g2o::SparseBlockMatrix< MatrixType >::~SparseBlockMatrix ( )

Definition at line 86 of file sparse_block_matrix.hpp.

Member Function Documentation

template<class MatrixType>
bool g2o::SparseBlockMatrix< MatrixType >::add ( SparseBlockMatrix< MatrixType > *&  dest) const

adds the current matrix to the destination

Definition at line 169 of file sparse_block_matrix.hpp.

template<class MatrixType >
SparseBlockMatrix< MatrixType >::SparseMatrixBlock * g2o::SparseBlockMatrix< MatrixType >::block ( int  r,
int  c,
bool  alloc = false 
)

returns the block at location r,c. if alloc=true he block is created if it does not exist

Definition at line 92 of file sparse_block_matrix.hpp.

template<class MatrixType >
const SparseBlockMatrix< MatrixType >::SparseMatrixBlock * g2o::SparseBlockMatrix< MatrixType >::block ( int  r,
int  c 
) const

returns the block at location r,c

Definition at line 114 of file sparse_block_matrix.hpp.

template<class MatrixType = MatrixXd>
const std::vector<IntBlockMap>& g2o::SparseBlockMatrix< MatrixType >::blockCols ( ) const
inline

the block matrices per block-column

Definition at line 178 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
std::vector<IntBlockMap>& g2o::SparseBlockMatrix< MatrixType >::blockCols ( )
inline

Definition at line 179 of file sparse_block_matrix.h.

template<class MatrixType >
void g2o::SparseBlockMatrix< MatrixType >::clear ( bool  dealloc = false)

this zeroes all the blocks. If dealloc=true the blocks are removed from memory

Definition at line 68 of file sparse_block_matrix.hpp.

template<class MatrixType >
SparseBlockMatrix< MatrixType > * g2o::SparseBlockMatrix< MatrixType >::clone ( ) const

deep copy of a sparse-block-matrix;

Definition at line 123 of file sparse_block_matrix.hpp.

template<class MatrixType = MatrixXd>
int g2o::SparseBlockMatrix< MatrixType >::colBaseOfBlock ( int  c) const
inline

where does the col at block-col r starts?

Definition at line 111 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
const std::vector<int>& g2o::SparseBlockMatrix< MatrixType >::colBlockIndices ( ) const
inline

indices of the column blocks

Definition at line 186 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
std::vector<int>& g2o::SparseBlockMatrix< MatrixType >::colBlockIndices ( )
inline

Definition at line 187 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
int g2o::SparseBlockMatrix< MatrixType >::cols ( ) const
inline

columns of the matrix

Definition at line 69 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
int g2o::SparseBlockMatrix< MatrixType >::colsOfBlock ( int  c) const
inline

how many cols does the block at block-col c has?

Definition at line 105 of file sparse_block_matrix.h.

template<class MatrixType >
void g2o::SparseBlockMatrix< MatrixType >::fillBlockStructure ( MatrixStructure ms) const

exports the non zero blocks in the structure matrix ms

Definition at line 520 of file sparse_block_matrix.hpp.

template<class MatrixType >
int g2o::SparseBlockMatrix< MatrixType >::fillCCS ( int *  Cp,
int *  Ci,
double *  Cx,
bool  upperTriangle = false 
) const

fill the CCS arrays of a matrix, arrays have to be allocated beforehand

Definition at line 490 of file sparse_block_matrix.hpp.

template<class MatrixType >
int g2o::SparseBlockMatrix< MatrixType >::fillCCS ( double *  Cx,
bool  upperTriangle = false 
) const

fill the CCS arrays of a matrix, arrays have to be allocated beforehand. This function only writes the values and assumes that column and row structures have already been written.

Definition at line 465 of file sparse_block_matrix.hpp.

template<class MatrixType>
int g2o::SparseBlockMatrix< MatrixType >::fillSparseBlockMatrixCCS ( SparseBlockMatrixCCS< MatrixType > &  blockCCS) const

copy into CCS structure

Returns
number of processed blocks, -1 on error

Definition at line 592 of file sparse_block_matrix.hpp.

template<class MatrixType>
int g2o::SparseBlockMatrix< MatrixType >::fillSparseBlockMatrixCCSTransposed ( SparseBlockMatrixCCS< MatrixType > &  blockCCS) const

copy as transposed into a CCS structure

Returns
number of processed blocks, -1 on error

Definition at line 610 of file sparse_block_matrix.hpp.

template<class MatrixType >
template<class MatrixResultType , class MatrixFactorType >
bool g2o::SparseBlockMatrix< MatrixType >::multiply ( SparseBlockMatrix< MatrixResultType > *&  dest,
const SparseBlockMatrix< MatrixFactorType > *  M 
) const

dest = (*this) * M

Definition at line 200 of file sparse_block_matrix.hpp.

template<class MatrixType >
void g2o::SparseBlockMatrix< MatrixType >::multiply ( double *&  dest,
const double *  src 
) const

dest = (*this) * src

Definition at line 235 of file sparse_block_matrix.hpp.

template<class MatrixType >
void g2o::SparseBlockMatrix< MatrixType >::multiplySymmetricUpperTriangle ( double *&  dest,
const double *  src 
) const

compute dest = (*this) * src However, assuming that this is a symmetric matrix where only the upper triangle is stored

Definition at line 258 of file sparse_block_matrix.hpp.

template<class MatrixType >
size_t g2o::SparseBlockMatrix< MatrixType >::nonZeroBlocks ( ) const

number of allocated blocks

Definition at line 354 of file sparse_block_matrix.hpp.

template<class MatrixType >
size_t g2o::SparseBlockMatrix< MatrixType >::nonZeros ( ) const

number of non-zero elements

Definition at line 362 of file sparse_block_matrix.hpp.

template<class MatrixType >
void g2o::SparseBlockMatrix< MatrixType >::rightMultiply ( double *&  dest,
const double *  src 
) const

dest = M * (*this)

Definition at line 285 of file sparse_block_matrix.hpp.

template<class MatrixType = MatrixXd>
int g2o::SparseBlockMatrix< MatrixType >::rowBaseOfBlock ( int  r) const
inline

where does the row at block-row r starts?

Definition at line 108 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
const std::vector<int>& g2o::SparseBlockMatrix< MatrixType >::rowBlockIndices ( ) const
inline

indices of the row blocks

Definition at line 182 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
std::vector<int>& g2o::SparseBlockMatrix< MatrixType >::rowBlockIndices ( )
inline

Definition at line 183 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
int g2o::SparseBlockMatrix< MatrixType >::rows ( ) const
inline

rows of the matrix

Definition at line 71 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
int g2o::SparseBlockMatrix< MatrixType >::rowsOfBlock ( int  r) const
inline

how many rows does the block at block-row r has?

Definition at line 102 of file sparse_block_matrix.h.

template<class MatrixType >
void g2o::SparseBlockMatrix< MatrixType >::scale ( double  a)

*this *= a

Definition at line 315 of file sparse_block_matrix.hpp.

template<class MatrixType >
SparseBlockMatrix< MatrixType > * g2o::SparseBlockMatrix< MatrixType >::slice ( int  rmin,
int  rmax,
int  cmin,
int  cmax,
bool  alloc = true 
) const

returns a view or a copy of the block matrix

Parameters
rminstarting block row
rmaxending block row
cminstarting block col
cmaxending block col
allocif true it makes a deep copy, if false it creates a view.

Definition at line 325 of file sparse_block_matrix.hpp.

template<class MatrixType>
bool g2o::SparseBlockMatrix< MatrixType >::symmPermutation ( SparseBlockMatrix< MatrixType > *&  dest,
const int *  pinv,
bool  onlyUpper = false 
) const

writes in dest a block permutaton specified by pinv.

Parameters
pinvarray such that new_block[i] = old_block[pinv[i]]

Definition at line 400 of file sparse_block_matrix.hpp.

template<class MatrixType>
void g2o::SparseBlockMatrix< MatrixType >::takePatternFromHash ( SparseBlockMatrixHashMap< MatrixType > &  hashMatrix)

take over the memory and matrix pattern from a hash matrix. The structure of the hash matrix will be cleared.

Definition at line 627 of file sparse_block_matrix.hpp.

template<class MatrixType >
template<class MatrixTransposedType >
bool g2o::SparseBlockMatrix< MatrixType >::transpose ( SparseBlockMatrix< MatrixTransposedType > *&  dest) const

transposes a block matrix, The transposed type should match the argument false on failure

Definition at line 138 of file sparse_block_matrix.hpp.

template<class MatrixType >
bool g2o::SparseBlockMatrix< MatrixType >::writeOctave ( const char *  filename,
bool  upperTriangle = true 
) const

write the content of this matrix to a stream loadable by Octave

Parameters
upperTriangledoes this matrix store only the upper triangular blocks

Definition at line 548 of file sparse_block_matrix.hpp.

Member Data Documentation

template<class MatrixType = MatrixXd>
std::vector<IntBlockMap> g2o::SparseBlockMatrix< MatrixType >::_blockCols
protected

array of maps of blocks. The index of the array represent a block column of the matrix and the block column is stored as a map row_block -> matrix_block_ptr.

Definition at line 218 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
std::vector<int> g2o::SparseBlockMatrix< MatrixType >::_colBlockIndices
protected

vector of the indices of the blocks along the cols

Definition at line 215 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
bool g2o::SparseBlockMatrix< MatrixType >::_hasStorage
protected

Definition at line 219 of file sparse_block_matrix.h.

template<class MatrixType = MatrixXd>
std::vector<int> g2o::SparseBlockMatrix< MatrixType >::_rowBlockIndices
protected

vector of the indices of the blocks along the rows.

Definition at line 214 of file sparse_block_matrix.h.


The documentation for this class was generated from the following files:


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