Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Friends | List of all members
gtsam::SymmetricBlockMatrix Class Reference

#include <SymmetricBlockMatrix.h>

Public Types

typedef Eigen::Block< MatrixBlock
 
typedef Eigen::Block< const MatrixconstBlock
 
typedef SymmetricBlockMatrix This
 

Public Member Functions

DenseIndexblockStart ()
 
DenseIndex blockStart () const
 
void choleskyPartial (DenseIndex nFrontals)
 
DenseIndex cols () const
 Column size. More...
 
DenseIndex getDim (DenseIndex block) const
 Number of dimensions for variable on this diagonal block. More...
 
DenseIndex nBlocks () const
 Block count. More...
 
DenseIndex rows () const
 Row size. More...
 
VerticalBlockMatrix split (DenseIndex nFrontals)
 
 SymmetricBlockMatrix ()
 Construct from an empty matrix (asserts that the matrix is empty) More...
 
template<typename CONTAINER >
 SymmetricBlockMatrix (const CONTAINER &dimensions, bool appendOneDimension=false)
 Construct from a container of the sizes of each block. More...
 
template<typename ITERATOR >
 SymmetricBlockMatrix (ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension=false)
 Construct from iterator over the sizes of each vertical block. More...
 
template<typename CONTAINER >
 SymmetricBlockMatrix (const CONTAINER &dimensions, const Matrix &matrix, bool appendOneDimension=false)
 Construct from a container of the sizes of each vertical block and a pre-prepared matrix. More...
 
Block getter methods.
Matrix block (DenseIndex I, DenseIndex J) const
 
Eigen::SelfAdjointView< Block, Eigen::UpperdiagonalBlock (DenseIndex J)
 Return the J'th diagonal block as a self adjoint view. More...
 
Eigen::SelfAdjointView< constBlock, Eigen::UpperdiagonalBlock (DenseIndex J) const
 Return the J'th diagonal block as a self adjoint view. More...
 
Vector diagonal (DenseIndex J) const
 Get the diagonal of the J'th diagonal block. More...
 
constBlock aboveDiagonalBlock (DenseIndex I, DenseIndex J) const
 Get block above the diagonal (I, J). More...
 
Eigen::SelfAdjointView< constBlock, Eigen::UpperselfadjointView (DenseIndex I, DenseIndex J) const
 Return the square sub-matrix that contains blocks(i:j, i:j). More...
 
Eigen::TriangularView< constBlock, Eigen::UppertriangularView (DenseIndex I, DenseIndex J) const
 Return the square sub-matrix that contains blocks(i:j, i:j) as a triangular view. More...
 
constBlock aboveDiagonalRange (DenseIndex i_startBlock, DenseIndex i_endBlock, DenseIndex j_startBlock, DenseIndex j_endBlock) const
 Get a range [i,j) from the matrix. Indices are in block units. More...
 
Block aboveDiagonalRange (DenseIndex i_startBlock, DenseIndex i_endBlock, DenseIndex j_startBlock, DenseIndex j_endBlock)
 Get a range [i,j) from the matrix. Indices are in block units. More...
 
Block setter methods.
template<typename XprType >
void setDiagonalBlock (DenseIndex I, const XprType &xpr)
 Set a diagonal block. Only the upper triangular portion of xpr is evaluated. More...
 
template<typename XprType >
void setOffDiagonalBlock (DenseIndex I, DenseIndex J, const XprType &xpr)
 Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated. More...
 
template<typename XprType >
void updateDiagonalBlock (DenseIndex I, const XprType &xpr)
 Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr. More...
 
template<typename XprType >
void updateOffDiagonalBlock (DenseIndex I, DenseIndex J, const XprType &xpr)
 
Accessing the full matrix.
Eigen::SelfAdjointView< Block, Eigen::UpperselfadjointView ()
 Get self adjoint view. More...
 
Eigen::SelfAdjointView< constBlock, Eigen::UpperselfadjointView () const
 Get self adjoint view. More...
 
