EssentialMatrixFactor.h
Go to the documentation of this file.
1 /*
2  * @file EssentialMatrixFactor.cpp
3  * @brief EssentialMatrixFactor class
4  * @author Frank Dellaert
5  * @date December 17, 2013
6  */
7 
8 #pragma once
9 
13 #include <iostream>
14 
15 namespace gtsam {
16 
20 class EssentialMatrixFactor: public NoiseModelFactor1<EssentialMatrix> {
21 
23 
26 
27 public:
28 
37  const SharedNoiseModel& model) :
38  Base(model, key) {
41  }
42 
51  template<class CALIBRATION>
53  const SharedNoiseModel& model, boost::shared_ptr<CALIBRATION> K) :
54  Base(model, key) {
55  assert(K);
56  vA_ = EssentialMatrix::Homogeneous(K->calibrate(pA));
57  vB_ = EssentialMatrix::Homogeneous(K->calibrate(pB));
58  }
59 
62  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
64  }
65 
67  void print(const std::string& s = "",
68  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
69  Base::print(s);
70  std::cout << " EssentialMatrixFactor with measurements\n ("
71  << vA_.transpose() << ")' and (" << vB_.transpose() << ")'"
72  << std::endl;
73  }
74 
76  Vector evaluateError(const EssentialMatrix& E, boost::optional<Matrix&> H =
77  boost::none) const override {
78  Vector error(1);
79  error << E.error(vA_, vB_, H);
80  return error;
81  }
82 
83 public:
85 };
86 
91 class EssentialMatrixFactor2: public NoiseModelFactor2<EssentialMatrix, double> {
92 
95  double f_;
96 
99 
100 public:
101 
111  const SharedNoiseModel& model) :
112  Base(model, key1, key2), dP1_(EssentialMatrix::Homogeneous(pA)), pn_(pB) {
113  f_ = 1.0;
114  }
115 
125  template<class CALIBRATION>
127  const SharedNoiseModel& model, boost::shared_ptr<CALIBRATION> K) :
128  Base(model, key1, key2), dP1_(
129  EssentialMatrix::Homogeneous(K->calibrate(pA))), pn_(K->calibrate(pB)) {
130  f_ = 0.5 * (K->fx() + K->fy());
131  }
132 
135  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
137  }
138 
140  void print(const std::string& s = "",
141  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
142  Base::print(s);
143  std::cout << " EssentialMatrixFactor2 with measurements\n ("
144  << dP1_.transpose() << ")' and (" << pn_.transpose()
145  << ")'" << std::endl;
146  }
147 
148  /*
149  * Vector of errors returns 2D vector
150  * @param E essential matrix
151  * @param d inverse depth d
152  */
153  Vector evaluateError(const EssentialMatrix& E, const double& d,
154  boost::optional<Matrix&> DE = boost::none, boost::optional<Matrix&> Dd =
155  boost::none) const override {
156 
157  // We have point x,y in image 1
158  // Given a depth Z, the corresponding 3D point P1 = Z*(x,y,1) = (x,y,1)/d
159  // We then convert to second camera by P2 = 1R2'*(P1-1T2)
160  // The homogeneous coordinates of can be written as
161  // 2R1*(P1-1T2) == 2R1*d*(P1-1T2) == 2R1*((x,y,1)-d*1T2)
162  // where we multiplied with d which yields equivalent homogeneous coordinates.
163  // Note that this is just the homography 2R1 for d==0
164  // The point d*P1 = (x,y,1) is computed in constructor as dP1_
165 
166  // Project to normalized image coordinates, then uncalibrate
167  Point2 pn(0,0);
168  if (!DE && !Dd) {
169 
170  Point3 _1T2 = E.direction().point3();
171  Point3 d1T2 = d * _1T2;
172  Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2); // 2R1*((x,y,1)-d*1T2)
173  pn = PinholeBase::Project(dP2);
174 
175  } else {
176 
177  // Calculate derivatives. TODO if slow: optimize with Mathematica
178  // 3*2 3*3 3*3
179  Matrix D_1T2_dir, DdP2_rot, DP2_point;
180 
181  Point3 _1T2 = E.direction().point3(D_1T2_dir);
182  Point3 d1T2 = d * _1T2;
183  Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2, DdP2_rot, DP2_point);
184 
185  Matrix23 Dpn_dP2;
186  pn = PinholeBase::Project(dP2, Dpn_dP2);
187 
188  if (DE) {
189  Matrix DdP2_E(3, 5);
190  DdP2_E << DdP2_rot, -DP2_point * d * D_1T2_dir; // (3*3), (3*3) * (3*2)
191  *DE = f_ * Dpn_dP2 * DdP2_E; // (2*3) * (3*5)
192  }
193 
194  if (Dd) // efficient backwards computation:
195  // (2*3) * (3*3) * (3*1)
196  *Dd = -f_ * (Dpn_dP2 * (DP2_point * _1T2));
197 
198  }
199  Point2 reprojectionError = pn - pn_;
200  return f_ * reprojectionError;
201  }
202 
203 public:
205 };
206 // EssentialMatrixFactor2
207 
214 
217 
219 
220 public:
221 
232  const Rot3& cRb, const SharedNoiseModel& model) :
233  EssentialMatrixFactor2(key1, key2, pA, pB, model), cRb_(cRb) {
234  }
235 
245  template<class CALIBRATION>
247  const Rot3& cRb, const SharedNoiseModel& model,
248  boost::shared_ptr<CALIBRATION> K) :
249  EssentialMatrixFactor2(key1, key2, pA, pB, model, K), cRb_(cRb) {
250  }
251 
254  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
256  }
257 
259  void print(const std::string& s = "",
260  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
261  Base::print(s);
262  std::cout << " EssentialMatrixFactor3 with rotation " << cRb_ << std::endl;
263  }
264 
265  /*
266  * Vector of errors returns 2D vector
267  * @param E essential matrix
268  * @param d inverse depth d
269  */
270  Vector evaluateError(const EssentialMatrix& E, const double& d,
271  boost::optional<Matrix&> DE = boost::none, boost::optional<Matrix&> Dd =
272  boost::none) const override {
273  if (!DE) {
274  // Convert E from body to camera frame
275  EssentialMatrix cameraE = cRb_ * E;
276  // Evaluate error
277  return Base::evaluateError(cameraE, d, boost::none, Dd);
278  } else {
279  // Version with derivatives
280  Matrix D_e_cameraE, D_cameraE_E; // 2*5, 5*5
281  EssentialMatrix cameraE = E.rotate(cRb_, D_cameraE_E);
282  Vector e = Base::evaluateError(cameraE, d, D_e_cameraE, Dd);
283  *DE = D_e_cameraE * D_cameraE_E; // (2*5) * (5*5)
284  return e;
285  }
286  }
287 
288 public:
290 };
291 // EssentialMatrixFactor3
292 
293 }// gtsam
294 
double error(const Values &c) const override
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
gtsam::NonlinearFactor::shared_ptr clone() const override
Key E(std::uint64_t j)
Eigen::Vector3d Vector3
Definition: Vector.h:43
noiseModel::Diagonal::shared_ptr model
Point2 pB(size_t i)
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H=boost::none) const
epipolar error, algebraic
Vector2 Point2
Definition: Point2.h:27
virtual Vector evaluateError(const X &x, boost::optional< Matrix & > H=boost::none) const =0
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
gtsam::Rot3 cRb
Vector3 vB_
Homogeneous versions, in ideal coordinates.
static Vector3 Homogeneous(const Point2 &p)
Static function to convert Point2 to homogeneous coordinates.
const Symbol key1('v', 1)
const Unit3 & direction() const
Direction.
Base class for all pinhole cameras.
gtsam::NonlinearFactor::shared_ptr clone() const override
NoiseModelFactor1< EssentialMatrix > Base
Eigen::VectorXd Vector
Definition: Vector.h:38
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
Point2 pn_
Measurement in image 2, in ideal coordinates.
GTSAM_EXPORT EssentialMatrix rotate(const Rot3 &cRb, OptionalJacobian< 5, 5 > HE=boost::none, OptionalJacobian< 5, 3 > HR=boost::none) const
Point3 dP1_
3D point corresponding to measurement in image 1
gtsam::NonlinearFactor::shared_ptr clone() const override
boost::shared_ptr< This > shared_ptr
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
GTSAM_EXPORT Point3 point3(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Point3.
Definition: Unit3.cpp:136
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model)
traits
Definition: chartTesting.h:28
Point2 pA(size_t i)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Non-linear factor base classes.
const Rot3 & rotation() const
Rotation.
const Symbol key2('v', 2)
static Point2 Project(const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint=boost::none)
Vector evaluateError(const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
NoiseModelFactor2< EssentialMatrix, double > Base
EssentialMatrixFactor(Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
Vector3 Point3
Definition: Point3.h:35
EssentialMatrixFactor3(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
Vector evaluateError(const EssentialMatrix &E, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 1D vector
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Rot3 cRb_
Rotation from body to camera frame.
double f_
approximate conversion factor for error scaling
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
EssentialMatrixFactor2(Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)


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