ProjectionFactor.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 
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/geometry/Point3.h>
27 #include <gtsam/geometry/Cal3_S2.h>
28 #include <optional>
29 
30 namespace gtsam {
31 
38  template <class POSE = Pose3, class LANDMARK = Point3,
39  class CALIBRATION = Cal3_S2>
40  class GenericProjectionFactor: public NoiseModelFactorN<POSE, LANDMARK> {
41  protected:
42 
43  // Keep a copy of measurement and calibration for I/O
45  std::shared_ptr<CALIBRATION> K_;
46  std::optional<POSE> body_P_sensor_;
47 
48  // verbosity handling for Cheirality Exceptions
51 
52  public:
53 
56 
57  // Provide access to the Matrix& version of evaluateError:
58  using Base::evaluateError;
59 
62 
64  typedef std::shared_ptr<This> shared_ptr;
65 
68  measured_(0, 0), throwCheirality_(false), verboseCheirality_(false) {
69  }
70 
82  Key poseKey, Key pointKey, const std::shared_ptr<CALIBRATION>& K,
83  std::optional<POSE> body_P_sensor = {}) :
84  Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
85  throwCheirality_(false), verboseCheirality_(false) {}
86 
99  GenericProjectionFactor(const Point2& measured, const SharedNoiseModel& model,
100  Key poseKey, Key pointKey, const std::shared_ptr<CALIBRATION>& K,
102  std::optional<POSE> body_P_sensor = {}) :
103  Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
104  throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
105 
108 
111  return std::static_pointer_cast<gtsam::NonlinearFactor>(
113 
119  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
120  std::cout << s << "GenericProjectionFactor, z = ";
121  traits<Point2>::Print(measured_);
122  if(this->body_P_sensor_)
123  this->body_P_sensor_->print(" sensor pose in body frame: ");
124  Base::print("", keyFormatter);
125  }
126 
128  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
129  const This *e = dynamic_cast<const This*>(&p);
130  return e
131  && Base::equals(p, tol)
132  && traits<Point2>::Equals(this->measured_, e->measured_, tol)
133  && this->K_->equals(*e->K_, tol)
134  && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));
135  }
136 
139  OptionalMatrixType H1, OptionalMatrixType H2) const override {
140  try {
141  if(body_P_sensor_) {
142  if(H1) {
143  gtsam::Matrix H0;
144  PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_, H0), *K_);
145  Point2 reprojectionError(camera.project(point, H1, H2, {}) - measured_);
146  *H1 = *H1 * H0;
147  return reprojectionError;
148  } else {
149  PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_), *K_);
150  return camera.project(point, H1, H2, {}) - measured_;
151  }
152  } else {
154  return camera.project(point, H1, H2, {}) - measured_;
155  }
156  } catch( CheiralityException& e) {
157  if (H1) *H1 = Matrix::Zero(2,6);
158  if (H2) *H2 = Matrix::Zero(2,3);
159  if (verboseCheirality_)
160  std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
161  " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
162  if (throwCheirality_)
163  throw CheiralityException(this->key2());
164  }
165  return Vector2::Constant(2.0 * K_->fx());
166  }
167 
169  const Point2& measured() const {
170  return measured_;
171  }
172 
174  const std::shared_ptr<CALIBRATION> calibration() const {
175  return K_;
176  }
177 
179  const std::optional<POSE>& body_P_sensor() const {
180  return body_P_sensor_;
181  }
182 
184  inline bool verboseCheirality() const { return verboseCheirality_; }
185 
187  inline bool throwCheirality() const { return throwCheirality_; }
188 
189  private:
190 
191 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
192  friend class boost::serialization::access;
194  template<class ARCHIVE>
195  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
196  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
197  ar & BOOST_SERIALIZATION_NVP(measured_);
198  ar & BOOST_SERIALIZATION_NVP(K_);
199  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
200  ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
201  ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
202  }
203 #endif
204 
205  public:
207 };
208 
210  template<class POSE, class LANDMARK, class CALIBRATION>
211  struct traits<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > :
212  public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
213  };
214 
215 } // \ namespace gtsam
std::shared_ptr< CALIBRATION > K_
shared pointer to calibration object
const gtsam::Key poseKey
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
const Point2 & measured() const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Vector2 Point2
Definition: Point2.h:32
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K, bool throwCheirality, bool verboseCheirality, std::optional< POSE > body_P_sensor={})
NoiseModelFactorN< POSE, LANDMARK > Base
shorthand for base class type
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const gtsam::Key pointKey
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Point2 measured_
2D measurement
Base class for all pinhole cameras.
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
Eigen::VectorXd Vector
Definition: Vector.h:38
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K, std::optional< POSE > body_P_sensor={})
const std::shared_ptr< CALIBRATION > calibration() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
const std::optional< POSE > & body_P_sensor() const
Class compose(const Class &g) const
Definition: Lie.h:48
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
traits
Definition: chartTesting.h:28
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
3D Point
float * p
GenericProjectionFactor< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
const G double tol
Definition: Group.h:86
Vector3 Point3
Definition: Point3.h:38
gtsam::NonlinearFactor::shared_ptr clone() const override
static const CalibratedCamera camera(kDefaultPose)
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
3D Pose
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:62
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The most common 5DOF 3D->2D calibration.
const char * what() const noexcept override
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
GenericProjectionFactor()
Default constructor.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:26