Added direct saving to/from files for graph/values serialization

release/4.3a0
Alex Cunningham 2013-06-13 14:29:31 +00:00
parent 527ea5e511
commit e1fc90ad14
4 changed files with 192 additions and 0 deletions

View File

@ -20,6 +20,7 @@
#pragma once #pragma once
#include <sstream> #include <sstream>
#include <fstream>
#include <string> #include <string>
// includes for standard serialization types // includes for standard serialization types
@ -57,6 +58,28 @@ void deserialize(const std::string& serialized, T& output) {
in_archive >> output; in_archive >> output;
} }
template<class T>
bool serializeToFile(const T& input, const std::string& filename) {
std::ofstream out_archive_stream(filename.c_str());
if (!out_archive_stream.is_open())
return false;
boost::archive::text_oarchive out_archive(out_archive_stream);
out_archive << input;
out_archive_stream.close();
return true;
}
template<class T>
bool deserializeFromFile(const std::string& filename, T& output) {
std::ifstream in_archive_stream(filename.c_str());
if (!in_archive_stream.is_open())
return false;
boost::archive::text_iarchive in_archive(in_archive_stream);
in_archive >> output;
in_archive_stream.close();
return true;
}
// Serialization to XML format with named structures // Serialization to XML format with named structures
template<class T> template<class T>
std::string serializeXML(const T& input, const std::string& name="data") { std::string serializeXML(const T& input, const std::string& name="data") {
@ -73,6 +96,28 @@ void deserializeXML(const std::string& serialized, T& output, const std::string&
in_archive >> boost::serialization::make_nvp(name.c_str(), output); in_archive >> boost::serialization::make_nvp(name.c_str(), output);
} }
template<class T>
bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name="data") {
std::ofstream out_archive_stream(filename.c_str());
if (!out_archive_stream.is_open())
return false;
boost::archive::xml_oarchive out_archive(out_archive_stream);
out_archive << boost::serialization::make_nvp(name.c_str(), input);;
out_archive_stream.close();
return true;
}
template<class T>
bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name="data") {
std::ifstream in_archive_stream(filename.c_str());
if (!in_archive_stream.is_open())
return false;
boost::archive::xml_iarchive in_archive(in_archive_stream);
in_archive >> boost::serialization::make_nvp(name.c_str(), output);
in_archive_stream.close();
return true;
}
// Serialization to binary format with named structures // Serialization to binary format with named structures
template<class T> template<class T>
std::string serializeBinary(const T& input, const std::string& name="data") { std::string serializeBinary(const T& input, const std::string& name="data") {
@ -89,4 +134,26 @@ void deserializeBinary(const std::string& serialized, T& output, const std::stri
in_archive >> boost::serialization::make_nvp(name.c_str(), output); in_archive >> boost::serialization::make_nvp(name.c_str(), output);
} }
template<class T>
bool deserializeToBinaryFile(const T& input, const std::string& filename, const std::string& name="data") {
std::ofstream out_archive_stream(filename.c_str());
if (!out_archive_stream.is_open())
return false;
boost::archive::binary_oarchive out_archive(out_archive_stream);
out_archive << boost::serialization::make_nvp(name.c_str(), input);;
out_archive_stream.close();
return true;
}
template<class T>
bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name="data") {
std::ifstream in_archive_stream(filename.c_str());
if (!in_archive_stream.is_open())
return false;
boost::archive::binary_iarchive in_archive(in_archive_stream);
in_archive >> boost::serialization::make_nvp(name.c_str(), output);
in_archive_stream.close();
return true;
}
} // \namespace gtsam } // \namespace gtsam

View File

@ -253,5 +253,61 @@ Values::shared_ptr gtsam::deserializeValuesXML(const std::string& serialized_val
} }
/* ************************************************************************* */ /* ************************************************************************* */
bool gtsam::serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname) {
return serializeToFile<NonlinearFactorGraph>(graph, fname);
}
/* ************************************************************************* */
bool gtsam::serializeGraphToXMLFile(const NonlinearFactorGraph& graph,
const std::string& fname, const std::string& name) {
return serializeToXMLFile<NonlinearFactorGraph>(graph, fname, name);
}
/* ************************************************************************* */
bool gtsam::serializeValuesToFile(const Values& values, const std::string& fname) {
return serializeToFile<Values>(values, fname);
}
/* ************************************************************************* */
bool gtsam::serializeValuesToXMLFile(const Values& values,
const std::string& fname, const std::string& name) {
return serializeToXMLFile<Values>(values, fname, name);
}
/* ************************************************************************* */
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToFile(const std::string& fname) {
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
if (!deserializeFromFile<NonlinearFactorGraph>(fname, *result))
throw std::invalid_argument("Failed to open file" + fname);
return result;
}
/* ************************************************************************* */
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToXMLFile(const std::string& fname,
const std::string& name) {
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
if (!deserializeFromXMLFile<NonlinearFactorGraph>(fname, *result, name))
throw std::invalid_argument("Failed to open file" + fname);
return result;
}
/* ************************************************************************* */
Values::shared_ptr gtsam::deserializeValuesToFile(const std::string& fname) {
Values::shared_ptr result(new Values());
if (!deserializeFromFile<Values>(fname, *result))
throw std::invalid_argument("Failed to open file" + fname);
return result;
}
/* ************************************************************************* */
Values::shared_ptr gtsam::deserializeValuesToXMLFile(const std::string& fname,
const std::string& name) {
Values::shared_ptr result(new Values());
if (!deserializeFromXMLFile<Values>(fname, *result, name))
throw std::invalid_argument("Failed to open file" + fname);
return result;
}
/* ************************************************************************* */

