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 
20 #include <boost/make_shared.hpp>
21 #include <boost/lexical_cast.hpp>
22 
23 namespace gtsam {
24 
30 template<class CAMERA>
31 class TriangulationFactor: public NoiseModelFactor1<Point3> {
32 
33 public:
34 
36  typedef CAMERA Camera;
37 
38 protected:
39 
42 
45 
47  typedef typename CAMERA::Measurement Measurement;
48 
49  // Keep a copy of measurement and calibration for I/O
50  const CAMERA camera_;
51  const Measurement measured_;
52 
53  // verbosity handling for Cheirality Exceptions
54  const bool throwCheirality_;
55  const bool verboseCheirality_;
56 
57 public:
58 
60  typedef boost::shared_ptr<This> shared_ptr;
61 
64  throwCheirality_(false), verboseCheirality_(false) {
65  }
66 
76  TriangulationFactor(const CAMERA& camera, const Measurement& measured,
77  const SharedNoiseModel& model, Key pointKey, bool throwCheirality = false,
78  bool verboseCheirality = false) :
79  Base(model, pointKey), camera_(camera), measured_(measured), throwCheirality_(
80  throwCheirality), verboseCheirality_(verboseCheirality) {
81  if (model && model->dim() != traits<Measurement>::dimension)
82  throw std::invalid_argument(
83  "TriangulationFactor must be created with "
84  + boost::lexical_cast<std::string>((int) traits<Measurement>::dimension)
85  + "-dimensional noise model.");
86  }
87 
89  ~TriangulationFactor() override {
90  }
91 
94  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
96  }
97 
103  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
104  DefaultKeyFormatter) const override {
105  std::cout << s << "TriangulationFactor,";
106  camera_.print("camera");
107  traits<Measurement>::Print(measured_, "z");
108  Base::print("", keyFormatter);
109  }
110 
112  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
113  const This *e = dynamic_cast<const This*>(&p);
114  return e && Base::equals(p, tol) && this->camera_.equals(e->camera_, tol)
115  && traits<Measurement>::Equals(this->measured_, e->measured_, tol);
116  }
117 
119  Vector evaluateError(const Point3& point, boost::optional<Matrix&> H2 =
120  boost::none) const override {
121  try {
122  return traits<Measurement>::Local(measured_, camera_.project2(point, boost::none, H2));
123  } catch (CheiralityException& e) {
124  if (H2)
125  *H2 = Matrix::Zero(traits<Measurement>::dimension, 3);
126  if (verboseCheirality_)
127  std::cout << e.what() << ": Landmark "
128  << DefaultKeyFormatter(this->key()) << " moved behind camera"
129  << std::endl;
130  if (throwCheirality_)
131  throw e;
132  return Eigen::Matrix<double,traits<Measurement>::dimension,1>::Constant(2.0 * camera_.calibration().fx());
133  }
134  }
135 
138  mutable Matrix A;
139  mutable Vector b;
140 
146  boost::shared_ptr<GaussianFactor> linearize(const Values& x) const override {
147  // Only linearize if the factor is active
148  if (!this->active(x))
149  return boost::shared_ptr<JacobianFactor>();
150 
151  // Allocate memory for Jacobian factor, do only once
152  if (Ab.rows() == 0) {
153  std::vector<size_t> dimensions(1, 3);
154  Ab = VerticalBlockMatrix(dimensions, traits<Measurement>::dimension, true);
155  A.resize(traits<Measurement>::dimension,3);
157  }
158 
159  // Would be even better if we could pass blocks to project
160  const Point3& point = x.at<Point3>(key());
161  b = traits<Measurement>::Local(camera_.project2(point, boost::none, A), measured_);
162  if (noiseModel_)
163  this->noiseModel_->WhitenSystem(A, b);
164 
165  Ab(0) = A;
166  Ab(1) = b;
167 
168  return boost::make_shared<JacobianFactor>(this->keys_, Ab);
169  }
170 
172  const Measurement& measured() const {
173  return measured_;
174  }
175 
177  inline bool verboseCheirality() const {
178  return verboseCheirality_;
179  }
180 
182  inline bool throwCheirality() const {
183  return throwCheirality_;
184  }
185 
186 private:
187 
190  template<class ARCHIVE>
191  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
192  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
193  ar & BOOST_SERIALIZATION_NVP(camera_);
194  ar & BOOST_SERIALIZATION_NVP(measured_);
195  ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
196  ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
197  }
198 };
199 } // \ namespace gtsam
200 
TriangulationFactor< CAMERA > This
shorthand for this class
TriangulationFactor()
Default constructor.
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
const Measurement measured_
2D measurement
noiseModel::Diagonal::shared_ptr model
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:43
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
const Measurement & measured() const
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
vector< size_t > dimensions(L.begin(), L.end())
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const gtsam::Key pointKey
virtual bool active(const Values &) const
VerticalBlockMatrix Ab
thread-safe (?) scratch memory for linearize
Point3 point(10, 0,-5)
Eigen::VectorXd Vector
Definition: Vector.h:38
const ValueType at(Key j) const
Definition: Values-inl.h:342
void serialize(ARCHIVE &ar, const unsigned int)
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:263
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
const bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
friend class boost::serialization::access
Serialization function.
gtsam::NonlinearFactor::shared_ptr clone() const override
const CAMERA camera_
CAMERA in which this landmark was seen.
Calibrated camera for which only pose is unknown.
traits
Definition: chartTesting.h:28
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
SharedNoiseModel noiseModel_
CAMERA::Measurement Measurement
shorthand for measurement type, e.g. Point2 or StereoPoint2
Non-linear factor base classes.
NoiseModelFactor1< Point3 > Base
shorthand for base class type
Vector evaluateError(const Point3 &point, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
boost::shared_ptr< GaussianFactor > linearize(const Values &x) const override
float * p
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
The matrix class, also used for vectors and row-vectors.
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
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
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
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
const char * what() const noexceptoverride
const bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
DenseIndex rows() const
Row size.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:16