template<typename XprType >
void setFullMatrix (const XprType &xpr)
 Set the entire active matrix. Only reads the upper triangular part of xpr. More...
 
void setZero ()
 Set the entire active matrix zero. More...
 
void negate ()
 Negate the entire active matrix. More...
 
void invertInPlace ()
 Invert the entire active matrix in place. More...
 

Static Public Member Functions

static SymmetricBlockMatrix LikeActiveViewOf (const SymmetricBlockMatrix &other)
 
static SymmetricBlockMatrix LikeActiveViewOf (const VerticalBlockMatrix &other)
 

Protected Member Functions

void assertInvariants () const
 
constBlock block_ (DenseIndex iBlock, DenseIndex jBlock, DenseIndex blockRows=1, DenseIndex blockCols=1) const
 Get an arbitrary block from the matrix. Indices are in block units. More...
 
Block block_ (DenseIndex iBlock, DenseIndex jBlock, DenseIndex blockRows=1, DenseIndex blockCols=1)
 Get an arbitrary block from the matrix. Indices are in block units. More...
 
std::array< DenseIndex, 4 > calcIndices (DenseIndex iBlock, DenseIndex jBlock, DenseIndex blockRows, DenseIndex blockCols) const
 Compute the indices into the underlying matrix for a given block. More...
 
template<typename ITERATOR >
void fillOffsets (ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension)
 
constBlock full () const
 Get the full matrix as a block. More...
 
Block full ()
 Get the full matrix as a block. More...
 
DenseIndex nActualBlocks () const
 Number of actual blocks in the full matrix. More...
 
DenseIndex nOffsets () const
 Number of offsets in the full matrix. More...
 
DenseIndex offset (DenseIndex block) const
 Get an offset for a block index (in the active view). More...
 

Protected Attributes

DenseIndex blockStart_
 Changes apparent matrix view, see main class comment. More...
 
Matrix matrix_
 The full matrix. More...
 
FastVector< DenseIndexvariableColOffsets_
 the starting columns of each block (0-based) More...
 

Private Member Functions

template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Friends

class boost::serialization::access
 
template<typename SymmetricBlockMatrixType >
class SymmetricBlockMatrixBlockExpr
 
class VerticalBlockMatrix
 

Detailed Description

Definition at line 51 of file SymmetricBlockMatrix.h.

Member Typedef Documentation

Definition at line 55 of file SymmetricBlockMatrix.h.

Definition at line 56 of file SymmetricBlockMatrix.h.

Definition at line 54 of file SymmetricBlockMatrix.h.

Constructor & Destructor Documentation

gtsam::SymmetricBlockMatrix::SymmetricBlockMatrix ( )
inline

Construct from an empty matrix (asserts that the matrix is empty)

Definition at line 66 of file SymmetricBlockMatrix.h.

template<typename CONTAINER >
gtsam::SymmetricBlockMatrix::SymmetricBlockMatrix ( const CONTAINER &  dimensions,
bool  appendOneDimension = false 
)
inline

Construct from a container of the sizes of each block.

Definition at line 75 of file SymmetricBlockMatrix.h.

template<typename ITERATOR >
gtsam::SymmetricBlockMatrix::SymmetricBlockMatrix ( ITERATOR  firstBlockDim,
ITERATOR  lastBlockDim,
bool  appendOneDimension = false 
)
inline

Construct from iterator over the sizes of each vertical block.

Definition at line 85 of file SymmetricBlockMatrix.h.

template<typename CONTAINER >
gtsam::SymmetricBlockMatrix::SymmetricBlockMatrix ( const CONTAINER &  dimensions,
const Matrix matrix,
bool  appendOneDimension = false 
)
inline

Construct from a container of the sizes of each vertical block and a pre-prepared matrix.

Definition at line 95 of file SymmetricBlockMatrix.h.

Member Function Documentation

constBlock gtsam::SymmetricBlockMatrix::aboveDiagonalBlock ( DenseIndex  I,
DenseIndex  J 
) const
inline

