GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
GeneralSFMFactor.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 
24 #include <gtsam/geometry/Point2.h>
25 #include <gtsam/geometry/Point3.h>
26 #include <gtsam/geometry/Pose3.h>
30 #include <gtsam/base/concepts.h>
31 #include <gtsam/base/Manifold.h>
32 #include <gtsam/base/Matrix.h>
34 #include <gtsam/base/types.h>
35 #include <gtsam/base/Testable.h>
36 #include <gtsam/base/Vector.h>
37 #include <gtsam/base/timing.h>
38 
39 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
40 #include <boost/serialization/nvp.hpp>
41 #endif
42 #include <iostream>
43 #include <string>
44 
45 namespace boost {
46 namespace serialization {
47 class access;
48 } /* namespace serialization */
49 } /* namespace boost */
50 
51 namespace gtsam {
52 
58 template<class CAMERA, class LANDMARK>
59 class GeneralSFMFactor: public NoiseModelFactorN<CAMERA, LANDMARK> {
60 
61  GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA)
62  GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK)
63 
64  static const int DimC = FixedDimension<CAMERA>::value;
65  static const int DimL = FixedDimension<LANDMARK>::value;
66  typedef Eigen::Matrix<double, 2, DimC> JacobianC;
67  typedef Eigen::Matrix<double, 2, DimL> JacobianL;
68 
69 protected:
70 
72 
73 public:
74 
77 
78  // Provide access to the Matrix& version of evaluateError:
79  using Base::evaluateError;
80 
81  // shorthand for a smart pointer to a factor
82  typedef std::shared_ptr<This> shared_ptr;
83 
91  GeneralSFMFactor(const Point2& measured, const SharedNoiseModel& model,
92  Key cameraKey, Key landmarkKey)
93  : Base(model, cameraKey, landmarkKey), measured_(measured) {}
94 
95  GeneralSFMFactor() : measured_(0.0, 0.0) {}
96  GeneralSFMFactor(const Point2& p) : measured_(p) {}
99  GeneralSFMFactor(double x, double y) : measured_(x, y) {}
101  ~GeneralSFMFactor() override {}
102 
104  gtsam::NonlinearFactor::shared_ptr clone() const override {
105  return std::static_pointer_cast<gtsam::NonlinearFactor>(
106  gtsam::NonlinearFactor::shared_ptr(new This(*this)));}
107 
113  void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
114  Base::print(s, keyFormatter);
115  traits<Point2>::Print(measured_, s + ".z");
116  }
117 
121  bool equals(const NonlinearFactor &p, double tol = 1e-9) const override {
122  const This* e = dynamic_cast<const This*>(&p);
123  return e && Base::equals(p, tol) && traits<Point2>::Equals(this->measured_, e->measured_, tol);
124  }
125 
127  Vector evaluateError(const CAMERA& camera, const LANDMARK& point,
128  OptionalMatrixType H1, OptionalMatrixType H2) const override {
129  try {
130  return camera.project2(point,H1,H2) - measured_;
131  }
132  catch( CheiralityException& e [[maybe_unused]]) {
133  if (H1) *H1 = JacobianC::Zero();
134  if (H2) *H2 = JacobianL::Zero();
135  //TODO Print the exception via logging
136  return Z_2x1;
137  }
138  }
139 
141  std::shared_ptr<GaussianFactor> linearize(const Values& values) const override {
142  // Only linearize if the factor is active
143  if (!this->active(values)) return std::shared_ptr<JacobianFactor>();
144 
145  const Key key1 = this->key1(), key2 = this->key2();
146  JacobianC H1;
147  JacobianL H2;
148  Vector2 b;
149  try {
150  const CAMERA& camera = values.at<CAMERA>(key1);
151  const LANDMARK& point = values.at<LANDMARK>(key2);
152  b = measured() - camera.project2(point, H1, H2);
153  } catch (CheiralityException& e [[maybe_unused]]) {
154  H1.setZero();
155  H2.setZero();
156  b.setZero();
157  //TODO Print the exception via logging
158  }
159 
160  // Whiten the system if needed
161  const SharedNoiseModel& noiseModel = this->noiseModel();
162  if (noiseModel && !noiseModel->isUnit()) {
163  // TODO: implement WhitenSystem for fixed size matrices and include
164  // above
165  H1 = noiseModel->Whiten(H1);
166  H2 = noiseModel->Whiten(H2);
167  b = noiseModel->Whiten(b);
168  }
169 
170  // Create new (unit) noiseModel, preserving constraints if applicable
171  SharedDiagonal model;
172  if (noiseModel && noiseModel->isConstrained()) {
173  model = std::static_pointer_cast<noiseModel::Constrained>(noiseModel)->unit();
174  }
175 
176  return std::make_shared<BinaryJacobianFactor<2, DimC, DimL> >(key1, H1, key2, H2, b, model);
177  }
178 
180  inline const Point2 measured() const {
181  return measured_;
182  }
183 
184 private:
185 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
186 
187  friend class boost::serialization::access;
188  template<class Archive>
189  void serialize(Archive & ar, const unsigned int /*version*/) {
190  // NoiseModelFactor2 instead of NoiseModelFactorN for backward compatibility
191  ar & boost::serialization::make_nvp("NoiseModelFactor2",
192  boost::serialization::base_object<Base>(*this));
193  ar & BOOST_SERIALIZATION_NVP(measured_);
194  }
195 #endif
196 };
197 
198 template<class CAMERA, class LANDMARK>
199 struct traits<GeneralSFMFactor<CAMERA, LANDMARK> > : Testable<
200  GeneralSFMFactor<CAMERA, LANDMARK> > {
201 };
202 
207 template<class CALIBRATION>
208 class GeneralSFMFactor2: public NoiseModelFactorN<Pose3, Point3, CALIBRATION> {
209 
210  GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION)
211  static const int DimK = FixedDimension<CALIBRATION>::value;
212 
213 protected:
214 
216 
217 public:
218 
222 
223  // shorthand for a smart pointer to a factor
224  typedef std::shared_ptr<This> shared_ptr;
225 
234  GeneralSFMFactor2(const Point2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, Key calibKey) :
235  Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {}
236  GeneralSFMFactor2():measured_(0.0,0.0) {}
237 
238  ~GeneralSFMFactor2() override {}
239 
241  gtsam::NonlinearFactor::shared_ptr clone() const override {
242  return std::static_pointer_cast<gtsam::NonlinearFactor>(
243  gtsam::NonlinearFactor::shared_ptr(new This(*this)));}
244 
250  void print(const std::string& s = "SFMFactor2", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
251  Base::print(s, keyFormatter);
252  traits<Point2>::Print(measured_, s + ".z");
253  }
254 
258  bool equals(const NonlinearFactor &p, double tol = 1e-9) const override {
259  const This* e = dynamic_cast<const This*>(&p);
260  return e && Base::equals(p, tol) && traits<Point2>::Equals(this->measured_, e->measured_, tol);
261  }
262 
264  Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib,
265  OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override {
266  try {
267  Camera camera(pose3,calib);
268  return camera.project(point, H1, H2, H3) - measured_;
269  }
270  catch( CheiralityException& e) {
271  if (H1) *H1 = Matrix::Zero(2, 6);
272  if (H2) *H2 = Matrix::Zero(2, 3);
273  if (H3) *H3 = Matrix::Zero(2, DimK);
274  std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2())
275  << " behind Camera " << DefaultKeyFormatter(this->key1()) << std::endl;
276  }
277  return Z_2x1;
278  }
279 
281  inline const Point2 measured() const {
282  return measured_;
283  }
284 
285 private:
286 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
287 
288  friend class boost::serialization::access;
289  template<class Archive>
290  void serialize(Archive & ar, const unsigned int /*version*/) {
291  // NoiseModelFactor3 instead of NoiseModelFactorN for backward compatibility
292  ar & boost::serialization::make_nvp("NoiseModelFactor3",
293  boost::serialization::base_object<Base>(*this));
294  ar & BOOST_SERIALIZATION_NVP(measured_);
295  }
296 #endif
297 };
298 
299 template<class CALIBRATION>
300 struct traits<GeneralSFMFactor2<CALIBRATION> > : Testable<
301  GeneralSFMFactor2<CALIBRATION> > {
302 };
303 
304 } //namespace
GeneralSFMFactor2()
default constructor
Definition: GeneralSFMFactor.h:236
Definition: GeneralSFMFactor.h:59
Definition: NonlinearFactor.h:431
Typedefs for easier changing of types.
Concept check for values that can be used in unit tests.
Definition: FastSet.h:35
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
const ValueType at(Key j) const
Definition: Values-inl.h:204
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GeneralSFMFactor.h:241
Definition: Factor.h:69
Definition: Testable.h:152
Vector2 Point2
Definition: Point2.h:32
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:161
GeneralSFMFactor2(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, Key calibKey)
Definition: GeneralSFMFactor.h:234
const Point2 measured() const
Definition: GeneralSFMFactor.h:281
Definition: Group.h:43
~GeneralSFMFactor2() override
destructor
Definition: GeneralSFMFactor.h:238
Definition: NonlinearFactor.h:68
A binary JacobianFactor specialization that uses fixed matrix math for speed.
NoiseModelFactorN< CAMERA, LANDMARK > Base
typedef for the base class
Definition: GeneralSFMFactor.h:76
PinholeCamera< CALIBRATION > Camera
typedef for camera type
Definition: GeneralSFMFactor.h:220
NoiseModelFactorN< Pose3, Point3, CALIBRATION > Base
typedef for the base class
Definition: GeneralSFMFactor.h:221
Vector evaluateError(const Pose3 &pose3, const Point3 &point, const CALIBRATION &calib, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
Definition: GeneralSFMFactor.h:264
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: GeneralSFMFactor.h:258
Point2 measured_
the 2D measurement
Definition: GeneralSFMFactor.h:215
GeneralSFMFactor< CAMERA, LANDMARK > This
typedef for this object
Definition: GeneralSFMFactor.h:75
Base class for all pinhole cameras.
Definition: Testable.h:112
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
Base class and basic functions for Manifold types.
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
GeneralSFMFactor(const Point2 &measured, const SharedNoiseModel &model, Key cameraKey, Key landmarkKey)
Definition: GeneralSFMFactor.h:91
Definition: GeneralSFMFactor.h:208
Definition: Values.h:65
typedef and functions to augment Eigen&#39;s MatrixXd
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
GeneralSFMFactor()
constructor that takes a Point2
Definition: GeneralSFMFactor.h:95
Definition: PinholeCamera.h:33
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
Non-linear factor base classes.
3D Point
Definition: CalibratedCamera.h:34
void print(const std::string &s="SFMFactor2", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: GeneralSFMFactor.h:250
Point2 measured_
the 2D measurement
Definition: GeneralSFMFactor.h:71
Vector3 Point3
Definition: Point3.h:38
2D Point
3D Pose
Definition: Pose3.h:37
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Timing utilities.
Definition: NoiseModel.h:390
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741