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 
30 namespace gtsam {
31 
35 template <class CAMERA>
36 class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
37  protected:
38  using Base = std::vector<CAMERA, typename Eigen::aligned_allocator<CAMERA>>;
39 
44  typedef typename CAMERA::Measurement Z;
45  typedef typename CAMERA::MeasurementVector ZVector;
46 
47  static const int D = traits<CAMERA>::dimension;
48  static const int ZDim = traits<Z>::dimension;
49 
51  static Vector ErrorVector(const ZVector& predicted, const ZVector& measured) {
52  // Check size
53  size_t m = predicted.size();
54  if (measured.size() != m)
55  throw std::runtime_error("CameraSet::errors: size mismatch");
56 
57  // Project and fill error vector
58  Vector b(ZDim * m);
59  for (size_t i = 0, row = 0; i < m; i++, row += ZDim) {
60  Vector bi = traits<Z>::Local(measured[i], predicted[i]);
61  if (ZDim == 3 && std::isnan(bi(1))) { // if it is a stereo point and the
62  // right pixel is missing (nan)
63  bi(1) = 0;
64  }
65  b.segment<ZDim>(row) = bi;
66  }
67  return b;
68  }
69 
70  public:
71  using Base::Base; // Inherit the vector constructors
72 
74  virtual ~CameraSet() = default;
75 
78  using FBlocks = std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD>>;
79 
85  virtual void print(const std::string& s = "") const {
86  std::cout << s << "CameraSet, cameras = \n";
87  for (size_t k = 0; k < this->size(); ++k) this->at(k).print(s);
88  }
89 
91  bool equals(const CameraSet& p, double tol = 1e-9) const {
92  if (this->size() != p.size()) return false;
93  bool camerasAreEqual = true;
94  for (size_t i = 0; i < this->size(); i++) {
95  if (this->at(i).equals(p.at(i), tol) == false) camerasAreEqual = false;
96  break;
97  }
98  return camerasAreEqual;
99  }
100 
107  template <class POINT>
108  ZVector project2(const POINT& point, //
109  FBlocks* Fs = nullptr, //
110  Matrix* E = nullptr) const {
111  static const int N = FixedDimension<POINT>::value;
112 
113  // Allocate result
114  size_t m = this->size();
115  ZVector z;
116  z.reserve(m);
117 
118  // Allocate derivatives
119  if (E) E->resize(ZDim * m, N);
120  if (Fs) Fs->resize(m);
121 
122  // Project and fill derivatives
123  for (size_t i = 0; i < m; i++) {
124  MatrixZD Fi;
126  z.emplace_back(this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0));
127  if (Fs) (*Fs)[i] = Fi;
128  if (E) E->block<ZDim, N>(ZDim * i, 0) = Ei;
129  }
130 
131  return z;
132  }
133 
140  template <class POINT, class... OptArgs>
141  typename std::enable_if<(sizeof...(OptArgs) != 0), ZVector>::type project2(
142  const POINT& point, OptArgs&... args) const {
143  // pass it to the pointer version of the function
144  return project2(point, (&args)...);
145  }
146 
148  template <class POINT>
150  FBlocks* Fs = nullptr, //
151  Matrix* E = nullptr) const {
152  return ErrorVector(project2(point, Fs, E), measured);
153  }
154 
159  template <class POINT, class... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
161  OptArgs&... args) const {
162  // pass it to the pointer version of the function
163  return reprojectionError(point, measured, (&args)...);
164  }
165 
172  template <int N,
173  int ND> // N = 2 or 3 (point dimension), ND is the camera dimension
175  const std::vector<
178  const Matrix& E, const Eigen::Matrix<double, N, N>& P, const Vector& b) {
179  // a single point is observed in m cameras
180  size_t m = Fs.size();
181 
182  // Create a SymmetricBlockMatrix (augmented hessian, with extra row/column
183  // with info vector)
184  size_t M1 = ND * m + 1;
185  std::vector<DenseIndex> dims(m + 1); // this also includes the b term
186  std::fill(dims.begin(), dims.end() - 1, ND);
187  dims.back() = 1;
188  SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1));
189 
190  // Blockwise Schur complement
191  for (size_t i = 0; i < m; i++) { // for each camera
192 
193  const Eigen::Matrix<double, ZDim, ND>& Fi = Fs[i];
194  const auto FiT = Fi.transpose();
195  const Eigen::Matrix<double, ZDim, N> Ei_P = //
196  E.block(ZDim * i, 0, ZDim, N) * P;
197 
198  // D = (Dx2) * ZDim
199  augmentedHessian.setOffDiagonalBlock(
200  i, m,
201  FiT * b.segment<ZDim>(ZDim * i) // F' * b
202  -
203  FiT *
204  (Ei_P *
205  (E.transpose() *
206  b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
207 
208  // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
209  augmentedHessian.setDiagonalBlock(
210  i,
211  FiT * (Fi - Ei_P * E.block(ZDim * i, 0, ZDim, N).transpose() * Fi));
212 
213  // upper triangular part of the hessian
214  for (size_t j = i + 1; j < m; j++) { // for each camera
215  const Eigen::Matrix<double, ZDim, ND>& Fj = Fs[j];
216 
217  // (DxD) = (Dx2) * ( (2x2) * (2xD) )
218  augmentedHessian.setOffDiagonalBlock(
219  i, j,
220  -FiT * (Ei_P * E.block(ZDim * j, 0, ZDim, N).transpose() * Fj));
221  }
222  } // end of for over cameras
223 
224  augmentedHessian.diagonalBlock(m)(0, 0) += b.squaredNorm();
225  return augmentedHessian;
226  }
227 
241  template <int N, int ND, int NDD>
243  const std::vector<
246  const Matrix& E, const Eigen::Matrix<double, N, N>& P, const Vector& b,
247  const KeyVector& jacobianKeys, const KeyVector& hessianKeys) {
248  size_t nrNonuniqueKeys = jacobianKeys.size();
249  size_t nrUniqueKeys = hessianKeys.size();
250 
251  // Marginalize point: note - we reuse the standard SchurComplement function.
252  SymmetricBlockMatrix augmentedHessian = SchurComplement<N, ND>(Fs, E, P, b);
253 
254  // Pack into an Hessian factor, allow space for b term.
255  std::vector<DenseIndex> dims(nrUniqueKeys + 1);
256  std::fill(dims.begin(), dims.end() - 1, NDD);
257  dims.back() = 1;
258  SymmetricBlockMatrix augmentedHessianUniqueKeys;
259 
260  // Deal with the fact that some blocks may share the same keys.
261  if (nrUniqueKeys == nrNonuniqueKeys) {
262  // Case when there is 1 calibration key per camera:
263  augmentedHessianUniqueKeys = SymmetricBlockMatrix(
264  dims, Matrix(augmentedHessian.selfadjointView()));
265  } else {
266  // When multiple cameras share a calibration we have to rearrange
267  // the results of the Schur complement matrix.
268  std::vector<DenseIndex> nonuniqueDims(nrNonuniqueKeys + 1); // includes b
269  std::fill(nonuniqueDims.begin(), nonuniqueDims.end() - 1, NDD);
270  nonuniqueDims.back() = 1;
271  augmentedHessian = SymmetricBlockMatrix(
272  nonuniqueDims, Matrix(augmentedHessian.selfadjointView()));
273 
274  // Get map from key to location in the new augmented Hessian matrix (the
275  // one including only unique keys).
276  std::map<Key, size_t> keyToSlotMap;
277  for (size_t k = 0; k < nrUniqueKeys; k++) {
278  keyToSlotMap[hessianKeys[k]] = k;
279  }
280 
281  // Initialize matrix to zero.
282  augmentedHessianUniqueKeys = SymmetricBlockMatrix(
283  dims, Matrix::Zero(NDD * nrUniqueKeys + 1, NDD * nrUniqueKeys + 1));
284 
285  // Add contributions for each key: note this loops over the hessian with
286  // nonUnique keys (augmentedHessian) and populates an Hessian that only
287  // includes the unique keys (that is what we want to return).
288  for (size_t i = 0; i < nrNonuniqueKeys; i++) { // rows
289  Key key_i = jacobianKeys.at(i);
290 
291  // Update information vector.
292  augmentedHessianUniqueKeys.updateOffDiagonalBlock(
293  keyToSlotMap[key_i], nrUniqueKeys,
294  augmentedHessian.aboveDiagonalBlock(i, nrNonuniqueKeys));
295 
296  // Update blocks.
297  for (size_t j = i; j < nrNonuniqueKeys; j++) { // cols
298  Key key_j = jacobianKeys.at(j);
299  if (i == j) {
300  augmentedHessianUniqueKeys.updateDiagonalBlock(
301  keyToSlotMap[key_i], augmentedHessian.diagonalBlock(i));
302  } else { // (i < j)
303  if (keyToSlotMap[key_i] != keyToSlotMap[key_j]) {
304  augmentedHessianUniqueKeys.updateOffDiagonalBlock(
305  keyToSlotMap[key_i], keyToSlotMap[key_j],
306  augmentedHessian.aboveDiagonalBlock(i, j));
307  } else {
308  augmentedHessianUniqueKeys.updateDiagonalBlock(
309  keyToSlotMap[key_i],
310  augmentedHessian.aboveDiagonalBlock(i, j) +
311  augmentedHessian.aboveDiagonalBlock(i, j).transpose());
312  }
313  }
314  }
315  }
316 
317  // Update bottom right element of the matrix.
318  augmentedHessianUniqueKeys.updateDiagonalBlock(
319  nrUniqueKeys, augmentedHessian.diagonalBlock(nrNonuniqueKeys));
320  }
321  return augmentedHessianUniqueKeys;
322  }
323 
330 #ifdef _WIN32
331 #if _MSC_VER < 1937
332  template <int N> // N = 2 or 3
334  const FBlocks& Fs, const Matrix& E, const Eigen::Matrix<double, N, N>& P,
335  const Vector& b) {
336  return SchurComplement<N, D>(Fs, E, P, b);
337  }
338 #endif
339 #endif
340 
342  template <int N> // N = 2 or 3 (point dimension)
344  const Matrix& E, double lambda,
345  bool diagonalDamping = false) {
346  Matrix EtE = E.transpose() * E;
347 
348  if (diagonalDamping) { // diagonal of the hessian
349  EtE.diagonal() += lambda * EtE.diagonal();
350  } else {
351  DenseIndex n = E.cols();
352  EtE += lambda * Eigen::MatrixXd::Identity(n, n);
353  }
354 
355  P = (EtE).inverse();
356  }
357 
359  static Matrix PointCov(const Matrix& E, const double lambda = 0.0,
360  bool diagonalDamping = false) {
361  if (E.cols() == 2) {
362  Matrix2 P2;
363  ComputePointCovariance<2>(P2, E, lambda, diagonalDamping);
364  return P2;
365  } else {
366  Matrix3 P3;
367  ComputePointCovariance<3>(P3, E, lambda, diagonalDamping);
368  return P3;
369  }
370  }
371 
377  const Matrix& E, const Vector& b,
378  const double lambda = 0.0,
379  bool diagonalDamping = false) {
380  if (E.cols() == 2) {
381  Matrix2 P;
382  ComputePointCovariance<2>(P, E, lambda, diagonalDamping);
383  return SchurComplement<2>(Fblocks, E, P, b);
384  } else {
385  Matrix3 P;
386  ComputePointCovariance<3>(P, E, lambda, diagonalDamping);
387  return SchurComplement<3>(Fblocks, E, P, b);
388  }
389  }
390 
396  template <int N> // N = 2 or 3 (point dimension)
398  const FBlocks& Fs, const Matrix& E, const Eigen::Matrix<double, N, N>& P,
399  const Vector& b, const KeyVector& allKeys, const KeyVector& keys,
400  /*output ->*/ SymmetricBlockMatrix& augmentedHessian) {
401  assert(keys.size() == Fs.size());
402  assert(keys.size() <= allKeys.size());
403 
404  FastMap<Key, size_t> KeySlotMap;
405  for (size_t slot = 0; slot < allKeys.size(); slot++)
406  KeySlotMap.emplace(allKeys[slot], slot);
407 
408  // Schur complement trick
409  // G = F' * F - F' * E * P * E' * F
410  // g = F' * (b - E * P * E' * b)
411 
412  // a single point is observed in m cameras
413  size_t m = Fs.size(); // cameras observing current point
414  size_t M = (augmentedHessian.rows() - 1) / D; // all cameras in the group
415  assert(allKeys.size() == M);
416 
417  // Blockwise Schur complement
418  for (size_t i = 0; i < m; i++) { // for each camera in the current factor
419 
420  const MatrixZD& Fi = Fs[i];
421  const auto FiT = Fi.transpose();
422  const Eigen::Matrix<double, 2, N> Ei_P =
423  E.template block<ZDim, N>(ZDim * i, 0) * P;
424 
425  // D = (DxZDim) * (ZDim)
426  // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7)
427  // we should map those to a slot in the local (grouped) hessian
428  // (0,1,2,3,4) Key cameraKey_i = this->keys_[i];
429  DenseIndex aug_i = KeySlotMap.at(keys[i]);
430 
431  // information vector - store previous vector
432  // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal();
433  // add contribution of current factor
434  augmentedHessian.updateOffDiagonalBlock(
435  aug_i, M,
436  FiT * b.segment<ZDim>(ZDim * i) // F' * b
437  -
438  FiT *
439  (Ei_P *
440  (E.transpose() *
441  b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
442 
443  // (DxD) += (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
444  // add contribution of current factor
445  // Eigen doesn't let us pass the expression so we call eval()
446  augmentedHessian.updateDiagonalBlock(
447  aug_i,
448  ((FiT *
449  (Fi -
450  Ei_P * E.template block<ZDim, N>(ZDim * i, 0).transpose() * Fi)))
451  .eval());
452 
453  // upper triangular part of the hessian
454  for (size_t j = i + 1; j < m; j++) { // for each camera
455  const MatrixZD& Fj = Fs[j];
456 
457  DenseIndex aug_j = KeySlotMap.at(keys[j]);
458 
459  // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) )
460  // off diagonal block - store previous block
461  // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal();
462  // add contribution of current factor
463  augmentedHessian.updateOffDiagonalBlock(
464  aug_i, aug_j,
465  -FiT * (Ei_P * E.template block<ZDim, N>(ZDim * j, 0).transpose() *
466  Fj));
467  }
468  } // end of for over cameras
469 
470  augmentedHessian.diagonalBlock(M)(0, 0) += b.squaredNorm();
471  }
472 
473  private:
474 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
475  friend class boost::serialization::access;
477  template <class ARCHIVE>
478  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
479  ar&(*this);
480  }
481 #endif
482 
483  public:
485 };
486 
487 template <class CAMERA>
488 const int CameraSet<CAMERA>::D;
489 
490 template <class CAMERA>
491 const int CameraSet<CAMERA>::ZDim;
492 
493 template <class CAMERA>
494 struct traits<CameraSet<CAMERA>> : public Testable<CameraSet<CAMERA>> {};
495 
496 template <class CAMERA>
497 struct traits<const CameraSet<CAMERA>> : public Testable<CameraSet<CAMERA>> {};
498 
499 } // 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:359
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:397
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:376
gtsam::FastMap< Key, size_t >
gtsam::CameraSet::project2
ZVector project2(const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Definition: CameraSet.h:108
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:352
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:242
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
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:149
CalibratedCamera.h
Calibrated camera for which only pose is unknown.
gtsam::CameraSet
A set of cameras, all with their own calibration.
Definition: CameraSet.h:36
gtsam::CameraSet::print
virtual void print(const std::string &s="") const
Definition: CameraSet.h:85
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:160
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:174
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:141
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:91
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::CameraSet::ZVector
CAMERA::MeasurementVector ZVector
Definition: CameraSet.h:45
M1
MatrixXf M1
Definition: Tutorial_SlicingCol.cpp:1
gtsam::CameraSet::Z
CAMERA::Measurement Z
Definition: CameraSet.h:44
gtsam::CameraSet::ZDim
static const int ZDim
Measurement dimension.
Definition: CameraSet.h:48
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:47
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:51
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:78
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:343
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 Sat Nov 16 2024 04:01:57