gtsam  4.0.0
gtsam
EssentialMatrix.h
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 
26 class GTSAM_EXPORT EssentialMatrix {
27  private:
28  Rot3 R_;
29  Unit3 t_;
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  static EssentialMatrix FromRotationAndDirection(const Rot3& aRb, const Unit3& aTb,
52  OptionalJacobian<5, 3> H1 = boost::none,
53  OptionalJacobian<5, 2> H2 = boost::none);
54 
56  static EssentialMatrix FromPose3(const Pose3& _1P2_,
57  OptionalJacobian<5, 6> H = boost::none);
58 
60  template<typename Engine>
61  static EssentialMatrix Random(Engine & rng) {
62  return EssentialMatrix(Rot3::Random(rng), Unit3::Random(rng));
63  }
64 
65  virtual ~EssentialMatrix() {}
66 
68 
71 
73  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 
89  typedef OptionalJacobian<dimension, dimension> ChartJacobian;
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  Point3 transformTo(const Point3& p,
142  OptionalJacobian<3, 5> DE = boost::none,
143  OptionalJacobian<3, 3> Dpoint = boost::none) const;
144 
150  EssentialMatrix rotate(const Rot3& cRb, OptionalJacobian<5, 5> HE =
151  boost::none, OptionalJacobian<5, 3> HR = boost::none) const;
152 
158  friend EssentialMatrix operator*(const Rot3& cRb, const EssentialMatrix& E) {
159  return E.rotate(cRb);
160  }
161 
163  double error(const Vector3& vA, const Vector3& vB,
164  OptionalJacobian<1, 5> H = boost::none) 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 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
180  Point3 transform_to(const Point3& p,
183  OptionalJacobian<3, 5> DE = boost::none,
184  OptionalJacobian<3, 3> Dpoint = boost::none) const {
185  return transformTo(p, DE, Dpoint);
186  };
188 #endif
189 
190  private:
193 
195  friend class boost::serialization::access;
196  template<class ARCHIVE>
197  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
198  ar & BOOST_SERIALIZATION_NVP(R_);
199  ar & BOOST_SERIALIZATION_NVP(t_);
200 
201  ar & boost::serialization::make_nvp("E11", E_(0, 0));
202  ar & boost::serialization::make_nvp("E12", E_(0, 1));
203  ar & boost::serialization::make_nvp("E13", E_(0, 2));
204  ar & boost::serialization::make_nvp("E21", E_(1, 0));
205  ar & boost::serialization::make_nvp("E22", E_(1, 1));
206  ar & boost::serialization::make_nvp("E23", E_(1, 2));
207  ar & boost::serialization::make_nvp("E31", E_(2, 0));
208  ar & boost::serialization::make_nvp("E32", E_(2, 1));
209  ar & boost::serialization::make_nvp("E33", E_(2, 2));
210  }
211 
213 
214  public:
215  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
216 };
217 
218 template<>
219 struct traits<EssentialMatrix> : public internal::Manifold<EssentialMatrix> {};
220 
221 template<>
222 struct traits<const EssentialMatrix> : public internal::Manifold<EssentialMatrix> {};
223 
224 } // namespace gtsam
225 
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.
Definition: Unit3.h:114
bool equals(const Rot3 &p, double tol=1e-9) const
equals with an tolerance
Definition: Rot3.cpp:98
Base class and basic functions for Manifold types.
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
Definition: EssentialMatrix.h:92
static Vector3 Homogeneous(const Point2 &p)
Static function to convert Point2 to homogeneous coordinates.
Definition: EssentialMatrix.h:34
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Definition: Point3.h:45
Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H=boost::none) const
The retract function.
Definition: Unit3.cpp:253
const Unit3 & direction() const
Direction.
Definition: EssentialMatrix.h:115
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Definition: Rot3.h:56
const Matrix3 & matrix() const
Return 3*3 matrix representation.
Definition: EssentialMatrix.h:120
2D Point
EssentialMatrix()
Default constructor.
Definition: EssentialMatrix.h:42
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:134
EssentialMatrix(const Rot3 &aRb, const Unit3 &aTb)
Construct from rotation and translation.
Definition: EssentialMatrix.h:46
const Unit3 & epipole_a() const
Return epipole in image_a , as Unit3 to allow for infinity.
Definition: EssentialMatrix.h:125
Unit3 epipole_b() const
Return epipole in image_b, as Unit3 to allow for infinity.
Definition: EssentialMatrix.h:130
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:133
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
3D Pose
double y() const
get y
Definition: Point2.h:106
static Unit3 Random(boost::mt19937 &rng)
Random direction, using boost::uniform_on_sphere.
Definition: Unit3.cpp:57
Vector2 localCoordinates(const Unit3 &s) const
The local coordinates function.
Definition: Unit3.cpp:283
Definition: Point2.h:40
bool equals(const EssentialMatrix &other, double tol=1e-8) const
assert equality up to a tolerance
Definition: EssentialMatrix.h:76
An essential matrix is like a Pose3, except with translation up to scale It is named after the 3*3 ma...
Definition: EssentialMatrix.h:26
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
static Rot3 Random(boost::mt19937 &rng)
Random, generates a random axis, then random angle \in [-p,pi].
Definition: Rot3.cpp:37
Vector5 localCoordinates(const EssentialMatrix &other) const
Compute the coordinates in the tangent space.
Definition: EssentialMatrix.h:97
Definition: Pose3.h:37
static EssentialMatrix Random(Engine &rng)
Random, using Rot3::Random and Unit3::Random.
Definition: EssentialMatrix.h:61
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:138
Point2 operator *(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:170
double x() const
get x
Definition: Point2.h:103
const Rot3 & rotation() const
Rotation.
Definition: EssentialMatrix.h:110