fixing serialization code when class has no base
parent
7d8ba565e5
commit
003224ac3f
|
@ -166,7 +166,6 @@ 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("LieMatrix",*this);
|
|
||||||
ar & boost::serialization::make_nvp("Matrix",
|
ar & boost::serialization::make_nvp("Matrix",
|
||||||
boost::serialization::base_object<Matrix>(*this));
|
boost::serialization::base_object<Matrix>(*this));
|
||||||
|
|
||||||
|
|
|
@ -123,7 +123,6 @@ 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("LieVector",*this);
|
|
||||||
ar & boost::serialization::make_nvp("Vector",
|
ar & boost::serialization::make_nvp("Vector",
|
||||||
boost::serialization::base_object<Vector>(*this));
|
boost::serialization::base_object<Vector>(*this));
|
||||||
}
|
}
|
||||||
|
|
|
@ -172,8 +172,6 @@ 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("Cal3Bundler",*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_);
|
||||||
|
|
|
@ -153,7 +153,6 @@ 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",*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_);
|
||||||
|
|
|
@ -131,8 +131,6 @@ 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("Cal3Unified",
|
|
||||||
boost::serialization::base_object<Cal3DS2>(*this));
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(xi_);
|
ar & BOOST_SERIALIZATION_NVP(xi_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -226,8 +226,6 @@ 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("Cal3_S2",*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_);
|
||||||
|
|
|
@ -214,8 +214,6 @@ 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",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(pose_);
|
ar & BOOST_SERIALIZATION_NVP(pose_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -176,7 +176,6 @@ 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("EssentialMatrix",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(aRb_);
|
ar & BOOST_SERIALIZATION_NVP(aRb_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(aTb_);
|
ar & BOOST_SERIALIZATION_NVP(aTb_);
|
||||||
|
|
||||||
|
|
|
@ -237,7 +237,6 @@ 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",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(x_);
|
ar & BOOST_SERIALIZATION_NVP(x_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(y_);
|
ar & BOOST_SERIALIZATION_NVP(y_);
|
||||||
}
|
}
|
||||||
|
|
|
@ -228,7 +228,6 @@ 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",*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_);
|
||||||
|
|
|
@ -301,7 +301,6 @@ 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",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(t_);
|
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(r_);
|
ar & BOOST_SERIALIZATION_NVP(r_);
|
||||||
}
|
}
|
||||||
|
|
|
@ -326,7 +326,6 @@ public:
|
||||||
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",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(R_);
|
ar & BOOST_SERIALIZATION_NVP(R_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(t_);
|
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||||
}
|
}
|
||||||
|
|
|
@ -235,7 +235,6 @@ 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",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(c_);
|
ar & BOOST_SERIALIZATION_NVP(c_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(s_);
|
ar & BOOST_SERIALIZATION_NVP(s_);
|
||||||
}
|
}
|
||||||
|
|
|
@ -456,7 +456,6 @@ 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",*this);
|
|
||||||
#ifndef GTSAM_USE_QUATERNIONS
|
#ifndef GTSAM_USE_QUATERNIONS
|
||||||
ar & boost::serialization::make_nvp("rot11", rot_(0,0));
|
ar & boost::serialization::make_nvp("rot11", rot_(0,0));
|
||||||
ar & boost::serialization::make_nvp("rot12", rot_(0,1));
|
ar & boost::serialization::make_nvp("rot12", rot_(0,1));
|
||||||
|
|
|
@ -147,7 +147,6 @@ 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("StereoCamera",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(leftCamPose_);
|
ar & BOOST_SERIALIZATION_NVP(leftCamPose_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(K_);
|
ar & BOOST_SERIALIZATION_NVP(K_);
|
||||||
}
|
}
|
||||||
|
|
|
@ -162,7 +162,6 @@ 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",*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_);
|
||||||
|
|
|
@ -146,7 +146,6 @@ 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("Unit3",*this);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(p_);
|
ar & BOOST_SERIALIZATION_NVP(p_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(B_);
|
ar & BOOST_SERIALIZATION_NVP(B_);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue