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 #include <boost/none.hpp>
40 #include <boost/optional/optional.hpp>
41 #include <boost/serialization/nvp.hpp>
42 #include <boost/smart_ptr/shared_ptr.hpp>
43 #include <iostream>
44 #include <string>
45 
46 namespace boost {
47 namespace serialization {
48 class access;
49 } /* namespace serialization */
50 } /* namespace boost */
51 
52 namespace gtsam {
53 
59 template<class CAMERA, class LANDMARK>
60 class GeneralSFMFactor: public NoiseModelFactor2<CAMERA, LANDMARK> {
61 
64 
65  static const int DimC = FixedDimension<CAMERA>::value;
66  static const int DimL = FixedDimension<LANDMARK>::value;
69 
70 protected:
71 
73 
74 public:
75 
78 
79  // shorthand for a smart pointer to a factor
80  typedef boost::shared_ptr<This> shared_ptr;
81 
90  Key cameraKey, Key landmarkKey)
91  : Base(model, cameraKey, landmarkKey), measured_(measured) {}
92 
93  GeneralSFMFactor() : measured_(0.0, 0.0) {}
94  GeneralSFMFactor(const Point2& p) : measured_(p) {}
97  GeneralSFMFactor(double x, double y) : measured_(x, y) {}
98 
99  ~GeneralSFMFactor() override {}
100 
102  gtsam::NonlinearFactor::shared_ptr clone() const override {
103  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
105 
111  void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
112  Base::print(s, keyFormatter);
113  traits<Point2>::Print(measured_, s + ".z");
114  }
115 
119  bool equals(const NonlinearFactor &p, double tol = 1e-9) const override {
120  const This* e = dynamic_cast<const This*>(&p);
121  return e && Base::equals(p, tol) && traits<Point2>::Equals(this->measured_, e->measured_, tol);
122  }
123 
125  Vector evaluateError(const CAMERA& camera, const LANDMARK& point,
126  boost::optional<Matrix&> H1=boost::none, boost::optional<Matrix&> H2=boost::none) const override {
127  try {
128  return camera.project2(point,H1,H2) - measured_;
129  }
130  catch( CheiralityException& e) {
131  if (H1) *H1 = JacobianC::Zero();
132  if (H2) *H2 = JacobianL::Zero();
133  //TODO Print the exception via logging
134  return Z_2x1;
135  }
136  }
137 
139  boost::shared_ptr<GaussianFactor> linearize(const Values& values) const override {
140  // Only linearize if the factor is active
141  if (!this->active(values)) return boost::shared_ptr<JacobianFactor>();
142 
143  const Key key1 = this->key1(), key2 = this->key2();
144  JacobianC H1;
145  JacobianL H2;
146  Vector2 b;
147  try {
148  const CAMERA& camera = values.at<CAMERA>(key1);
149  const LANDMARK& point = values.at<LANDMARK>(key2);
150  b = measured() - camera.project2(point, H1, H2);
151  } catch (CheiralityException& e) {
152  H1.setZero();
153  H2.setZero();
154  b.setZero();
155  //TODO Print the exception via logging
156  }
157 
158  // Whiten the system if needed
159  const SharedNoiseModel& noiseModel = this->noiseModel();
160  if (noiseModel && !noiseModel->isUnit()) {
161  // TODO: implement WhitenSystem for fixed size matrices and include
162  // above
163  H1 = noiseModel->Whiten(H1);
164  H2 = noiseModel->Whiten(H2);
165  b = noiseModel->Whiten(b);
166  }
167 
168  // Create new (unit) noiseModel, preserving constraints if applicable
170  if (noiseModel && noiseModel->isConstrained()) {
171  model = boost::static_pointer_cast<noiseModel::Constrained>(noiseModel)->unit();
172  }
173 
174  return boost::make_shared<BinaryJacobianFactor<2, DimC, DimL> >(key1, H1, key2, H2, b, model);
175  }
176 
178  inline const Point2 measured() const {
179  return measured_;
180  }
181 
182 private:
184  friend class boost::serialization::access;
185  template<class Archive>
186  void serialize(Archive & ar, const unsigned int /*version*/) {
187  ar & boost::serialization::make_nvp("NoiseModelFactor2",
188  boost::serialization::base_object<Base>(*this));
189  ar & BOOST_SERIALIZATION_NVP(measured_);
190  }
191 };
192 
193 template<class CAMERA, class LANDMARK>
194 struct traits<GeneralSFMFactor<CAMERA, LANDMARK> > : Testable<
195  GeneralSFMFactor<CAMERA, LANDMARK> > {
196 };
197 
202 template<class CALIBRATION>
203 class GeneralSFMFactor2: public NoiseModelFactor3<Pose3, Point3, CALIBRATION> {
204 
205  GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION);
206  static const int DimK = FixedDimension<CALIBRATION>::value;
207 
208 protected:
209 
211 
212 public:
213 
217 
218  // shorthand for a smart pointer to a factor
219  typedef boost::shared_ptr<This> shared_ptr;
220 
229  GeneralSFMFactor2(const Point2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, Key calibKey) :
230  Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {}
231  GeneralSFMFactor2():measured_(0.0,0.0) {}
232 
233  ~GeneralSFMFactor2() override {}
234 
237  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
239 
245  void print(const std::string& s = "SFMFactor2", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
246  Base::print(s, keyFormatter);
247  traits<Point2>::Print(measured_, s + ".z");
248  }
249 
253  bool equals(const NonlinearFactor &p, double tol = 1e-9) const override {
254  const This* e = dynamic_cast<const This*>(&p);
255  return e && Base::equals(p, tol) && traits<Point2>::Equals(this->measured_, e->measured_, tol);
256  }
257 
259  Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib,
260  boost::optional<Matrix&> H1=boost::none,
261  boost::optional<Matrix&> H2=boost::none,
262  boost::optional<Matrix&> H3=boost::none) const override
263  {
264  try {
265  Camera camera(pose3,calib);
266  return camera.project(point, H1, H2, H3) - measured_;
267  }
268  catch( CheiralityException& e) {
269  if (H1) *H1 = Matrix::Zero(2, 6);
270  if (H2) *H2 = Matrix::Zero(2, 3);
271  if (H3) *H3 = Matrix::Zero(2, DimK);
272  std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2())
273  << " behind Camera " << DefaultKeyFormatter(this->key1()) << std::endl;
274  }
275  return Z_2x1;
276  }
277 
279  inline const Point2 measured() const {
280  return measured_;
281  }
282 
283 private:
285  friend class boost::serialization::access;
286  template<class Archive>
287  void serialize(Archive & ar, const unsigned int /*version*/) {
288  ar & boost::serialization::make_nvp("NoiseModelFactor3",
289  boost::serialization::base_object<Base>(*this));
290  ar & BOOST_SERIALIZATION_NVP(measured_);
291  }
292 };
293 
294 template<class CALIBRATION>
295 struct traits<GeneralSFMFactor2<CALIBRATION> > : Testable<
296  GeneralSFMFactor2<CALIBRATION> > {
297 };
298 
299 } //namespace
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
GeneralSFMFactor2()
default constructor
const gtsam::Key poseKey
NoiseModelFactor2< CAMERA, LANDMARK > Base
typedef for the base class
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Typedefs for easier changing of types.
Scalar * y
void serialize(Archive &ar, Eigen::Matrix< Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_ > &m, const unsigned int version)
Definition: base/Matrix.h:591
Scalar * b
Definition: benchVecAdd.cpp:17
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.
noiseModel::Diagonal::shared_ptr model
gtsam::NonlinearFactor::shared_ptr clone() const override
Vector2 Point2
Definition: Point2.h:27
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
GeneralSFMFactor2(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, Key calibKey)
~GeneralSFMFactor2() override
destructor
leaf::MyValues values
A binary JacobianFactor specialization that uses fixed matrix math for speed.
Eigen::Matrix< double, 2, DimC > JacobianC
boost::shared_ptr< This > shared_ptr
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
PinholeCamera< CALIBRATION > Camera
typedef for camera type
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Point2 measured_
the 2D measurement
Point3 point(10, 0,-5)
const Symbol key1('v', 1)
GeneralSFMFactor< CAMERA, LANDMARK > This
typedef for this object
Base class for all pinhole cameras.
Eigen::VectorXd Vector
Definition: Vector.h:38
const ValueType at(Key j) const
Definition: Values-inl.h:342
Base class and basic functions for Manifold types.
Eigen::Matrix< double, 2, DimL > JacobianL
static Pose3 pose3(rt3, pt3)
boost::shared_ptr< This > shared_ptr
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
GeneralSFMFactor(const Point2 &measured, const SharedNoiseModel &model, Key cameraKey, Key landmarkKey)
Vector evaluateError(const Pose3 &pose3, const Point3 &point, const CALIBRATION &calib, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
NoiseModelFactor3< Pose3, Point3, CALIBRATION > Base
typedef for the base class
#define This
GeneralSFMFactor()
constructor that takes a Point2
const Point2 measured() const
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
Non-linear factor base classes.
boost::shared_ptr< This > shared_ptr
const Symbol key2('v', 2)
3D Point
float * p
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
#define GTSAM_CONCEPT_MANIFOLD_TYPE(T)
Definition: Manifold.h:181
void serialize(Archive &ar, const unsigned int)
void print(const std::string &s="SFMFactor2", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
GeneralSFMFactor2< CALIBRATION > This
Point2 measured_
the 2D measurement
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
The matrix class, also used for vectors and row-vectors.
Point3 measured
static const CalibratedCamera camera(kDefaultPose)
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 x
2D Point
3D Pose
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:59
Timing utilities.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
const char * what() const noexceptoverride


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:07