From fafa3326f32073be6f453817c9c7bdfa9b09ebda Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 22 Jan 2014 00:59:22 -0500 Subject: [PATCH] Streaming implemented with test --- gtsam/geometry/tests/testEssentialMatrix.cpp | 36 ++++++++++++++++++++ 1 file changed, 36 insertions(+) diff --git a/gtsam/geometry/tests/testEssentialMatrix.cpp b/gtsam/geometry/tests/testEssentialMatrix.cpp index 56fc8d8ad..1e94f12f3 100644 --- a/gtsam/geometry/tests/testEssentialMatrix.cpp +++ b/gtsam/geometry/tests/testEssentialMatrix.cpp @@ -10,6 +10,7 @@ #include #include #include +#include using namespace std; using namespace gtsam; @@ -121,6 +122,41 @@ TEST (EssentialMatrix, FromPose3_b) { EXPECT(assert_equal(expectedH, actualH, 1e-8)); } +/* ************************************************************************* */ +ostream& operator <<(ostream& os, const gtsam::EssentialMatrix& E) { + gtsam::Rot3 R = E.rotation(); + gtsam::Sphere2 d = E.direction(); + os.precision(10); + os << R.xyz().transpose() << " " << d.point3().vector().transpose() << " "; + return os; +} + +/* ************************************************************************* */ +istream& operator >>(istream& fs, gtsam::EssentialMatrix& E) { + double rx, ry, rz, dx, dy, dz; + + // Read the rotation rxyz + fs >> rx >> ry >> rz; + + // Read the translation dxyz + fs >> dx >> dy >> dz; + + // Create EssentialMatrix: Construct from rotation and translation + gtsam::Rot3 rot = gtsam::Rot3::RzRyRx(rx, ry, rz); + gtsam::Sphere2 dt = gtsam::Sphere2(dx, dy, dz); + E = gtsam::EssentialMatrix(rot, dt); + return fs; +} + +//************************************************************************* +TEST (EssentialMatrix, streaming) { + EssentialMatrix expected(c1Rc2, c1Tc2), actual; + stringstream ss; + ss << expected; + ss >> actual; + EXPECT(assert_equal(expected, actual)); +} + /* ************************************************************************* */ int main() { TestResult tr;