testSerializationGeometry.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/geometry/Pose2.h>
20 #include <gtsam/geometry/Unit3.h>
22 #include <gtsam/geometry/Cal3_S2.h>
26 #include <gtsam/geometry/Cal3DS2.h>
31 
34 
35 using namespace std;
36 using namespace gtsam;
37 using namespace gtsam::serializationTestHelpers;
38 
39 /* ************************************************************************* */
40 static Point3 pt3(1.0, 2.0, 3.0);
41 static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
42 static Pose3 pose3(rt3, pt3);
43 
44 static Unit3 unit3(1.0, 2.1, 3.4);
46 
47 static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5);
48 static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0);
49 static Cal3Bundler cal3(1.0, 2.0, 3.0);
50 static Cal3_S2Stereo cal4(1.0, 2.0, 3.0, 4.0, 5.0, 6.0);
53 static Cal3Unified cal6(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0);
54 
57 static StereoPoint2 spt(1.0, 2.0, 3.0);
58 
59 /* ************************************************************************* */
60 TEST (Serialization, text_geometry) {
61  EXPECT(equalsObj<gtsam::Point2>(Point2(1.0, 2.0)));
62  EXPECT(equalsObj<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
63  EXPECT(equalsObj<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
64 
65  EXPECT(equalsObj<gtsam::Unit3>(Unit3(1.0, 2.1, 3.4)));
66  EXPECT(equalsObj<gtsam::EssentialMatrix>(EssentialMatrix(rt3, unit3)));
67 
68  EXPECT(equalsObj(pt3));
69  EXPECT(equalsObj<gtsam::Rot3>(rt3));
70  EXPECT(equalsObj<gtsam::Pose3>(Pose3(rt3, pt3)));
71 
72  EXPECT(equalsObj(cal1));
73  EXPECT(equalsObj(cal2));
74  EXPECT(equalsObj(cal3));
75  EXPECT(equalsObj(cal4));
76  EXPECT(equalsObj(cal5));
77  EXPECT(equalsObj(cal6));
78 
79  EXPECT(equalsObj(cam1));
80  EXPECT(equalsObj(cam2));
81  EXPECT(equalsObj(spt));
82 }
83 
84 /* ************************************************************************* */
85 TEST (Serialization, xml_geometry) {
86  EXPECT(equalsXML<gtsam::Point2>(Point2(1.0, 2.0)));
87  EXPECT(equalsXML<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
88  EXPECT(equalsXML<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
89 
90  EXPECT(equalsXML<gtsam::Unit3>(Unit3(1.0, 2.1, 3.4)));
91  EXPECT(equalsXML<gtsam::EssentialMatrix>(EssentialMatrix(rt3, unit3)));
92 
93  EXPECT(equalsXML<gtsam::Point3>(pt3));
94  EXPECT(equalsXML<gtsam::Rot3>(rt3));
95  EXPECT(equalsXML<gtsam::Pose3>(Pose3(rt3, pt3)));
96 
97  EXPECT(equalsXML(cal1));
98  EXPECT(equalsXML(cal2));
99  EXPECT(equalsXML(cal3));
100  EXPECT(equalsXML(cal4));
101  EXPECT(equalsXML(cal5));
102 
103  EXPECT(equalsXML(cam1));
104  EXPECT(equalsXML(cam2));
105  EXPECT(equalsXML(spt));
106 }
107 
108 /* ************************************************************************* */
109 TEST (Serialization, binary_geometry) {
110  EXPECT(equalsBinary<gtsam::Point2>(Point2(1.0, 2.0)));
111  EXPECT(equalsBinary<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
112  EXPECT(equalsBinary<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
113 
114  EXPECT(equalsBinary<gtsam::Unit3>(Unit3(1.0, 2.1, 3.4)));
115  EXPECT(equalsBinary<gtsam::EssentialMatrix>(EssentialMatrix(rt3, unit3)));
116 
117  EXPECT(equalsBinary<gtsam::Point3>(pt3));
118  EXPECT(equalsBinary<gtsam::Rot3>(rt3));
119  EXPECT(equalsBinary<gtsam::Pose3>(Pose3(rt3, pt3)));
120 
121  EXPECT(equalsBinary(cal1));
122  EXPECT(equalsBinary(cal2));
123  EXPECT(equalsBinary(cal3));
124  EXPECT(equalsBinary(cal4));
125  EXPECT(equalsBinary(cal5));
126 
127  EXPECT(equalsBinary(cam1));
128  EXPECT(equalsBinary(cam2));
129  EXPECT(equalsBinary(spt));
130 }
131 
132 /* ************************************************************************* */
133 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
134 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
cal1
static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5)
main
int main()
Definition: testSerializationGeometry.cpp:133
cam1
static PinholeCamera< Cal3_S2 > cam1(pose3, cal1)
EssentialMatrix.h
Pose2.h
2D Pose
TEST
TEST(Serialization, text_geometry)
Definition: testSerializationGeometry.cpp:60
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
Cal3_S2.h
The most common 5DOF 3D->2D calibration.
gtsam::Cal3DS2
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
Definition: Cal3DS2.h:35
TestHarness.h
pose3
static Pose3 pose3(rt3, pt3)
ematrix
static EssentialMatrix ematrix(rt3, unit3)
cal3
static Cal3Bundler cal3(1.0, 2.0, 3.0)
CalibratedCamera.h
Calibrated camera for which only pose is unknown.
Unit3.h
cal4
static Cal3_S2Stereo cal4(1.0, 2.0, 3.0, 4.0, 5.0, 6.0)
pt3
static Point3 pt3(1.0, 2.0, 3.0)
gtsam::EssentialMatrix
Definition: EssentialMatrix.h:26
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
cal4ptr
static Cal3_S2Stereo::shared_ptr cal4ptr(new Cal3_S2Stereo(cal4))
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::Cal3Bundler
Calibration used by Bundler.
Definition: Cal3Bundler.h:32
cal6
static Cal3Unified cal6(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0)
gtsam::Cal3_S2Stereo::shared_ptr
std::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
cal2
static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0)
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
Cal3_S2Stereo.h
The most common 5DOF 3D->2D calibration + Stereo baseline.
spt
static StereoPoint2 spt(1.0, 2.0, 3.0)
StereoPoint2.h
A 2D stereo point (uL,uR,v)
gtsam::CalibratedCamera
Definition: CalibratedCamera.h:251
Cal3Unified.h
Unified Calibration Model, see Mei07icra for details.
serializationTestHelpers.h
TestResult
Definition: TestResult.h:26
cam2
static StereoCamera cam2(pose3, cal4ptr)
gtsam
traits
Definition: SFMdata.h:40
gtsam::Cal3_S2Stereo
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
Cal3DS2.h
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
gtsam::StereoPoint2
Definition: StereoPoint2.h:34
std
Definition: BFloat16.h:88
gtsam::Cal3Unified
Calibration of a omni-directional camera with mirror + lens radial distortion.
Definition: Cal3Unified.h:45
gtsam::StereoCamera
Definition: StereoCamera.h:47
rt3
static Rot3 rt3
Definition: testSerializationGeometry.cpp:41
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
cal5
static CalibratedCamera cal5(Pose3(rt3, pt3))
Cal3Bundler.h
Calibration used by Bundler.
unit3
static Unit3 unit3(1.0, 2.1, 3.4)
StereoCamera.h
A Stereo Camera based on two Simple Cameras.
gtsam::Pose2
Definition: Pose2.h:39


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