testSerializationNonlinear.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/nonlinear/Values.h>
20 #include <gtsam/inference/Symbol.h>
22 #include <gtsam/geometry/Pose2.h>
23 #include <gtsam/geometry/Cal3_S2.h>
24 #include <gtsam/geometry/Cal3DS2.h>
26 
29 
30 using namespace std;
31 using namespace gtsam;
32 using namespace gtsam::serializationTestHelpers;
33 
34 /* ************************************************************************* */
35 // Export all classes derived from Value
44 
45 namespace detail {
46 template<class T> struct pack {
47  typedef T type;
48 };
49 }
50 
51 /* ************************************************************************* */
55 
56 /* ************************************************************************* */
57 static Point3 pt3(1.0, 2.0, 3.0);
58 static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
59 static Pose3 pose3(rt3, pt3);
60 
61 static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5);
62 static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0);
63 static Cal3Bundler cal3(1.0, 2.0, 3.0);
64 
65 TEST (Serialization, TemplatedValues) {
68  EXPECT(equalsObj(chv1));
70  EXPECT(equalsObj(pc));
71 
72  Values values;
73  values.insert(1,pt3);
74 
75  EXPECT(equalsObj(values));
76  values.insert(Symbol('a',0), PinholeCal3S2(pose3, cal1));
77  values.insert(Symbol('s',5), PinholeCal3DS2(pose3, cal2));
78  values.insert(Symbol('d',47), PinholeCal3Bundler(pose3, cal3));
79  values.insert(Symbol('a',5), PinholeCal3S2(pose3, cal1));
80  EXPECT(equalsObj(values));
81  EXPECT(equalsXML(values));
82  EXPECT(equalsBinary(values));
83 }
84 
85 /* ************************************************************************* */
86 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
87 /* ************************************************************************* */
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
void insert(Key j, const Value &val)
Definition: Values.cpp:140
int RealScalar int RealScalar int RealScalar * pc
leaf::MyValues values
Definition: Half.h:150
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Base class for all pinhole cameras.
static Cal3Bundler cal3(1.0, 2.0, 3.0)
static Pose3 pose3(rt3, pt3)
static Rot3 rt3
#define EXPECT(condition)
Definition: Test.h:151
PinholeCamera< Cal3DS2 > PinholeCal3DS2
static Point3 pt3(1.0, 2.0, 3.0)
traits
Definition: chartTesting.h:28
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2)
static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0)
Vector3 Point3
Definition: Point3.h:35
2D Pose
Calibration used by Bundler.
PinholeCamera< Cal3Bundler > PinholeCal3Bundler
PinholeCamera< Cal3_S2 > PinholeCal3S2
The most common 5DOF 3D->2D calibration.
TEST(Serialization, TemplatedValues)
static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:27