fix serialization linking error
parent
7e72051814
commit
651f593c0f
|
|
@ -8,8 +8,6 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <boost/pool/singleton_pool.hpp>
|
#include <boost/pool/singleton_pool.hpp>
|
||||||
#include <boost/serialization/serialization.hpp>
|
|
||||||
#include <boost/serialization/export.hpp>
|
|
||||||
#include <gtsam/base/Value.h>
|
#include <gtsam/base/Value.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
@ -21,16 +19,7 @@ private:
|
||||||
struct PoolTag { };
|
struct PoolTag { };
|
||||||
|
|
||||||
protected:
|
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:
|
public:
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -143,12 +143,19 @@ namespace gtsam {
|
||||||
virtual ~Value() {}
|
virtual ~Value() {}
|
||||||
|
|
||||||
private:
|
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;
|
friend class boost::serialization::access;
|
||||||
template<class ARCHIVE>
|
template<class ARCHIVE>
|
||||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
void serialize(ARCHIVE & ar, const unsigned int version) {}
|
||||||
std::cout << "value serialization" << std::endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -111,6 +111,8 @@ private:
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version)
|
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(f_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(k1_);
|
ar & BOOST_SERIALIZATION_NVP(k1_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(k2_);
|
ar & BOOST_SERIALIZATION_NVP(k2_);
|
||||||
|
|
|
||||||
|
|
@ -114,6 +114,8 @@ private:
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version)
|
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(fx_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(fy_);
|
ar & BOOST_SERIALIZATION_NVP(fy_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(s_);
|
ar & BOOST_SERIALIZATION_NVP(s_);
|
||||||
|
|
|
||||||
|
|
@ -174,6 +174,8 @@ namespace gtsam {
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
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(fx_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(fy_);
|
ar & BOOST_SERIALIZATION_NVP(fy_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(s_);
|
ar & BOOST_SERIALIZATION_NVP(s_);
|
||||||
|
|
|
||||||
|
|
@ -81,6 +81,8 @@ namespace gtsam {
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version)
|
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_NVP(b_);
|
||||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Cal3_S2);
|
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Cal3_S2);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -157,6 +157,8 @@ private:
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
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_);
|
ar & BOOST_SERIALIZATION_NVP(pose_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -279,6 +279,9 @@ private:
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
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(pose_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(k_);
|
ar & BOOST_SERIALIZATION_NVP(k_);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -189,6 +189,8 @@ private:
|
||||||
template<class ARCHIVE>
|
template<class ARCHIVE>
|
||||||
void serialize(ARCHIVE & ar, const unsigned int version)
|
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(x_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(y_);
|
ar & BOOST_SERIALIZATION_NVP(y_);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -204,6 +204,8 @@ namespace gtsam {
|
||||||
template<class ARCHIVE>
|
template<class ARCHIVE>
|
||||||
void serialize(ARCHIVE & ar, const unsigned int version)
|
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(x_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(y_);
|
ar & BOOST_SERIALIZATION_NVP(y_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(z_);
|
ar & BOOST_SERIALIZATION_NVP(z_);
|
||||||
|
|
|
||||||
|
|
@ -269,6 +269,8 @@ private:
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
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(t_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(r_);
|
ar & BOOST_SERIALIZATION_NVP(r_);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -233,6 +233,8 @@ namespace gtsam {
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
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(R_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(t_);
|
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -239,6 +239,8 @@ namespace gtsam {
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class ARCHIVE>
|
template<class ARCHIVE>
|
||||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
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(c_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(s_);
|
ar & BOOST_SERIALIZATION_NVP(s_);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -362,6 +362,8 @@ namespace gtsam {
|
||||||
template<class ARCHIVE>
|
template<class ARCHIVE>
|
||||||
void serialize(ARCHIVE & ar, const unsigned int version)
|
void serialize(ARCHIVE & ar, const unsigned int version)
|
||||||
{
|
{
|
||||||
|
ar & boost::serialization::make_nvp("Rot3",
|
||||||
|
boost::serialization::base_object<Value>(*this));
|
||||||
#ifndef GTSAM_DEFAULT_QUATERNIONS
|
#ifndef GTSAM_DEFAULT_QUATERNIONS
|
||||||
ar & BOOST_SERIALIZATION_NVP(r1_);
|
ar & BOOST_SERIALIZATION_NVP(r1_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(r2_);
|
ar & BOOST_SERIALIZATION_NVP(r2_);
|
||||||
|
|
|
||||||
|
|
@ -148,6 +148,8 @@ namespace gtsam {
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class ARCHIVE>
|
template<class ARCHIVE>
|
||||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
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(uL_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(uR_);
|
ar & BOOST_SERIALIZATION_NVP(uR_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(v_);
|
ar & BOOST_SERIALIZATION_NVP(v_);
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue