36 using namespace gtsam;
41 static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
48 static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.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);
60 TEST (Serialization, text_geometry) {
62 EXPECT(equalsObj<gtsam::Pose2>(
Pose2(1.0, 2.0, 0.3)));
63 EXPECT(equalsObj<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
65 EXPECT(equalsObj<gtsam::Unit3>(
Unit3(1.0, 2.1, 3.4)));
69 EXPECT(equalsObj<gtsam::Rot3>(rt3));
85 TEST (Serialization, xml_geometry) {
87 EXPECT(equalsXML<gtsam::Pose2>(
Pose2(1.0, 2.0, 0.3)));
88 EXPECT(equalsXML<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
90 EXPECT(equalsXML<gtsam::Unit3>(
Unit3(1.0, 2.1, 3.4)));
94 EXPECT(equalsXML<gtsam::Rot3>(rt3));
109 TEST (Serialization, binary_geometry) {
111 EXPECT(equalsBinary<gtsam::Pose2>(
Pose2(1.0, 2.0, 0.3)));
112 EXPECT(equalsBinary<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
114 EXPECT(equalsBinary<gtsam::Unit3>(
Unit3(1.0, 2.1, 3.4)));
117 EXPECT(equalsBinary<gtsam::Point3>(
pt3));
118 EXPECT(equalsBinary<gtsam::Rot3>(rt3));
static Cal3Unified cal6(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0)
static PinholeCamera< Cal3_S2 > cam1(pose3, cal1)
static int runAllTests(TestResult &result)
static CalibratedCamera cal5(Pose3(rt3, pt3))
static StereoCamera cam2(pose3, cal4ptr)
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Represents a 3D point on a unit sphere.
Base class for all pinhole cameras.
static EssentialMatrix ematrix(rt3, unit3)
static Cal3Bundler cal3(1.0, 2.0, 3.0)
The most common 5DOF 3D->2D calibration, stereo version.
#define EXPECT(condition)
static Pose3 pose3(rt3, pt3)
The most common 5DOF 3D->2D calibration.
TEST(Serialization, text_geometry)
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
std::shared_ptr< Cal3_S2Stereo > shared_ptr
Calibrated camera for which only pose is unknown.
static Unit3 unit3(1.0, 2.1, 3.4)
Calibration of a omni-directional camera with mirror + lens radial distortion.
The most common 5DOF 3D->2D calibration + Stereo baseline.
Calibration used by Bundler.
static StereoPoint2 spt(1.0, 2.0, 3.0)
A Stereo Camera based on two Simple Cameras.
static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0)
A 2D stereo point (uL,uR,v)
static Cal3_S2Stereo cal4(1.0, 2.0, 3.0, 4.0, 5.0, 6.0)
Unified Calibration Model, see Mei07icra for details.
static Cal3_S2Stereo::shared_ptr cal4ptr(new Cal3_S2Stereo(cal4))
static Point3 pt3(1.0, 2.0, 3.0)
Calibration used by Bundler.
static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5)
The most common 5DOF 3D->2D calibration.