Get block above the diagonal (I, J).

Definition at line 155 of file SymmetricBlockMatrix.h.

constBlock gtsam::SymmetricBlockMatrix::aboveDiagonalRange ( DenseIndex  i_startBlock,
DenseIndex  i_endBlock,
DenseIndex  j_startBlock,
DenseIndex  j_endBlock 
) const
inline

Get a range [i,j) from the matrix. Indices are in block units.

Definition at line 175 of file SymmetricBlockMatrix.h.

Block gtsam::SymmetricBlockMatrix::aboveDiagonalRange ( DenseIndex  i_startBlock,
DenseIndex  i_endBlock,
DenseIndex  j_startBlock,
DenseIndex  j_endBlock 
)
inline

Get a range [i,j) from the matrix. Indices are in block units.

Definition at line 186 of file SymmetricBlockMatrix.h.

void gtsam::SymmetricBlockMatrix::assertInvariants ( ) const
inlineprotected

Definition at line 373 of file SymmetricBlockMatrix.h.

Matrix gtsam::SymmetricBlockMatrix::block ( DenseIndex  I,
DenseIndex  J 
) const

Get a copy of a block (anywhere in the matrix). This method makes a copy - use the methods below if performance is critical.

Definition at line 54 of file SymmetricBlockMatrix.cpp.

constBlock gtsam::SymmetricBlockMatrix::block_ ( DenseIndex  iBlock,
DenseIndex  jBlock,
DenseIndex  blockRows = 1,
DenseIndex  blockCols = 1 
) const
inlineprotected

Get an arbitrary block from the matrix. Indices are in block units.

Definition at line 333 of file SymmetricBlockMatrix.h.

Block gtsam::SymmetricBlockMatrix::block_ ( DenseIndex  iBlock,
DenseIndex  jBlock,
DenseIndex  blockRows = 1,
DenseIndex  blockCols = 1 
)
inlineprotected

Get an arbitrary block from the matrix. Indices are in block units.

Definition at line 341 of file SymmetricBlockMatrix.h.

DenseIndex& gtsam::SymmetricBlockMatrix::blockStart ( )
inline

Retrieve or modify the first logical block, i.e. the block referenced by block index 0. Blocks before it will be inaccessible, except by accessing the underlying matrix using matrix().

Definition at line 287 of file SymmetricBlockMatrix.h.

DenseIndex gtsam::SymmetricBlockMatrix::blockStart ( ) const
inline

Retrieve the first logical block, i.e. the block referenced by block index 0. Blocks before it will be inaccessible, except by accessing the underlying matrix using matrix().

Definition at line 291 of file SymmetricBlockMatrix.h.

std::array<DenseIndex, 4> gtsam::SymmetricBlockMatrix::calcIndices ( DenseIndex  iBlock,
DenseIndex  jBlock,
DenseIndex  blockRows,
DenseIndex  blockCols 
) const
inlineprotected

Compute the indices into the underlying matrix for a given block.

Definition at line 359 of file SymmetricBlockMatrix.h.

void gtsam::SymmetricBlockMatrix::choleskyPartial ( DenseIndex  nFrontals)

