CameraSet.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 
19 #pragma once
20 
21 #include <gtsam/base/FastMap.h>
23 #include <gtsam/base/Testable.h>
24 #include <gtsam/geometry/CalibratedCamera.h> // for Cheirality exception
25 #include <gtsam/geometry/Point3.h>
26 #include <gtsam/inference/Key.h>
27 
28 #include <vector>
29 #include <cassert>
30 
31 namespace gtsam {
32 
36 template <class CAMERA>
37 class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
38  protected:
39  using Base = std::vector<CAMERA, typename Eigen::aligned_allocator<CAMERA>>;
40 
45  typedef typename CAMERA::Measurement Z;
46  typedef typename CAMERA::MeasurementVector ZVector;
47 
48  static const int D = traits<CAMERA>::dimension;
49  static const int ZDim = traits<Z>::dimension;
50 
52  static Vector ErrorVector(const ZVector& predicted, const ZVector& measured) {
53  // Check size
54  size_t m = predicted.size();
55  if (measured.size() != m)
56  throw std::runtime_error("CameraSet::errors: size mismatch");
57 
58  // Project and fill error vector
59  Vector b(ZDim * m);
60  for (size_t i = 0, row = 0; i < m; i++, row += ZDim) {
61  Vector bi = traits<Z>::Local(measured[i], predicted[i]);
62  if (ZDim == 3 && std::isnan(bi(1))) { // if it is a stereo point and the
63  // right pixel is missing (nan)
64  bi(1) = 0;
65  }
66  b.segment<ZDim>(row) = bi;
67  }
68  return b;
69  }
70 
71  public:
72  using Base::Base; // Inherit the vector constructors
73 
75  virtual ~CameraSet() = default;
76 
79  using FBlocks = std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD>>;
80 
86  virtual void print(const std::string& s = "") const {
87  std::cout << s << "CameraSet, cameras = \n";
88  for (size_t k = 0; k < this->size(); ++k) this->at(k).print(s);
89  }
90 
92  bool equals(const CameraSet& p, double tol = 1e-9) const {
93  if (this->size() != p.size()) return false;
94  bool camerasAreEqual = true;
95  for (size_t i = 0; i < this->size(); i++) {
96  if (this->at(i).equals(p.at(i), tol) == false) camerasAreEqual = false;
97  break;
98  }
99  return camerasAreEqual;
100  }
101 
108  template <class POINT>
109  ZVector project2(const POINT& point, //
110  FBlocks* Fs = nullptr, //
111  Matrix* E = nullptr) const {
112  static const int N = FixedDimension<POINT>::value;
113 
114  // Allocate result
115  size_t m = this->size();
116  ZVector z;
117  z.reserve(m);
118 
119  // Allocate derivatives
120  if (E) E->resize(ZDim * m, N);
121  if (Fs) Fs->resize(m);
122 
123  // Project and fill derivatives
124  for (size_t i = 0; i < m; i++) {
125  MatrixZD Fi;
127  z.emplace_back(this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0));
128  if (Fs) (*Fs)[i] = Fi;
129  if (E) E->block<ZDim, N>(ZDim * i, 0) = Ei;
130  }
131 
132  return z;
133  }
134 
141  template <class POINT, class... OptArgs>
142  typename std::enable_if<(sizeof...(OptArgs) != 0), ZVector>::type project2(
143  const POINT& point, OptArgs&... args) const {
144  // pass it to the pointer version of the function
145  return project2(point, (&args)...);
146  }
147 
149  template <class POINT>
151  FBlocks* Fs = nullptr, //
152  Matrix* E = nullptr) const {
153  return ErrorVector(project2(point, Fs, E), measured);
154  }
155 
160  template <class POINT, class... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
162  OptArgs&... args) const {
163  // pass it to the pointer version of the function
164  return reprojectionError(point, measured, (&args)...);
165  }
166 
173  template <int N,
174  int ND> // N = 2 or 3 (point dimension), ND is the camera dimension
176  const std::vector<
179  const Matrix& E, const Eigen::Matrix<double, N, N>& P, const Vector& b) {
180  // a single point is observed in m cameras
181  size_t m = Fs.size();
182 
183  // Create a SymmetricBlockMatrix (augmented hessian, with extra row/column
184  // with info vector)
185  size_t M1 = ND * m + 1;
186  std::vector<DenseIndex> dims(m + 1); // this also includes the b term
187  std::fill(dims.begin(), dims.end() - 1, ND);
188  dims.back() = 1;
189  SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1));
190 
191  // Blockwise Schur complement
192  for (size_t i = 0; i < m; i++) { // for each camera
193 
194  const Eigen::Matrix<double, ZDim, ND>& Fi = Fs[i];
195  const auto FiT = Fi.transpose();
196  const Eigen::Matrix<double, ZDim, N> Ei_P = //
197  E.block(ZDim * i, 0, ZDim, N) * P;
198 
199  // D = (Dx2) * ZDim
200  augmentedHessian.setOffDiagonalBlock(
201  i, m,
202  FiT * b.segment<ZDim>(ZDim * i) // F' * b
203  -
204  FiT *
205  (Ei_P *
206  (E.transpose() *
207  b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
208 
209  // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
210  augmentedHessian.setDiagonalBlock(
211  i,
212  FiT * (Fi - Ei_P * E.block(ZDim * i, 0, ZDim, N).transpose() * Fi));
213 
214  // upper triangular part of the hessian
215  for (size_t j = i + 1; j < m; j++) { // for each camera
216  const Eigen::Matrix<double, ZDim, ND>& Fj = Fs[j];
217 
218  // (DxD) = (Dx2) * ( (2x2) * (2xD) )
219  augmentedHessian.setOffDiagonalBlock(
220  i, j,
221  -FiT * (Ei_P * E.block(ZDim * j, 0, ZDim, N).transpose() * Fj));
222  }
223  } // end of for over cameras
224 
225  augmentedHessian.diagonalBlock(m)(0, 0) += b.squaredNorm();
226  return augmentedHessian;
227  }
228 
242  template <int N, int ND, int NDD>
244  const std::vector<
247  const Matrix& E, const Eigen::Matrix<double, N, N>& P, const Vector& b,
248  const KeyVector& jacobianKeys, const KeyVector& hessianKeys) {
249  size_t nrNonuniqueKeys = jacobianKeys.size();
250  size_t nrUniqueKeys = hessianKeys.size();
251 
252  // Marginalize point: note - we reuse the standard SchurComplement function.
253  SymmetricBlockMatrix augmentedHessian = SchurComplement<N, ND>(Fs, E, P, b);
254 
255  // Pack into an Hessian factor, allow space for b term.
256  std::vector<DenseIndex> dims(nrUniqueKeys + 1);
257  std::fill(dims.begin(), dims.end() - 1, NDD);
258  dims.back() = 1;
259  SymmetricBlockMatrix augmentedHessianUniqueKeys;
260 
261  // Deal with the fact that some blocks may share the same keys.
262  if (nrUniqueKeys == nrNonuniqueKeys) {
263  // Case when there is 1 calibration key per camera:
264  augmentedHessianUniqueKeys = SymmetricBlockMatrix(
265  dims, Matrix(augmentedHessian.selfadjointView()));
266  } else {
267  // When multiple cameras share a calibration we have to rearrange
268  // the results of the Schur complement matrix.
269  std::vector<DenseIndex> nonuniqueDims(nrNonuniqueKeys + 1); // includes b
270  std::fill(nonuniqueDims.begin(), nonuniqueDims.end() - 1, NDD);
271  nonuniqueDims.back() = 1;
272  augmentedHessian = SymmetricBlockMatrix(
273  nonuniqueDims, Matrix(augmentedHessian.selfadjointView()));
274 
275  // Get map from key to location in the new augmented Hessian matrix (the
276  // one including only unique keys).
277  std::map<Key, size_t> keyToSlotMap;
278  for (size_t k = 0; k < nrUniqueKeys; k++) {
279  keyToSlotMap[hessianKeys[k]] = k;
280  }
281 
282  // Initialize matrix to zero.
283  augmentedHessianUniqueKeys = SymmetricBlockMatrix(
284  dims, Matrix::Zero(NDD * nrUniqueKeys + 1, NDD * nrUniqueKeys + 1));
285 
286  // Add contributions for each key: note this loops over the hessian with
287  // nonUnique keys (augmentedHessian) and populates an Hessian that only
288  // includes the unique keys (that is what we want to return).
289  for (size_t i = 0; i < nrNonuniqueKeys; i++) { // rows
290  Key key_i = jacobianKeys.at(i);
291 
292  // Update information vector.
293  augmentedHessianUniqueKeys.updateOffDiagonalBlock(
294  keyToSlotMap[key_i], nrUniqueKeys,
295  augmentedHessian.aboveDiagonalBlock(i, nrNonuniqueKeys));
296 
297  // Update blocks.
298  for (size_t j = i; j < nrNonuniqueKeys; j++) { // cols
299  Key key_j = jacobianKeys.at(j);
300  if (i == j) {
301  augmentedHessianUniqueKeys.updateDiagonalBlock(
302  keyToSlotMap[key_i], augmentedHessian.diagonalBlock(i));
303  } else { // (i < j)
304  if (keyToSlotMap[key_i] != keyToSlotMap[key_j]) {
305  augmentedHessianUniqueKeys.updateOffDiagonalBlock(
306  keyToSlotMap[key_i], keyToSlotMap[key_j],
307  augmentedHessian.aboveDiagonalBlock(i, j));
308  } else {
309  augmentedHessianUniqueKeys.updateDiagonalBlock(
310  keyToSlotMap[key_i],
311  augmentedHessian.aboveDiagonalBlock(i, j) +
312  augmentedHessian.aboveDiagonalBlock(i, j).transpose());
313  }
314  }
315  }
316  }
317 
318  // Update bottom right element of the matrix.
319  augmentedHessianUniqueKeys.updateDiagonalBlock(
320  nrUniqueKeys, augmentedHessian.diagonalBlock(nrNonuniqueKeys));
321  }
322  return augmentedHessianUniqueKeys;
323  }
324 
331 #ifdef _WIN32
332 #if _MSC_VER < 1937
333  template <int N> // N = 2 or 3
335  const FBlocks& Fs, const Matrix& E, const Eigen::Matrix<double, N, N>& P,
336  const Vector& b) {
337  return SchurComplement<N, D>(Fs, E, P, b);
338  }
339 #endif
340 #endif
341 
343  template <int N> // N = 2 or 3 (point dimension)
345  const Matrix& E, double lambda,
346  bool diagonalDamping = false) {
347  Matrix EtE = E.transpose() * E;
348 
349  if (diagonalDamping) { // diagonal of the hessian
350  EtE.diagonal() += lambda * EtE.diagonal();
351  } else {
352  DenseIndex n = E.cols();
353  EtE += lambda * Eigen::MatrixXd::Identity(n, n);
354  }
355 
356  P = (EtE).inverse();
357  }
358 
360  static Matrix PointCov(const Matrix& E, const double lambda = 0.0,
361  bool diagonalDamping = false) {
362  if (E.cols() == 2) {
363  Matrix2 P2;
364  ComputePointCovariance<2>(P2, E, lambda, diagonalDamping);
365  return P2;
366  } else {
367  Matrix3 P3;
368  ComputePointCovariance<3>(P3, E, lambda, diagonalDamping);
369  return P3;
370  }
371  }
372 
378  const Matrix& E, const Vector& b,
379  const double lambda = 0.0,
380  bool diagonalDamping = false) {
381  if (E.cols() == 2) {
382  Matrix2 P;
383  ComputePointCovariance<2>(P, E, lambda, diagonalDamping);
384  return SchurComplement<2>(Fblocks, E, P, b);
385  } else {
386  Matrix3 P;
387  ComputePointCovariance<3>(P, E, lambda, diagonalDamping);
388  return SchurComplement<3>(Fblocks, E, P, b);
389  }
390  }
391 
397  template <int N> // N = 2 or 3 (point dimension)
399  const FBlocks& Fs, const Matrix& E, const Eigen::Matrix<double, N, N>& P,
400  const Vector& b, const KeyVector& allKeys, const KeyVector& keys,
401  /*output ->*/ SymmetricBlockMatrix& augmentedHessian) {
402  assert(keys.size() == Fs.size());
403  assert(keys.size() <= allKeys.size());
404 
405  FastMap<Key, size_t> KeySlotMap;
406  for (size_t slot = 0; slot < allKeys.size(); slot++)
407  KeySlotMap.emplace(allKeys[slot], slot);
408 
409  // Schur complement trick
410  // G = F' * F - F' * E * P * E' * F
411  // g = F' * (b - E * P * E' * b)
412 
413  // a single point is observed in m cameras
414  size_t m = Fs.size(); // cameras observing current point
415  size_t M = (augmentedHessian.rows() - 1) / D; // all cameras in the group
416  assert(allKeys.size() == M);
417 
418  // Blockwise Schur complement
419  for (size_t i = 0; i < m; i++) { // for each camera in the current factor
420 
421  const MatrixZD& Fi = Fs[i];
422  const auto FiT = Fi.transpose();
423  const Eigen::Matrix<double, 2, N> Ei_P =
424  E.template block<ZDim, N>(ZDim * i, 0) * P;
425 
426  // D = (DxZDim) * (ZDim)
427  // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7)
428  // we should map those to a slot in the local (grouped) hessian
429  // (0,1,2,3,4) Key cameraKey_i = this->keys_[i];
430  DenseIndex aug_i = KeySlotMap.at(keys[i]);
431 
432  // information vector - store previous vector
433  // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal();
434  // add contribution of current factor
435  augmentedHessian.updateOffDiagonalBlock(
436  aug_i, M,
437  FiT * b.segment<ZDim>(ZDim * i) // F' * b
438  -
439  FiT *
440  (Ei_P *
441  (E.transpose() *
442  b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
443 
444  // (DxD) += (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
445  // add contribution of current factor
446  // Eigen doesn't let us pass the expression so we call eval()
447  augmentedHessian.updateDiagonalBlock(
448  aug_i,
449  ((FiT *
450  (Fi -
451  Ei_P * E.template block<ZDim, N>(ZDim * i, 0).transpose() * Fi)))
452  .eval());
453 
454  // upper triangular part of the hessian
455  for (size_t j = i + 1; j < m; j++) { // for each camera
456  const MatrixZD& Fj = Fs[j];
457 
458  DenseIndex aug_j = KeySlotMap.at(keys[j]);
459 
460  // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) )
461  // off diagonal block - store previous block
462  // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal();
463  // add contribution of current factor
464  augmentedHessian.updateOffDiagonalBlock(
465  aug_i, aug_j,
466  -FiT * (Ei_P * E.template block<ZDim, N>(ZDim * j, 0).transpose() *
467  Fj));
468  }
469  } // end of for over cameras
470 
471  augmentedHessian.diagonalBlock(M)(0, 0) += b.squaredNorm();
472  }
473 
474  private:
475 #if GTSAM_ENABLE_BOOST_SERIALIZATION
476  friend class boost::serialization::access;
478  template <class ARCHIVE>
479  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
480  ar&(*this);
481  }
482 #endif
483 
484  public:
486 };
487 
488 template <class CAMERA>
489 const int CameraSet<CAMERA>::D;
490 
491 template <class CAMERA>
492 const int CameraSet<CAMERA>::ZDim;
493 
494 template <class CAMERA>
495 struct traits<CameraSet<CAMERA>> : public Testable<CameraSet<CAMERA>> {};
496 
497 template <class CAMERA>
498 struct traits<const CameraSet<CAMERA>> : public Testable<CameraSet<CAMERA>> {};
499 
500 } // namespace gtsam
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
gtsam::CameraSet::PointCov
static Matrix PointCov(const Matrix &E, const double lambda=0.0, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter, dynamic version.
Definition: CameraSet.h:360
gtsam::SymmetricBlockMatrix::setOffDiagonalBlock
void setOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated.
Definition: SymmetricBlockMatrix.h:203
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::CameraSet::UpdateSchurComplement
static void UpdateSchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &allKeys, const KeyVector &keys, SymmetricBlockMatrix &augmentedHessian)
Definition: CameraSet.h:398
Testable.h
Concept check for values that can be used in unit tests.
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::CameraSet::SchurComplement
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fblocks, const Matrix &E, const Vector &b, const double lambda=0.0, bool diagonalDamping=false)
Definition: CameraSet.h:377
gtsam::FastMap< Key, size_t >
gtsam::CameraSet::project2
ZVector project2(const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Definition: CameraSet.h:109
measured
Point2 measured(-17, 30)
type
Definition: pytypes.h:1525
gtsam::SymmetricBlockMatrix::selfadjointView
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
Definition: SymmetricBlockMatrix.h:158
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::SymmetricBlockMatrix::setDiagonalBlock
void setDiagonalBlock(DenseIndex I, const XprType &xpr)
Set a diagonal block. Only the upper triangular portion of xpr is evaluated.
Definition: SymmetricBlockMatrix.h:197
Point3.h
3D Point
isnan
#define isnan(X)
Definition: main.h:93
gtsam::P3
static const Matrix93 P3
Definition: SO3.cpp:404
gtsam::CameraSet::SchurComplementAndRearrangeBlocks
static SymmetricBlockMatrix SchurComplementAndRearrangeBlocks(const std::vector< Eigen::Matrix< double, ZDim, ND >, Eigen::aligned_allocator< Eigen::Matrix< double, ZDim, ND >>> &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &jacobianKeys, const KeyVector &hessianKeys)
Definition: CameraSet.h:243
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::CameraSet::reprojectionError
Vector reprojectionError(const POINT &point, const ZVector &measured, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Calculate vector [project2(point)-z] of re-projection errors.
Definition: CameraSet.h:150
CalibratedCamera.h
Calibrated camera for which only pose is unknown.
gtsam::CameraSet
A set of cameras, all with their own calibration.
Definition: CameraSet.h:37
gtsam::CameraSet::print
virtual void print(const std::string &s="") const
Definition: CameraSet.h:86
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
n
int n
Definition: BiCGSTAB_simple.cpp:1
Key.h
simulated2D::Measurement
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:278
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
Eigen::aligned_allocator
STL compatible allocator to use with types requiring a non standrad alignment.
Definition: Memory.h:878
FBlocks
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Definition: testSmartProjectionPoseFactorRollingShutter.cpp:222
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::CameraSet::reprojectionError
Vector reprojectionError(const POINT &point, const ZVector &measured, OptArgs &... args) const
Definition: CameraSet.h:161
gtsam::row
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
gtsam::CameraSet::SchurComplement
static SymmetricBlockMatrix SchurComplement(const std::vector< Eigen::Matrix< double, ZDim, ND >, Eigen::aligned_allocator< Eigen::Matrix< double, ZDim, ND >>> &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
Definition: CameraSet.h:175
SymmetricBlockMatrix.h
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
gtsam::CameraSet::project2
std::enable_if<(sizeof...(OptArgs) !=0), ZVector >::type project2(const POINT &point, OptArgs &... args) const
Definition: CameraSet.h:142
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::CameraSet::equals
bool equals(const CameraSet &p, double tol=1e-9) const
equals
Definition: CameraSet.h:92
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::CameraSet::ZVector
CAMERA::MeasurementVector ZVector
Definition: CameraSet.h:46
M1
MatrixXf M1
Definition: Tutorial_SlicingCol.cpp:1
gtsam::CameraSet::Z
CAMERA::Measurement Z
Definition: CameraSet.h:45
gtsam::CameraSet::ZDim
static const int ZDim
Measurement dimension.
Definition: CameraSet.h:49
lambda
static double lambda[]
Definition: jv.c:524
gtsam::SymmetricBlockMatrix::rows
DenseIndex rows() const
Row size.
Definition: SymmetricBlockMatrix.h:116
E
DiscreteKey E(5, 2)
gtsam::b
const G & b
Definition: Group.h:79
gtsam::SymmetricBlockMatrix::updateDiagonalBlock
void updateDiagonalBlock(DenseIndex I, const XprType &xpr)
Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr.
Definition: SymmetricBlockMatrix.h:214
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
gtsam::SymmetricBlockMatrix::updateOffDiagonalBlock
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Definition: SymmetricBlockMatrix.h:230
args
Definition: pytypes.h:2210
gtsam::CameraSet::D
static const int D
Camera dimension.
Definition: CameraSet.h:48
p
float * p
Definition: Tutorial_Map_using.cpp:9
Base::Base
Base()=default
gtsam::SymmetricBlockMatrix::diagonalBlock
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J'th diagonal block as a self adjoint view.
Definition: SymmetricBlockMatrix.h:137
P
static double P[]
Definition: ellpe.c:68
gtsam::tol
const G double tol
Definition: Group.h:79
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
N
#define N
Definition: igam.h:9
gtsam::FixedDimension
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:161
gtsam::SymmetricBlockMatrix::aboveDiagonalBlock
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
Definition: SymmetricBlockMatrix.h:152
Base
Definition: test_virtual_functions.cpp:156
gtsam::CameraSet::ErrorVector
static Vector ErrorVector(const ZVector &predicted, const ZVector &measured)
Make a vector of re-projection errors.
Definition: CameraSet.h:52
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::SymmetricBlockMatrix
Definition: SymmetricBlockMatrix.h:53
enable_if_t
typename std::enable_if< B, T >::type enable_if_t
from cpp_future import (convenient aliases from C++14/17)
Definition: wrap/pybind11/include/pybind11/detail/common.h:654
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::CameraSet::FBlocks
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Definition: CameraSet.h:79
gtsam::CameraSet::ComputePointCovariance
static void ComputePointCovariance(Eigen::Matrix< double, N, N > &P, const Matrix &E, double lambda, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter.
Definition: CameraSet.h:344
P2
static double P2[]
Definition: jv.c:557
FastMap.h
A thin wrapper around std::map that uses boost's fast_pool_allocator.
gtsam::CameraSet::~CameraSet
virtual ~CameraSet()=default
Destructor.
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Wed Jan 1 2025 04:01:13