13 #include <gtsam/slam/serialization.h> 24 #include <boost/assign/std/vector.hpp> 25 #include <boost/filesystem.hpp> 28 using namespace gtsam;
30 namespace fs = boost::filesystem;
32 static string topdir = TOPSRCDIR;
34 static string topdir =
"TOPSRCDIR_NOT_CONFIGURED";
50 graph.
addPrior(234,
Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(Vector::Ones(3)));
57 TEST( testSerialization, text_graph_serialization ) {
65 TEST( testSerialization, xml_graph_serialization ) {
73 TEST( testSerialization, text_values_serialization ) {
81 TEST( testSerialization, xml_values_serialization ) {
89 TEST( testSerialization, serialization_file ) {
91 fs::remove_all(
"actual");
92 fs::create_directory(
"actual");
93 string path =
"actual/";
NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string &fname, const std::string &name="graph")
Values::shared_ptr deserializeValuesFromXMLFile(const std::string &fname, const std::string &name="values")
static int runAllTests(TestResult &result)
void insert(Key j, const Value &val)
NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string &serialized_graph)
Values::shared_ptr deserializeValues(const std::string &serialized_values)
IsDerived< DERIVEDFACTOR > add(boost::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
bool serializeGraphToFile(const NonlinearFactorGraph &graph, const std::string &fname)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
bool serializeGraphToXMLFile(const NonlinearFactorGraph &graph, const std::string &fname, const std::string &name="graph")
static Rot3 Rx(double t)
Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Values::shared_ptr deserializeValuesXML(const std::string &serialized_values, const std::string &name="values")
Values::shared_ptr deserializeValuesFromFile(const std::string &fname)
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::string serializeGraph(const NonlinearFactorGraph &graph)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
std::string serializeGraphXML(const NonlinearFactorGraph &graph, const std::string &name="graph")
NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string &serialized_graph, const std::string &name="graph")
NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string &fname)
TEST(testSerialization, text_graph_serialization)
std::string serializeValues(const Values &values)
static Rot2 fromAngle(double theta)
Named constructor from angle in radians.
std::string serializeValuesXML(const Values &values, const std::string &name="values")
NonlinearFactorGraph exampleGraph()
bool serializeValuesToXMLFile(const Values &values, const std::string &fname, const std::string &name="values")
bool serializeValuesToFile(const Values &values, const std::string &fname)