SmartFactorBase.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 
22 #pragma once
23 
27 
31 
32 #include <boost/optional.hpp>
33 #include <boost/serialization/optional.hpp>
34 #include <boost/make_shared.hpp>
35 #include <vector>
36 
37 namespace gtsam {
38 
47 template<class CAMERA>
49 
50 private:
53  typedef typename CAMERA::Measurement Z;
54  typedef typename CAMERA::MeasurementVector ZVector;
55 
56 public:
57 
58  static const int Dim = traits<CAMERA>::dimension;
59  static const int ZDim = traits<Z>::dimension;
60  typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD; // F blocks (derivatives wrpt camera)
61  typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks; // vector of F blocks
62 
63 protected:
71 
77  ZVector measured_;
78 
79  boost::optional<Pose3> body_P_sensor_;
80 
81  // Cache for Fblocks, to avoid a malloc ever time we re-linearize
82  mutable FBlocks Fs;
83 
84  public:
86 
88  typedef boost::shared_ptr<This> shared_ptr;
89 
92 
95 
97  SmartFactorBase(const SharedNoiseModel& sharedNoiseModel,
98  boost::optional<Pose3> body_P_sensor = boost::none,
99  size_t expectedNumberCameras = 10)
100  : body_P_sensor_(body_P_sensor), Fs(expectedNumberCameras) {
101 
102  if (!sharedNoiseModel)
103  throw std::runtime_error("SmartFactorBase: sharedNoiseModel is required");
104 
105  SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast<
106  noiseModel::Isotropic>(sharedNoiseModel);
107 
108  if (!sharedIsotropic)
109  throw std::runtime_error("SmartFactorBase: needs isotropic");
110 
111  noiseModel_ = sharedIsotropic;
112  }
113 
115  ~SmartFactorBase() override {
116  }
117 
123  void add(const Z& measured, const Key& key) {
124  if(std::find(keys_.begin(), keys_.end(), key) != keys_.end()) {
125  throw std::invalid_argument(
126  "SmartFactorBase::add: adding duplicate measurement for key.");
127  }
128  this->measured_.push_back(measured);
129  this->keys_.push_back(key);
130  }
131 
135  void add(const ZVector& measurements, const KeyVector& cameraKeys) {
136  assert(measurements.size() == cameraKeys.size());
137  for (size_t i = 0; i < measurements.size(); i++) {
138  this->add(measurements[i], cameraKeys[i]);
139  }
140  }
141 
146  template<class SFM_TRACK>
147  void add(const SFM_TRACK& trackToAdd) {
148  for (size_t k = 0; k < trackToAdd.number_measurements(); k++) {
149  this->measured_.push_back(trackToAdd.measurements[k].second);
150  this->keys_.push_back(trackToAdd.measurements[k].first);
151  }
152  }
153 
155  size_t dim() const override {
156  return ZDim * this->measured_.size();
157  }
158 
160  const ZVector& measured() const {
161  return measured_;
162  }
163 
165  virtual Cameras cameras(const Values& values) const {
166  Cameras cameras;
167  for(const Key& k: this->keys_)
168  cameras.push_back(values.at<CAMERA>(k));
169  return cameras;
170  }
171 
177  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
178  DefaultKeyFormatter) const override {
179  std::cout << s << "SmartFactorBase, z = \n";
180  for (size_t k = 0; k < measured_.size(); ++k) {
181  std::cout << "measurement, p = " << measured_[k] << "\t";
182  noiseModel_->print("noise model = ");
183  }
184  if(body_P_sensor_)
185  body_P_sensor_->print("body_P_sensor_:\n");
186  Base::print("", keyFormatter);
187  }
188 
190  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
191  const This *e = dynamic_cast<const This*>(&p);
192 
193  bool areMeasurementsEqual = true;
194  for (size_t i = 0; i < measured_.size(); i++) {
195  if (traits<Z>::Equals(this->measured_.at(i), e->measured_.at(i), tol) == false)
196  areMeasurementsEqual = false;
197  break;
198  }
199  return e && Base::equals(p, tol) && areMeasurementsEqual;
200  }
201 
204  template <class POINT>
206  const Cameras& cameras, const POINT& point,
207  boost::optional<typename Cameras::FBlocks&> Fs = boost::none, //
208  boost::optional<Matrix&> E = boost::none) const {
209  Vector ue = cameras.reprojectionError(point, measured_, Fs, E);
210  if (body_P_sensor_ && Fs) {
211  const Pose3 sensor_P_body = body_P_sensor_->inverse();
212  constexpr int camera_dim = traits<CAMERA>::dimension;
213  constexpr int pose_dim = traits<Pose3>::dimension;
214 
215  for (size_t i = 0; i < Fs->size(); i++) {
216  const Pose3 world_P_body = cameras[i].pose() * sensor_P_body;
218  J.setZero();
220  // Call compose to compute Jacobian for camera extrinsics
221  world_P_body.compose(*body_P_sensor_, H);
222  // Assign extrinsics part of the Jacobian
223  J.template block<pose_dim, pose_dim>(0, 0) = H;
224  Fs->at(i) = Fs->at(i) * J;
225  }
226  }
227  correctForMissingMeasurements(cameras, ue, Fs, E);
228  return ue;
229  }
230 
235  virtual void correctForMissingMeasurements(const Cameras& cameras, Vector& ue, boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
236  boost::optional<Matrix&> E = boost::none) const {}
237 
242  template<class POINT>
243  Vector whitenedError(const Cameras& cameras, const POINT& point) const {
244  Vector e = cameras.reprojectionError(point, measured_);
245  if (noiseModel_)
246  noiseModel_->whitenInPlace(e);
247  return e;
248  }
249 
256  template<class POINT>
257  double totalReprojectionError(const Cameras& cameras,
258  const POINT& point) const {
259  Vector e = whitenedError(cameras, point);
260  return 0.5 * e.dot(e);
261  }
262 
264  static Matrix PointCov(Matrix& E) {
265  return (E.transpose() * E).inverse();
266  }
267 
274  template<class POINT>
275  void computeJacobians(FBlocks& Fs, Matrix& E, Vector& b,
276  const Cameras& cameras, const POINT& point) const {
277  // Project into Camera set and calculate derivatives
278  // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar)
279  // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z|
280  // = |A*dx - (z-h(x_bar))|
281  b = -unwhitenedError(cameras, point, Fs, E);
282  }
283 
285  template<class POINT>
286  void computeJacobiansSVD(FBlocks& Fs, Matrix& Enull,
287  Vector& b, const Cameras& cameras, const POINT& point) const {
288 
289  Matrix E;
290  computeJacobians(Fs, E, b, cameras, point);
291 
292  static const int N = FixedDimension<POINT>::value; // 2 (Unit3) or 3 (Point3)
293 
294  // Do SVD on A
296  Vector s = svd.singularValues();
297  size_t m = this->keys_.size();
298  Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns
299  }
300 
302  boost::shared_ptr<RegularHessianFactor<Dim> > createHessianFactor(
303  const Cameras& cameras, const Point3& point, const double lambda = 0.0,
304  bool diagonalDamping = false) const {
305 
306  Matrix E;
307  Vector b;
308  computeJacobians(Fs, E, b, cameras, point);
309 
310  // build augmented hessian
311  SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fs, E, b);
312 
313  return boost::make_shared<RegularHessianFactor<Dim> >(keys_,
314  augmentedHessian);
315  }
316 
322  void updateAugmentedHessian(const Cameras& cameras, const Point3& point,
323  const double lambda, bool diagonalDamping,
324  SymmetricBlockMatrix& augmentedHessian,
325  const KeyVector allKeys) const {
326  Matrix E;
327  Vector b;
328  computeJacobians(Fs, E, b, cameras, point);
329  Cameras::UpdateSchurComplement(Fs, E, b, allKeys, keys_, augmentedHessian);
330  }
331 
333  void whitenJacobians(FBlocks& F, Matrix& E, Vector& b) const {
334  noiseModel_->WhitenSystem(E, b);
335  // TODO make WhitenInPlace work with any dense matrix type
336  for (size_t i = 0; i < F.size(); i++)
337  F[i] = noiseModel_->Whiten(F[i]);
338  }
339 
341  boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> > //
343  double lambda = 0.0, bool diagonalDamping = false) const {
344  Matrix E;
345  Vector b;
346  FBlocks F;
347  computeJacobians(F, E, b, cameras, point);
348  whitenJacobians(F, E, b);
349  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
350  return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(keys_, F, E,
351  P, b);
352  }
353 
357  boost::shared_ptr<JacobianFactorQ<Dim, ZDim> > createJacobianQFactor(
358  const Cameras& cameras, const Point3& point, double lambda = 0.0,
359  bool diagonalDamping = false) const {
360  Matrix E;
361  Vector b;
362  FBlocks F;
363  computeJacobians(F, E, b, cameras, point);
364  const size_t M = b.size();
365  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
366  SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma());
367  return boost::make_shared<JacobianFactorQ<Dim, ZDim> >(keys_, F, E, P, b, n);
368  }
369 
374  boost::shared_ptr<JacobianFactor> createJacobianSVDFactor(
375  const Cameras& cameras, const Point3& point, double lambda = 0.0) const {
376  size_t m = this->keys_.size();
377  FBlocks F;
378  Vector b;
379  const size_t M = ZDim * m;
380  Matrix E0(M, M - 3);
381  computeJacobiansSVD(F, E0, b, cameras, point);
383  noiseModel_->sigma());
384  return boost::make_shared<JacobianFactorSVD<Dim, ZDim> >(keys_, F, E0, b, n);
385  }
386 
388  static void FillDiagonalF(const FBlocks& Fs, Matrix& F) {
389  size_t m = Fs.size();
390  F.resize(ZDim * m, Dim * m);
391  F.setZero();
392  for (size_t i = 0; i < m; ++i)
393  F.block<ZDim, Dim>(ZDim * i, Dim * i) = Fs.at(i);
394  }
395 
396 
398  if(body_P_sensor_)
399  return *body_P_sensor_;
400  else
401  return Pose3(); // if unspecified, the transformation is the identity
402  }
403 
404 private:
405 
407  friend class boost::serialization::access;
408  template<class ARCHIVE>
409  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
410  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
411  ar & BOOST_SERIALIZATION_NVP(noiseModel_);
412  ar & BOOST_SERIALIZATION_NVP(measured_);
413  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
414  }
415 };
416 // end class SmartFactorBase
417 
418 // Definitions need to avoid link errors (above are only declarations)
419 template<class CAMERA> const int SmartFactorBase<CAMERA>::Dim;
420 template<class CAMERA> const int SmartFactorBase<CAMERA>::ZDim;
421 
422 } // \ namespace gtsam
Matrix3f m
SmartFactorBase(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
Constructor.
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:210
void add(const SFM_TRACK &trackToAdd)
Vector whitenedError(const Cameras &cameras, const POINT &point) const
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
EIGEN_DEVICE_FUNC Matrix< _Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setZero(Index size)
Key E(std::uint64_t j)
CAMERA::Measurement Z
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
const SingularValuesType & singularValues() const
Definition: SVDBase.h:111
Base class to create smart factors on poses or cameras.
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
void serialize(ARCHIVE &ar, const unsigned int)
boost::shared_ptr< JacobianFactorQ< Dim, ZDim > > createJacobianQFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
leaf::MyValues values
boost::shared_ptr< RegularHessianFactor< Dim > > createHessianFactor(const Cameras &cameras, const Point3 &point, const double lambda=0.0, bool diagonalDamping=false) const
Linearize to a Hessianfactor.
SmartFactorBase()
Default Constructor, for serialization.
CameraSet< CAMERA > Cameras
We use the new CameraSte data structure to refer to a set of cameras.
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
noiseModel::Isotropic::shared_ptr SharedIsotropic
Definition: NoiseModel.h:738
boost::optional< Pose3 > body_P_sensor_
Pose of the camera in the body frame.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
#define N
Definition: gksort.c:12
SharedIsotropic noiseModel_
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
CAMERA::MeasurementVector ZVector
~SmartFactorBase() override
Virtual destructor, subclasses from NonlinearFactor.
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
Vector reprojectionError(const POINT &point, const ZVector &measured, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Calculate vector [project2(point)-z] of re-projection errors.
Definition: CameraSet.h:136
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Point3 point(10, 0,-5)
static Matrix PointCov(Matrix &E)
Computes Point Covariance P from E.
Base class for smart factors This base class has no internal point, but it has a measurement, noise model and an optional sensor pose. This class mainly computes the derivatives and returns them as a variety of factors. The methods take a Cameras argument, which should behave like PinholeCamera, and the value of a point, which is kept in the base class.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Class compose(const Class &g) const
Definition: Lie.h:47
Signature::Row F
Definition: Signature.cpp:53
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:50
Eigen::VectorXd Vector
Definition: Vector.h:38
const ValueType at(Key j) const
Definition: Values-inl.h:342
static void FillDiagonalF(const FBlocks &Fs, Matrix &F)
Create BIG block-diagonal matrix F from Fblocks.
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:263
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
HessianFactor class with constant sized blocks.
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
JacobiRotation< float > J
const G & b
Definition: Group.h:83
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
void add(const ZVector &measurements, const KeyVector &cameraKeys)
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
traits
Definition: chartTesting.h:28
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
Pose3 body_P_sensor() const
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Non-linear factor base classes.
size_t dim() const override
get the dimension (number of rows!) of the factor
void add(const Z &measured, const Key &key)
void updateAugmentedHessian(const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
Definition: Matrix.cpp:559
static const int Dim
Camera dimension.
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Two-sided Jacobi SVD decomposition of a rectangular matrix.
float * p
SmartFactorBase< CAMERA > This
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
Eigen::Matrix< double, ZDim, Dim > MatrixZD
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:246
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
const ZVector & measured() const
boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > createRegularImplicitSchurFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
Return Jacobians as RegularImplicitSchurFactor with raw access.
NonlinearFactor Base
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
virtual void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
static const int ZDim
Measurement dimension.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
SVD version.
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
Definition: CameraSet.h:149


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:14