(2.0_prep branch) Merged in additional changes from virtual_values branch r8901-r8902

release/4.3a0
Richard Roberts 2012-02-03 17:20:23 +00:00
parent 820b33bd55
commit 3d9e818d1e
4 changed files with 35 additions and 2 deletions

View File

@ -18,7 +18,16 @@ private:
struct PoolTag { };
protected:
DerivedValue() {}
DerivedValue() {
// Register the base/derived class relationship for boost::serialization
// See: http://www.boost.org/doc/libs/1_45_0/libs/serialization/doc/serialization.html#runtimecasting
static bool first = true;
if (first) {
boost::serialization::void_cast_register<DERIVED, Value>(
static_cast<DERIVED *>(NULL), static_cast<Value *>(NULL) );
first = false;
}
}
public:

View File

@ -19,7 +19,7 @@
#pragma once
#include <memory>
#include <boost/serialization/assume_abstract.hpp>
#include <gtsam/base/Vector.h>
namespace gtsam {
@ -142,6 +142,16 @@ namespace gtsam {
/** Virutal destructor */
virtual ~Value() {}
private:
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
std::cout << "value serialization" << std::endl;
}
};
} /* namespace gtsam */
BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value)

View File

@ -32,6 +32,7 @@
#include <boost/iterator/transform_iterator.hpp>
#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <boost/ptr_container/serialize_ptr_map.hpp>
#include <gtsam/base/Value.h>
#include <gtsam/base/FastMap.h>
@ -244,6 +245,14 @@ namespace gtsam {
*/
Ordering::shared_ptr orderingArbitrary(Index firstVar = 0) const;
private:
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & BOOST_SERIALIZATION_NVP(values_);
}
};
/* ************************************************************************* */

View File

@ -37,6 +37,7 @@
#include <boost/archive/xml_iarchive.hpp>
#include <boost/archive/xml_oarchive.hpp>
#include <gtsam/geometry/Point2.h>
// whether to print the serialized text to stdout
const bool verbose = false;
@ -439,6 +440,10 @@ TEST (Serialization, gaussianISAM) {
BOOST_CLASS_EXPORT_GUID(simulated2D::Prior, "gtsam::simulated2D::Prior" );
BOOST_CLASS_EXPORT_GUID(simulated2D::Odometry, "gtsam::simulated2D::Odometry" );
BOOST_CLASS_EXPORT_GUID(simulated2D::Measurement, "gtsam::simulated2D::Measurement");
BOOST_CLASS_EXPORT(gtsam::Point2)
BOOST_CLASS_EXPORT(gtsam::Point3)
BOOST_CLASS_EXPORT(gtsam::Pose2)
BOOST_CLASS_EXPORT(gtsam::Pose3)
/* ************************************************************************* */
TEST (Serialization, smallExample) {
using namespace example;