gtsam_unstable, test folders ifdefs

release/4.3a0
kartik arcot 2023-01-18 12:03:30 -08:00 committed by Kartik Arcot
parent a5b6968cbf
commit 3250cf49ca
33 changed files with 69 additions and 3 deletions

View File

@ -157,6 +157,7 @@ public:
/// @}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
@ -164,6 +165,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(first);
ar & BOOST_SERIALIZATION_NVP(second);
}
#endif
};

View File

@ -51,6 +51,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -59,6 +60,7 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor3",
boost::serialization::base_object<Base>(*this));
}
#endif
}; // \VelocityConstraint3
}

View File

@ -90,6 +90,7 @@ private:
/// @name Advanced Interface
/// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION //
// Serialization function
friend class boost::serialization::access;
template<class Archive>
@ -97,6 +98,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(azimuth_);
ar & BOOST_SERIALIZATION_NVP(elevation_);
}
#endif
};

View File

@ -172,6 +172,7 @@ private:
/// @name Advanced Interface
/// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
@ -179,6 +180,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(pose_);
ar & BOOST_SERIALIZATION_NVP(k_);
}
#endif
/// @}
}; // \class InvDepthCamera
} // \namesapce gtsam
} // \namespace gtsam

View File

@ -130,6 +130,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION //
// Serialization function
friend class boost::serialization::access;
template<class Archive>
@ -137,6 +138,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(T_);
ar & BOOST_SERIALIZATION_NVP(z_);
}
#endif
}; // \class Pose3Upright

View File

@ -59,6 +59,7 @@ public:
const Values& linearizationPoint() const { return lin_points_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -67,6 +68,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(lin_points_);
}
#endif
};
@ -146,8 +148,8 @@ public:
Vector error_vector(const Values& c) const;
private:
/** Serialization function */
friend class boost::serialization::access;
/** Serialization function */
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("LinearizedJacobianFactor",

View File

@ -415,6 +415,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -424,6 +425,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
};
// \class BetweenFactorEM

View File

@ -94,6 +94,7 @@ namespace gtsam {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -103,6 +104,7 @@ namespace gtsam {
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
}; // \class BiasedGPSFactor
} /// namespace gtsam

View File

@ -706,6 +706,7 @@ public:
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -713,6 +714,7 @@ private:
ar & boost::serialization::make_nvp("NonlinearFactor2",
boost::serialization::base_object<Base>(*this));
}
#endif

View File

@ -573,6 +573,7 @@ public:
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -580,6 +581,7 @@ private:
ar & boost::serialization::make_nvp("NonlinearFactor2",
boost::serialization::base_object<Base>(*this));
}
#endif

View File

@ -113,6 +113,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -121,6 +122,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(dt_);
ar & BOOST_SERIALIZATION_NVP(tau_);
}
#endif
SharedGaussian calcDiscreteNoiseModel(const SharedGaussian& model, double delta_t){
/* Q_d (approx)= Q * delta_t */

View File

@ -413,6 +413,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -420,6 +421,7 @@ private:
ar & boost::serialization::make_nvp("NonlinearFactor2",
boost::serialization::base_object<Base>(*this));
}
#endif
}; // \class InertialNavFactor_GlobalVelocity

View File

@ -113,6 +113,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -121,5 +122,6 @@ private:
ar & BOOST_SERIALIZATION_NVP(measured_);
ar & BOOST_SERIALIZATION_NVP(K_);
}
#endif
};
} // \ namespace gtsam

View File

@ -135,6 +135,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -143,6 +144,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(measured_);
ar & BOOST_SERIALIZATION_NVP(K_);
}
#endif
};
} // \ namespace gtsam

View File

@ -142,6 +142,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -151,6 +152,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(K_);
ar & BOOST_SERIALIZATION_NVP(referencePoint_);
}
#endif
};
} // \ namespace gtsam

View File

@ -140,6 +140,7 @@ public:
private:
/// Serialization function
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
@ -147,6 +148,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(measured_);
ar & BOOST_SERIALIZATION_NVP(K_);
}
#endif
};
/**
@ -269,8 +271,8 @@ public:
private:
/// Serialization function
friend class boost::serialization::access;
/// Serialization function
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);

View File

@ -213,6 +213,7 @@ namespace gtsam {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -224,5 +225,6 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
}
#endif
};
} // \ namespace gtsam

View File

@ -140,6 +140,7 @@ namespace gtsam {
const std::vector<size_t>& indices() const { return indices_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -151,6 +152,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(indices_);
// ar & BOOST_SERIALIZATION_NVP(H_);
}
#endif
}; // \class PartialPriorFactor
} /// namespace gtsam

View File

@ -119,6 +119,7 @@ namespace gtsam {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -127,6 +128,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
}; // \class PoseBetweenFactor
} /// namespace gtsam

View File

@ -101,6 +101,7 @@ namespace gtsam {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -109,6 +110,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(prior_);
ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
}
#endif
};
} /// namespace gtsam

View File

@ -92,6 +92,7 @@ class PoseToPointFactor : public NoiseModelFactorN<POSE, POINT> {
const POINT& measured() const { return measured_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -102,6 +103,7 @@ class PoseToPointFactor : public NoiseModelFactorN<POSE, POINT> {
boost::serialization::base_object<Base>(*this));
ar& BOOST_SERIALIZATION_NVP(measured_);
}
#endif
}; // \class PoseToPointFactor

View File

@ -171,6 +171,7 @@ namespace gtsam {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -181,6 +182,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
}
#endif
};
/// traits

View File

@ -151,6 +151,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -160,6 +161,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC
ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
}
#endif
};
/// traits

View File

@ -194,6 +194,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
inline bool throwCheirality() const { return throwCheirality_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template <class ARCHIVE>
@ -206,6 +207,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
ar& BOOST_SERIALIZATION_NVP(throwCheirality_);
ar& BOOST_SERIALIZATION_NVP(verboseCheirality_);
}
#endif
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

View File

@ -65,6 +65,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -74,6 +75,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
}; // RelativeElevationFactor

View File

@ -456,12 +456,14 @@ class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template <class ARCHIVE>
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
}
#endif
};
// end of class declaration

View File

@ -501,6 +501,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -509,6 +510,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality);
ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality);
}
#endif
};
/// traits

View File

@ -288,6 +288,7 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -295,6 +296,7 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(K_all_);
}
#endif
};
// end of class declaration

View File

@ -141,6 +141,7 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor
Base::Cameras cameras(const Values& values) const override;
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template <class ARCHIVE>
@ -148,6 +149,7 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar& BOOST_SERIALIZATION_NVP(K_all_);
}
#endif
}; // end of class declaration

View File

@ -216,6 +216,7 @@ namespace gtsam {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -224,6 +225,7 @@ namespace gtsam {
boost::serialization::base_object<Base>(*this));
//ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
}; // \class TransformBtwRobotsUnaryFactor
/// traits

View File

@ -414,6 +414,7 @@ namespace gtsam {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -422,6 +423,7 @@ namespace gtsam {
boost::serialization::base_object<Base>(*this));
//ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
}; // \class TransformBtwRobotsUnaryFactorEM
/// traits

View File

@ -160,6 +160,7 @@ namespace simulated2D {
/// Default constructor
GenericPrior() { }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -167,6 +168,7 @@ namespace simulated2D {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
};
/**

View File

@ -695,6 +695,7 @@ public:
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -704,6 +705,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar &BOOST_SERIALIZATION_NVP(measured_);
}
#endif
};
TEST(ExpressionFactor, variadicTemplate) {