EssentialMatrix.h
Go to the documentation of this file.
1 /*
2  * @file EssentialMatrix.h
3  * @brief EssentialMatrix class
4  * @author Frank Dellaert
5  * @date December 17, 2013
6  */
7 
8 #pragma once
9 
10 #include <gtsam/geometry/Pose3.h>
11 #include <gtsam/geometry/Unit3.h>
12 #include <gtsam/geometry/Point2.h>
13 #include <gtsam/base/Manifold.h>
14 
15 #include <iosfwd>
16 #include <string>
17 
18 namespace gtsam {
19 
27  private:
28  Rot3 R_;
30  Matrix3 E_;
31 
32  public:
34  static Vector3 Homogeneous(const Point2& p) {
35  return Vector3(p.x(), p.y(), 1);
36  }
37 
40 
42  EssentialMatrix() :E_(t_.skew()) {
43  }
44 
46  EssentialMatrix(const Rot3& aRb, const Unit3& aTb) :
47  R_(aRb), t_(aTb), E_(t_.skew() * R_.matrix()) {
48  }
49 
51  GTSAM_EXPORT static EssentialMatrix FromRotationAndDirection(const Rot3& aRb, const Unit3& aTb,
52  OptionalJacobian<5, 3> H1 = {},
53  OptionalJacobian<5, 2> H2 = {});
54 
56  GTSAM_EXPORT static EssentialMatrix FromPose3(const Pose3& _1P2_,
57  OptionalJacobian<5, 6> H = {});
58 
60  template<typename Engine>
61  static EssentialMatrix Random(Engine & rng) {
63  }
64 
65  virtual ~EssentialMatrix() {}
66 
68 
71 
73  GTSAM_EXPORT void print(const std::string& s = "") const;
74 
76  bool equals(const EssentialMatrix& other, double tol = 1e-8) const {
77  return R_.equals(other.R_, tol)
78  && t_.equals(other.t_, tol);
79  }
80 
82 
85  enum { dimension = 5 };
86  inline static size_t Dim() { return dimension;}
87  inline size_t dim() const { return dimension;}
88 
90 
92  EssentialMatrix retract(const Vector5& xi) const {
93  return EssentialMatrix(R_.retract(xi.head<3>()), t_.retract(xi.tail<2>()));
94  }
95 
97  Vector5 localCoordinates(const EssentialMatrix& other) const {
98  auto v1 = R_.localCoordinates(other.R_);
99  auto v2 = t_.localCoordinates(other.t_);
100  Vector5 v;
101  v << v1, v2;
102  return v;
103  }
105 
108 
110  inline const Rot3& rotation() const {
111  return R_;
112  }
113 
115  inline const Unit3& direction() const {
116  return t_;
117  }
118 
120  inline const Matrix3& matrix() const {
121  return E_;
122  }
123 
125  inline const Unit3& epipole_a() const {
126  return t_;
127  }
128 
130  inline Unit3 epipole_b() const {
131  return R_.unrotate(t_);
132  }
133 
141  GTSAM_EXPORT Point3 transformTo(const Point3& p,
142  OptionalJacobian<3, 5> DE = {},
143  OptionalJacobian<3, 3> Dpoint = {}) const;
144 
150  GTSAM_EXPORT EssentialMatrix rotate(const Rot3& cRb, OptionalJacobian<5, 5> HE =
151  {}, OptionalJacobian<5, 3> HR = {}) const;
152 
159  return E.rotate(cRb);
160  }
161 
163  GTSAM_EXPORT double error(const Vector3& vA, const Vector3& vB,
164  OptionalJacobian<1, 5> H = {}) const;
165 
167 
170 
172  GTSAM_EXPORT friend std::ostream& operator <<(std::ostream& os, const EssentialMatrix& E);
173 
175  GTSAM_EXPORT friend std::istream& operator >>(std::istream& is, EssentialMatrix& E);
176 
178 
179  private:
182 
183 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
184 
185  friend class boost::serialization::access;
186  template<class ARCHIVE>
187  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
188  ar & BOOST_SERIALIZATION_NVP(R_);
189  ar & BOOST_SERIALIZATION_NVP(t_);
190 
191  ar & boost::serialization::make_nvp("E11", E_(0, 0));
192  ar & boost::serialization::make_nvp("E12", E_(0, 1));
193  ar & boost::serialization::make_nvp("E13", E_(0, 2));
194  ar & boost::serialization::make_nvp("E21", E_(1, 0));
195  ar & boost::serialization::make_nvp("E22", E_(1, 1));
196  ar & boost::serialization::make_nvp("E23", E_(1, 2));
197  ar & boost::serialization::make_nvp("E31", E_(2, 0));
198  ar & boost::serialization::make_nvp("E32", E_(2, 1));
199  ar & boost::serialization::make_nvp("E33", E_(2, 2));
200  }
201 #endif
202 
204 
205  public:
207 };
208 
209 template<>
210 struct traits<EssentialMatrix> : public internal::Manifold<EssentialMatrix> {};
211 
212 template<>
213 struct traits<const EssentialMatrix> : public internal::Manifold<EssentialMatrix> {};
214 
215 } // namespace gtsam
216 
gtsam::EssentialMatrix::dim
size_t dim() const
Definition: EssentialMatrix.h:87
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::EssentialMatrix::direction
const Unit3 & direction() const
Direction.
Definition: EssentialMatrix.h:115
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
gtsam::EssentialMatrix::dimension
@ dimension
Definition: EssentialMatrix.h:85
aRb
Rot3 aRb
Definition: testFundamentalMatrix.cpp:146
gtsam::Rot3::Random
static Rot3 Random(std::mt19937 &rng)
Definition: Rot3.cpp:39
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
gtsam::EssentialMatrix::error
GTSAM_EXPORT double error(const Vector3 &vA, const Vector3 &vB, OptionalJacobian< 1, 5 > H={}) const
epipolar error, algebraic
Definition: EssentialMatrix.cpp:104
gtsam::EssentialMatrix::operator<<
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const EssentialMatrix &E)
stream to stream
gtsam::EssentialMatrix::epipole_b
Unit3 epipole_b() const
Return epipole in image_b, as Unit3 to allow for infinity.
Definition: EssentialMatrix.h:130
gtsam::EssentialMatrix::operator*
friend EssentialMatrix operator*(const Rot3 &cRb, const EssentialMatrix &E)
Definition: EssentialMatrix.h:158
gtsam::EssentialMatrix::print
GTSAM_EXPORT void print(const std::string &s="") const
print with optional string
Definition: EssentialMatrix.cpp:48
gtsam::EssentialMatrix::R_
Rot3 R_
Rotation.
Definition: EssentialMatrix.h:28
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::internal::Manifold
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
os
ofstream os("timeSchurFactors.csv")
gtsam::EssentialMatrix::retract
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
Definition: EssentialMatrix.h:92
gtsam::Rot3::unrotate
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
Definition: Rot3.cpp:135
example1::vB
Vector vB(size_t i)
Definition: testEssentialMatrixFactor.cpp:52
Point2.h
2D Point
Unit3.h
example1::vA
Vector vA(size_t i)
Definition: testEssentialMatrixFactor.cpp:51
gtsam::EssentialMatrix::Homogeneous
static Vector3 Homogeneous(const Point2 &p)
Static function to convert Point2 to homogeneous coordinates.
Definition: EssentialMatrix.h:34
gtsam::EssentialMatrix::FromRotationAndDirection
static GTSAM_EXPORT EssentialMatrix FromRotationAndDirection(const Rot3 &aRb, const Unit3 &aTb, OptionalJacobian< 5, 3 > H1={}, OptionalJacobian< 5, 2 > H2={})
Named constructor with derivatives.
Definition: EssentialMatrix.cpp:16
gtsam::EssentialMatrix::EssentialMatrix
EssentialMatrix()
Default constructor.
Definition: EssentialMatrix.h:42
gtsam::EssentialMatrix::localCoordinates
Vector5 localCoordinates(const EssentialMatrix &other) const
Compute the coordinates in the tangent space.
Definition: EssentialMatrix.h:97
gtsam::EssentialMatrix
Definition: EssentialMatrix.h:26
gtsam::EssentialMatrix::rotate
GTSAM_EXPORT EssentialMatrix rotate(const Rot3 &cRb, OptionalJacobian< 5, 5 > HE={}, OptionalJacobian< 5, 3 > HR={}) const
Definition: EssentialMatrix.cpp:73
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::EssentialMatrix::rotation
const Rot3 & rotation() const
Rotation.
Definition: EssentialMatrix.h:110
gtsam::EssentialMatrix::EssentialMatrix
EssentialMatrix(const Rot3 &aRb, const Unit3 &aTb)
Construct from rotation and translation.
Definition: EssentialMatrix.h:46
example2::aTb
Point3 aTb
Definition: testEssentialMatrixFactor.cpp:541
Manifold.h
Base class and basic functions for Manifold types.
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::LieGroup::localCoordinates
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:136
gtsam::Unit3::retract
Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H={}) const
The retract function.
Definition: Unit3.cpp:255
gtsam::EssentialMatrix::epipole_a
const Unit3 & epipole_a() const
Return epipole in image_a , as Unit3 to allow for infinity.
Definition: EssentialMatrix.h:125
E
DiscreteKey E(5, 2)
gtsam::EssentialMatrix::matrix
const Matrix3 & matrix() const
Return 3*3 matrix representation.
Definition: EssentialMatrix.h:120
gtsam::EssentialMatrix::t_
Unit3 t_
Translation.
Definition: EssentialMatrix.h:29
gtsam::EssentialMatrix::equals
bool equals(const EssentialMatrix &other, double tol=1e-8) const
assert equality up to a tolerance
Definition: EssentialMatrix.h:76
gtsam
traits
Definition: SFMdata.h:40
gtsam::EssentialMatrix::transformTo
GTSAM_EXPORT Point3 transformTo(const Point3 &p, OptionalJacobian< 3, 5 > DE={}, OptionalJacobian< 3, 3 > Dpoint={}) const
takes point in world coordinates and transforms it to pose with |t|==1
Definition: EssentialMatrix.cpp:55
gtsam::EssentialMatrix::~EssentialMatrix
virtual ~EssentialMatrix()
Definition: EssentialMatrix.h:65
gtsam::EssentialMatrix::Dim
static size_t Dim()
Definition: EssentialMatrix.h:86
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::EssentialMatrix::Random
static EssentialMatrix Random(Engine &rng)
Random, using Rot3::Random and Unit3::Random.
Definition: EssentialMatrix.h:61
v2
Vector v2
Definition: testSerializationBase.cpp:39
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::Unit3::equals
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.
Definition: Unit3.h:115
gtsam::Unit3::Random
static Unit3 Random(std::mt19937 &rng)
Definition: Unit3.cpp:55
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::EssentialMatrix::operator>>
GTSAM_EXPORT friend std::istream & operator>>(std::istream &is, EssentialMatrix &E)
stream from stream
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::LieGroup::retract
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
gtsam::EssentialMatrix::E_
Matrix3 E_
Essential matrix.
Definition: EssentialMatrix.h:30
cRb
gtsam::Rot3 cRb
Definition: testEssentialMatrixFactor.cpp:33
gtsam::Rot3::equals
bool equals(const Rot3 &p, double tol=1e-9) const
Definition: Rot3.cpp:99
Pose3
Definition: testDependencies.h:3
gtsam::EssentialMatrix::ChartJacobian
OptionalJacobian< dimension, dimension > ChartJacobian
Definition: EssentialMatrix.h:89
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
Pose3.h
3D Pose
gtsam::Unit3::localCoordinates
Vector2 localCoordinates(const Unit3 &s) const
The local coordinates function.
Definition: Unit3.cpp:285
v1
Vector v1
Definition: testSerializationBase.cpp:38
gtsam::EssentialMatrix::FromPose3
static GTSAM_EXPORT EssentialMatrix FromPose3(const Pose3 &_1P2_, OptionalJacobian< 5, 6 > H={})
Named constructor converting a Pose3 with scale to EssentialMatrix (no scale)
Definition: EssentialMatrix.cpp:27
HR
#define HR
Definition: mincover.c:26


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:16