gtsam  4.0.0
gtsam
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 <boost/optional.hpp>
26 
27 namespace gtsam {
28 
34  template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
35  class GenericProjectionFactor: public NoiseModelFactor2<POSE, LANDMARK> {
36  protected:
37 
38  // Keep a copy of measurement and calibration for I/O
40  boost::shared_ptr<CALIBRATION> K_;
41  boost::optional<POSE> body_P_sensor_;
42 
43  // verbosity handling for Cheirality Exceptions
46 
47  public:
48 
51 
54 
56  typedef boost::shared_ptr<This> shared_ptr;
57 
60  measured_(0, 0), throwCheirality_(false), verboseCheirality_(false) {
61  }
62 
74  Key poseKey, Key pointKey, const boost::shared_ptr<CALIBRATION>& K,
75  boost::optional<POSE> body_P_sensor = boost::none) :
76  Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
77  throwCheirality_(false), verboseCheirality_(false) {}
78 
92  Key poseKey, Key pointKey, const boost::shared_ptr<CALIBRATION>& K,
94  boost::optional<POSE> body_P_sensor = boost::none) :
95  Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
97 
100 
102  virtual gtsam::NonlinearFactor::shared_ptr clone() const {
103  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
104  gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
105 
111  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
112  std::cout << s << "GenericProjectionFactor, z = ";
114  if(this->body_P_sensor_)
115  this->body_P_sensor_->print(" sensor pose in body frame: ");
116  Base::print("", keyFormatter);
117  }
118 
120  virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const {
121  const This *e = dynamic_cast<const This*>(&p);
122  return e
123  && Base::equals(p, tol)
124  && traits<Point2>::Equals(this->measured_, e->measured_, tol)
125  && this->K_->equals(*e->K_, tol)
126  && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));
127  }
128 
130  Vector evaluateError(const Pose3& pose, const Point3& point,
131  boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 = boost::none) const {
132  try {
133  if(body_P_sensor_) {
134  if(H1) {
135  gtsam::Matrix H0;
136  PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_, H0), *K_);
137  Point2 reprojectionError(camera.project(point, H1, H2, boost::none) - measured_);
138  *H1 = *H1 * H0;
139  return reprojectionError;
140  } else {
141  PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_), *K_);
142  return camera.project(point, H1, H2, boost::none) - measured_;
143  }
144  } else {
145  PinholeCamera<CALIBRATION> camera(pose, *K_);
146  return camera.project(point, H1, H2, boost::none) - measured_;
147  }
148  } catch( CheiralityException& e) {
149  if (H1) *H1 = Matrix::Zero(2,6);
150  if (H2) *H2 = Matrix::Zero(2,3);
151  if (verboseCheirality_)
152  std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
153  " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
154  if (throwCheirality_)
155  throw CheiralityException(this->key2());
156  }
157  return Vector2::Constant(2.0 * K_->fx());
158  }
159 
161  const Point2& measured() const {
162  return measured_;
163  }
164 
166  inline const boost::shared_ptr<CALIBRATION> calibration() const {
167  return K_;
168  }
169 
171  inline bool verboseCheirality() const { return verboseCheirality_; }
172 
174  inline bool throwCheirality() const { return throwCheirality_; }
175 
176  private:
177 
180  template<class ARCHIVE>
181  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
182  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
183  ar & BOOST_SERIALIZATION_NVP(measured_);
184  ar & BOOST_SERIALIZATION_NVP(K_);
185  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
186  ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
187  ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
188  }
189 
190  public:
191  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
192 };
193 
195  template<class POSE, class LANDMARK, class CALIBRATION>
196  struct traits<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > :
197  public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
198  };
199 
200 } // \ namespace gtsam
Point2 measured_
2D measurement
Definition: ProjectionFactor.h:39
This is the base class for all factor types.
Definition: Factor.h:54
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:345
const Point2 & measured() const
return the measurement
Definition: ProjectionFactor.h:161
A simple camera class with a Cal3_S2 calibration.
Definition: PinholeCamera.h:33
Definition: Point3.h:45
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Print.
Definition: NonlinearFactor.cpp:63
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: ProjectionFactor.h:111
Vector evaluateError(const Pose3 &pose, const Point3 &point, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const
Evaluate error h(x)-z and optionally derivatives.
Definition: ProjectionFactor.h:130
NoiseModelFactor2< POSE, LANDMARK > Base
shorthand for base class type
Definition: ProjectionFactor.h:50
GenericProjectionFactor< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
Definition: ProjectionFactor.h:53
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
const boost::shared_ptr< CALIBRATION > calibration() const
return the calibration object
Definition: ProjectionFactor.h:166
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const boost::shared_ptr< CALIBRATION > &K, boost::optional< POSE > body_P_sensor=boost::none)
Constructor TODO: Mark argument order standard (keys, measurement, parameters)
Definition: ProjectionFactor.h:73
Definition: CalibratedCamera.h:32
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:377
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Non-linear factor base classes.
Definition: Point2.h:40
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Definition: ProjectionFactor.h:45
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: ProjectionFactor.h:102
virtual bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: ProjectionFactor.h:120
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const boost::shared_ptr< CALIBRATION > &K, bool throwCheirality, bool verboseCheirality, boost::optional< POSE > body_P_sensor=boost::none)
Constructor with exception-handling flags TODO: Mark argument order standard (keys,...
Definition: ProjectionFactor.h:91
boost::shared_ptr< CALIBRATION > K_
shared pointer to calibration object
Definition: ProjectionFactor.h:40
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
friend class boost::serialization::access
Serialization function.
Definition: ProjectionFactor.h:179
Definition: Pose3.h:37
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:71
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
Definition: ProjectionFactor.h:44
bool verboseCheirality() const
return verbosity
Definition: ProjectionFactor.h:171
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition: ProjectionFactor.h:174
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: ProjectionFactor.h:56
boost::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
Definition: ProjectionFactor.h:41
virtual ~GenericProjectionFactor()
Virtual destructor.
Definition: ProjectionFactor.h:99
GenericProjectionFactor()
Default constructor.
Definition: ProjectionFactor.h:59
Definition: ProjectionFactor.h:35