/* * @brief Unit tests for serialization of library classes * @author Frank Dellaert * @author Alex Cunningham */ /* ************************************************************************* */ // Serialization testing code. /* ************************************************************************* */ #include #include #include // includes for standard serialization types //#include //#include //#include #include #include #include #include // whether to print the serialized text to stdout 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; // 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; } // This version requires equality operator template bool equality() { T input; T output; roundtrip(input,output); return input==output; } template bool equality(const T& input) { T output; roundtrip(input,output); return input==output; } // This version requires equals template bool equalsEmpty() { T input; T output; roundtrip(input,output); return input.equals(output); } template bool equalsObj(const T& input) { T output; roundtrip(input,output); return input.equals(output); } // De-referenced version for pointers template bool equalsDereferenced(const T& input) { T output; roundtrip(input,output); return input->equals(*output); } /* ************************************************************************* */ // 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); // 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::xml_iarchive in_archive(in_archive_stream); in_archive >> BOOST_SERIALIZATION_NVP(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) { T output; roundtripXML(input,output); return input==output; } // This version requires equals template bool equalsXML() { T input; T output; roundtripXML(input,output); return input.equals(output); } template bool equalsXML(const T& input) { T output; roundtripXML(input,output); return input.equals(output); } /* ************************************************************************* */ // Actual Tests /* ************************************************************************* */ #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());} /* ************************************************************************* */ // Testing XML /* ************************************************************************* */ //TEST( Point2, equalsXML) { CHECK(equalsXML());} //TEST( VectorConfig, equalsXML) { CHECK(equalsXML());} //TEST( Cal3_S2, equalsXML) { CHECK(equalsXML());} //TEST( GaussianConditional, equalsXML) { CHECK(equalsXML());} //TEST( SymbolicConditional, equalsXML) { CHECK(equalsXML());} // 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)); //} /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */