testSerialization.cpp
Go to the documentation of this file.
1 
11 
12 #include <gtsam/geometry/Pose2.h>
13 #include <gtsam/geometry/Pose3.h>
14 
17 
19 
20 #include <boost/filesystem.hpp>
21 
22 #include <iostream>
23 #include <cstdlib>
24 #include <fstream>
25 #include <sstream>
26 
27 using namespace std;
28 using namespace gtsam;
29 namespace fs = boost::filesystem;
30 #ifdef TOPSRCDIR
31 static string topdir = TOPSRCDIR;
32 #else
33 static string topdir = "TOPSRCDIR_NOT_CONFIGURED"; // If TOPSRCDIR is not defined, we error
34 #endif
35 
37  Values result;
38  result.insert(234, gtsam::Rot2::fromAngle(0.1));
39  result.insert(123, gtsam::Point2(1.0, 2.0));
40  result.insert(254, gtsam::Pose2(1.0, 2.0, 0.3));
41  result.insert(678, gtsam::Rot3::Rx(0.1));
42  result.insert(498, gtsam::Point3(1.0, 2.0, 3.0));
43  result.insert(345, gtsam::Pose3(Rot3::Rx(0.1), Point3(1.0, 2.0, 3.0)));
44  return result;
45 }
46 
49  graph.addPrior(234, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(Vector::Ones(3)));
50  graph.add(BetweenFactor<Pose2>(234, 567, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(Vector::Ones(3))));
51  graph.add(BearingRangeFactor<Pose2,Point2>(234, 567, Rot2::fromAngle(0.3), 2.0, noiseModel::Diagonal::Sigmas(Vector::Ones(2))));
52  return graph;
53 }
54 
55 /* ************************************************************************* */
56 TEST( testSerialization, text_graph_serialization ) {
58  string serialized = serializeGraph(graph);
59  NonlinearFactorGraph actGraph = *deserializeGraph(serialized);
60  EXPECT(assert_equal(graph, actGraph));
61 }
62 
63 /* ************************************************************************* */
64 TEST( testSerialization, xml_graph_serialization ) {
66  string serialized = serializeGraphXML(graph, "graph1");
67  NonlinearFactorGraph actGraph = *deserializeGraphXML(serialized, "graph1");
68  EXPECT(assert_equal(graph, actGraph));
69 }
70 
71 /* ************************************************************************* */
72 TEST( testSerialization, text_values_serialization ) {
74  string serialized = serializeValues(values);
75  Values actValues = *deserializeValues(serialized);
76  EXPECT(assert_equal(values, actValues));
77 }
78 
79 /* ************************************************************************* */
80 TEST( testSerialization, xml_values_serialization ) {
82  string serialized = serializeValuesXML(values, "values1");
83  Values actValues = *deserializeValuesXML(serialized, "values1");
84  EXPECT(assert_equal(values, actValues, 1e-5));
85 }
86 
87 /* ************************************************************************* */
88 TEST( testSerialization, serialization_file ) {
89  // Create files in folder in build folder
90  fs::remove_all("actual");
91  fs::create_directory("actual");
92  string path = "actual/";
93 
96 
97  // Serialize objects using each configuration
98  EXPECT(serializeGraphToFile(graph, path + "graph.dat"));
99  EXPECT(serializeGraphToXMLFile(graph, path + "graph.xml", "graph1"));
100 
101  EXPECT(serializeValuesToFile(values, path + "values.dat"));
102  EXPECT(serializeValuesToXMLFile(values, path + "values.xml", "values1"));
103 
104  // Deserialize
105  NonlinearFactorGraph actGraph = *deserializeGraphFromFile(path + "graph.dat");
106  NonlinearFactorGraph actGraphXML = *deserializeGraphFromXMLFile(path + "graph.xml", "graph1");
107 
108  Values actValues = *deserializeValuesFromFile(path + "values.dat");
109  Values actValuesXML = *deserializeValuesFromXMLFile(path + "values.xml", "values1");
110 
111  // Verify
112  EXPECT(assert_equal(graph, actGraph));
113  EXPECT(assert_equal(graph, actGraphXML));
114 
115  EXPECT(assert_equal(values, actValues));
116  EXPECT(assert_equal(values, actValuesXML));
117 }
118 
119 /* ************************************************************************* */
120 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
121 /* ************************************************************************* */
std::string serializeGraph(const NonlinearFactorGraph &graph)
NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string &serialized_graph)
static int runAllTests(TestResult &result)
Vector2 Point2
Definition: Point2.h:32
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
leaf::MyValues values
Values::shared_ptr deserializeValuesFromFile(const std::string &fname)
int main()
Definition: BFloat16.h:88
NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string &fname, const std::string &name="graph")
NonlinearFactorGraph graph
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:214
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
std::string serializeValuesXML(const Values &values, const std::string &name="values")
static Rot3 Rx(double t)
Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Definition: Rot3M.cpp:56
static string topdir
Values result
Values exampleValues()
#define EXPECT(condition)
Definition: Test.h:150
Values::shared_ptr deserializeValuesXML(const std::string &serialized_values, const std::string &name="values")
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Values::shared_ptr deserializeValues(const std::string &serialized_values)
NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string &fname)
traits
Definition: chartTesting.h:28
bool serializeGraphToXMLFile(const NonlinearFactorGraph &graph, const std::string &fname, const std::string &name="graph")
std::string serializeGraphXML(const NonlinearFactorGraph &graph, const std::string &name="graph")
bool serializeGraphToFile(const NonlinearFactorGraph &graph, const std::string &fname)
TEST(testSerialization, text_graph_serialization)
Values::shared_ptr deserializeValuesFromXMLFile(const std::string &fname, const std::string &name="values")
std::string serializeValues(const Values &values)
static Rot2 fromAngle(double theta)
Named constructor from angle in radians.
Definition: Rot2.h:61
void insert(Key j, const Value &val)
Definition: Values.cpp:155
bool serializeValuesToFile(const Values &values, const std::string &fname)
Vector3 Point3
Definition: Point3.h:38
NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string &serialized_graph, const std::string &name="graph")
2D Pose
3D Pose
NonlinearFactorGraph exampleGraph()
bool serializeValuesToXMLFile(const Values &values, const std::string &fname, const std::string &name="values")


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:18