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 
138  template <class POINT, class... OptArgs>
139  ZVector project2(const POINT& point, OptArgs&... args) const {
140  // pass it to the pointer version of the function
141  return project2(point, (&args)...);
142  }
143 
145  template <class POINT>
146  Vector reprojectionError(const POINT& point, const ZVector& measured,
147  FBlocks* Fs = nullptr, //
148  Matrix* E = nullptr) const {
149  return ErrorVector(project2(point, Fs, E), measured);
150  }
151 
156  template <class POINT, class... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
157  Vector reprojectionError(const POINT& point, const ZVector& measured,
158  OptArgs&... args) const {
159  // pass it to the pointer version of the function
160  return reprojectionError(point, measured, (&args)...);
161  }
162 
169  template <int N,
170  int ND> // N = 2 or 3 (point dimension), ND is the camera dimension
172  const std::vector<
175  const Matrix& E, const Eigen::Matrix<double, N, N>& P, const Vector& b) {
176  // a single point is observed in m cameras
177  size_t m = Fs.size();
178 
179  // Create a SymmetricBlockMatrix (augmented hessian, with extra row/column
180  // with info vector)
181  size_t M1 = ND * m + 1;
182  std::vector<DenseIndex> dims(m + 1); // this also includes the b term
183  std::fill(dims.begin(), dims.end() - 1, ND);
184  dims.back() = 1;
185  SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1));
186 
187  // Blockwise Schur complement
188  for (size_t i = 0; i < m; i++) { // for each camera
189 
190  const Eigen::Matrix<double, ZDim, ND>& Fi = Fs[i];
191  const auto FiT = Fi.transpose();
192  const Eigen::Matrix<double, ZDim, N> Ei_P = //
193  E.block(ZDim * i, 0, ZDim, N) * P;
194 
195  // D = (Dx2) * ZDim
196  augmentedHessian.setOffDiagonalBlock(
197  i, m,
198  FiT * b.segment<ZDim>(ZDim * i) // F' * b
199  -
200  FiT *
201  (Ei_P *
202  (E.transpose() *
203  b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
204 
205  // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
206  augmentedHessian.setDiagonalBlock(
207  i,
208  FiT * (Fi - Ei_P * E.block(ZDim * i, 0, ZDim, N).transpose() * Fi));
209 
210  // upper triangular part of the hessian
211  for (size_t j = i + 1; j < m; j++) { // for each camera
212  const Eigen::Matrix<double, ZDim, ND>& Fj = Fs[j];
213 
214  // (DxD) = (Dx2) * ( (2x2) * (2xD) )
215  augmentedHessian.setOffDiagonalBlock(
216  i, j,
217  -FiT * (Ei_P * E.block(ZDim * j, 0, ZDim, N).transpose() * Fj));
218  }
219  } // end of for over cameras
220 
221  augmentedHessian.diagonalBlock(m)(0, 0) += b.squaredNorm();
222  return augmentedHessian;
223  }
224 
238  template <int N, int ND, int NDD>
240  const std::vector<
243  const Matrix& E, const Eigen::Matrix<double, N, N>& P, const Vector& b,
244  const KeyVector& jacobianKeys, const KeyVector& hessianKeys) {
245  size_t nrNonuniqueKeys = jacobianKeys.size();
246  size_t nrUniqueKeys = hessianKeys.size();
247 
248  // Marginalize point: note - we reuse the standard SchurComplement function.
249  SymmetricBlockMatrix augmentedHessian = SchurComplement<N, ND>(Fs, E, P, b);
250 
251  // Pack into an Hessian factor, allow space for b term.
252  std::vector<DenseIndex> dims(nrUniqueKeys + 1);
253  std::fill(dims.begin(), dims.end() - 1, NDD);
254  dims.back() = 1;
255  SymmetricBlockMatrix augmentedHessianUniqueKeys;
256 
257  // Deal with the fact that some blocks may share the same keys.
258  if (nrUniqueKeys == nrNonuniqueKeys) {
259  // Case when there is 1 calibration key per camera:
260  augmentedHessianUniqueKeys = SymmetricBlockMatrix(
261  dims, Matrix(augmentedHessian.selfadjointView()));
262  } else {
263  // When multiple cameras share a calibration we have to rearrange
264  // the results of the Schur complement matrix.
265  std::vector<DenseIndex> nonuniqueDims(nrNonuniqueKeys + 1); // includes b
266  std::fill(nonuniqueDims.begin(), nonuniqueDims.end() - 1, NDD);
267  nonuniqueDims.back() = 1;
268  augmentedHessian = SymmetricBlockMatrix(
269  nonuniqueDims, Matrix(augmentedHessian.selfadjointView()));
270 
271  // Get map from key to location in the new augmented Hessian matrix (the
272  // one including only unique keys).
273  std::map<Key, size_t> keyToSlotMap;
274  for (size_t k = 0; k < nrUniqueKeys; k++) {
275  keyToSlotMap[hessianKeys[k]] = k;
276  }
277 
278  // Initialize matrix to zero.
279  augmentedHessianUniqueKeys = SymmetricBlockMatrix(
280  dims, Matrix::Zero(NDD * nrUniqueKeys + 1, NDD * nrUniqueKeys + 1));
281 
282  // Add contributions for each key: note this loops over the hessian with
283  // nonUnique keys (augmentedHessian) and populates an Hessian that only
284  // includes the unique keys (that is what we want to return).
285  for (size_t i = 0; i < nrNonuniqueKeys; i++) { // rows
286  Key key_i = jacobianKeys.at(i);
287 
288  // Update information vector.
289  augmentedHessianUniqueKeys.updateOffDiagonalBlock(
290  keyToSlotMap[key_i], nrUniqueKeys,
291  augmentedHessian.aboveDiagonalBlock(i, nrNonuniqueKeys));
292 
293  // Update blocks.
294  for (size_t j = i; j < nrNonuniqueKeys; j++) { // cols
295  Key key_j = jacobianKeys.at(j);
296  if (i == j) {
297  augmentedHessianUniqueKeys.updateDiagonalBlock(
298  keyToSlotMap[key_i], augmentedHessian.diagonalBlock(i));
299  } else { // (i < j)
300  if (keyToSlotMap[key_i] != keyToSlotMap[key_j]) {
301  augmentedHessianUniqueKeys.updateOffDiagonalBlock(
302  keyToSlotMap[key_i], keyToSlotMap[key_j],
303  augmentedHessian.aboveDiagonalBlock(i, j));
304  } else {
305  augmentedHessianUniqueKeys.updateDiagonalBlock(
306  keyToSlotMap[key_i],
307  augmentedHessian.aboveDiagonalBlock(i, j) +
308  augmentedHessian.aboveDiagonalBlock(i, j).transpose());
309  }
310  }
311  }
312  }
313 
314  // Update bottom right element of the matrix.
315  augmentedHessianUniqueKeys.updateDiagonalBlock(
316  nrUniqueKeys, augmentedHessian.diagonalBlock(nrNonuniqueKeys));
317  }
318  return augmentedHessianUniqueKeys;
319  }
320 
327  template <int N> // N = 2 or 3
329  const FBlocks& Fs, const Matrix& E, const Eigen::Matrix<double, N, N>& P,
330  const Vector& b) {
331  return SchurComplement<N, D>(Fs, E, P, b);
332  }
333 
335  template <int N> // N = 2 or 3 (point dimension)
337  const Matrix& E, double lambda,
338  bool diagonalDamping = false) {
339  Matrix EtE = E.transpose() * E;
340 
341  if (diagonalDamping) { // diagonal of the hessian
342  EtE.diagonal() += lambda * EtE.diagonal();
343  } else {
344  DenseIndex n = E.cols();
345  EtE += lambda * Eigen::MatrixXd::Identity(n, n);
346  }
347 
348  P = (EtE).inverse();
349  }
350 
352  static Matrix PointCov(const Matrix& E, const double lambda = 0.0,
353  bool diagonalDamping = false) {
354  if (E.cols() == 2) {
355  Matrix2 P2;
356  ComputePointCovariance<2>(P2, E, lambda, diagonalDamping);
357  return P2;
358  } else {
359  Matrix3 P3;
360  ComputePointCovariance<3>(P3, E, lambda, diagonalDamping);
361  return P3;
362  }
363  }
364 
370  const Matrix& E, const Vector& b,
371  const double lambda = 0.0,
372  bool diagonalDamping = false) {
373  if (E.cols() == 2) {
374  Matrix2 P;
375  ComputePointCovariance<2>(P, E, lambda, diagonalDamping);
376  return SchurComplement<2>(Fblocks, E, P, b);
377  } else {
378  Matrix3 P;
379  ComputePointCovariance<3>(P, E, lambda, diagonalDamping);
380  return SchurComplement<3>(Fblocks, E, P, b);
381  }
382  }
383 
389  template <int N> // N = 2 or 3 (point dimension)
391  const FBlocks& Fs, const Matrix& E, const Eigen::Matrix<double, N, N>& P,
392  const Vector& b, const KeyVector& allKeys, const KeyVector& keys,
393  /*output ->*/ SymmetricBlockMatrix& augmentedHessian) {
394  assert(keys.size() == Fs.size());
395  assert(keys.size() <= allKeys.size());
396 
397  FastMap<Key, size_t> KeySlotMap;
398  for (size_t slot = 0; slot < allKeys.size(); slot++)
399  KeySlotMap.emplace(allKeys[slot], slot);
400 
401  // Schur complement trick
402  // G = F' * F - F' * E * P * E' * F
403  // g = F' * (b - E * P * E' * b)
404 
405  // a single point is observed in m cameras
406  size_t m = Fs.size(); // cameras observing current point
407  size_t M = (augmentedHessian.rows() - 1) / D; // all cameras in the group
408  assert(allKeys.size() == M);
409 
410  // Blockwise Schur complement
411  for (size_t i = 0; i < m; i++) { // for each camera in the current factor
412 
413  const MatrixZD& Fi = Fs[i];
414  const auto FiT = Fi.transpose();
415  const Eigen::Matrix<double, 2, N> Ei_P =
416  E.template block<ZDim, N>(ZDim * i, 0) * P;
417 
418  // D = (DxZDim) * (ZDim)
419  // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7)
420  // we should map those to a slot in the local (grouped) hessian
421  // (0,1,2,3,4) Key cameraKey_i = this->keys_[i];
422  DenseIndex aug_i = KeySlotMap.at(keys[i]);
423 
424  // information vector - store previous vector
425  // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal();
426  // add contribution of current factor
427  augmentedHessian.updateOffDiagonalBlock(
428  aug_i, M,
429  FiT * b.segment<ZDim>(ZDim * i) // F' * b
430  -
431  FiT *
432  (Ei_P *
433  (E.transpose() *
434  b))); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1)
435 
436  // (DxD) += (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) )
437  // add contribution of current factor
438  // TODO(gareth): Eigen doesn't let us pass the expression. Call eval() for
439  // now...
440  augmentedHessian.updateDiagonalBlock(
441  aug_i,
442  ((FiT *
443  (Fi -
444  Ei_P * E.template block<ZDim, N>(ZDim * i, 0).transpose() * Fi)))
445  .eval());
446 
447  // upper triangular part of the hessian
448  for (size_t j = i + 1; j < m; j++) { // for each camera
449  const MatrixZD& Fj = Fs[j];
450 
451  DenseIndex aug_j = KeySlotMap.at(keys[j]);
452 
453  // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) )
454  // off diagonal block - store previous block
455  // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal();
456  // add contribution of current factor
457  augmentedHessian.updateOffDiagonalBlock(
458  aug_i, aug_j,
459  -FiT * (Ei_P * E.template block<ZDim, N>(ZDim * j, 0).transpose() *
460  Fj));
461  }
462  } // end of for over cameras
463 
464  augmentedHessian.diagonalBlock(M)(0, 0) += b.squaredNorm();
465  }
466 
467  private:
468 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
469  friend class boost::serialization::access;
471  template <class ARCHIVE>
472  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
473  ar&(*this);
474  }
475 #endif
476 
477  public:
479 };
480 
481 template <class CAMERA>
482 const int CameraSet<CAMERA>::D;
483 
484 template <class CAMERA>
485 const int CameraSet<CAMERA>::ZDim;
486 
487 template <class CAMERA>
488 struct traits<CameraSet<CAMERA>> : public Testable<CameraSet<CAMERA>> {};
489 
490 template <class CAMERA>
491 struct traits<const CameraSet<CAMERA>> : public Testable<CameraSet<CAMERA>> {};
492 
493 } // namespace gtsam
Point2 measured(-17, 30)
Matrix3f m
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:352
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
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:239
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
bool equals(const CameraSet &p, double tol=1e-9) const
equals
Definition: CameraSet.h:91
Concept check for values that can be used in unit tests.
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
void setOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated. ...
std::string serialize(const T &input)
serializes to a string
Vector reprojectionError(const POINT &point, const ZVector &measured, OptArgs &... args) const
Definition: CameraSet.h:157
Definition: pytypes.h:2012
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:161
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:146
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
virtual ~CameraSet()=default
Destructor.
MatrixXf M1
#define N
Definition: gksort.c:12
static Vector ErrorVector(const ZVector &predicted, const ZVector &measured)
Make a vector of re-projection errors.
Definition: CameraSet.h:51
A set of cameras, all with their own calibration.
Definition: CameraSet.h:36
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:171
static const Matrix93 P3
Definition: SO3.cpp:352
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:108
static const int D
Camera dimension.
Definition: CameraSet.h:47
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
ZVector project2(const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Definition: CameraSet.h:108
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
DenseIndex rows() const
Row size.
void setDiagonalBlock(DenseIndex I, const XprType &xpr)
Set a diagonal block. Only the upper triangular portion of xpr is evaluated.
virtual void print(const std::string &s="") const
Definition: CameraSet.h:85
Eigen::VectorXd Vector
Definition: Vector.h:38
STL compatible allocator to use with types requiring a non standrad alignment.
Definition: Memory.h:878
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fblocks, const Matrix &E, const Vector &b, const double lambda=0.0, bool diagonalDamping=false)
Definition: CameraSet.h:369
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:278
CAMERA::Measurement Z
Definition: CameraSet.h:44
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
void updateDiagonalBlock(DenseIndex I, const XprType &xpr)
Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr...
static const int ZDim
Measurement dimension.
Definition: CameraSet.h:48
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Definition: CameraSet.h:78
const G & b
Definition: Group.h:86
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
Calibrated camera for which only pose is unknown.
static const Point3 P2(3.5,-8.2, 4.2)
CAMERA::MeasurementVector ZVector
Definition: CameraSet.h:45
traits
Definition: chartTesting.h:28
A thin wrapper around std::map that uses boost&#39;s fast_pool_allocator.
DiscreteKey E(5, 2)
3D Point
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:336
float * p
typename std::enable_if< B, T >::type enable_if_t
from cpp_future import (convenient aliases from C++14/17)
Base()=default
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
const G double tol
Definition: Group.h:86
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J&#39;th diagonal block as a self adjoint view.
const KeyVector keys
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
The matrix class, also used for vectors and row-vectors.
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:390
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
std::ptrdiff_t j
#define isnan(X)
Definition: main.h:93
ZVector project2(const POINT &point, OptArgs &... args) const
Definition: CameraSet.h:139
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
Definition: CameraSet.h:328


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:00