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 
21 #include <gtsam/geometry/Cal3_S2.h>
24 #include <gtsam_unstable/dllexport.h>
25 
26 
27 namespace gtsam {
28 
34 template <class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
36  : public NoiseModelFactorN<POSE, POSE, LANDMARK, CALIBRATION> {
37  protected:
39 
40  // verbosity handling for Cheirality Exceptions
43 
44  public:
46  typedef NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> Base;
47 
48  // Provide access to the Matrix& version of evaluateError:
49  using Base::evaluateError;
50 
53 
55  typedef std::shared_ptr<This> shared_ptr;
56 
59  measured_(0.0, 0.0), throwCheirality_(false), verboseCheirality_(false) {
60  }
61 
62 
79  Key poseKey, Key transformKey, Key pointKey, Key calibKey,
80  bool throwCheirality = false, bool verboseCheirality = false) :
81  Base(model, poseKey, transformKey, pointKey, calibKey), measured_(measured),
83 
85  ~ProjectionFactorPPPC() override {}
86 
89  return std::static_pointer_cast<NonlinearFactor>(
90  NonlinearFactor::shared_ptr(new This(*this))); }
91 
97  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
98  std::cout << s << "ProjectionFactorPPPC, z = ";
100  Base::print("", keyFormatter);
101  }
102 
104  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
105  const This *e = dynamic_cast<const This*>(&p);
106  return e
107  && Base::equals(p, tol)
108  && traits<Point2>::Equals(this->measured_, e->measured_, tol);
109  }
110 
112  Vector evaluateError(const Pose3& pose, const Pose3& transform, const Point3& point, const CALIBRATION& K,
114  OptionalMatrixType H4) const override {
115  try {
116  if(H1 || H2 || H3 || H4) {
117  Matrix H0, H02;
118  const PinholeCamera<CALIBRATION> camera(pose.compose(transform, H0, H02), K);
119  const Point2 reprojectionError(camera.project(point, H1, H3, H4) - measured_);
120  *H2 = *H1 * H02;
121  *H1 = *H1 * H0;
122  return reprojectionError;
123  } else {
125  return camera.project(point, H1, H3, H4) - measured_;
126  }
127  } catch( CheiralityException& e) {
128  if (H1) *H1 = Matrix::Zero(2,6);
129  if (H2) *H2 = Matrix::Zero(2,6);
130  if (H3) *H3 = Matrix::Zero(2,3);
131  if (H4) *H4 = Matrix::Zero(2,CALIBRATION::Dim());
132  if (verboseCheirality_)
133  std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
134  " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
135  if (throwCheirality_)
136  throw e;
137  }
138  return Vector::Ones(2) * 2.0 * K.fx();
139  }
140 
142  const Point2& measured() const {
143  return measured_;
144  }
145 
147  inline bool verboseCheirality() const { return verboseCheirality_; }
148 
150  inline bool throwCheirality() const { return throwCheirality_; }
151 
152  private:
153 
154 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
155  friend class boost::serialization::access;
157  template<class ARCHIVE>
158  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
159  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
160  ar & BOOST_SERIALIZATION_NVP(measured_);
161  ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
162  ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
163  }
164 #endif
165 };
166 
168  template<class POSE, class LANDMARK, class CALIBRATION>
169  struct traits<ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> > :
170  public Testable<ProjectionFactorPPPC<POSE, LANDMARK, CALIBRATION> > {
171  };
172 
173 } // \ namespace gtsam
gtsam::ProjectionFactorPPPC::ProjectionFactorPPPC
ProjectionFactorPPPC(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key transformKey, Key pointKey, Key calibKey, bool throwCheirality=false, bool verboseCheirality=false)
Definition: ProjectionFactorPPPC.h:78
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
gtsam::ProjectionFactorPPPC::Base
NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION > Base
shorthand for base class type
Definition: ProjectionFactorPPPC.h:46
gtsam::ProjectionFactorPPPC::verboseCheirality
bool verboseCheirality() const
Definition: ProjectionFactorPPPC.h:147
gtsam::ProjectionFactorPPPC::measured_
Point2 measured_
2D measurement
Definition: ProjectionFactorPPPC.h:38
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
gtsam::ProjectionFactorPPPC::~ProjectionFactorPPPC
~ProjectionFactorPPPC() override
Definition: ProjectionFactorPPPC.h:85
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
pointKey
const gtsam::Key pointKey
Definition: testRelativeElevationFactor.cpp:25
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Cal3_S2.h
The most common 5DOF 3D->2D calibration.
gtsam::ProjectionFactorPPPC::ProjectionFactorPPPC
ProjectionFactorPPPC()
Default constructor.
Definition: ProjectionFactorPPPC.h:58
gtsam::ProjectionFactorPPPC::clone
NonlinearFactor::shared_ptr clone() const override
Definition: ProjectionFactorPPPC.h:88
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Factor
Definition: Factor.h:70
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
poseKey
const gtsam::Key poseKey
Definition: testPoseRotationPrior.cpp:29
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::CheiralityException
Definition: CalibratedCamera.h:34
gtsam::ProjectionFactorPPPC::shared_ptr
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: ProjectionFactorPPPC.h:55
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::ProjectionFactorPPPC::equals
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: ProjectionFactorPPPC.h:104
gtsam::ProjectionFactorPPPC::verboseCheirality_
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Definition: ProjectionFactorPPPC.h:42
gtsam::KeyFormatter
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
gtsam::Pose3
Definition: Pose3.h:37
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
gtsam::ProjectionFactorPPPC::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: ProjectionFactorPPPC.h:97
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
transform
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::NoiseModelFactorN< POSE, POSE, LANDMARK, Cal3_S2 >::key1
Key key1() const
Definition: NonlinearFactor.h:731
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::ProjectionFactorPPPC::measured
const Point2 & measured() const
Definition: ProjectionFactorPPPC.h:142
NonlinearFactor.h
Non-linear factor base classes.
gtsam::NoiseModelFactorN< POSE, POSE, LANDMARK, Cal3_S2 >::key2
Key key2() const
Definition: NonlinearFactor.h:735
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
K
#define K
Definition: igam.h:8
gtsam::ProjectionFactorPPPC::throwCheirality
bool throwCheirality() const
Definition: ProjectionFactorPPPC.h:150
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
gtsam::ProjectionFactorPPPC::throwCheirality_
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
Definition: ProjectionFactorPPPC.h:41
camera
static const CalibratedCamera camera(kDefaultPose)
Base
Definition: test_virtual_functions.cpp:156
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::ProjectionFactorPPPC::evaluateError
Vector evaluateError(const Pose3 &pose, const Pose3 &transform, const Point3 &point, const CALIBRATION &K, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: ProjectionFactorPPPC.h:112
gtsam::ProjectionFactorPPPC
Definition: ProjectionFactorPPPC.h:35
gtsam::ProjectionFactorPPPC::This
ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
Definition: ProjectionFactorPPPC.h:52


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:53