Given the augmented Hessian [A1'A1 A1'A2 A1'b A2'A1 A2'A2 A2'b b'A1 b'A2 b'b] on x1 and x2, does partial Cholesky in-place to obtain [R Sd;0 L] such that R'R = A1'A1 R'Sd = [A1'A2 A1'b] L'L is the augmented Hessian on the the separator x2 R and Sd can be interpreted as a GaussianConditional |R*x1 + S*x2 - d]^2

Definition at line 65 of file SymmetricBlockMatrix.cpp.

DenseIndex gtsam::SymmetricBlockMatrix::cols ( void  ) const
inline

Column size.

Definition at line 122 of file SymmetricBlockMatrix.h.

Vector gtsam::SymmetricBlockMatrix::diagonal ( DenseIndex  J) const
inline

Get the diagonal of the J'th diagonal block.

Definition at line 150 of file SymmetricBlockMatrix.h.

Eigen::SelfAdjointView<Block, Eigen::Upper> gtsam::SymmetricBlockMatrix::diagonalBlock ( DenseIndex  J)
inline

Return the J'th diagonal block as a self adjoint view.

Definition at line 140 of file SymmetricBlockMatrix.h.

Eigen::SelfAdjointView<constBlock, Eigen::Upper> gtsam::SymmetricBlockMatrix::diagonalBlock ( DenseIndex  J) const
inline

Return the J'th diagonal block as a self adjoint view.

Definition at line 145 of file SymmetricBlockMatrix.h.

template<typename ITERATOR >
void gtsam::SymmetricBlockMatrix::fillOffsets ( ITERATOR  firstBlockDim,
ITERATOR  lastBlockDim,
bool  appendOneDimension 
)
inlineprotected

Definition at line 381 of file SymmetricBlockMatrix.h.

constBlock gtsam::SymmetricBlockMatrix::full ( ) const
inlineprotected

Get the full matrix as a block.

Definition at line 349 of file SymmetricBlockMatrix.h.

Block gtsam::SymmetricBlockMatrix::full ( )
inlineprotected

Get the full matrix as a block.

Definition at line 354 of file SymmetricBlockMatrix.h.

DenseIndex gtsam::SymmetricBlockMatrix::getDim ( DenseIndex  block) const
inline

Number of dimensions for variable on this diagonal block.

Definition at line 128 of file SymmetricBlockMatrix.h.

void gtsam::SymmetricBlockMatrix::invertInPlace ( )
inline

Invert the entire active matrix in place.

Definition at line 273 of file SymmetricBlockMatrix.h.

SymmetricBlockMatrix gtsam::SymmetricBlockMatrix::LikeActiveViewOf ( const SymmetricBlockMatrix other)
static

Copy the block structure, but do not copy the matrix data. If blockStart() has been modified, this copies the structure of the corresponding matrix view. In the destination SymmetricBlockMatrix, blockStart() will be 0.

Definition at line 28 of file SymmetricBlockMatrix.cpp.

SymmetricBlockMatrix gtsam::SymmetricBlockMatrix::LikeActiveViewOf ( const VerticalBlockMatrix other)
static

Copy the block structure, but do not copy the matrix data. If blockStart() has been modified, this copies the structure of the corresponding matrix view. In the destination SymmetricBlockMatrix, blockStart() will be 0.

Definition at line 41 of file SymmetricBlockMatrix.cpp.

DenseIndex gtsam::SymmetricBlockMatrix::nActualBlocks ( ) const
inlineprotected

Number of actual blocks in the full matrix.

Definition at line 320 of file SymmetricBlockMatrix.h.

DenseIndex gtsam::SymmetricBlockMatrix::nBlocks ( ) const
inline

Block count.

Definition at line 125 of file SymmetricBlockMatrix.h.

void gtsam::SymmetricBlockMatrix::negate ( )
inline

Negate the entire active matrix.

Definition at line 268 of file SymmetricBlockMatrix.h.

DenseIndex gtsam::SymmetricBlockMatrix::nOffsets ( ) const
inlineprotected

Number of offsets in the full matrix.

Definition at line 315 of file SymmetricBlockMatrix.h.

DenseIndex gtsam::SymmetricBlockMatrix::offset ( DenseIndex  block) const
inlineprotected

Get an offset for a block index (in the active view).

Definition at line 325 of file SymmetricBlockMatrix.h.

DenseIndex gtsam::SymmetricBlockMatrix::rows ( void  ) const
inline

Row size.

Definition at line 119 of file SymmetricBlockMatrix.h.

Eigen::SelfAdjointView<constBlock, Eigen::Upper> gtsam::SymmetricBlockMatrix::selfadjointView ( DenseIndex  I,
DenseIndex  J 
) const
inline

Return the square sub-matrix that contains blocks(i:j, i:j).

Definition at line 161 of file SymmetricBlockMatrix.h.

Eigen::SelfAdjointView<Block, Eigen::Upper> gtsam::SymmetricBlockMatrix::selfadjointView ( )
inline

Get self adjoint view.

Definition at line 247 of file SymmetricBlockMatrix.h.

Eigen::SelfAdjointView<constBlock, Eigen::Upper> gtsam::SymmetricBlockMatrix::selfadjointView ( ) const
inline

Get self adjoint view.

Definition at line 252 of file SymmetricBlockMatrix.h.

template<class ARCHIVE >
void gtsam::SymmetricBlockMatrix::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 404 of file SymmetricBlockMatrix.h.

template<typename XprType >
void gtsam::SymmetricBlockMatrix::setDiagonalBlock ( DenseIndex  I,
const XprType &  xpr 
)
inline

Set a diagonal block. Only the upper triangular portion of xpr is evaluated.

Definition at line 200 of file SymmetricBlockMatrix.h.

template<typename XprType >
void gtsam::SymmetricBlockMatrix::setFullMatrix ( const XprType &  xpr)
inline

Set the entire active matrix. Only reads the upper triangular part of xpr.

Definition at line 258 of file SymmetricBlockMatrix.h.

template<typename XprType >
void gtsam::SymmetricBlockMatrix::setOffDiagonalBlock ( DenseIndex  I,
DenseIndex  J,
const XprType &  xpr 
)
inline

Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated.

Definition at line 206 of file SymmetricBlockMatrix.h.

void gtsam::SymmetricBlockMatrix::setZero ( )
inline

Set the entire active matrix zero.

Definition at line 263 of file SymmetricBlockMatrix.h.

VerticalBlockMatrix gtsam::SymmetricBlockMatrix::split ( DenseIndex  nFrontals)

After partial Cholesky, we can optionally split off R and Sd, to be interpreted as a GaussianConditional |R*x1 + S*x2 - d]^2. We leave the symmetric lower block L in place, and adjust block_start so now *this refers to it.

