diff --git a/gtsam/base/ConcurrentMap.h b/gtsam/base/ConcurrentMap.h index e88f6eed9..66d06d324 100644 --- a/gtsam/base/ConcurrentMap.h +++ b/gtsam/base/ConcurrentMap.h @@ -113,7 +113,6 @@ private: std::copy(this->begin(), this->end(), map.begin()); ar & BOOST_SERIALIZATION_NVP(map); } -#endif template void load(Archive& ar, const unsigned int /*version*/) { @@ -124,6 +123,7 @@ private: this->insert(map.begin(), map.end()); } BOOST_SERIALIZATION_SPLIT_MEMBER() +#endif }; } diff --git a/gtsam/base/MatrixSerialization.h b/gtsam/base/MatrixSerialization.h index f79d7b27f..9cf730230 100644 --- a/gtsam/base/MatrixSerialization.h +++ b/gtsam/base/MatrixSerialization.h @@ -18,6 +18,8 @@ // \callgraph +// Defined only if boost serialization is enabled +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include @@ -87,3 +89,4 @@ void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) { } // namespace serialization } // namespace boost +#endif diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 69f578156..c36de42ab 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -132,4 +132,6 @@ namespace gtsam { } /* namespace gtsam */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value) +#endif diff --git a/gtsam/base/VectorSerialization.h b/gtsam/base/VectorSerialization.h index 97df02a75..7acf108f4 100644 --- a/gtsam/base/VectorSerialization.h +++ b/gtsam/base/VectorSerialization.h @@ -16,6 +16,8 @@ * @date February 2022 */ +// Defined only if boost serialization is enabled +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include @@ -63,3 +65,4 @@ BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector2) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector3) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector6) +#endif diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 7aab743db..09b36cdc8 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -17,6 +17,7 @@ * @date Feb 7, 2012 */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include @@ -175,3 +176,4 @@ bool equalsDereferencedBinary(const T& input = T()) { } // \namespace serializationTestHelpers } // \namespace gtsam +#endif diff --git a/gtsam/base/std_optional_serialization.h b/gtsam/base/std_optional_serialization.h index f59c71cd3..07a02c228 100644 --- a/gtsam/base/std_optional_serialization.h +++ b/gtsam/base/std_optional_serialization.h @@ -9,6 +9,8 @@ * Inspired from this PR: https://github.com/boostorg/serialization/pull/163 * ---------------------------------------------------------------------------- */ +// Defined only if boost serialization is enabled +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include #include @@ -97,4 +99,4 @@ void serialize(Archive& ar, std::optional& t, const unsigned int version) { } // namespace serialization } // namespace boost - +#endif diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index 33236d8e1..52e6adff7 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -23,6 +23,7 @@ #include +#include #include #include diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 4d68bc525..f17786056 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -445,6 +445,7 @@ namespace gtsam { private: using Base = DecisionTree::Node; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -454,6 +455,7 @@ namespace gtsam { ar& BOOST_SERIALIZATION_NVP(branches_); ar& BOOST_SERIALIZATION_NVP(allSame_); } +#endif }; // Choice /****************************************************************************/ diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index 1589d5c4d..f3949b512 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -378,12 +378,14 @@ namespace gtsam { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& BOOST_SERIALIZATION_NVP(root_); } +#endif }; // DecisionTree template diff --git a/gtsam/discrete/tests/CMakeLists.txt b/gtsam/discrete/tests/CMakeLists.txt index cff0bb6fc..3067e54be 100644 --- a/gtsam/discrete/tests/CMakeLists.txt +++ b/gtsam/discrete/tests/CMakeLists.txt @@ -1,7 +1,7 @@ # if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) # create a semicolon seperated list of files to exclude - set(EXCLUDE_TESTS "testSerializationDiscrete.cpp") + set(EXCLUDE_TESTS "testSerializationDiscrete.cpp" "testDiscreteFactor.cpp") else() set(EXCLUDE_TESTS "") endif() diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 8da57d50d..725c1481f 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -156,8 +156,8 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 6a030fa6f..277c865c5 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -416,6 +416,7 @@ private: /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -424,6 +425,7 @@ private: & boost::serialization::make_nvp("PinholeBase", boost::serialization::base_object(*this)); } +#endif /// @} }; diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 96c691242..7670e1e88 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -431,6 +431,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -440,6 +441,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 421619d19..cd67bfb8c 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -99,6 +99,7 @@ template <> GTSAM_EXPORT Vector9 SO3::vec(OptionalJacobian<9, 3> H) const; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template /** Serialization function */ void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) { @@ -113,6 +114,7 @@ void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) { ar& boost::serialization::make_nvp("R32", M(2, 1)); ar& boost::serialization::make_nvp("R33", M(2, 2)); } +#endif namespace so3 { diff --git a/gtsam/geometry/SO4.h b/gtsam/geometry/SO4.h index f1c6815cc..834cab746 100644 --- a/gtsam/geometry/SO4.h +++ b/gtsam/geometry/SO4.h @@ -78,6 +78,7 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = {}); */ GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {}); +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template /** Serialization function */ void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) { @@ -102,6 +103,7 @@ void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) { ar &boost::serialization::make_nvp("Q43", M(3, 2)); ar &boost::serialization::make_nvp("Q44", M(3, 3)); } +#endif /* * Define the traits. internal::LieGroup provides both Lie group and Testable diff --git a/gtsam/geometry/SphericalCamera.h b/gtsam/geometry/SphericalCamera.h index 8d10b4efe..a9c38cd69 100644 --- a/gtsam/geometry/SphericalCamera.h +++ b/gtsam/geometry/SphericalCamera.h @@ -223,12 +223,14 @@ class GTSAM_EXPORT SphericalCamera { static size_t Dim() { return 6; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { ar& BOOST_SERIALIZATION_NVP(pose_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/geometry/tests/testBearingRange.cpp b/gtsam/geometry/tests/testBearingRange.cpp index 8c5d2208e..1216a6396 100644 --- a/gtsam/geometry/tests/testBearingRange.cpp +++ b/gtsam/geometry/tests/testBearingRange.cpp @@ -25,7 +25,6 @@ using namespace std; using namespace gtsam; -using namespace serializationTestHelpers; typedef BearingRange BearingRange2D; BearingRange2D br2D(1, 2); @@ -45,13 +44,6 @@ TEST(BearingRange, 2D) { EXPECT(assert_equal(expected, actual)); } -/* ************************************************************************* */ -TEST(BearingRange, Serialization2D) { - EXPECT(equalsObj(br2D)); - EXPECT(equalsXML(br2D)); - EXPECT(equalsBinary(br2D)); -} - //****************************************************************************** TEST(BearingRange3D, Concept) { BOOST_CONCEPT_ASSERT((IsManifold)); @@ -64,12 +56,22 @@ TEST(BearingRange, 3D) { EXPECT(assert_equal(expected, actual)); } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +using namespace serializationTestHelpers; +/* ************************************************************************* */ +TEST(BearingRange, Serialization2D) { + EXPECT(equalsObj(br2D)); + EXPECT(equalsXML(br2D)); + EXPECT(equalsBinary(br2D)); +} + /* ************************************************************************* */ TEST(BearingRange, Serialization3D) { EXPECT(equalsObj(br3D)); EXPECT(equalsXML(br3D)); EXPECT(equalsBinary(br3D)); } +#endif /* ************************************************************************* */ int main() { diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 29d4aee5e..0c4c2c725 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -499,12 +499,14 @@ TEST(Unit3, CopyAssign) { } /* ************************************************************************* */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION TEST(actualH, Serialization) { Unit3 p(0, 1, 0); EXPECT(serializationTestHelpers::equalsObj(p)); EXPECT(serializationTestHelpers::equalsXML(p)); EXPECT(serializationTestHelpers::equalsBinary(p)); } +#endif /* ************************************************************************* */ diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index f71ad76da..24bc94d80 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -676,12 +676,14 @@ class TriangulationResult : public std::optional { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int version) { ar& BOOST_SERIALIZATION_NVP(status); } +#endif }; /// triangulateSafe: extensive checking of the outcome diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index e315f902a..375e82698 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -435,7 +435,6 @@ namespace gtsam { ar << BOOST_SERIALIZATION_NVP(model_); } } -#endif template void load(ARCHIVE & ar, const unsigned int version) { @@ -454,6 +453,7 @@ namespace gtsam { } BOOST_SERIALIZATION_SPLIT_MEMBER() +#endif }; // JacobianFactor /// traits template<> @@ -462,7 +462,9 @@ struct traits : public Testable { } // \ namespace gtsam +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION BOOST_CLASS_VERSION(gtsam::JacobianFactor, 1) +#endif #include diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 9710e2cb7..5b4c58fe3 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -162,12 +162,14 @@ class GTSAM_EXPORT Null : public Base { static shared_ptr Create(); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); } +#endif }; /** Implementation of the "Fair" robust error model (Zhang97ivc) @@ -194,6 +196,7 @@ class GTSAM_EXPORT Fair : public Base { double modelParameter() const { return c_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -201,6 +204,7 @@ class GTSAM_EXPORT Fair : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** The "Huber" robust error model (Zhang97ivc). @@ -227,6 +231,7 @@ class GTSAM_EXPORT Huber : public Base { double modelParameter() const { return k_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -234,6 +239,7 @@ class GTSAM_EXPORT Huber : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(k_); } +#endif }; /** Implementation of the "Cauchy" robust error model (Lee2013IROS). @@ -265,6 +271,7 @@ class GTSAM_EXPORT Cauchy : public Base { double modelParameter() const { return k_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -273,6 +280,7 @@ class GTSAM_EXPORT Cauchy : public Base { ar &BOOST_SERIALIZATION_NVP(k_); ar &BOOST_SERIALIZATION_NVP(ksquared_); } +#endif }; /** Implementation of the "Tukey" robust error model (Zhang97ivc). @@ -299,6 +307,7 @@ class GTSAM_EXPORT Tukey : public Base { double modelParameter() const { return c_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -306,6 +315,7 @@ class GTSAM_EXPORT Tukey : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** Implementation of the "Welsch" robust error model (Zhang97ivc). @@ -332,6 +342,7 @@ class GTSAM_EXPORT Welsch : public Base { double modelParameter() const { return c_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -340,6 +351,7 @@ class GTSAM_EXPORT Welsch : public Base { ar &BOOST_SERIALIZATION_NVP(c_); ar &BOOST_SERIALIZATION_NVP(csquared_); } +#endif }; /** Implementation of the "Geman-McClure" robust error model (Zhang97ivc). @@ -369,6 +381,7 @@ class GTSAM_EXPORT GemanMcClure : public Base { double c_; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -376,6 +389,7 @@ class GTSAM_EXPORT GemanMcClure : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** DCS implements the Dynamic Covariance Scaling robust error model @@ -407,6 +421,7 @@ class GTSAM_EXPORT DCS : public Base { double c_; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -414,6 +429,7 @@ class GTSAM_EXPORT DCS : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** L2WithDeadZone implements a standard L2 penalty, but with a dead zone of @@ -445,6 +461,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base { double modelParameter() const { return k_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -452,6 +469,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(k_); } +#endif }; } // namespace mEstimator diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 63e22f9ad..ccc0a321e 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -267,6 +267,7 @@ namespace gtsam { virtual Matrix covariance() const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -274,7 +275,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(sqrt_information_); } - +#endif }; // Gaussian //--------------------------------------------------------------------------------------- @@ -362,6 +363,7 @@ namespace gtsam { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -370,6 +372,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(sigmas_); ar & BOOST_SERIALIZATION_NVP(invsigmas_); } +#endif }; // Diagonal //--------------------------------------------------------------------------------------- @@ -517,6 +520,7 @@ namespace gtsam { shared_ptr unit() const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -524,6 +528,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal); ar & BOOST_SERIALIZATION_NVP(mu_); } +#endif }; // Constrained @@ -585,6 +590,7 @@ namespace gtsam { inline double sigma() const { return sigma_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -593,6 +599,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(sigma_); ar & BOOST_SERIALIZATION_NVP(invsigma_); } +#endif }; @@ -634,12 +641,14 @@ namespace gtsam { void unwhitenInPlace(Eigen::Block& /*v*/) const override {} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Isotropic); } +#endif }; /** @@ -727,6 +736,7 @@ namespace gtsam { const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -735,6 +745,7 @@ namespace gtsam { ar & boost::serialization::make_nvp("robust_", const_cast(robust_)); ar & boost::serialization::make_nvp("noise_", const_cast(noise_)); } +#endif }; // Helper function diff --git a/gtsam/linear/SubgraphBuilder.cpp b/gtsam/linear/SubgraphBuilder.cpp index ebca21dbe..97d681547 100644 --- a/gtsam/linear/SubgraphBuilder.cpp +++ b/gtsam/linear/SubgraphBuilder.cpp @@ -93,6 +93,7 @@ vector Subgraph::edgeIndices() const { return eid; } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /****************************************************************************/ void Subgraph::save(const std::string &fn) const { std::ofstream os(fn.c_str()); @@ -110,6 +111,7 @@ Subgraph Subgraph::load(const std::string &fn) { is.close(); return subgraph; } +#endif /****************************************************************************/ ostream &operator<<(ostream &os, const Subgraph::Edge &edge) { diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 506183a72..fe8f704dc 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -84,16 +84,18 @@ class GTSAM_EXPORT Subgraph { iterator end() { return edges_.end(); } const_iterator end() const { return edges_.end(); } - void save(const std::string &fn) const; - static Subgraph load(const std::string &fn); friend std::ostream &operator<<(std::ostream &os, const Subgraph &subgraph); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive &ar, const unsigned int /*version*/) { ar &BOOST_SERIALIZATION_NVP(edges_); } + void save(const std::string &fn) const; + static Subgraph load(const std::string &fn); +#endif }; /****************************************************************************/ diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index d163394bf..05439bafc 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -208,6 +208,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -218,6 +219,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); } +#endif }; // AHRSFactor diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index dfd8b3287..d61db2166 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -132,6 +132,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -142,6 +143,7 @@ private: ar & boost::serialization::make_nvp("AttitudeFactor", boost::serialization::base_object(*this)); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW @@ -215,6 +217,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -225,6 +228,7 @@ private: ar & boost::serialization::make_nvp("AttitudeFactor", boost::serialization::base_object(*this)); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 25b72034c..94a37c2d2 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -225,6 +225,7 @@ public: /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -233,6 +234,7 @@ public: ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index 518a11358..cd89dd464 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -166,6 +166,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// Serialization function friend class boost::serialization::access; template @@ -176,6 +177,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(nT_); } +#endif }; } /// namespace gtsam diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 2c2ca5f80..59ff688af 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -248,6 +248,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -256,6 +257,7 @@ public: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); } +#endif }; // class ImuFactor diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index c4b2caa9b..c80399f14 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -181,6 +181,7 @@ class GTSAM_EXPORT PreintegratedRotation { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -190,6 +191,7 @@ class GTSAM_EXPORT PreintegratedRotation { ar& BOOST_SERIALIZATION_NVP(deltaRij_); ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); } +#endif #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 7c4a0097c..128de5847 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -231,6 +231,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -241,6 +242,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { ar &BOOST_SERIALIZATION_NVP(measured_); ar &BOOST_SERIALIZATION_NVP(func_); } +#endif }; /// traits diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index ddf275f38..c8ab0c2af 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -275,6 +275,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -285,6 +286,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(value_); } +#endif }; // \NonlinearEquality1 diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index d56bceb7d..d22409875 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -717,6 +717,7 @@ protected: } } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -724,6 +725,7 @@ protected: ar& boost::serialization::make_nvp( "NoiseModelFactor", boost::serialization::base_object(*this)); } +#endif public: /// @name Shortcut functions `key1()` -> `key<1>()` diff --git a/gtsam/nonlinear/tests/CMakeLists.txt b/gtsam/nonlinear/tests/CMakeLists.txt index 69a3700f2..4f098275a 100644 --- a/gtsam/nonlinear/tests/CMakeLists.txt +++ b/gtsam/nonlinear/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(nonlinear "test*.cpp" "" "gtsam") +# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests +if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) + # create a semicolon seperated list of files to exclude + set(EXCLUDE_TESTS "testSerializationNonlinear.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index bfc766857..193a89a5a 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -164,6 +164,7 @@ class RangeFactorWithTransform : public ExpressionFactorN { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; /** Serialization function */ template @@ -175,6 +176,7 @@ class RangeFactorWithTransform : public ExpressionFactorN { ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); } +#endif }; // \ RangeFactorWithTransform /// traits diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 7be202194..3e5b154e3 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -176,12 +176,14 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & boost::serialization::make_nvp("BetweenFactor", boost::serialization::base_object >(*this)); } +#endif }; // \class BetweenConstraint /// traits diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 405c0d4a6..a496971e2 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -161,6 +161,7 @@ struct BoundingConstraint2: public NoiseModelFactorN { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -171,6 +172,7 @@ private: ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); } +#endif }; } // \namespace gtsam diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 5f9d02819..5605ad58e 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -284,6 +284,7 @@ public: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -293,6 +294,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; template diff --git a/gtsam/slam/tests/CMakeLists.txt b/gtsam/slam/tests/CMakeLists.txt index 7208ef65d..e5dd0830e 100644 --- a/gtsam/slam/tests/CMakeLists.txt +++ b/gtsam/slam/tests/CMakeLists.txt @@ -1,7 +1,8 @@ # if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) # create a semicolon seperated list of files to exclude - set(EXCLUDE_TESTS "testSerializationDatataset.cpp" "testSerializationInSlam.cpp") + set(EXCLUDE_TESTS "testSerializationDataset.cpp" "testSerializationInSlam.cpp") + message(STATUS "Excluding tests: ${EXCLUDE_TESTS}") else() set(EXCLUDE_TESTS "") endif() diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.h b/gtsam_unstable/nonlinear/LinearizedFactor.h index f050676e5..689c97c3a 100644 --- a/gtsam_unstable/nonlinear/LinearizedFactor.h +++ b/gtsam_unstable/nonlinear/LinearizedFactor.h @@ -148,6 +148,7 @@ public: Vector error_vector(const Values& c) const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; /** Serialization function */ template @@ -156,6 +157,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(Ab_); } +#endif }; /// traits @@ -277,6 +279,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -284,6 +287,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(info_); } +#endif }; /// traits diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index fb4588955..22a725d47 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -139,8 +139,8 @@ public: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -271,6 +271,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; /// Serialization function template @@ -279,6 +280,7 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; } // \ namespace gtsam diff --git a/tests/simulated2D.h b/tests/simulated2D.h index f00b35617..612dd1891 100644 --- a/tests/simulated2D.h +++ b/tests/simulated2D.h @@ -210,6 +210,7 @@ namespace simulated2D { /// Default constructor GenericOdometry() { } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -217,6 +218,7 @@ namespace simulated2D { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; /** @@ -259,6 +261,7 @@ namespace simulated2D { /// Default constructor GenericMeasurement() { } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -266,6 +269,7 @@ namespace simulated2D { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; /** Typedefs for regular use */