gtsam  4.0.0
gtsam
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 
21 #pragma once
22 
23 #include <gtsam/slam/JacobianFactorQ.h>
24 #include <gtsam/slam/JacobianFactorSVD.h>
26 
30 
31 #include <boost/optional.hpp>
32 #include <boost/serialization/optional.hpp>
33 #include <boost/make_shared.hpp>
34 #include <vector>
35 
36 namespace gtsam {
37 
46 template<class CAMERA>
48 
49 private:
50  typedef NonlinearFactor Base;
52  typedef typename CAMERA::Measurement Z;
53  typedef typename CAMERA::MeasurementVector ZVector;
54 
55 public:
56 
57  static const int Dim = traits<CAMERA>::dimension;
58  static const int ZDim = traits<Z>::dimension;
59  typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD; // F blocks (derivatives wrpt camera)
60  typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks; // vector of F blocks
61 
62 protected:
69  SharedIsotropic noiseModel_;
70 
76  ZVector measured_;
77 
79  boost::optional<Pose3> body_P_sensor_;
80 
82  // Cache for Fblocks, to avoid a malloc ever time we re-linearize
83  mutable FBlocks Fs;
84 
85 public:
86 
87  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
88 
90  typedef boost::shared_ptr<This> shared_ptr;
91 
94 
97 
99  SmartFactorBase(const SharedNoiseModel& sharedNoiseModel,
100  boost::optional<Pose3> body_P_sensor = boost::none,
101  size_t expectedNumberCameras = 10)
102  : body_P_sensor_(body_P_sensor), Fs(expectedNumberCameras) {
103 
104  if (!sharedNoiseModel)
105  throw std::runtime_error("SmartFactorBase: sharedNoiseModel is required");
106 
107  SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast<
108  noiseModel::Isotropic>(sharedNoiseModel);
109 
110  if (!sharedIsotropic)
111  throw std::runtime_error("SmartFactorBase: needs isotropic");
112 
113  noiseModel_ = sharedIsotropic;
114  }
115 
117  virtual ~SmartFactorBase() {
118  }
119 
126  void add(const Z& measured_i, const Key& cameraKey_i) {
127  this->measured_.push_back(measured_i);
128  this->keys_.push_back(cameraKey_i);
129  }
130 
134  void add(ZVector& measurements, KeyVector& cameraKeys) {
135  for (size_t i = 0; i < measurements.size(); i++) {
136  this->measured_.push_back(measurements.at(i));
137  this->keys_.push_back(cameraKeys.at(i));
138  }
139  }
140 
145  template<class SFM_TRACK>
146  void add(const SFM_TRACK& trackToAdd) {
147  for (size_t k = 0; k < trackToAdd.number_measurements(); k++) {
148  this->measured_.push_back(trackToAdd.measurements[k].second);
149  this->keys_.push_back(trackToAdd.measurements[k].first);
150  }
151  }
152 
154  virtual size_t dim() const {
155  return ZDim * this->measured_.size();
156  }
157 
159  const ZVector& measured() const {
160  return measured_;
161  }
162 
164  virtual Cameras cameras(const Values& values) const {
166  for(const Key& k: this->keys_)
167  cameras.push_back(values.at<CAMERA>(k));
168  return cameras;
169  }
170 
176  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
177  DefaultKeyFormatter) const {
178  std::cout << s << "SmartFactorBase, z = \n";
179  for (size_t k = 0; k < measured_.size(); ++k) {
180  std::cout << "measurement, p = " << measured_[k] << "\t";
181  noiseModel_->print("noise model = ");
182  }
183  if(body_P_sensor_)
184  body_P_sensor_->print("body_P_sensor_:\n");
185  Base::print("", keyFormatter);
186  }
187 
189  virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const {
190  const This *e = dynamic_cast<const This*>(&p);
191 
192  bool areMeasurementsEqual = true;
193  for (size_t i = 0; i < measured_.size(); i++) {
194  if (traits<Z>::Equals(this->measured_.at(i), e->measured_.at(i), tol) == false)
195  areMeasurementsEqual = false;
196  break;
197  }
198  return e && Base::equals(p, tol) && areMeasurementsEqual;
199  }
200 
202  template<class POINT>
203  Vector unwhitenedError(const Cameras& cameras, const POINT& point,
204  boost::optional<typename Cameras::FBlocks&> Fs = boost::none, //
205  boost::optional<Matrix&> E = boost::none) const {
206  Vector ue = cameras.reprojectionError(point, measured_, Fs, E);
207  if(body_P_sensor_ && Fs){
208  for(size_t i=0; i < Fs->size(); i++){
209  Pose3 w_Pose_body = (cameras[i].pose()).compose(body_P_sensor_->inverse());
210  Matrix J(6, 6);
211  Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J);
212  Fs->at(i) = Fs->at(i) * J;
213  }
214  }
216  return ue;
217  }
218 
223  virtual void correctForMissingMeasurements(const Cameras& cameras, Vector& ue, boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
224  boost::optional<Matrix&> E = boost::none) const {}
225 
230  template<class POINT>
231  Vector whitenedError(const Cameras& cameras, const POINT& point) const {
232  Vector e = cameras.reprojectionError(point, measured_);
233  if (noiseModel_)
234  noiseModel_->whitenInPlace(e);
235  return e;
236  }
237 
244  template<class POINT>
246  const POINT& point) const {
247  Vector e = whitenedError(cameras, point);
248  return 0.5 * e.dot(e);
249  }
250 
252  static Matrix PointCov(Matrix& E) {
253  return (E.transpose() * E).inverse();
254  }
255 
262  template<class POINT>
263  void computeJacobians(FBlocks& Fs, Matrix& E, Vector& b,
264  const Cameras& cameras, const POINT& point) const {
265  // Project into Camera set and calculate derivatives
266  // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar)
267  // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z|
268  // = |A*dx - (z-h(x_bar))|
269  b = -unwhitenedError(cameras, point, Fs, E);
270  }
271 
273  template<class POINT>
274  void computeJacobiansSVD(FBlocks& Fs, Matrix& Enull,
275  Vector& b, const Cameras& cameras, const POINT& point) const {
276 
277  Matrix E;
278  computeJacobians(Fs, E, b, cameras, point);
279 
280  static const int N = FixedDimension<POINT>::value; // 2 (Unit3) or 3 (Point3)
281 
282  // Do SVD on A
283  Eigen::JacobiSVD<Matrix> svd(E, Eigen::ComputeFullU);
284  Vector s = svd.singularValues();
285  size_t m = this->keys_.size();
286  Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns
287  }
288 
290  boost::shared_ptr<RegularHessianFactor<Dim> > createHessianFactor(
291  const Cameras& cameras, const Point3& point, const double lambda = 0.0,
292  bool diagonalDamping = false) const {
293 
294  Matrix E;
295  Vector b;
296  computeJacobians(Fs, E, b, cameras, point);
297 
298  // build augmented hessian
299  SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fs, E, b);
300 
301  return boost::make_shared<RegularHessianFactor<Dim> >(keys_,
302  augmentedHessian);
303  }
304 
310  void updateAugmentedHessian(const Cameras& cameras, const Point3& point,
311  const double lambda, bool diagonalDamping,
312  SymmetricBlockMatrix& augmentedHessian,
313  const KeyVector allKeys) const {
314  Matrix E;
315  Vector b;
316  computeJacobians(Fs, E, b, cameras, point);
317  Cameras::UpdateSchurComplement(Fs, E, b, allKeys, keys_, augmentedHessian);
318  }
319 
321  void whitenJacobians(FBlocks& F, Matrix& E, Vector& b) const {
322  noiseModel_->WhitenSystem(E, b);
323  // TODO make WhitenInPlace work with any dense matrix type
324  for (size_t i = 0; i < F.size(); i++)
325  F[i] = noiseModel_->Whiten(F[i]);
326  }
327 
329  boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> > //
331  double lambda = 0.0, bool diagonalDamping = false) const {
332  Matrix E;
333  Vector b;
334  FBlocks F;
335  computeJacobians(F, E, b, cameras, point);
336  whitenJacobians(F, E, b);
337  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
338  return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(keys_, F, E,
339  P, b);
340  }
341 
345  boost::shared_ptr<JacobianFactorQ<Dim, ZDim> > createJacobianQFactor(
346  const Cameras& cameras, const Point3& point, double lambda = 0.0,
347  bool diagonalDamping = false) const {
348  Matrix E;
349  Vector b;
350  FBlocks F;
351  computeJacobians(F, E, b, cameras, point);
352  const size_t M = b.size();
353  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
354  SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma());
355  return boost::make_shared<JacobianFactorQ<Dim, ZDim> >(keys_, F, E, P, b, n);
356  }
357 
362  boost::shared_ptr<JacobianFactor> createJacobianSVDFactor(
363  const Cameras& cameras, const Point3& point, double lambda = 0.0) const {
364  size_t m = this->keys_.size();
365  FBlocks F;
366  Vector b;
367  const size_t M = ZDim * m;
368  Matrix E0(M, M - 3);
369  computeJacobiansSVD(F, E0, b, cameras, point);
370  SharedIsotropic n = noiseModel::Isotropic::Sigma(M - 3,
371  noiseModel_->sigma());
372  return boost::make_shared<JacobianFactorSVD<Dim, ZDim> >(keys_, F, E0, b, n);
373  }
374 
376  static void FillDiagonalF(const FBlocks& Fs, Matrix& F) {
377  size_t m = Fs.size();
378  F.resize(ZDim * m, Dim * m);
379  F.setZero();
380  for (size_t i = 0; i < m; ++i)
381  F.block<ZDim, Dim>(ZDim * i, Dim * i) = Fs.at(i);
382  }
383 
384 
385  Pose3 body_P_sensor() const{
386  if(body_P_sensor_)
387  return *body_P_sensor_;
388  else
389  return Pose3(); // if unspecified, the transformation is the identity
390  }
391 
392 private:
393 
395  friend class boost::serialization::access;
396  template<class ARCHIVE>
397  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
398  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
399  ar & BOOST_SERIALIZATION_NVP(noiseModel_);
400  ar & BOOST_SERIALIZATION_NVP(measured_);
401  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
402  }
403 };
404 // end class SmartFactorBase
405 
406 // Definitions need to avoid link errors (above are only declarations)
407 template<class CAMERA> const int SmartFactorBase<CAMERA>::Dim;
408 template<class CAMERA> const int SmartFactorBase<CAMERA>::ZDim;
409 
410 } // \ namespace gtsam
This is the base class for all factor types.
Definition: Factor.h:54
CameraSet< CAMERA > Cameras
We use the new CameraSte data structure to refer to a set of cameras.
Definition: SmartFactorBase.h:93
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
Vector whitenedError(const Cameras &cameras, const POINT &point) const
Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z] Noise model applied.
Definition: SmartFactorBase.h:231
ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:342
const ZVector & measured() const
return the measurements
Definition: SmartFactorBase.h:159
Definition: Point3.h:45
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
SVD version.
Definition: SmartFactorBase.h:274
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Calculate the error of the factor.
Definition: SmartFactorBase.h:245
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:164
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
SVD computes economy SVD A=U*S*V'.
Definition: Matrix.cpp:555
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
An isotropic noise model corresponds to a scaled diagonal covariance To construct,...
Definition: NoiseModel.h:519
virtual void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
This corrects the Jacobians for the case in which some pixel measurement is missing (nan) In practice...
Definition: SmartFactorBase.h:223
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.
Definition: SmartFactorBase.h:330
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:36
HessianFactor class with constant sized blocks.
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Compute F, E, and b (called below in both vanilla and SVD versions), where F is a vector of derivativ...
Definition: SmartFactorBase.h:263
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives.
Definition: SmartFactorBase.h:203
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
static const int ZDim
Measurement dimension.
Definition: SmartFactorBase.h:58
void add(const Z &measured_i, const Key &cameraKey_i)
Add a new measurement and pose key.
Definition: SmartFactorBase.h:126
virtual size_t dim() const
get the dimension (number of rows!) of the factor
Definition: SmartFactorBase.h:154
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartFactorBase.h:90
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
void add(ZVector &measurements, KeyVector &cameraKeys)
Add a bunch of measurements, together with the camera keys.
Definition: SmartFactorBase.h:134
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Non-linear factor base classes.
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
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)
Applies Schur complement (exploiting block structure) to get a smart factor on cameras,...
Definition: CameraSet.h:246
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: NonlinearFactor.cpp:26
virtual bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: SmartFactorBase.h:189
Base class for smart factors This base class has no internal point, but it has a measurement,...
Definition: SmartFactorBase.h:47
SmartFactorBase()
Default Constructor, for serialization.
Definition: SmartFactorBase.h:96
SharedIsotropic noiseModel_
As of Feb 22, 2015, the noise model is the same for all measurements and is isotropic.
Definition: SmartFactorBase.h:69
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix G = F' * F - F' * E * P * ...
Definition: CameraSet.h:149
Base class to create smart factors on poses or cameras.
SmartFactorBase(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
Constructor.
Definition: SmartFactorBase.h:99
Definition: SymmetricBlockMatrix.h:51
static Matrix PointCov(Matrix &E)
Computes Point Covariance P from E.
Definition: SmartFactorBase.h:252
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: SmartFactorBase.h:176
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Return Jacobians as JacobianFactorSVD TODO lambda is currently ignored.
Definition: SmartFactorBase.h:362
boost::shared_ptr< JacobianFactorQ< Dim, ZDim > > createJacobianQFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
Return Jacobians as JacobianFactorQ.
Definition: SmartFactorBase.h:345
void add(const SFM_TRACK &trackToAdd)
Adds an entire SfM_track (collection of cameras observing a single point).
Definition: SmartFactorBase.h:146
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 int Dim
Camera dimension.
Definition: SmartFactorBase.h:57
void updateAugmentedHessian(const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
Add the contribution of the smart factor to a pre-allocated Hessian, using sparse linear algebra.
Definition: SmartFactorBase.h:310
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:561
Definition: Pose3.h:37
static void FillDiagonalF(const FBlocks &Fs, Matrix &F)
Create BIG block-diagonal matrix F from Fblocks.
Definition: SmartFactorBase.h:376
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:321
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.
Definition: SmartFactorBase.h:290
boost::optional< Pose3 > body_P_sensor_
Pose of the camera in the body frame.
Definition: SmartFactorBase.h:79
virtual ~SmartFactorBase()
Virtual destructor, subclasses from NonlinearFactor.
Definition: SmartFactorBase.h:117
ZVector measured_
2D measurement and noise model for each of the m views We keep a copy of measurements for I/O and com...
Definition: SmartFactorBase.h:76