Definition at line 74 of file SymmetricBlockMatrix.cpp.

Eigen::TriangularView<constBlock, Eigen::Upper> gtsam::SymmetricBlockMatrix::triangularView ( DenseIndex  I,
DenseIndex  J 
) const
inline

Return the square sub-matrix that contains blocks(i:j, i:j) as a triangular view.

Definition at line 168 of file SymmetricBlockMatrix.h.

template<typename XprType >
void gtsam::SymmetricBlockMatrix::updateDiagonalBlock ( DenseIndex  I,
const XprType &  xpr 
)
inline

Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr.

Definition at line 217 of file SymmetricBlockMatrix.h.

template<typename XprType >
void gtsam::SymmetricBlockMatrix::updateOffDiagonalBlock ( DenseIndex  I,
DenseIndex  J,
const XprType &  xpr 
)
inline

Update an off diagonal block. NOTE(emmett): This assumes noalias().

Definition at line 233 of file SymmetricBlockMatrix.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 402 of file SymmetricBlockMatrix.h.

template<typename SymmetricBlockMatrixType >
friend class SymmetricBlockMatrixBlockExpr
friend

Definition at line 398 of file SymmetricBlockMatrix.h.

friend class VerticalBlockMatrix
friend

Definition at line 397 of file SymmetricBlockMatrix.h.

Member Data Documentation

DenseIndex gtsam::SymmetricBlockMatrix::blockStart_
protected

Changes apparent matrix view, see main class comment.

Definition at line 62 of file SymmetricBlockMatrix.h.

Matrix gtsam::SymmetricBlockMatrix::matrix_
protected

The full matrix.

Definition at line 59 of file SymmetricBlockMatrix.h.

FastVector<DenseIndex> gtsam::SymmetricBlockMatrix::variableColOffsets_
protected

the starting columns of each block (0-based)

Definition at line 60 of file SymmetricBlockMatrix.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:31