View File

@ -35,6 +35,28 @@ std::string serializeValuesXML(const Values& values, const std::string& name = "
Values::shared_ptr deserializeValuesXML(const std::string& serialized_values, Values::shared_ptr deserializeValuesXML(const std::string& serialized_values,
const std::string& name = "values"); const std::string& name = "values");
// Serialize to/from files
// serialize functions return true if successful
// Filename arguments include path
// Serialize
bool serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname);
bool serializeGraphToXMLFile(const NonlinearFactorGraph& graph,
const std::string& fname, const std::string& name = "graph");
bool serializeValuesToFile(const Values& values, const std::string& fname);
bool serializeValuesToXMLFile(const Values& values,
const std::string& fname, const std::string& name = "values");
// Deserialize
NonlinearFactorGraph::shared_ptr deserializeGraphToFile(const std::string& fname);
NonlinearFactorGraph::shared_ptr deserializeGraphToXMLFile(const std::string& fname,
const std::string& name = "graph");
Values::shared_ptr deserializeValuesToFile(const std::string& fname);
Values::shared_ptr deserializeValuesToXMLFile(const std::string& fname,
const std::string& name = "values");
} // \namespace gtsam } // \namespace gtsam

View File

@ -16,9 +16,23 @@
#include <gtsam/slam/PriorFactor.h> #include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h> #include <gtsam/slam/BetweenFactor.h>
#include <gtsam/slam/BearingRangeFactor.h>
#include <stdlib.h>
#include <fstream>
#include <sstream>
#include <boost/assign/std/vector.hpp>
#include <boost/filesystem.hpp>
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace boost::assign;
namespace fs = boost::filesystem;
#ifdef TOPSRCDIR
static string topdir = TOPSRCDIR;
#else
static string topdir = "TOPSRCDIR_NOT_CONFIGURED"; // If TOPSRCDIR is not defined, we error
#endif
Values exampleValues() { Values exampleValues() {
Values result; Values result;
@ -35,6 +49,7 @@ NonlinearFactorGraph exampleGraph() {
NonlinearFactorGraph graph; NonlinearFactorGraph graph;
graph.add(PriorFactor<Pose2>(234, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3)))); graph.add(PriorFactor<Pose2>(234, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3))));
graph.add(BetweenFactor<Pose2>(234, 567, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3)))); graph.add(BetweenFactor<Pose2>(234, 567, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3))));
graph.add(BearingRangeFactor<Pose2,Point2>(234, 567, Rot2::fromAngle(0.3), 2.0, noiseModel::Diagonal::Sigmas(ones(2))));
return graph; return graph;
} }
@ -70,6 +85,38 @@ TEST( testSerialization, xml_values_serialization ) {
EXPECT(assert_equal(values, actValues, 1e-5)); EXPECT(assert_equal(values, actValues, 1e-5));
} }
/* ************************************************************************* */
TEST( testSerialization, serialization_file ) {
// Create files in folder in build folder
fs::remove_all("actual");
fs::create_directory("actual");
string path = "actual/";
NonlinearFactorGraph graph = exampleGraph();
Values values = exampleValues();
// Serialize objects using each configuration
EXPECT(serializeGraphToFile(graph, path + "graph.dat"));
EXPECT(serializeGraphToXMLFile(graph, path + "graph.xml", "graph1"));
EXPECT(serializeValuesToFile(values, path + "values.dat"));
EXPECT(serializeValuesToXMLFile(values, path + "values.xml", "values1"));
// Deserialize
NonlinearFactorGraph actGraph = *deserializeGraphToFile(path + "graph.dat");
NonlinearFactorGraph actGraphXML = *deserializeGraphToXMLFile(path + "graph.xml", "graph1");
Values actValues = *deserializeValuesToFile(path + "values.dat");
Values actValuesXML = *deserializeValuesToXMLFile(path + "values.xml", "values1");
// Verify
EXPECT(assert_equal(graph, actGraph));
EXPECT(assert_equal(graph, actGraphXML));
EXPECT(assert_equal(values, actValues));
EXPECT(assert_equal(values, actValuesXML));
}
/* ************************************************************************* */ /* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); } int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */ /* ************************************************************************* */