Changed naming convention for deserialization functions
parent
cabcb3efc8
commit
a8199f2ed0
12
gtsam.h
12
gtsam.h
|
|
@ -2144,13 +2144,13 @@ bool serializeValuesToXMLFile(const gtsam::Values& values, string fname);
|
||||||
bool serializeValuesToXMLFile(const gtsam::Values& values, string fname, string name);
|
bool serializeValuesToXMLFile(const gtsam::Values& values, string fname, string name);
|
||||||
|
|
||||||
// Deserialize
|
// Deserialize
|
||||||
gtsam::NonlinearFactorGraph* deserializeGraphToFile(string fname);
|
gtsam::NonlinearFactorGraph* deserializeGraphFromFile(string fname);
|
||||||
gtsam::NonlinearFactorGraph* deserializeGraphToXMLFile(string fname);
|
gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname);
|
||||||
gtsam::NonlinearFactorGraph* deserializeGraphToXMLFile(string fname, string name);
|
gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname, string name);
|
||||||
|
|
||||||
gtsam::Values* deserializeValuesToFile(string fname);
|
gtsam::Values* deserializeValuesFromFile(string fname);
|
||||||
gtsam::Values* deserializeValuesToXMLFile(string fname);
|
gtsam::Values* deserializeValuesFromXMLFile(string fname);
|
||||||
gtsam::Values* deserializeValuesToXMLFile(string fname, string name);
|
gtsam::Values* deserializeValuesFromXMLFile(string fname, string name);
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// Utilities
|
// Utilities
|
||||||
|
|
|
||||||
|
|
@ -275,7 +275,7 @@ bool gtsam::serializeValuesToXMLFile(const Values& values,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToFile(const std::string& fname) {
|
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphFromFile(const std::string& fname) {
|
||||||
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
|
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
|
||||||
if (!deserializeFromFile<NonlinearFactorGraph>(fname, *result))
|
if (!deserializeFromFile<NonlinearFactorGraph>(fname, *result))
|
||||||
throw std::invalid_argument("Failed to open file" + fname);
|
throw std::invalid_argument("Failed to open file" + fname);
|
||||||
|
|
@ -283,7 +283,7 @@ NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToFile(const std::string
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToXMLFile(const std::string& fname,
|
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphFromXMLFile(const std::string& fname,
|
||||||
const std::string& name) {
|
const std::string& name) {
|
||||||
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
|
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
|
||||||
if (!deserializeFromXMLFile<NonlinearFactorGraph>(fname, *result, name))
|
if (!deserializeFromXMLFile<NonlinearFactorGraph>(fname, *result, name))
|
||||||
|
|
@ -292,7 +292,7 @@ NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToXMLFile(const std::str
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Values::shared_ptr gtsam::deserializeValuesToFile(const std::string& fname) {
|
Values::shared_ptr gtsam::deserializeValuesFromFile(const std::string& fname) {
|
||||||
Values::shared_ptr result(new Values());
|
Values::shared_ptr result(new Values());
|
||||||
if (!deserializeFromFile<Values>(fname, *result))
|
if (!deserializeFromFile<Values>(fname, *result))
|
||||||
throw std::invalid_argument("Failed to open file" + fname);
|
throw std::invalid_argument("Failed to open file" + fname);
|
||||||
|
|
@ -300,7 +300,7 @@ Values::shared_ptr gtsam::deserializeValuesToFile(const std::string& fname) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Values::shared_ptr gtsam::deserializeValuesToXMLFile(const std::string& fname,
|
Values::shared_ptr gtsam::deserializeValuesFromXMLFile(const std::string& fname,
|
||||||
const std::string& name) {
|
const std::string& name) {
|
||||||
Values::shared_ptr result(new Values());
|
Values::shared_ptr result(new Values());
|
||||||
if (!deserializeFromXMLFile<Values>(fname, *result, name))
|
if (!deserializeFromXMLFile<Values>(fname, *result, name))
|
||||||
|
|
|
||||||
|
|
@ -49,12 +49,12 @@ bool serializeValuesToXMLFile(const Values& values,
|
||||||
const std::string& fname, const std::string& name = "values");
|
const std::string& fname, const std::string& name = "values");
|
||||||
|
|
||||||
// Deserialize
|
// Deserialize
|
||||||
NonlinearFactorGraph::shared_ptr deserializeGraphToFile(const std::string& fname);
|
NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string& fname);
|
||||||
NonlinearFactorGraph::shared_ptr deserializeGraphToXMLFile(const std::string& fname,
|
NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string& fname,
|
||||||
const std::string& name = "graph");
|
const std::string& name = "graph");
|
||||||
|
|
||||||
Values::shared_ptr deserializeValuesToFile(const std::string& fname);
|
Values::shared_ptr deserializeValuesFromFile(const std::string& fname);
|
||||||
Values::shared_ptr deserializeValuesToXMLFile(const std::string& fname,
|
Values::shared_ptr deserializeValuesFromXMLFile(const std::string& fname,
|
||||||
const std::string& name = "values");
|
const std::string& name = "values");
|
||||||
|
|
||||||
} // \namespace gtsam
|
} // \namespace gtsam
|
||||||
|
|
|
||||||
|
|
@ -103,11 +103,11 @@ TEST( testSerialization, serialization_file ) {
|
||||||
EXPECT(serializeValuesToXMLFile(values, path + "values.xml", "values1"));
|
EXPECT(serializeValuesToXMLFile(values, path + "values.xml", "values1"));
|
||||||
|
|
||||||
// Deserialize
|
// Deserialize
|
||||||
NonlinearFactorGraph actGraph = *deserializeGraphToFile(path + "graph.dat");
|
NonlinearFactorGraph actGraph = *deserializeGraphFromFile(path + "graph.dat");
|
||||||
NonlinearFactorGraph actGraphXML = *deserializeGraphToXMLFile(path + "graph.xml", "graph1");
|
NonlinearFactorGraph actGraphXML = *deserializeGraphFromXMLFile(path + "graph.xml", "graph1");
|
||||||
|
|
||||||
Values actValues = *deserializeValuesToFile(path + "values.dat");
|
Values actValues = *deserializeValuesFromFile(path + "values.dat");
|
||||||
Values actValuesXML = *deserializeValuesToXMLFile(path + "values.xml", "values1");
|
Values actValuesXML = *deserializeValuesFromXMLFile(path + "values.xml", "values1");
|
||||||
|
|
||||||
// Verify
|
// Verify
|
||||||
EXPECT(assert_equal(graph, actGraph));
|
EXPECT(assert_equal(graph, actGraph));
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue