Added wrapping for graph/values serialization with tests in Matlab. Values serializes correctly, but graphs do not in either case.

release/4.3a0
Alex Cunningham 2013-06-12 19:30:22 +00:00
parent 666e30a59b
commit e69af84c36
3 changed files with 44 additions and 0 deletions

27
gtsam.h
View File

@ -2102,6 +2102,33 @@ pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(string filename,
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D_robust(string filename,
gtsam::noiseModel::Base* model);
//*************************************************************************
// Serialization
//*************************************************************************
#include <gtsam/slam/serialization.h>
// Serialize/Deserialize a NonlinearFactorGraph
string serializeGraph(const gtsam::NonlinearFactorGraph& graph);
gtsam::NonlinearFactorGraph* deserializeGraph(string serialized_graph);
string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph);
string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph, string name);
gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph);
gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph, string name);
// Serialize/Deserialize a Values
string serializeValues(const gtsam::Values& values);
gtsam::Values* deserializeValues(string serialized_values);
string serializeValuesXML(const gtsam::Values& values);
string serializeValuesXML(const gtsam::Values& values, string name);
gtsam::Values* deserializeValuesXML(string serialized_values);
gtsam::Values* deserializeValuesXML(string serialized_values, string name);
//*************************************************************************
// Utilities
//*************************************************************************

View File

@ -68,4 +68,12 @@ point_1 = result.at(symbol('l',1));
marginals.marginalCovariance(symbol('l',1));
CHECK('point_1.equals(Point2(2,2),1e-4)',point_1.equals(Point2(2,2),1e-4));
%% Check that serialization works properly
serialized_values = serializeValues(initialEstimate);
deserializedValues = deserializeValues(serialized_values);
CHECK('initialEstimate.equals(deserializedValues)',initialEstimate.equals(deserializedValues,1e-9));
% FAILS: unregistered class?
% serialized_graph = serializeGraph(graph);
% deserializedGraph = deserializeGraph(serialized_graph);
% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9));

View File

@ -61,3 +61,12 @@ pose_1 = result.at(1);
CHECK('pose_1.equals(Pose2,1e-4)',pose_1.equals(Pose2,1e-4));
%% Check that serialization works properly
serialized_values = serializeValues(initialEstimate);
deserializedValues = deserializeValues(serialized_values);
CHECK('initialEstimate.equals(deserializedValues)',initialEstimate.equals(deserializedValues,1e-9));
% FAILS: unregistered class?
% serialized_graph = serializeGraph(graph);
% deserializedGraph = deserializeGraph(serialized_graph);
% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9));