VerticalBlockMatrix.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
18 #pragma once
19 
20 #include <gtsam/base/Matrix.h>
22 #include <gtsam/base/FastVector.h>
23 
24 #include <cassert>
25 
26 namespace gtsam {
27 
28  // Forward declarations
29  class SymmetricBlockMatrix;
30 
44  class GTSAM_EXPORT VerticalBlockMatrix
45  {
46  public:
50 
51  protected:
54 
58 
59  public:
61  VerticalBlockMatrix() : rowStart_(0), rowEnd_(0), blockStart_(0) {
62  variableColOffsets_.push_back(0);
63  }
64 
65  // Destructor
66  ~VerticalBlockMatrix() = default;
67 
68  // Copy constructor (default)
70 
71  // Copy assignment operator (default)
72  VerticalBlockMatrix& operator=(const VerticalBlockMatrix& other) = default;
73 
74  // Move constructor
76  : matrix_(std::move(other.matrix_)),
77  variableColOffsets_(std::move(other.variableColOffsets_)),
78  rowStart_(other.rowStart_),
79  rowEnd_(other.rowEnd_),
80  blockStart_(other.blockStart_) {
81  other.rowStart_ = 0;
82  other.rowEnd_ = 0;
83  other.blockStart_ = 0;
84  }
85 
86  // Move assignment operator
88  if (this != &other) {
89  matrix_ = std::move(other.matrix_);
90  variableColOffsets_ = std::move(other.variableColOffsets_);
91  rowStart_ = other.rowStart_;
92  rowEnd_ = other.rowEnd_;
93  blockStart_ = other.blockStart_;
94 
95  other.rowStart_ = 0;
96  other.rowEnd_ = 0;
97  other.blockStart_ = 0;
98  }
99  return *this;
100  }
101 
103  template<typename CONTAINER>
104  VerticalBlockMatrix(const CONTAINER& dimensions, DenseIndex height,
105  bool appendOneDimension = false) :
106  variableColOffsets_(dimensions.size() + (appendOneDimension ? 2 : 1)),
107  rowStart_(0), rowEnd_(height), blockStart_(0) {
108  fillOffsets(dimensions.begin(), dimensions.end(), appendOneDimension);
109  matrix_.resize(height, variableColOffsets_.back());
110  assertInvariants();
111  }
112 
114  template<typename CONTAINER, typename DERIVED>
115  VerticalBlockMatrix(const CONTAINER& dimensions,
116  const Eigen::MatrixBase<DERIVED>& matrix, bool appendOneDimension = false) :
117  matrix_(matrix), variableColOffsets_(dimensions.size() + (appendOneDimension ? 2 : 1)),
118  rowStart_(0), rowEnd_(matrix.rows()), blockStart_(0) {
119  fillOffsets(dimensions.begin(), dimensions.end(), appendOneDimension);
120  if (variableColOffsets_.back() != matrix_.cols())
121  throw std::invalid_argument(
122  "Requested to create a VerticalBlockMatrix with dimensions that do not sum to the total columns of the provided matrix.");
123  assertInvariants();
124  }
125 
127  template<typename ITERATOR>
128  VerticalBlockMatrix(ITERATOR firstBlockDim, ITERATOR lastBlockDim,
129  DenseIndex height, bool appendOneDimension = false) :
130  variableColOffsets_((lastBlockDim-firstBlockDim) + (appendOneDimension ? 2 : 1)),
131  rowStart_(0), rowEnd_(height), blockStart_(0) {
132  fillOffsets(firstBlockDim, lastBlockDim, appendOneDimension);
133  matrix_.resize(height, variableColOffsets_.back());
134  assertInvariants();
135  }
136 
142  static VerticalBlockMatrix LikeActiveViewOf(const VerticalBlockMatrix& rhs);
143 
147  static VerticalBlockMatrix LikeActiveViewOf(const SymmetricBlockMatrix& rhs, DenseIndex height);
148 
150  DenseIndex rows() const { assertInvariants(); return rowEnd_ - rowStart_; }
151 
153  DenseIndex cols() const { assertInvariants(); return variableColOffsets_.back() - variableColOffsets_[blockStart_]; }
154 
156  DenseIndex nBlocks() const { assertInvariants(); return variableColOffsets_.size() - 1 - blockStart_; }
157 
160 
162  const constBlock operator()(DenseIndex block) const { return range(block, block+1); }
163 
165  Block range(DenseIndex startBlock, DenseIndex endBlock) {
166  assertInvariants();
167  DenseIndex actualStartBlock = startBlock + blockStart_;
168  DenseIndex actualEndBlock = endBlock + blockStart_;
169  if(startBlock != 0 || endBlock != 0) {
170  checkBlock(actualStartBlock);
171  assert(actualEndBlock < (DenseIndex)variableColOffsets_.size());
172  }
173  const DenseIndex startCol = variableColOffsets_[actualStartBlock];
174  const DenseIndex rangeCols = variableColOffsets_[actualEndBlock] - startCol;
175  return matrix_.block(rowStart_, startCol, this->rows(), rangeCols);
176  }
177 
178  const constBlock range(DenseIndex startBlock, DenseIndex endBlock) const {
179  assertInvariants();
180  DenseIndex actualStartBlock = startBlock + blockStart_;
181  DenseIndex actualEndBlock = endBlock + blockStart_;
182  if(startBlock != 0 || endBlock != 0) {
183  checkBlock(actualStartBlock);
184  assert(actualEndBlock < (DenseIndex)variableColOffsets_.size());
185  }
186  const DenseIndex startCol = variableColOffsets_[actualStartBlock];
187  const DenseIndex rangeCols = variableColOffsets_[actualEndBlock] - startCol;
188  return ((const Matrix&)matrix_).block(rowStart_, startCol, this->rows(), rangeCols);
189  }
190 
192  Block full() { return range(0, nBlocks()); }
193 
195  const constBlock full() const { return range(0, nBlocks()); }
196 
198  assertInvariants();
199  DenseIndex actualBlock = block + blockStart_;
200  checkBlock(actualBlock);
201  return variableColOffsets_[actualBlock];
202  }
203 
205  const DenseIndex& rowStart() const { return rowStart_; }
206 
208  DenseIndex& rowStart() { return rowStart_; }
209 
211  const DenseIndex& rowEnd() const { return rowEnd_; }
212 
214  DenseIndex& rowEnd() { return rowEnd_; }
215 
217  const DenseIndex& firstBlock() const { return blockStart_; }
218 
220  DenseIndex& firstBlock() { return blockStart_; }
221 
223  const Matrix& matrix() const { return matrix_; }
224 
226  Matrix& matrix() { return matrix_; }
227 
228  protected:
229  void assertInvariants() const {
230  assert(matrix_.cols() == variableColOffsets_.back());
231  assert(blockStart_ < (DenseIndex)variableColOffsets_.size());
232  assert(rowStart_ <= matrix_.rows());
233  assert(rowEnd_ <= matrix_.rows());
234  assert(rowStart_ <= rowEnd_);
235  }
236 
238  static_cast<void>(block); //Disable unused varibale warnings.
239  assert(matrix_.cols() == variableColOffsets_.back());
240  assert(block < (DenseIndex)variableColOffsets_.size() - 1);
241  assert(variableColOffsets_[block] < matrix_.cols() && variableColOffsets_[block+1] <= matrix_.cols());
242  }
243 
244  template<typename ITERATOR>
245  void fillOffsets(ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension) {
246  variableColOffsets_[0] = 0;
247  DenseIndex j=0;
248  for(ITERATOR dim=firstBlockDim; dim!=lastBlockDim; ++dim, ++j)
249  variableColOffsets_[j+1] = variableColOffsets_[j] + *dim;
250  if(appendOneDimension)
251  variableColOffsets_[j+1] = variableColOffsets_[j] + 1;
252  }
253 
254  friend class SymmetricBlockMatrix;
255 
256  private:
257 #if GTSAM_ENABLE_BOOST_SERIALIZATION
258 
259  friend class boost::serialization::access;
260  template<class ARCHIVE>
261  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
262  ar & BOOST_SERIALIZATION_NVP(matrix_);
263  ar & BOOST_SERIALIZATION_NVP(variableColOffsets_);
264  ar & BOOST_SERIALIZATION_NVP(rowStart_);
265  ar & BOOST_SERIALIZATION_NVP(rowEnd_);
266  ar & BOOST_SERIALIZATION_NVP(blockStart_);
267  }
268 #endif
269  };
270 
271 }
gtsam::VerticalBlockMatrix::rowEnd
const DenseIndex & rowEnd() const
Definition: VerticalBlockMatrix.h:211
gtsam::VerticalBlockMatrix::firstBlock
DenseIndex & firstBlock()
Definition: VerticalBlockMatrix.h:220
gtsam::VerticalBlockMatrix::matrix_
Matrix matrix_
The full matrix.
Definition: VerticalBlockMatrix.h:52
MatrixSerialization.h
Serialization for matrices.
dimensions
const std::vector< size_t > dimensions
Definition: testVerticalBlockMatrix.cpp:27
Eigen::Block
Expression of a fixed-size or dynamic-size block.
Definition: Block.h:103
FastVector.h
A thin wrapper around std::vector that uses a custom allocator.
gtsam::VerticalBlockMatrix::operator=
VerticalBlockMatrix & operator=(VerticalBlockMatrix &&other) noexcept
Definition: VerticalBlockMatrix.h:87
gtsam::VerticalBlockMatrix::operator()
const constBlock operator()(DenseIndex block) const
Definition: VerticalBlockMatrix.h:162
gtsam::VerticalBlockMatrix::VerticalBlockMatrix
VerticalBlockMatrix(VerticalBlockMatrix &&other) noexcept
Definition: VerticalBlockMatrix.h:75
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
Matrix.h
typedef and functions to augment Eigen's MatrixXd
gtsam::VerticalBlockMatrix::range
Block range(DenseIndex startBlock, DenseIndex endBlock)
Definition: VerticalBlockMatrix.h:165
gtsam::VerticalBlockMatrix::blockStart_
DenseIndex blockStart_
Changes apparent matrix view, see main class comment.
Definition: VerticalBlockMatrix.h:57
gtsam::VerticalBlockMatrix::full
Block full()
Definition: VerticalBlockMatrix.h:192
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::VerticalBlockMatrix::Block
Eigen::Block< Matrix > Block
Definition: VerticalBlockMatrix.h:48
gtsam::VerticalBlockMatrix::VerticalBlockMatrix
VerticalBlockMatrix(const CONTAINER &dimensions, DenseIndex height, bool appendOneDimension=false)
Definition: VerticalBlockMatrix.h:104
rows
int rows
Definition: Tutorial_commainit_02.cpp:1
block
m m block(1, 0, 2, 2)<< 4
gtsam::VerticalBlockMatrix::range
const constBlock range(DenseIndex startBlock, DenseIndex endBlock) const
Definition: VerticalBlockMatrix.h:178
gtsam::VerticalBlockMatrix::rowEnd
DenseIndex & rowEnd()
Definition: VerticalBlockMatrix.h:214
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
gtsam::VerticalBlockMatrix::firstBlock
const DenseIndex & firstBlock() const
Definition: VerticalBlockMatrix.h:217
gtsam::VerticalBlockMatrix::rowStart
const DenseIndex & rowStart() const
Definition: VerticalBlockMatrix.h:205
gtsam::VerticalBlockMatrix::rowEnd_
DenseIndex rowEnd_
Changes apparent matrix view, see main class comment.
Definition: VerticalBlockMatrix.h:56
gtsam::VerticalBlockMatrix::variableColOffsets_
FastVector< DenseIndex > variableColOffsets_
the starting columns of each block (0-based)
Definition: VerticalBlockMatrix.h:53
gtsam::VerticalBlockMatrix
Definition: VerticalBlockMatrix.h:44
gtsam::VerticalBlockMatrix::rowStart
DenseIndex & rowStart()
Definition: VerticalBlockMatrix.h:208
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::VerticalBlockMatrix::VerticalBlockMatrix
VerticalBlockMatrix()
Definition: VerticalBlockMatrix.h:61
gtsam::VerticalBlockMatrix::nBlocks
DenseIndex nBlocks() const
Block count.
Definition: VerticalBlockMatrix.h:156
gtsam::VerticalBlockMatrix::VerticalBlockMatrix
VerticalBlockMatrix(const CONTAINER &dimensions, const Eigen::MatrixBase< DERIVED > &matrix, bool appendOneDimension=false)
Definition: VerticalBlockMatrix.h:115
gtsam::VerticalBlockMatrix::offset
DenseIndex offset(DenseIndex block) const
Definition: VerticalBlockMatrix.h:197
gtsam::VerticalBlockMatrix::This
VerticalBlockMatrix This
Definition: VerticalBlockMatrix.h:47
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
gtsam::VerticalBlockMatrix::matrix
Matrix & matrix()
Definition: VerticalBlockMatrix.h:226
gtsam::VerticalBlockMatrix::constBlock
Eigen::Block< const Matrix > constBlock
Definition: VerticalBlockMatrix.h:49
gtsam
traits
Definition: SFMdata.h:40
gtsam::VerticalBlockMatrix::cols
DenseIndex cols() const
Column size.
Definition: VerticalBlockMatrix.h:153
gtsam::VerticalBlockMatrix::full
const constBlock full() const
Definition: VerticalBlockMatrix.h:195
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
gtsam::VerticalBlockMatrix::matrix
const Matrix & matrix() const
Definition: VerticalBlockMatrix.h:223
gtsam::VerticalBlockMatrix::rows
DenseIndex rows() const
Row size.
Definition: VerticalBlockMatrix.h:150
gtsam::VerticalBlockMatrix::assertInvariants
void assertInvariants() const
Definition: VerticalBlockMatrix.h:229
gtsam::VerticalBlockMatrix::VerticalBlockMatrix
VerticalBlockMatrix(ITERATOR firstBlockDim, ITERATOR lastBlockDim, DenseIndex height, bool appendOneDimension=false)
Definition: VerticalBlockMatrix.h:128
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
gtsam::SymmetricBlockMatrix
Definition: SymmetricBlockMatrix.h:53
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::VerticalBlockMatrix::checkBlock
void checkBlock(DenseIndex block) const
Definition: VerticalBlockMatrix.h:237
gtsam::VerticalBlockMatrix::fillOffsets
void fillOffsets(ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension)
Definition: VerticalBlockMatrix.h:245
gtsam::VerticalBlockMatrix::operator()
Block operator()(DenseIndex block)
Definition: VerticalBlockMatrix.h:159
gtsam::VerticalBlockMatrix::rowStart_
DenseIndex rowStart_
Changes apparent matrix view, see main class comment.
Definition: VerticalBlockMatrix.h:55


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:09:02