diff --git a/tests/testSerialization.cpp b/tests/testSerialization.cpp index 5f4e82ce7..493e990f3 100644 --- a/tests/testSerialization.cpp +++ b/tests/testSerialization.cpp @@ -13,9 +13,9 @@ #include // includes for standard serialization types -//#include -//#include -//#include +#include +#include +#include #include #include @@ -28,33 +28,28 @@ const bool verbose = false; // Templated round-trip serialization template void roundtrip(const T& input, T& output) { - // Serialize std::ostringstream out_archive_stream; - boost::archive::text_oarchive out_archive(out_archive_stream); - out_archive << input; + { + boost::archive::text_oarchive out_archive(out_archive_stream); + out_archive << input; + } // Convert to string std::string serialized = out_archive_stream.str(); if (verbose) std::cout << serialized << std::endl << std::endl; // De-serialize - std::istringstream in_archive_stream(serialized); - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; + { + std::istringstream in_archive_stream(serialized); + boost::archive::text_iarchive in_archive(in_archive_stream); + in_archive >> output; + } } // This version requires equality operator template -bool equality() { - T input; - T output; - roundtrip(input,output); - return input==output; -} - -template -bool equality(const T& input) { +bool equality(const T& input = T()) { T output; roundtrip(input,output); return input==output; @@ -62,15 +57,7 @@ bool equality(const T& input) { // This version requires equals template -bool equalsEmpty() { - T input; - T output; - roundtrip(input,output); - return input.equals(output); -} - -template -bool equalsObj(const T& input) { +bool equalsObj(const T& input = T()) { T output; roundtrip(input,output); return input.equals(output); @@ -88,33 +75,27 @@ bool equalsDereferenced(const T& input) { // Templated round-trip serialization using XML template void roundtripXML(const T& input, T& output) { - // Serialize - std::ostringstream out_archive_stream; - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << BOOST_SERIALIZATION_NVP(input); + std::string serialized; + { + std::ostringstream out_archive_stream; + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp("data", input); - // Convert to string - std::string serialized = out_archive_stream.str(); + // Convert to string + serialized = out_archive_stream.str(); + } if (verbose) std::cout << serialized << std::endl << std::endl; // De-serialize std::istringstream in_archive_stream(serialized); boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> BOOST_SERIALIZATION_NVP(output); + in_archive >> boost::serialization::make_nvp("data", output); } // This version requires equality operator template -bool equalityXML() { - T input; - T output; - roundtripXML(input,output); - return input==output; -} - -template -bool equalityXML(const T& input) { +bool equalityXML(const T& input = T()) { T output; roundtripXML(input,output); return input==output; @@ -122,15 +103,7 @@ bool equalityXML(const T& input) { // This version requires equals template -bool equalsXML() { - T input; - T output; - roundtripXML(input,output); - return input.equals(output); -} - -template -bool equalsXML(const T& input) { +bool equalsXML(const T& input = T()) { T output; roundtripXML(input,output); return input.equals(output); @@ -141,79 +114,71 @@ bool equalsXML(const T& input) { /* ************************************************************************* */ #include -//#include -//#include -//#include -//#include -//#include -//#include +#include +#include +#include +#include +#include +#include //#include -//#include //#include //#include +#include + #include using namespace std; using namespace gtsam; /* ************************************************************************* */ -//TEST( Point2, equalsEmpty) { CHECK(equalsEmpty());} -//TEST( VectorConfig, equalsEmpty) { CHECK(equalsEmpty());} -//TEST( GaussianConditional, equalsEmpty) { CHECK(equalsEmpty());} - - +TEST (Serialization, text_geometry) { + EXPECT(equalsObj(Point2(1.0, 2.0))); + EXPECT(equalsObj(Pose2(1.0, 2.0, 0.3))); + EXPECT(equalsObj(Rot2::fromDegrees(30.0))); + EXPECT(equalsObj(Point3(1.0, 2.0, 3.0))); + EXPECT(equalsObj()); + EXPECT(equalsObj(Rot3::RzRyRx(1.0, 3.0, 2.0))); +} /* ************************************************************************* */ -// Testing XML +TEST (Serialization, xml_geometry) { + EXPECT(equalsXML(Point2(1.0, 2.0))); + EXPECT(equalsXML(Pose2(1.0, 2.0, 0.3))); + EXPECT(equalsXML(Rot2::fromDegrees(30.0))); + EXPECT(equalsXML(Point3(1.0, 2.0, 3.0))); + EXPECT(equalsXML()); + EXPECT(equalsXML(Rot3::RzRyRx(1.0, 3.0, 2.0))); +} + /* ************************************************************************* */ -//TEST( Point2, equalsXML) { CHECK(equalsXML());} +TEST (Serialization, text_linear) { + // NOT WORKING: +// EXPECT(equalsObj()); +// EXPECT(equalsObj()); +} -//TEST( VectorConfig, equalsXML) { CHECK(equalsXML());} -//TEST( Cal3_S2, equalsXML) { CHECK(equalsXML());} -//TEST( GaussianConditional, equalsXML) { CHECK(equalsXML());} -//TEST( SymbolicConditional, equalsXML) { CHECK(equalsXML());} +/* ************************************************************************* */ +TEST (Serialization, xml_linear) { + // NOT WORKING: +// EXPECT(equalsXML()); +// EXPECT(equalsXML()); +} +/* ************************************************************************* */ +TEST (Serialization, text_planar) { + EXPECT(equalsObj(gtsam::planarSLAM::PoseKey(2))); + EXPECT(equalsObj(gtsam::planarSLAM::PointKey(2))); + EXPECT(equalsObj()); +} -// The two tests below will not run, however, as CameraMarkerFactor -// is not registered by the serialization code in FactorGraph -//TEST( FactorGraph, equals1) -//{ -// FactorGraph graph; -// graph.push_back(f); -// CHECK(equalsObj(graph)); -//} -//TEST( NonlinearFactorGraph, equals) -//{ -// NonlinearFactorGraph graph; -// graph.push_back(f); -// CHECK(equalsObj(graph)); -//} - -// It *does* work if we explicitly instantiate with the factor type -//TEST( FactorGraph, equals2) -//{ -// FactorGraph graph; -// graph.push_back(f); -// CHECK(equalsObj(graph)); -//} - -// And, as we explicitly registered the three CameraMarkerFactor types in -// the EasySLAMGraph serialize, this will also work :-)) -// see http://www.boost.org/doc/libs/1_35_0/libs/serialization/doc/serialization.html#derivedpointers -//TEST( EasySLAMGraph, equals2) -//{ -// EasySLAMGraph graph = createExampleGraph(); -// CHECK(equalsObj(graph)); -//} -// -//// EasySLAMConfig is no problem either: -//TEST( EasySLAMConfig, equals2) -//{ -// EasySLAMConfig c = createExampleConfig(); -// CHECK(equalsObj(c)); -//} +/* ************************************************************************* */ +TEST (Serialization, xml_planar) { + EXPECT(equalsXML(gtsam::planarSLAM::PoseKey(2))); + EXPECT(equalsXML(gtsam::planarSLAM::PointKey(2))); + EXPECT(equalsXML()); +} /* ************************************************************************* */ int main() {