diff --git a/gtsam/base/DerivedValue.h b/gtsam/base/DerivedValue.h index 66e7d79a4..0a66eb01f 100644 --- a/gtsam/base/DerivedValue.h +++ b/gtsam/base/DerivedValue.h @@ -8,8 +8,6 @@ #pragma once #include -#include -#include #include 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( - static_cast(NULL), static_cast(NULL) ); - first = false; - } - } + DerivedValue() {} public: diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 99b5248d6..3f1afdbbc 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -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(*this)); + * Alternatively, if the derived class is template-based, for example PinholeCamera, + * it can put the following code in its serialization function + * ar & boost::serialization::void_cast_register, Value>( + * static_cast *>(NULL), + * static_cast(NULL)); + * See more: http://www.boost.org/doc/libs/1_45_0/libs/serialization/doc/serialization.html#runtimecasting + * */ friend class boost::serialization::access; template - void serialize(ARCHIVE & ar, const unsigned int version) { - std::cout << "value serialization" << std::endl; - } + void serialize(ARCHIVE & ar, const unsigned int version) {} }; diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 65dd1a19a..259a07c9b 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -111,6 +111,8 @@ private: template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Cal3Bundler", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(f_); ar & BOOST_SERIALIZATION_NVP(k1_); ar & BOOST_SERIALIZATION_NVP(k2_); diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 0044f1c35..9b94eccb5 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -114,6 +114,8 @@ private: template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Cal3DS2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(s_); diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index 910994df7..93e43483a 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -174,6 +174,8 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Cal3_S2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(s_); diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index a8366e35f..7bbafd7d5 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -81,6 +81,8 @@ namespace gtsam { template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Cal3_S2Stereo", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(b_); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Cal3_S2); } diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 5458b88f0..12cfc706d 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -157,6 +157,8 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("CalibratedCamera", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(pose_); } diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 7d6cb218d..fa907dd40 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -279,6 +279,9 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::void_cast_register, Value>( + static_cast *>(NULL), + static_cast(NULL)); ar & BOOST_SERIALIZATION_NVP(pose_); ar & BOOST_SERIALIZATION_NVP(k_); } diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 898307334..fe7792733 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -189,6 +189,8 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Point2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(y_); } diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 8233b341a..ad66a845c 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -204,6 +204,8 @@ namespace gtsam { template void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Point3", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(y_); ar & BOOST_SERIALIZATION_NVP(z_); diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 2bcf65181..877eb93a1 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -269,6 +269,8 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Pose2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(r_); } diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index f052d86f1..fd4bc08df 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -233,6 +233,8 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Pose3", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(R_); ar & BOOST_SERIALIZATION_NVP(t_); } diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 2adbae4bd..8e33794e4 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -239,6 +239,8 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Rot2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(s_); } diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index b640ac615..8eead3ff9 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -362,6 +362,8 @@ namespace gtsam { template void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("Rot3", + boost::serialization::base_object(*this)); #ifndef GTSAM_DEFAULT_QUATERNIONS ar & BOOST_SERIALIZATION_NVP(r1_); ar & BOOST_SERIALIZATION_NVP(r2_); diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 63538b6d5..43701e4e8 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -148,6 +148,8 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("StereoPoint2", + boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(uL_); ar & BOOST_SERIALIZATION_NVP(uR_); ar & BOOST_SERIALIZATION_NVP(v_);