TriangulationFactor.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 
18 #pragma once
19 
22 
23 namespace gtsam {
24 
30 template<class CAMERA>
31 class TriangulationFactor: public NoiseModelFactorN<Point3> {
32 
33 public:
34 
36  using Camera = CAMERA;
37 
38 protected:
39 
42 
45 
47  using Measurement = typename CAMERA::Measurement;
48 
49  // Keep a copy of measurement and calibration for I/O
50  const CAMERA camera_;
52 
53  // verbosity handling for Cheirality Exceptions
54  const bool throwCheirality_;
55  const bool verboseCheirality_;
56 
57 public:
59 
61  using shared_ptr = std::shared_ptr<This>;
62 
63  // Provide access to the Matrix& version of evaluateError:
64  using NoiseModelFactor1<Point3>::evaluateError;
65 
68  throwCheirality_(false), verboseCheirality_(false) {
69  }
70 
81  const SharedNoiseModel& model, Key pointKey, bool throwCheirality = false,
82  bool verboseCheirality = false) :
83  Base(model, pointKey), camera_(camera), measured_(measured), throwCheirality_(
84  throwCheirality), verboseCheirality_(verboseCheirality) {
85  if (model && model->dim() != traits<Measurement>::dimension)
86  throw std::invalid_argument(
87  "TriangulationFactor must be created with "
88  + std::to_string((int) traits<Measurement>::dimension)
89  + "-dimensional noise model.");
90  }
91 
93  ~TriangulationFactor() override {
94  }
95 
98  return std::static_pointer_cast<gtsam::NonlinearFactor>(
100  }
101 
107  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
108  DefaultKeyFormatter) const override {
109  std::cout << s << "TriangulationFactor,";
110  camera_.print("camera");
111  traits<Measurement>::Print(measured_, "z");
112  Base::print("", keyFormatter);
113  }
114 
116  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
117  const This *e = dynamic_cast<const This*>(&p);
118  return e && Base::equals(p, tol) && this->camera_.equals(e->camera_, tol)
119  && traits<Measurement>::Equals(this->measured_, e->measured_, tol);
120  }
121 
123  Vector evaluateError(const Point3& point, OptionalMatrixType H2) const override {
124  try {
125  return traits<Measurement>::Local(measured_, camera_.project2(point, OptionalNone, H2));
126  } catch (CheiralityException& e) {
127  if (H2)
128  *H2 = Matrix::Zero(traits<Measurement>::dimension, 3);
129  if (verboseCheirality_)
130  std::cout << e.what() << ": Landmark "
131  << DefaultKeyFormatter(this->key()) << " moved behind camera"
132  << std::endl;
133  if (throwCheirality_)
134  throw e;
135  return camera_.defaultErrorWhenTriangulatingBehindCamera();
136  }
137  }
138 
141  mutable Matrix A;
142  mutable Vector b;
143 
149  std::shared_ptr<GaussianFactor> linearize(const Values& x) const override {
150  // Only linearize if the factor is active
151  if (!this->active(x))
152  return std::shared_ptr<JacobianFactor>();
153 
154  // Allocate memory for Jacobian factor, do only once
155  if (Ab.rows() == 0) {
156  std::vector<size_t> dimensions(1, 3);
157  Ab = VerticalBlockMatrix(dimensions, traits<Measurement>::dimension, true);
158  A.resize(traits<Measurement>::dimension,3);
160  }
161 
162  // Would be even better if we could pass blocks to project
163  const Point3& point = x.at<Point3>(key());
164  b = traits<Measurement>::Local(camera_.project2(point, {}, A), measured_);
165  if (noiseModel_)
166  this->noiseModel_->WhitenSystem(A, b);
167 
168  Ab(0) = A;
169  Ab(1) = b;
170 
171  return std::make_shared<JacobianFactor>(this->keys_, Ab);
172  }
173 
175  const Measurement& measured() const {
176  return measured_;
177  }
178 
180  inline bool verboseCheirality() const {
181  return verboseCheirality_;
182  }
183 
185  inline bool throwCheirality() const {
186  return throwCheirality_;
187  }
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(camera_);
198  ar & BOOST_SERIALIZATION_NVP(measured_);
199  ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
200  ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
201  }
202 #endif
203 };
204 } // \ namespace gtsam
205 
TriangulationFactor()
Default constructor.
TriangulationFactor< CAMERA > This
shorthand for this class
Vector evaluateError(const Point3 &point, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
std::string serialize(const T &input)
serializes to a string
const Measurement measured_
2D measurement
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
Definition: Values-inl.h:204
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
DenseIndex rows() const
Row size.
TriangulationFactor(const CAMERA &camera, const Measurement &measured, const SharedNoiseModel &model, Key pointKey, bool throwCheirality=false, bool verboseCheirality=false)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:841
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:87
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const gtsam::Key pointKey
VerticalBlockMatrix Ab
thread-safe (?) scratch memory for linearize
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
#define OptionalNone
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:278
const bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:75
gtsam::NonlinearFactor::shared_ptr clone() const override
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
const CAMERA camera_
CAMERA in which this landmark was seen.
Calibrated camera for which only pose is unknown.
traits
Definition: chartTesting.h:28
SharedNoiseModel noiseModel_
Non-linear factor base classes.
virtual bool active(const Values &) const
std::shared_ptr< This > shared_ptr
const Measurement & measured() const
float * p
typename CAMERA::Measurement Measurement
shorthand for measurement type, e.g. Point2 or StereoPoint2
const G double tol
Definition: Group.h:86
Vector3 Point3
Definition: Point3.h:38
Definition: camera.h:36
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
const std::vector< size_t > dimensions
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
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
const bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
const char * what() const noexcept override


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:33