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

Sparse matrix which using blocks. More...

#include <sparse_block_matrix.h>

List of all members.

Public Types

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

Public Member Functions

bool add (SparseBlockMatrix< MatrixType > *&dest) const
 adds the current matrix to the destination
SparseMatrixBlockblock (int r, int c, bool alloc=false)
const SparseMatrixBlockblock (int r, int c) const
 returns the block at location r,c
const std::vector< IntBlockMap > & blockCols () const
 the block matrices per block-column
std::vector< IntBlockMap > & blockCols ()
void clear (bool dealloc=false)
SparseBlockMatrixclone () const
 deep copy of a sparse-block-matrix;
int colBaseOfBlock (int c) const
 where does the col at block-col r starts?
const std::vector< int > & colBlockIndices () const
 indices of the column blocks
std::vector< int > & colBlockIndices ()
int cols () const
 columns of the matrix
int colsOfBlock (int c) const
 how many cols does the block at block-col c has?
void fillBlockStructure (MatrixStructure &ms) const
 exports the non zero blocks in the structure matrix ms
int fillCCS (int *Cp, int *Ci, double *Cx, bool upperTriangle=false) const
 Fill the CCS arrays of a matrix, arrays have to be allocated beforehand.
int fillCCS (double *Cx, bool upperTriangle=false) const
template<class MatrixResultType , class MatrixFactorType >
bool multiply (SparseBlockMatrix< MatrixResultType > *&dest, const SparseBlockMatrix< MatrixFactorType > *M) const
 dest = (*this) * M
void multiply (double *&dest, const double *src) const
 dest = (*this) * src
size_t nonZeroBlocks () const
 number of allocated blocks
size_t nonZeros () const
 number of non-zero elements
void rightMultiply (double *&dest, const double *src) const
 dest = M * (*this)
int rowBaseOfBlock (int r) const
 where does the row at block-row r starts?
const std::vector< int > & rowBlockIndices () const
 indices of the row blocks
std::vector< int > & rowBlockIndices ()
int rows () const
 rows of the matrix
int rowsOfBlock (int r) const
 how many rows does the block at block-row r has?
void scale (double a)
 *this *= a
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
template<class MatrixTransposedType >
bool transpose (SparseBlockMatrix< MatrixTransposedType > *&dest) const
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.

Detailed Description

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

Sparse matrix which using 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 rhe 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 49 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 62 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 53 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:
rbi,:array 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.
rbi,:array 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.
rb,:number of row blocks
cb,:number of col blocks
hasStorage,:set 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 48 of file sparse_block_matrix.hpp.

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

Definition at line 60 of file sparse_block_matrix.hpp.

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

Definition at line 91 of file sparse_block_matrix.hpp.


Member Function Documentation

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

adds the current matrix to the destination

Definition at line 224 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 103 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 137 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 195 of file sparse_block_matrix.h.

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

Definition at line 196 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 ( void  ) const

deep copy of a sparse-block-matrix;

Definition at line 148 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 122 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 203 of file sparse_block_matrix.h.

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

Definition at line 204 of file sparse_block_matrix.h.

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

columns of the matrix

Definition at line 56 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 110 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 739 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 700 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 666 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 272 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 380 of file sparse_block_matrix.hpp.

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

number of allocated blocks

Definition at line 517 of file sparse_block_matrix.hpp.

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

number of non-zero elements

Definition at line 528 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 416 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 118 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 199 of file sparse_block_matrix.h.

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

Definition at line 200 of file sparse_block_matrix.h.

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

rows of the matrix

Definition at line 59 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 454 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:
rmin,:starting block row
rmax,:ending block row
cmin,:starting block col
cmax,:ending block col
alloc,:if true it makes a deep copy, if false it creates a view.

Definition at line 473 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:
pinv,:array such that new_block[i] = old_block[pinv[i]]

Definition at line 589 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 179 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 777 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 225 of file sparse_block_matrix.h.

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

Definition at line 218 of file sparse_block_matrix.h.

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

Definition at line 227 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.

vector of the indices of the blocks along the cols

Definition at line 217 of file sparse_block_matrix.h.


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


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