Removed extraneous headers that were causing problems related to boost serialization and added testSerialization with conditional compiling (--enable-serialization). Currently, the test is all commented out, and it should not affect those not using the flag.
parent
d17aef492c
commit
a461680a2b
|
@ -1,8 +1,5 @@
|
|||
/* config.h.in. Generated from configure.ac by autoheader. */
|
||||
|
||||
/* boost serialization flag */
|
||||
#undef HAVE_BOOST_SERIALIZATION
|
||||
|
||||
/* Define to 1 if you have the <dlfcn.h> header file. */
|
||||
#undef HAVE_DLFCN_H
|
||||
|
||||
|
|
27
configure.ac
27
configure.ac
|
@ -98,7 +98,7 @@ AC_ARG_ENABLE([ldl],
|
|||
[case "${enableval}" in
|
||||
yes) ldl=true ;;
|
||||
no) ldl=false ;;
|
||||
*) AC_MSG_ERROR([bad value ${enableval} for --enable-debug]) ;;
|
||||
*) AC_MSG_ERROR([bad value ${enableval} for --enable-ldl]) ;;
|
||||
esac],[ldl=false])
|
||||
|
||||
AM_CONDITIONAL([USE_LDL], [test x$ldl = xtrue])
|
||||
|
@ -114,6 +114,17 @@ AC_ARG_ENABLE([profiling],
|
|||
|
||||
AM_CONDITIONAL([USE_PROFILING], [test x$profiling = xtrue])
|
||||
|
||||
# enable serialization in serialization test
|
||||
AC_ARG_ENABLE([serialization],
|
||||
[ --enable-serialization Enable serialization with boost serialization],
|
||||
[case "${enableval}" in
|
||||
yes) serialization=true ;;
|
||||
no) serialization=false ;;
|
||||
*) AC_MSG_ERROR([bad value ${enableval} for --enable-serialization]) ;;
|
||||
esac],[serialization=false])
|
||||
|
||||
AM_CONDITIONAL([ENABLE_SERIALIZATION], [test x$serialization = xtrue])
|
||||
|
||||
# Checks for programs.
|
||||
AC_PROG_CXX
|
||||
AC_PROG_CC
|
||||
|
@ -160,13 +171,13 @@ AC_ARG_WITH([boost],
|
|||
AC_SUBST([boost])
|
||||
|
||||
# ask for boost serialization
|
||||
AC_ARG_WITH([boost_serialization],
|
||||
[AS_HELP_STRING([--with-boost-serialization],
|
||||
[(optional) use the Serialization library from boost - specify the library linking command with the full name of the library
|
||||
e.g. --with-boost-serialization=-lboost_serialization-gcc-mt-d-1_33_1])],
|
||||
[AC_DEFINE([HAVE_BOOST_SERIALIZATION], ["<boost/foreach.hpp>"], [boost serialization flag])
|
||||
#AC_ARG_WITH([boost_serialization],
|
||||
# [AS_HELP_STRING([--with-boost-serialization],
|
||||
# [(optional) use the Serialization library from boost - specify the library linking command with the full name of the library
|
||||
# e.g. --with-boost-serialization=-lboost_serialization-gcc-mt-d-1_33_1])],
|
||||
# [AC_DEFINE([HAVE_BOOST_SERIALIZATION], ["<boost/foreach.hpp>"], [boost serialization flag])
|
||||
#
|
||||
#AC_SUBST([boost_serialization])
|
||||
|
||||
boost_serialization=$withval ])
|
||||
AC_SUBST([boost_serialization])
|
||||
|
||||
AC_OUTPUT
|
||||
|
|
|
@ -10,8 +10,8 @@
|
|||
|
||||
#include <list>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/serialization/list.hpp>
|
||||
#include <boost/serialization/shared_ptr.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
//#include <boost/serialization/shared_ptr.hpp>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
|
|
@ -10,8 +10,8 @@
|
|||
|
||||
#include <list>
|
||||
#include <vector>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#include <boost/serialization/list.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
#include <stdexcept>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
|
|
@ -9,9 +9,9 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/utility.hpp> // for noncopyable
|
||||
#include <boost/serialization/string.hpp>
|
||||
#include <boost/serialization/access.hpp>
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
//#include <boost/serialization/string.hpp>
|
||||
//#include <boost/serialization/access.hpp>
|
||||
//#include <boost/serialization/nvp.hpp>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
|
|
|
@ -11,10 +11,10 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#include <boost/serialization/list.hpp>
|
||||
#include <boost/serialization/vector.hpp>
|
||||
#include <boost/serialization/shared_ptr.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
//#include <boost/serialization/vector.hpp>
|
||||
//#include <boost/serialization/shared_ptr.hpp>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/inference/BayesNet.h>
|
||||
|
|
|
@ -11,8 +11,8 @@
|
|||
#include <map>
|
||||
#include <list>
|
||||
#include <vector>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#include <boost/serialization/list.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
#include <stdexcept>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
|
|
@ -11,8 +11,8 @@
|
|||
#include <map>
|
||||
#include <list>
|
||||
#include <vector>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#include <boost/serialization/list.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
#include <stdexcept>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
#include <list>
|
||||
#include <iostream>
|
||||
#include <boost/format.hpp>
|
||||
#include <boost/serialization/serialization.hpp>
|
||||
//#include <boost/serialization/serialization.hpp>
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#ifdef GTSAM_MAGIC_KEY
|
||||
#include <boost/lexical_cast.hpp>
|
||||
|
@ -273,7 +273,9 @@ namespace gtsam {
|
|||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive & ar, const unsigned int version) {
|
||||
ar & BOOST_SERIALIZATION_NVP(this->j_);
|
||||
typedef TypedSymbol<T,C> Base;
|
||||
ar & boost::serialization::make_nvp("TypedLabeledSymbol",
|
||||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(label_);
|
||||
}
|
||||
};
|
||||
|
|
|
@ -9,8 +9,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <list>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#include <boost/serialization/list.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/inference/BayesNet.h>
|
||||
|
|
|
@ -13,7 +13,8 @@
|
|||
#include <iostream>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/foreach.hpp> // TODO: make cpp file
|
||||
#include <boost/serialization/list.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <gtsam/inference/Conditional.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
|
|
|
@ -12,8 +12,8 @@
|
|||
#include <list>
|
||||
#include <boost/utility.hpp>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#include <boost/serialization/shared_ptr.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/shared_ptr.hpp>
|
||||
|
||||
#include <gtsam/inference/Conditional.h>
|
||||
#include <gtsam/linear/VectorConfig.h>
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/tuple/tuple.hpp>
|
||||
#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
#include <boost/foreach.hpp>
|
||||
#include <list>
|
||||
#include <set>
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <map>
|
||||
#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
#include <boost/numeric/ublas/storage.hpp>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <map>
|
||||
#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Vector.h>
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#include <map>
|
||||
#include <set>
|
||||
|
||||
#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
|
||||
#include <gtsam/base/Vector.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
|
|
@ -17,6 +17,11 @@ check_PROGRAMS += testSymbolicBayesNet testSymbolicFactorGraph testTupleConfig
|
|||
check_PROGRAMS += testNonlinearEqualityConstraint testBoundingConstraint
|
||||
check_PROGRAMS += testTransformConstraint testLinearApproxFactor
|
||||
|
||||
# only if serialization is available
|
||||
if ENABLE_SERIALIZATION
|
||||
check_PROGRAMS += testSerialization
|
||||
endif
|
||||
|
||||
# experimental
|
||||
#check_PROGRAMS += testFusionTupleConfig # Doesn't work on Macs
|
||||
|
||||
|
@ -32,7 +37,13 @@ noinst_PROGRAMS = timeGaussianFactorGraph timeFactorOverhead
|
|||
#----------------------------------------------------------------------------------------------------
|
||||
TESTS = $(check_PROGRAMS)
|
||||
AM_CPPFLAGS = -I$(boost) -I$(BORG_SRCROOT)
|
||||
AM_LDFLAGS = $(BOOST_LDFLAGS) $(boost_serialization)
|
||||
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
||||
|
||||
# link to serialization library for test
|
||||
if ENABLE_SERIALIZATION
|
||||
AM_LDFLAGS += -lboost_serialization
|
||||
endif
|
||||
|
||||
LDADD = ../libgtsam.la ../CppUnitLite/libCppUnitLite.a
|
||||
AM_DEFAULT_SOURCE_EXT = .cpp
|
||||
|
||||
|
|
|
@ -0,0 +1,223 @@
|
|||
/*
|
||||
* @brief Unit tests for serialization of library classes
|
||||
* @author Frank Dellaert
|
||||
* @author Alex Cunningham
|
||||
*/
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Serialization testing code.
|
||||
/* ************************************************************************* */
|
||||
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
#include <string>
|
||||
|
||||
// includes for standard serialization types
|
||||
//#include <boost/serialization/vector.hpp>
|
||||
//#include <boost/serialization/map.hpp>
|
||||
//#include <boost/serialization/list.hpp>
|
||||
|
||||
#include <boost/archive/text_oarchive.hpp>
|
||||
#include <boost/archive/text_iarchive.hpp>
|
||||
#include <boost/archive/xml_iarchive.hpp>
|
||||
#include <boost/archive/xml_oarchive.hpp>
|
||||
|
||||
// whether to print the serialized text to stdout
|
||||
const bool verbose = false;
|
||||
|
||||
// Templated round-trip serialization
|
||||
template<class T>
|
||||
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<class T>
|
||||
bool equality() {
|
||||
T input;
|
||||
T output;
|
||||
roundtrip<T>(input,output);
|
||||
return input==output;
|
||||
}
|
||||
|
||||
template<class T>
|
||||
bool equality(const T& input) {
|
||||
T output;
|
||||
roundtrip<T>(input,output);
|
||||
return input==output;
|
||||
}
|
||||
|
||||
// This version requires equals
|
||||
template<class T>
|
||||
bool equalsEmpty() {
|
||||
T input;
|
||||
T output;
|
||||
roundtrip<T>(input,output);
|
||||
return input.equals(output);
|
||||
}
|
||||
|
||||
template<class T>
|
||||
bool equalsObj(const T& input) {
|
||||
T output;
|
||||
roundtrip<T>(input,output);
|
||||
return input.equals(output);
|
||||
}
|
||||
|
||||
// De-referenced version for pointers
|
||||
template<class T>
|
||||
bool equalsDereferenced(const T& input) {
|
||||
T output;
|
||||
roundtrip<T>(input,output);
|
||||
return input->equals(*output);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Templated round-trip serialization using XML
|
||||
template<class T>
|
||||
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<class T>
|
||||
bool equalityXML() {
|
||||
T input;
|
||||
T output;
|
||||
roundtripXML<T>(input,output);
|
||||
return input==output;
|
||||
}
|
||||
|
||||
template<class T>
|
||||
bool equalityXML(const T& input) {
|
||||
T output;
|
||||
roundtripXML<T>(input,output);
|
||||
return input==output;
|
||||
}
|
||||
|
||||
// This version requires equals
|
||||
template<class T>
|
||||
bool equalsXML() {
|
||||
T input;
|
||||
T output;
|
||||
roundtripXML<T>(input,output);
|
||||
return input.equals(output);
|
||||
}
|
||||
|
||||
template<class T>
|
||||
bool equalsXML(const T& input) {
|
||||
T output;
|
||||
roundtripXML<T>(input,output);
|
||||
return input.equals(output);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Actual Tests
|
||||
/* ************************************************************************* */
|
||||
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
//#include <gtsam/geometry/Pose2.h>
|
||||
//#include <gtsam/geometry/Rot2.h>
|
||||
//#include <gtsam/geometry/Point3.h>
|
||||
//#include <gtsam/geometry/Pose3.h>
|
||||
//#include <gtsam/geometry/Rot3.h>
|
||||
//#include <gtsam/geometry/Cal3_S2.h>
|
||||
|
||||
//#include <gtsam/linear/VectorConfig.h>
|
||||
//#include <gtsam/inference/FactorGraph-inl.h>
|
||||
//#include <gtsam/linear/GaussianConditional.h>
|
||||
//#include <gtsam/inference/SymbolicConditional.h>
|
||||
|
||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
/* ************************************************************************* */
|
||||
//TEST( Point2, equalsEmpty) { CHECK(equalsEmpty<gtsam::Point2>());}
|
||||
//TEST( VectorConfig, equalsEmpty) { CHECK(equalsEmpty<VectorConfig>());}
|
||||
//TEST( GaussianConditional, equalsEmpty) { CHECK(equalsEmpty<GaussianConditional>());}
|
||||
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Testing XML
|
||||
/* ************************************************************************* */
|
||||
//TEST( Point2, equalsXML) { CHECK(equalsXML<gtsam::Point2>());}
|
||||
|
||||
//TEST( VectorConfig, equalsXML) { CHECK(equalsXML<VectorConfig>());}
|
||||
//TEST( Cal3_S2, equalsXML) { CHECK(equalsXML<Cal3_S2>());}
|
||||
//TEST( GaussianConditional, equalsXML) { CHECK(equalsXML<GaussianConditional>());}
|
||||
//TEST( SymbolicConditional, equalsXML) { CHECK(equalsXML<SymbolicConditional>());}
|
||||
|
||||
|
||||
// The two tests below will not run, however, as CameraMarkerFactor
|
||||
// is not registered by the serialization code in FactorGraph
|
||||
//TEST( FactorGraph, equals1)
|
||||
//{
|
||||
// FactorGraph<NonlinearFactor> 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<CameraMarkerFactor> 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);
|
||||
}
|
||||
/* ************************************************************************* */
|
Loading…
Reference in New Issue