27 #ifndef G2O_SPARSE_BLOCK_MATRIX_DIAGONAL_H 28 #define G2O_SPARSE_BLOCK_MATRIX_DIAGONAL_H 32 #include <Eigen/StdVector> 34 #include "../../config.h" 46 template <
class MatrixType>
58 typedef std::vector<MatrixType, Eigen::aligned_allocator<MatrixType> >
DiagonalVector;
77 void multiply(
double*& dest,
const double* src)
const 81 dest=
new double[destSize];
82 memset(dest,0, destSize*
sizeof(
double));
86 Eigen::Map<Eigen::VectorXd> destVec(dest, destSize);
87 Eigen::Map<const Eigen::VectorXd> srcVec(src,
rows());
90 # pragma omp parallel for default (shared) schedule(dynamic, 10) 92 for (
int i=0; i < static_cast<int>(
_diagonal.size()); ++i){
94 int srcOffset = destOffset;
95 const SparseMatrixBlock& A =
_diagonal[i];
const std::vector< int > & blockIndices() const
indices of the row blocks
DiagonalVector & diagonal()
void axpy(const MatrixType &A, const Eigen::Map< const Eigen::VectorXd > &x, int xoff, Eigen::Map< Eigen::VectorXd > &y, int yoff)
int baseOfBlock(int r) const
where does the row /col at block-row / block-column r starts?
const DiagonalVector & diagonal() const
the block matrices per block-column
int cols() const
columns of the matrix
void multiply(double *&dest, const double *src) const
int rows() const
rows of the matrix
SparseBlockMatrixDiagonal(const std::vector< int > &blockIndices)
MatrixType SparseMatrixBlock
this is the type of the elementary block, it is an Eigen::Matrix.
int dimOfBlock(int r) const
how many rows/cols does the block at block-row / block-column r has?
const std::vector< int > & _blockIndices
vector of the indices of the blocks along the diagonal
std::vector< MatrixType, Eigen::aligned_allocator< MatrixType > > DiagonalVector
Sparse matrix which uses blocks on the diagonal.