testEssentialMatrix.cpp
Go to the documentation of this file.
1 /*
2  * @file testEssentialMatrix.cpp
3  * @brief Test EssentialMatrix class
4  * @author Frank Dellaert
5  * @date December 17, 2013
6  */
7 
11 #include <gtsam/base/Testable.h>
13 #include <sstream>
14 
15 using namespace std;
16 using namespace gtsam;
17 
20 
21 //*************************************************************************
22 // Create two cameras and corresponding essential matrix E
23 Rot3 trueRotation = Rot3::Yaw(M_PI_2);
24 Point3 trueTranslation(0.1, 0, 0);
25 Unit3 trueDirection(trueTranslation);
27 
28 //*************************************************************************
30  EssentialMatrix actual(trueRotation, trueDirection), expected(trueRotation, trueDirection);
31  EXPECT(assert_equal(expected, actual));
32 }
33 
34 //*************************************************************************
35 TEST(EssentialMatrix, FromRotationAndDirection) {
36  Matrix actualH1, actualH2;
38  trueE, EssentialMatrix::FromRotationAndDirection(trueRotation, trueDirection, actualH1, actualH2),
39  1e-8));
40 
41  Matrix expectedH1 = numericalDerivative11<EssentialMatrix, Rot3>(
42  boost::bind(EssentialMatrix::FromRotationAndDirection, _1, trueDirection, boost::none,
43  boost::none),
44  trueRotation);
45  EXPECT(assert_equal(expectedH1, actualH1, 1e-7));
46 
47  Matrix expectedH2 = numericalDerivative11<EssentialMatrix, Unit3>(
48  boost::bind(EssentialMatrix::FromRotationAndDirection, trueRotation, _1, boost::none,
49  boost::none),
51  EXPECT(assert_equal(expectedH2, actualH2, 1e-7));
52 }
53 
54 //*************************************************************************
55 TEST (EssentialMatrix, FromPose3) {
58  EssentialMatrix actual = EssentialMatrix::FromPose3(pose);
59  EXPECT(assert_equal(expected, actual));
60 }
61 
62 //*******************************************************************************
63 TEST(EssentialMatrix, localCoordinates0) {
65  Vector expected = Z_5x1;
66  Vector actual = E.localCoordinates(E);
67  EXPECT(assert_equal(expected, actual, 1e-8));
68 }
69 
70 //*************************************************************************
71 TEST (EssentialMatrix, localCoordinates) {
72 
73  // Pose between two cameras
75  EssentialMatrix hx = EssentialMatrix::FromPose3(pose);
76  Vector actual = hx.localCoordinates(EssentialMatrix::FromPose3(pose));
77  EXPECT(assert_equal(Z_5x1, actual, 1e-8));
78 
79  Vector6 d;
80  d << 0.1, 0.2, 0.3, 0, 0, 0;
81  Vector actual2 = hx.localCoordinates(
82  EssentialMatrix::FromPose3(pose.retract(d)));
83  EXPECT(assert_equal(d.head(5), actual2, 1e-8));
84 }
85 
86 //*************************************************************************
87 TEST (EssentialMatrix, retract0) {
88  EssentialMatrix actual = trueE.retract(Z_5x1);
89  EXPECT(assert_equal(trueE, actual));
90 }
91 
92 //*************************************************************************
93 TEST (EssentialMatrix, retract1) {
95  EssentialMatrix actual = trueE.retract((Vector(5) << 0.1, 0, 0, 0, 0).finished());
96  EXPECT(assert_equal(expected, actual));
97 }
98 
99 //*************************************************************************
100 TEST (EssentialMatrix, retract2) {
102  trueDirection.retract(Vector2(0.1, 0)));
103  EssentialMatrix actual = trueE.retract((Vector(5) << 0, 0, 0, 0.1, 0).finished());
104  EXPECT(assert_equal(expected, actual));
105 }
106 
107 //*************************************************************************
108 TEST (EssentialMatrix, RoundTrip) {
109  Vector5 d;
110  d << 0.1, 0.2, 0.3, 0.4, 0.5;
111  EssentialMatrix e, hx = e.retract(d);
112  Vector actual = e.localCoordinates(hx);
113  EXPECT(assert_equal(d, actual, 1e-8));
114 }
115 
116 //*************************************************************************
118  return E.transformTo(point);
119 }
121  // test with a more complicated EssentialMatrix
122  Rot3 aRb2 = Rot3::Yaw(M_PI / 3.0) * Rot3::Pitch(M_PI_4)
123  * Rot3::Roll(M_PI / 6.0);
124  Point3 aTb2(19.2, 3.7, 5.9);
125  EssentialMatrix E(aRb2, Unit3(aTb2));
126  //EssentialMatrix E(aRb, Unit3(aTb).retract(Vector2(0.1, 0)));
127  static Point3 P(0.2, 0.7, -2);
128  Matrix actH1, actH2;
129  E.transformTo(P, actH1, actH2);
130  Matrix expH1 = numericalDerivative21(transform_to_, E, P), //
131  expH2 = numericalDerivative22(transform_to_, E, P);
132  EXPECT(assert_equal(expH1, actH1, 1e-8));
133  EXPECT(assert_equal(expH2, actH2, 1e-8));
134 }
135 
136 //*************************************************************************
138  return E.rotate(cRb);
139 }
141  // Suppose the essential matrix is specified in a body coordinate frame B
142  // which is rotated with respect to the camera frame C, via rotation bRc.
143  // The rotation between body and camera is:
144  Point3 bX(1, 0, 0), bY(0, 1, 0), bZ(0, 0, 1);
145  Rot3 bRc(bX, bZ, -bY), cRb = bRc.inverse();
146 
147  // Let's compute the ground truth E in body frame:
148  Rot3 b1Rb2 = bRc * trueRotation * cRb;
149  Point3 b1Tb2 = bRc * trueTranslation;
150  EssentialMatrix bodyE(b1Rb2, Unit3(b1Tb2));
151  EXPECT(assert_equal(bodyE, bRc * trueE, 1e-8));
152  EXPECT(assert_equal(bodyE, trueE.rotate(bRc), 1e-8));
153 
154  // Let's go back to camera frame:
155  EXPECT(assert_equal(trueE, cRb * bodyE, 1e-8));
156  EXPECT(assert_equal(trueE, bodyE.rotate(cRb), 1e-8));
157 
158  // Derivatives
159  Matrix actH1, actH2;
160  try {
161  bodyE.rotate(cRb, actH1, actH2);
162  } catch (exception& e) {
163  } // avoid exception
164  Matrix expH1 = numericalDerivative21(rotate_, bodyE, cRb), //
165  expH2 = numericalDerivative22(rotate_, bodyE, cRb);
166  EXPECT(assert_equal(expH1, actH1, 1e-7));
167  // Does not work yet EXPECT(assert_equal(expH2, actH2, 1e-8));
168 }
169 
170 //*************************************************************************
171 TEST (EssentialMatrix, FromPose3_a) {
172  Matrix actualH;
173  Pose3 pose(trueRotation, trueTranslation); // Pose between two cameras
174  EXPECT(assert_equal(trueE, EssentialMatrix::FromPose3(pose, actualH), 1e-8));
175  Matrix expectedH = numericalDerivative11<EssentialMatrix, Pose3>(
176  boost::bind(EssentialMatrix::FromPose3, _1, boost::none), pose);
177  EXPECT(assert_equal(expectedH, actualH, 1e-7));
178 }
179 
180 //*************************************************************************
181 TEST (EssentialMatrix, FromPose3_b) {
182  Matrix actualH;
183  Rot3 c1Rc2 = Rot3::Ypr(0.1, -0.2, 0.3);
184  Point3 c1Tc2(0.4, 0.5, 0.6);
185  EssentialMatrix E(c1Rc2, Unit3(c1Tc2));
186  Pose3 pose(c1Rc2, c1Tc2); // Pose between two cameras
187  EXPECT(assert_equal(E, EssentialMatrix::FromPose3(pose, actualH), 1e-8));
188  Matrix expectedH = numericalDerivative11<EssentialMatrix, Pose3>(
189  boost::bind(EssentialMatrix::FromPose3, _1, boost::none), pose);
190  EXPECT(assert_equal(expectedH, actualH, 1e-5));
191 }
192 
193 //*************************************************************************
194 TEST (EssentialMatrix, streaming) {
196  stringstream ss;
197  ss << expected;
198  ss >> actual;
199  EXPECT(assert_equal(expected, actual));
200 }
201 
202 //*************************************************************************
203 TEST (EssentialMatrix, epipoles) {
204  // Create an E
205  Rot3 c1Rc2 = Rot3::Ypr(0.1, -0.2, 0.3);
206  Point3 c1Tc2(0.4, 0.5, 0.6);
207  EssentialMatrix E(c1Rc2, Unit3(c1Tc2));
208 
209  // Calculate expected values through SVD
210  Matrix U, V;
211  Vector S;
212  gtsam::svd(E.matrix(), U, S, V);
213 
214  // take care of SVD sign ambiguity
215  if (U(0, 2) > 0) {
216  U = -U;
217  V = -V;
218  }
219 
220  // check rank 2 constraint
221  CHECK(std::abs(S(2))<1e-10);
222 
223  // check epipoles not at infinity
224  CHECK(std::abs(U(2,2))>1e-10 && std::abs(V(2,2))>1e-10);
225 
226  // Check epipoles
227 
228  // Epipole in image 1 is just E.direction()
229  Unit3 e1(-U(0, 2), -U(1, 2), -U(2, 2));
230  Unit3 actual = E.epipole_a();
231  EXPECT(assert_equal(e1, actual));
232 
233  // take care of SVD sign ambiguity
234  if (V(0, 2) < 0) {
235  U = -U;
236  V = -V;
237  }
238 
239  // Epipole in image 2 is E.rotation().unrotate(E.direction())
240  Unit3 e2(V(0, 2), V(1, 2), V(2, 2));
241  EXPECT(assert_equal(e2, E.epipole_b()));
242 }
243 
244 /* ************************************************************************* */
245 int main() {
246  TestResult tr;
247  return TestRegistry::runAllTests(tr);
248 }
249 /* ************************************************************************* */
250 
GTSAM_EXPORT Point3 transformTo(const Point3 &p, OptionalJacobian< 3, 5 > DE=boost::none, OptionalJacobian< 3, 3 > Dpoint=boost::none) const
takes point in world coordinates and transforms it to pose with |t|==1
#define CHECK(condition)
Definition: Test.h:109
Key E(std::uint64_t j)
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Matrix expected
Definition: testMatrix.cpp:974
const Matrix3 & matrix() const
Return 3*3 matrix representation.
GTSAM_EXPORT Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H=boost::none) const
The retract function.
Definition: Unit3.cpp:247
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
gtsam::Point3 bX(1, 0, 0)
#define M_PI
Definition: main.h:78
gtsam::Point3 bY(0, 1, 0)
Vector5 localCoordinates(const EssentialMatrix &other) const
Compute the coordinates in the tangent space.
Definition: Half.h:150
EssentialMatrix trueE(trueRotation, trueDirection)
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
EssentialMatrix retract(const Vector5 &xi) const
Retract delta to manifold.
Point3 trueTranslation(0.1, 0, 0)
gtsam::Rot3 cRb
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
Point3 point(10, 0,-5)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Eigen::VectorXd Vector
Definition: Vector.h:38
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Key S(std::uint64_t j)
GTSAM_EXPORT EssentialMatrix rotate(const Rot3 &cRb, OptionalJacobian< 5, 5 > HE=boost::none, OptionalJacobian< 5, 3 > HR=boost::none) const
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
#define EXPECT(condition)
Definition: Test.h:151
P rotate(const T &r, const P &pt)
Definition: lieProxies.h:47
EssentialMatrix rotate_(const EssentialMatrix &E, const Rot3 &cRb)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Point3 bZ(0, 0, 1)
static std::stringstream ss
Definition: testBTree.cpp:33
Calibrated camera for which only pose is unknown.
Unit3 trueDirection(trueTranslation)
traits
Definition: chartTesting.h:28
int main()
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:130
EssentialMatrix bodyE
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
Definition: Manifold.h:180
Rot3 trueRotation
Point3 transform_to_(const EssentialMatrix &E, const Point3 &point)
Unit3 epipole_b() const
Return epipole in image_b, as Unit3 to allow for infinity.
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
Definition: Matrix.cpp:559
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
Vector3 Point3
Definition: Point3.h:35
#define abs(x)
Definition: datatypes.h:17
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
const Unit3 & epipole_a() const
Return epipole in image_a , as Unit3 to allow for infinity.
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:174
TEST(EssentialMatrix, equality)


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