ProjectionFactorPPPC.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 
23 #include <gtsam/geometry/Cal3_S2.h>
24 #include <boost/optional.hpp>
25 
26 namespace gtsam {
27 
33  template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
34  class ProjectionFactorPPPC: public NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> {
35  protected:
36 
38 
39  // verbosity handling for Cheirality Exceptions
42 
43  public:
44 
47 
50 
52  typedef boost::shared_ptr<This> shared_ptr;
53 
56  measured_(0.0, 0.0), throwCheirality_(false), verboseCheirality_(false) {
57  }
58 
69  Key poseKey, Key transformKey, Key pointKey, Key calibKey) :
70  Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured),
71  throwCheirality_(false), verboseCheirality_(false) {}
72 
85  Key poseKey, Key transformKey, Key pointKey, Key calibKey,
87  Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured),
88  throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
89 
91  ~ProjectionFactorPPPC() override {}
92 
95  return boost::static_pointer_cast<NonlinearFactor>(
96  NonlinearFactor::shared_ptr(new This(*this))); }
97 
103  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
104  std::cout << s << "ProjectionFactorPPPC, z = ";
105  traits<Point2>::Print(measured_);
106  Base::print("", keyFormatter);
107  }
108 
110  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
111  const This *e = dynamic_cast<const This*>(&p);
112  return e
113  && Base::equals(p, tol)
114  && traits<Point2>::Equals(this->measured_, e->measured_, tol);
115  }
116 
118  Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point, const CALIBRATION& K,
119  boost::optional<Matrix&> H1 = boost::none,
120  boost::optional<Matrix&> H2 = boost::none,
121  boost::optional<Matrix&> H3 = boost::none,
122  boost::optional<Matrix&> H4 = boost::none) const override {
123  try {
124  if(H1 || H2 || H3 || H4) {
125  Matrix H0, H02;
126  PinholeCamera<CALIBRATION> camera(pose.compose(transform, H0, H02), K);
127  Point2 reprojectionError(camera.project(point, H1, H3, H4) - measured_);
128  *H2 = *H1 * H02;
129  *H1 = *H1 * H0;
130  return reprojectionError;
131  } else {
132  PinholeCamera<CALIBRATION> camera(pose.compose(transform), K);
133  return camera.project(point, H1, H3, H4) - measured_;
134  }
135  } catch( CheiralityException& e) {
136  if (H1) *H1 = Matrix::Zero(2,6);
137  if (H2) *H2 = Matrix::Zero(2,6);
138  if (H3) *H3 = Matrix::Zero(2,3);
139  if (H4) *H4 = Matrix::Zero(2,CALIBRATION::Dim());
140  if (verboseCheirality_)
141  std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
142  " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
143  if (throwCheirality_)
144  throw e;
145  }
146  return Vector::Ones(2) * 2.0 * K.fx();
147  }
148 
150  const Point2& measured() const {
151  return measured_;
152  }
153 
155  inline bool verboseCheirality() const { return verboseCheirality_; }
156 
158  inline bool throwCheirality() const { return throwCheirality_; }
159 
160  private:
161 
164  template<class ARCHIVE>
165  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
166  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
167  ar & BOOST_SERIALIZATION_NVP(measured_);
168  ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
169  ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
170  }
171  };
172 
174  template<class POSE, class LANDMARK, class CALIBRATION>
175  struct traits<ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> > :
176  public Testable<ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> > {
177  };
178 
179 } // \ namespace gtsam
Point2 measured_
2D measurement
Vector evaluateError(const Pose3 &pose, const Pose3 &transform, const Point3 &point, const CALIBRATION &K, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
const gtsam::Key poseKey
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
void serialize(ARCHIVE &ar, const unsigned int)
noiseModel::Diagonal::shared_ptr model
Vector2 Point2
Definition: Point2.h:27
ProjectionFactorPPPC()
Default constructor.
ProjectionFactorPPPC(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key transformKey, Key pointKey, Key calibKey)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactor::shared_ptr clone() const override
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const gtsam::Key pointKey
Point3 point(10, 0,-5)
ProjectionFactorPPPC(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key transformKey, Key pointKey, Key calibKey, bool throwCheirality, bool verboseCheirality)
Base class for all pinhole cameras.
const Point2 & measured() const
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Class compose(const Class &g) const
Definition: Lie.h:47
Eigen::VectorXd Vector
Definition: Vector.h:38
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
friend class boost::serialization::access
Serialization function.
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
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
traits
Definition: chartTesting.h:28
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Non-linear factor base classes.
float * p
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
static const CalibratedCamera camera(kDefaultPose)
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
ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
The most common 5DOF 3D->2D calibration.
const char * what() const noexceptoverride
NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION > Base
shorthand for base class type


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