fix serialization linking error

release/4.3a0
Duy-Nguyen Ta 2012-02-03 18:44:33 +00:00
parent 7e72051814
commit 651f593c0f
15 changed files with 39 additions and 16 deletions

View File

@ -8,8 +8,6 @@
#pragma once
#include <boost/pool/singleton_pool.hpp>
#include <boost/serialization/serialization.hpp>
#include <boost/serialization/export.hpp>
#include <gtsam/base/Value.h>
namespace gtsam {
@ -21,16 +19,7 @@ private:
struct PoolTag { };
protected:
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;
}
}
DerivedValue() {}
public:

View File

@ -143,12 +143,19 @@ namespace gtsam {
virtual ~Value() {}
private:
/** Serialization function */
/** Serialization function
* All DERIVED classes derived from Value must put the following line in their serialization function:
* ar & boost::serialization::make_nvp("DERIVED", boost::serialization::base_object<Value>(*this));
* Alternatively, if the derived class is template-based, for example PinholeCamera<Calibration>,
* it can put the following code in its serialization function
* ar & boost::serialization::void_cast_register<PinholeCamera<Calibration>, Value>(
* static_cast<PinholeCamera<Calibration> *>(NULL),
* static_cast<Value *>(NULL));
* See more: http://www.boost.org/doc/libs/1_45_0/libs/serialization/doc/serialization.html#runtimecasting
* */
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
std::cout << "value serialization" << std::endl;
}
void serialize(ARCHIVE & ar, const unsigned int version) {}
};

View File

@ -111,6 +111,8 @@ private:
template<class Archive>
void serialize(Archive & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Cal3Bundler",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(f_);
ar & BOOST_SERIALIZATION_NVP(k1_);
ar & BOOST_SERIALIZATION_NVP(k2_);

View File

@ -114,6 +114,8 @@ private:
template<class Archive>
void serialize(Archive & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Cal3DS2",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(fx_);
ar & BOOST_SERIALIZATION_NVP(fy_);
ar & BOOST_SERIALIZATION_NVP(s_);

View File

@ -174,6 +174,8 @@ namespace gtsam {
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Cal3_S2",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(fx_);
ar & BOOST_SERIALIZATION_NVP(fy_);
ar & BOOST_SERIALIZATION_NVP(s_);

View File

@ -81,6 +81,8 @@ namespace gtsam {
template<class Archive>
void serialize(Archive & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Cal3_S2Stereo",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(b_);
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Cal3_S2);
}

View File

@ -157,6 +157,8 @@ private:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("CalibratedCamera",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(pose_);
}

View File

@ -279,6 +279,9 @@ private:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::void_cast_register<PinholeCamera<Calibration>, Value>(
static_cast<PinholeCamera<Calibration> *>(NULL),
static_cast<Value *>(NULL));
ar & BOOST_SERIALIZATION_NVP(pose_);
ar & BOOST_SERIALIZATION_NVP(k_);
}

View File

@ -189,6 +189,8 @@ private:
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Point2",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(x_);
ar & BOOST_SERIALIZATION_NVP(y_);
}

View File

@ -204,6 +204,8 @@ namespace gtsam {
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Point3",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(x_);
ar & BOOST_SERIALIZATION_NVP(y_);
ar & BOOST_SERIALIZATION_NVP(z_);

View File

@ -269,6 +269,8 @@ private:
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Pose2",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(t_);
ar & BOOST_SERIALIZATION_NVP(r_);
}

View File

@ -233,6 +233,8 @@ namespace gtsam {
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Pose3",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(R_);
ar & BOOST_SERIALIZATION_NVP(t_);
}

View File

@ -239,6 +239,8 @@ namespace gtsam {
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("Rot2",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(c_);
ar & BOOST_SERIALIZATION_NVP(s_);
}

View File

@ -362,6 +362,8 @@ namespace gtsam {
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version)
{
ar & boost::serialization::make_nvp("Rot3",
boost::serialization::base_object<Value>(*this));
#ifndef GTSAM_DEFAULT_QUATERNIONS
ar & BOOST_SERIALIZATION_NVP(r1_);
ar & BOOST_SERIALIZATION_NVP(r2_);

View File

@ -148,6 +148,8 @@ namespace gtsam {
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("StereoPoint2",
boost::serialization::base_object<Value>(*this));
ar & BOOST_SERIALIZATION_NVP(uL_);
ar & BOOST_SERIALIZATION_NVP(uR_);
ar & BOOST_SERIALIZATION_NVP(v_);