Changed serialization interface to return shared versions of graph/values to avoid copies in matlab
parent
19f7da62dd
commit
666e30a59b
|
@ -208,9 +208,9 @@ std::string gtsam::serializeGraph(const NonlinearFactorGraph& graph) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
NonlinearFactorGraph gtsam::deserializeGraph(const std::string& serialized_graph) {
|
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraph(const std::string& serialized_graph) {
|
||||||
NonlinearFactorGraph result;
|
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
|
||||||
deserialize<NonlinearFactorGraph>(serialized_graph, result);
|
deserialize<NonlinearFactorGraph>(serialized_graph, *result);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -220,10 +220,10 @@ std::string gtsam::serializeGraphXML(const NonlinearFactorGraph& graph, const st
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
NonlinearFactorGraph gtsam::deserializeGraphXML(const std::string& serialized_graph,
|
NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphXML(const std::string& serialized_graph,
|
||||||
const std::string& name) {
|
const std::string& name) {
|
||||||
NonlinearFactorGraph result;
|
NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph());
|
||||||
deserializeXML<NonlinearFactorGraph>(serialized_graph, result, name);
|
deserializeXML<NonlinearFactorGraph>(serialized_graph, *result, name);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -233,9 +233,9 @@ std::string gtsam::serializeValues(const Values& values) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Values gtsam::deserializeValues(const std::string& serialized_values) {
|
Values::shared_ptr gtsam::deserializeValues(const std::string& serialized_values) {
|
||||||
Values result;
|
Values::shared_ptr result(new Values());
|
||||||
deserialize<Values>(serialized_values, result);
|
deserialize<Values>(serialized_values, *result);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -245,10 +245,10 @@ std::string gtsam::serializeValuesXML(const Values& values, const std::string& n
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Values gtsam::deserializeValuesXML(const std::string& serialized_values,
|
Values::shared_ptr gtsam::deserializeValuesXML(const std::string& serialized_values,
|
||||||
const std::string& name) {
|
const std::string& name) {
|
||||||
Values result;
|
Values::shared_ptr result(new Values());
|
||||||
deserializeXML<Values>(serialized_values, result, name);
|
deserializeXML<Values>(serialized_values, *result, name);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -16,23 +16,23 @@ namespace gtsam {
|
||||||
// Serialize/Deserialize a NonlinearFactorGraph
|
// Serialize/Deserialize a NonlinearFactorGraph
|
||||||
std::string serializeGraph(const NonlinearFactorGraph& graph);
|
std::string serializeGraph(const NonlinearFactorGraph& graph);
|
||||||
|
|
||||||
NonlinearFactorGraph deserializeGraph(const std::string& serialized_graph);
|
NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string& serialized_graph);
|
||||||
|
|
||||||
std::string serializeGraphXML(const NonlinearFactorGraph& graph,
|
std::string serializeGraphXML(const NonlinearFactorGraph& graph,
|
||||||
const std::string& name = "graph");
|
const std::string& name = "graph");
|
||||||
|
|
||||||
NonlinearFactorGraph deserializeGraphXML(const std::string& serialized_graph,
|
NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string& serialized_graph,
|
||||||
const std::string& name = "graph");
|
const std::string& name = "graph");
|
||||||
|
|
||||||
|
|
||||||
// Serialize/Deserialize a Values
|
// Serialize/Deserialize a Values
|
||||||
std::string serializeValues(const Values& values);
|
std::string serializeValues(const Values& values);
|
||||||
|
|
||||||
Values deserializeValues(const std::string& serialized_values);
|
Values::shared_ptr deserializeValues(const std::string& serialized_values);
|
||||||
|
|
||||||
std::string serializeValuesXML(const Values& values, const std::string& name = "values");
|
std::string serializeValuesXML(const Values& values, const std::string& name = "values");
|
||||||
|
|
||||||
Values 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");
|
||||||
|
|
||||||
} // \namespace gtsam
|
} // \namespace gtsam
|
||||||
|
|
|
@ -42,7 +42,7 @@ NonlinearFactorGraph exampleGraph() {
|
||||||
TEST( testSerialization, text_graph_serialization ) {
|
TEST( testSerialization, text_graph_serialization ) {
|
||||||
NonlinearFactorGraph graph = exampleGraph();
|
NonlinearFactorGraph graph = exampleGraph();
|
||||||
string serialized = serializeGraph(graph);
|
string serialized = serializeGraph(graph);
|
||||||
NonlinearFactorGraph actGraph = deserializeGraph(serialized);
|
NonlinearFactorGraph actGraph = *deserializeGraph(serialized);
|
||||||
EXPECT(assert_equal(graph, actGraph));
|
EXPECT(assert_equal(graph, actGraph));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -50,7 +50,7 @@ TEST( testSerialization, text_graph_serialization ) {
|
||||||
TEST( testSerialization, xml_graph_serialization ) {
|
TEST( testSerialization, xml_graph_serialization ) {
|
||||||
NonlinearFactorGraph graph = exampleGraph();
|
NonlinearFactorGraph graph = exampleGraph();
|
||||||
string serialized = serializeGraphXML(graph, "graph1");
|
string serialized = serializeGraphXML(graph, "graph1");
|
||||||
NonlinearFactorGraph actGraph = deserializeGraphXML(serialized, "graph1");
|
NonlinearFactorGraph actGraph = *deserializeGraphXML(serialized, "graph1");
|
||||||
EXPECT(assert_equal(graph, actGraph));
|
EXPECT(assert_equal(graph, actGraph));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -58,7 +58,7 @@ TEST( testSerialization, xml_graph_serialization ) {
|
||||||
TEST( testSerialization, text_values_serialization ) {
|
TEST( testSerialization, text_values_serialization ) {
|
||||||
Values values = exampleValues();
|
Values values = exampleValues();
|
||||||
string serialized = serializeValues(values);
|
string serialized = serializeValues(values);
|
||||||
Values actValues = deserializeValues(serialized);
|
Values actValues = *deserializeValues(serialized);
|
||||||
EXPECT(assert_equal(values, actValues));
|
EXPECT(assert_equal(values, actValues));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -66,7 +66,7 @@ TEST( testSerialization, text_values_serialization ) {
|
||||||
TEST( testSerialization, xml_values_serialization ) {
|
TEST( testSerialization, xml_values_serialization ) {
|
||||||
Values values = exampleValues();
|
Values values = exampleValues();
|
||||||
string serialized = serializeValuesXML(values, "values1");
|
string serialized = serializeValuesXML(values, "values1");
|
||||||
Values actValues = deserializeValuesXML(serialized, "values1");
|
Values actValues = *deserializeValuesXML(serialized, "values1");
|
||||||
EXPECT(assert_equal(values, actValues, 1e-5));
|
EXPECT(assert_equal(values, actValues, 1e-5));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue