diff --git a/cmake/HandleGeneralOptions.cmake b/cmake/HandleGeneralOptions.cmake index 64fa6b407..83cf9bbb9 100644 --- a/cmake/HandleGeneralOptions.cmake +++ b/cmake/HandleGeneralOptions.cmake @@ -29,6 +29,13 @@ option(GTSAM_ALLOW_DEPRECATED_SINCE_V43 "Allow use of methods/functions depr option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON) option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" ON) option(GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR "Use the slower but correct version of BetweenFactor" OFF) +option(GTSAM_ENABLE_BOOST_SERIALIZATION "Enable Boost serialization" ON) + +#TODO(kartikarcot) defining it in config.h.in did not work +if (GTSAM_ENABLE_BOOST_SERIALIZATION) + add_definitions(-DGTSAM_ENABLE_BOOST_SERIALIZATION) +endif() + if(NOT MSVC AND NOT XCODE_VERSION) option(GTSAM_BUILD_WITH_CCACHE "Use ccache compiler cache" ON) endif() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 7fc33f921..1584a3a35 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -2,4 +2,12 @@ set (excluded_examples elaboratePoint2KalmanFilter.cpp ) +# if GTSAM_ENABLE_BOOST_SERIALIZATION is not set then SolverComparer.cpp will not compile +if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) + set (excluded_examples + ${excluded_examples} + SolverComparer.cpp + ) +endif() + gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam;gtsam_unstable;${Boost_PROGRAM_OPTIONS_LIBRARY}") diff --git a/gtsam/base/ConcurrentMap.h b/gtsam/base/ConcurrentMap.h index 8d5f56675..66d06d324 100644 --- a/gtsam/base/ConcurrentMap.h +++ b/gtsam/base/ConcurrentMap.h @@ -48,8 +48,10 @@ using ConcurrentMapBase = gtsam::FastMap; #endif +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include +#endif #include #include @@ -100,6 +102,7 @@ public: #endif private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -120,6 +123,7 @@ private: this->insert(map.begin(), map.end()); } BOOST_SERIALIZATION_SPLIT_MEMBER() +#endif }; } diff --git a/gtsam/base/FastList.h b/gtsam/base/FastList.h index 29ecd7dbc..d7c2dd6f4 100644 --- a/gtsam/base/FastList.h +++ b/gtsam/base/FastList.h @@ -21,10 +21,11 @@ #include #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include -#include #include +#endif namespace gtsam { @@ -76,12 +77,14 @@ public: } 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 }; diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index 1f68c8d28..359c865a5 100644 --- a/gtsam/base/FastMap.h +++ b/gtsam/base/FastMap.h @@ -19,8 +19,10 @@ #pragma once #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include +#endif #include namespace gtsam { @@ -67,12 +69,14 @@ public: bool exists(const KEY& e) const { return this->find(e) != this->end(); } 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 }; } diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index 1fceebad5..b7c00801b 100644 --- a/gtsam/base/FastSet.h +++ b/gtsam/base/FastSet.h @@ -19,11 +19,13 @@ #pragma once #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if BOOST_VERSION >= 107400 #include #endif #include #include +#endif #include #include @@ -121,12 +123,14 @@ public: } 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 }; } diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index f83a067fb..bbf0f57ad 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -175,6 +175,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -183,6 +184,7 @@ public: boost::serialization::base_object(*this)); ar & boost::serialization::make_nvp("value", value_); } +#endif // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html 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/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index e8afe6e38..1783857cb 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -21,7 +21,9 @@ #include #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include #include @@ -384,6 +386,7 @@ namespace gtsam { template friend class SymmetricBlockMatrixBlockExpr; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -396,6 +399,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(variableColOffsets_); ar & BOOST_SERIALIZATION_NVP(blockStart_); } +#endif }; /// Foward declare exception class diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index f824b388e..c36de42ab 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -21,8 +21,10 @@ #include // Configuration from CMake #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include +#endif #include namespace gtsam { @@ -119,13 +121,17 @@ namespace gtsam { * The last two links explain why these export lines have to be in the same source module that includes * any of the archive class headers. * */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & /*ar*/, const unsigned int /*version*/) { } +#endif }; } /* 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/VerticalBlockMatrix.h b/gtsam/base/VerticalBlockMatrix.h index ef6691cac..777441300 100644 --- a/gtsam/base/VerticalBlockMatrix.h +++ b/gtsam/base/VerticalBlockMatrix.h @@ -219,6 +219,7 @@ namespace gtsam { friend class SymmetricBlockMatrix; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -229,6 +230,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(rowEnd_); ar & BOOST_SERIALIZATION_NVP(blockStart_); } +#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/tests/CMakeLists.txt b/gtsam/base/tests/CMakeLists.txt index 8e99ef5ba..ae8a12581 100644 --- a/gtsam/base/tests/CMakeLists.txt +++ b/gtsam/base/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(base "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 "testSerializationBase.cpp" "testStdOptionalSerialization.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(base "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") 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/base/treeTraversal-inst.h b/gtsam/base/treeTraversal-inst.h index 4c6d74806..5d2f1b49a 100644 --- a/gtsam/base/treeTraversal-inst.h +++ b/gtsam/base/treeTraversal-inst.h @@ -28,6 +28,7 @@ #include #include #include +#include namespace gtsam { diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index da72bf71f..f17786056 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -154,6 +154,7 @@ namespace gtsam { private: using Base = DecisionTree::Node; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -162,6 +163,7 @@ namespace gtsam { ar& BOOST_SERIALIZATION_NVP(constant_); ar& BOOST_SERIALIZATION_NVP(nrAssignments_); } +#endif }; // Leaf /****************************************************************************/ @@ -443,6 +445,7 @@ namespace gtsam { private: using Base = DecisionTree::Node; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -452,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 af6101296..f3949b512 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -23,7 +23,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include #include @@ -117,10 +119,12 @@ namespace gtsam { virtual bool isLeaf() const = 0; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) {} +#endif }; /** ------------------------ Node base class --------------------------- */ @@ -374,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/DecisionTreeFactor.h b/gtsam/discrete/DecisionTreeFactor.h index 9150c459a..74899b729 100644 --- a/gtsam/discrete/DecisionTreeFactor.h +++ b/gtsam/discrete/DecisionTreeFactor.h @@ -253,6 +253,7 @@ namespace gtsam { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -261,6 +262,7 @@ namespace gtsam { ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(ADT); ar& BOOST_SERIALIZATION_NVP(cardinalities_); } +#endif }; // traits diff --git a/gtsam/discrete/DiscreteBayesNet.h b/gtsam/discrete/DiscreteBayesNet.h index 469bfc768..9005f975f 100644 --- a/gtsam/discrete/DiscreteBayesNet.h +++ b/gtsam/discrete/DiscreteBayesNet.h @@ -150,12 +150,14 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet { /// @} 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 }; // traits diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 854f5f43d..183cf8561 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -268,6 +268,7 @@ class GTSAM_EXPORT DiscreteConditional bool forceComplete) const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -275,6 +276,7 @@ class GTSAM_EXPORT DiscreteConditional ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor); ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional); } +#endif }; // DiscreteConditional diff --git a/gtsam/discrete/DiscreteKey.h b/gtsam/discrete/DiscreteKey.h index fe348ee62..3a626c6b3 100644 --- a/gtsam/discrete/DiscreteKey.h +++ b/gtsam/discrete/DiscreteKey.h @@ -21,7 +21,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include #include @@ -79,6 +81,7 @@ namespace gtsam { /// Check equality to another DiscreteKeys object. bool equals(const DiscreteKeys& other, double tol = 0) const; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -87,6 +90,7 @@ namespace gtsam { "DiscreteKeys", boost::serialization::base_object>(*this)); } +#endif }; // DiscreteKeys diff --git a/gtsam/discrete/DiscreteLookupDAG.h b/gtsam/discrete/DiscreteLookupDAG.h index 3b8e6d6db..d3fd65ebe 100644 --- a/gtsam/discrete/DiscreteLookupDAG.h +++ b/gtsam/discrete/DiscreteLookupDAG.h @@ -126,12 +126,14 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet { /// @} 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 }; // traits diff --git a/gtsam/discrete/tests/CMakeLists.txt b/gtsam/discrete/tests/CMakeLists.txt index e968fac91..3067e54be 100644 --- a/gtsam/discrete/tests/CMakeLists.txt +++ b/gtsam/discrete/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(discrete "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 "testSerializationDiscrete.cpp" "testDiscreteFactor.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index ca767c1f1..7e6210914 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -22,7 +22,9 @@ #include #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include namespace gtsam { @@ -147,6 +149,7 @@ public: /// @{ private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// Serialization function template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -155,6 +158,7 @@ private: } friend class boost::serialization::access; +#endif /// @} diff --git a/gtsam/geometry/Cal3.h b/gtsam/geometry/Cal3.h index a55010ce0..1b66eb336 100644 --- a/gtsam/geometry/Cal3.h +++ b/gtsam/geometry/Cal3.h @@ -184,6 +184,7 @@ class GTSAM_EXPORT Cal3 { /// @{ private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -194,6 +195,7 @@ class GTSAM_EXPORT Cal3 { ar& BOOST_SERIALIZATION_NVP(u0_); ar& BOOST_SERIALIZATION_NVP(v0_); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index c12f5448f..725c1481f 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -156,6 +156,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -166,6 +167,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { ar& BOOST_SERIALIZATION_NVP(k2_); ar& BOOST_SERIALIZATION_NVP(tol_); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 7252f15dc..a7ca08afc 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -104,6 +104,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -111,6 +112,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { ar& boost::serialization::make_nvp( "Cal3DS2", boost::serialization::base_object(*this)); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h index 185521b77..b0ef0368b 100644 --- a/gtsam/geometry/Cal3DS2_Base.h +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -156,6 +156,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 { /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -168,6 +169,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 { ar& BOOST_SERIALIZATION_NVP(p2_); ar& BOOST_SERIALIZATION_NVP(tol_); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3Fisheye.h b/gtsam/geometry/Cal3Fisheye.h index d3faf3a92..3f1cac148 100644 --- a/gtsam/geometry/Cal3Fisheye.h +++ b/gtsam/geometry/Cal3Fisheye.h @@ -184,6 +184,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 { /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -195,6 +196,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 { ar& BOOST_SERIALIZATION_NVP(k3_); ar& BOOST_SERIALIZATION_NVP(k4_); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index de292b3b7..309b6dca1 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -138,6 +138,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -146,6 +147,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base { "Cal3Unified", boost::serialization::base_object(*this)); ar& BOOST_SERIALIZATION_NVP(xi_); } +#endif }; template <> diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index ed62c5dd1..885be614f 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -132,6 +132,7 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 { /// @{ private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -139,6 +140,7 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 { ar& boost::serialization::make_nvp( "Cal3_S2", boost::serialization::base_object(*this)); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index 39ca1b099..4fee1a022 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -143,6 +143,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 { /// @{ private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -151,6 +152,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 { "Cal3_S2", boost::serialization::base_object(*this)); ar& BOOST_SERIALIZATION_NVP(b_); } +#endif /// @} }; diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index c8e27444e..277c865c5 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -25,7 +25,9 @@ #include #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif namespace gtsam { @@ -228,12 +230,14 @@ public: 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 }; // end of class PinholeBase @@ -412,6 +416,7 @@ private: /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -420,6 +425,7 @@ private: & boost::serialization::make_nvp("PinholeBase", boost::serialization::base_object(*this)); } +#endif /// @} }; diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 4521cbb82..1db86cfde 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -465,12 +465,14 @@ class CameraSet : public std::vector> { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar&(*this); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index ea980d667..d514c4f19 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -180,6 +180,7 @@ class EssentialMatrix { /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -197,6 +198,7 @@ class EssentialMatrix { ar & boost::serialization::make_nvp("E32", E_(2, 1)); ar & boost::serialization::make_nvp("E33", E_(2, 2)); } +#endif /// @} diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 8f299f854..23b595c84 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -326,6 +326,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -335,6 +336,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 813f04aaa..7670e1e88 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -217,6 +217,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -225,6 +226,7 @@ private: & boost::serialization::make_nvp("PinholeBase", boost::serialization::base_object(*this)); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW @@ -429,6 +431,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -438,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/PinholeSet.h b/gtsam/geometry/PinholeSet.h index 7541f886b..55269f9d6 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -64,12 +64,14 @@ public: 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 }; template diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 575d1fe41..76beea11a 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -19,7 +19,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index b1fd26bb2..8da83817d 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -26,7 +26,9 @@ #include #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include namespace gtsam { diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index c106cb4d4..e3ff1416c 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -326,6 +326,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION // // Serialization function friend class boost::serialization::access; template @@ -333,6 +334,7 @@ public: ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(r_); } +#endif public: // Align for Point2, which is either derived from, or is typedef, of Vector2 diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 7e4f30bb4..35a9ea301 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -389,6 +389,7 @@ public: friend std::ostream &operator<<(std::ostream &os, const Pose3& p); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -396,6 +397,7 @@ public: ar & BOOST_SERIALIZATION_NVP(R_); ar & BOOST_SERIALIZATION_NVP(t_); } +#endif /// @} #ifdef GTSAM_USE_QUATERNIONS diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 26e6e6b7a..63b914434 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -213,6 +213,7 @@ namespace gtsam { static Rot2 ClosestTo(const Matrix2& M); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -220,6 +221,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(s_); } +#endif }; diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index b98c03dce..0b3798baa 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -528,6 +528,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -550,6 +551,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup { ar& boost::serialization::make_nvp("z", quaternion_.z()); #endif } +#endif #ifdef GTSAM_USE_QUATERNIONS // only align if quaternion, Matrix3 has no alignment requirements diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 6f78bed4e..cd67bfb8c 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -99,8 +99,9 @@ template <> GTSAM_EXPORT Vector9 SO3::vec(OptionalJacobian<9, 3> H) const; -/** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template +/** Serialization function */ void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) { Matrix3& M = R.matrix_; ar& boost::serialization::make_nvp("R11", M(0, 0)); @@ -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 529935006..834cab746 100644 --- a/gtsam/geometry/SO4.h +++ b/gtsam/geometry/SO4.h @@ -78,8 +78,9 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = {}); */ GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {}); -/** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template +/** Serialization function */ void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) { Matrix4 &M = Q.matrix_; ar &boost::serialization::make_nvp("Q11", M(0, 0)); @@ -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/SOn.h b/gtsam/geometry/SOn.h index b8b9deb3b..7e1762b3f 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -24,7 +24,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include // TODO(frank): how to avoid? #include @@ -323,6 +325,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { /// @name Serialization /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template friend void save(Archive&, SO&, const unsigned int); template @@ -331,6 +334,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { friend void serialize(Archive&, SO&, const unsigned int); friend class boost::serialization::access; friend class Rot3; // for serialize +#endif /// @} }; @@ -375,6 +379,7 @@ template <> GTSAM_EXPORT typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ template void serialize( @@ -384,6 +389,7 @@ void serialize( Matrix& M = Q.matrix_; ar& BOOST_SERIALIZATION_NVP(M); } +#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 202aefa9f..a9c38cd69 100644 --- a/gtsam/geometry/SphericalCamera.h +++ b/gtsam/geometry/SphericalCamera.h @@ -26,7 +26,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif namespace gtsam { @@ -52,6 +54,7 @@ class GTSAM_EXPORT EmptyCal { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -59,6 +62,7 @@ class GTSAM_EXPORT EmptyCal { ar& boost::serialization::make_nvp( "EmptyCal", boost::serialization::base_object(*this)); } +#endif }; /** @@ -219,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/StereoCamera.h b/gtsam/geometry/StereoCamera.h index 6ccebd8c2..2a483ffcf 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -179,12 +179,14 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_NVP(leftCamPose_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index bce5beb2a..bd335dfbb 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -20,7 +20,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif namespace gtsam { @@ -146,6 +148,7 @@ private: /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -154,6 +157,7 @@ private: ar & BOOST_SERIALIZATION_NVP(uR_); ar & BOOST_SERIALIZATION_NVP(v_); } +#endif /// @} diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index ebc320747..72dd49c29 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -199,12 +199,14 @@ private: /// @name Advanced Interface /// @{ +#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(p_); } +#endif /// @} diff --git a/gtsam/geometry/tests/CMakeLists.txt b/gtsam/geometry/tests/CMakeLists.txt index b1499ee9d..97b41c1fd 100644 --- a/gtsam/geometry/tests/CMakeLists.txt +++ b/gtsam/geometry/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(geometry "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 "testSerializationGeometry.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(geometry "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") 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 160ab0480..24bc94d80 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -611,6 +611,7 @@ struct GTSAM_EXPORT TriangulationParameters { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -620,6 +621,7 @@ private: ar & BOOST_SERIALIZATION_NVP(landmarkDistanceThreshold); ar & BOOST_SERIALIZATION_NVP(dynamicOutlierRejectionThreshold); } +#endif }; /** @@ -674,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/hybrid/GaussianMixture.h b/gtsam/hybrid/GaussianMixture.h index 5b4bc0f74..2d715c6e3 100644 --- a/gtsam/hybrid/GaussianMixture.h +++ b/gtsam/hybrid/GaussianMixture.h @@ -255,6 +255,7 @@ class GTSAM_EXPORT GaussianMixture /// Check whether `given` has values for all frontal keys. bool allFrontalsGiven(const VectorValues &given) const; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -263,6 +264,7 @@ class GTSAM_EXPORT GaussianMixture ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional); ar &BOOST_SERIALIZATION_NVP(conditionals_); } +#endif }; /// Return the DiscreteKey vector as a set. diff --git a/gtsam/hybrid/GaussianMixtureFactor.h b/gtsam/hybrid/GaussianMixtureFactor.h index 30899ca7b..2088a7837 100644 --- a/gtsam/hybrid/GaussianMixtureFactor.h +++ b/gtsam/hybrid/GaussianMixtureFactor.h @@ -152,6 +152,7 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -159,6 +160,7 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(factors_); } +#endif }; // traits diff --git a/gtsam/hybrid/HybridBayesNet.h b/gtsam/hybrid/HybridBayesNet.h index ef35ae29d..2b0042b8d 100644 --- a/gtsam/hybrid/HybridBayesNet.h +++ b/gtsam/hybrid/HybridBayesNet.h @@ -228,12 +228,14 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet { */ void updateDiscreteConditionals(const DecisionTreeFactor &prunedDecisionTree); +#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 }; /// traits diff --git a/gtsam/hybrid/HybridBayesTree.h b/gtsam/hybrid/HybridBayesTree.h index 236ebf8b7..e0e6db98e 100644 --- a/gtsam/hybrid/HybridBayesTree.h +++ b/gtsam/hybrid/HybridBayesTree.h @@ -114,12 +114,14 @@ class GTSAM_EXPORT HybridBayesTree : public BayesTree { /// @} 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 }; /// traits diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index b38942bf5..64bdcb2c1 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -204,6 +204,7 @@ class GTSAM_EXPORT HybridConditional /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -225,6 +226,7 @@ class GTSAM_EXPORT HybridConditional static_cast(NULL), static_cast(NULL)); } } +#endif }; // HybridConditional diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index ebd1d289a..8fa23b1f9 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -137,6 +137,7 @@ class GTSAM_EXPORT HybridFactor : public Factor { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -148,6 +149,7 @@ class GTSAM_EXPORT HybridFactor : public Factor { ar &BOOST_SERIALIZATION_NVP(discreteKeys_); ar &BOOST_SERIALIZATION_NVP(continuousKeys_); } +#endif }; // HybridFactor diff --git a/gtsam/hybrid/tests/CMakeLists.txt b/gtsam/hybrid/tests/CMakeLists.txt index 06ad2c505..ddb5ff640 100644 --- a/gtsam/hybrid/tests/CMakeLists.txt +++ b/gtsam/hybrid/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(hybrid "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 "testSerializationHybrid.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(hybrid "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index d9450e107..85bc710b1 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -259,6 +259,7 @@ namespace gtsam { template friend class EliminatableClusterTree; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -266,6 +267,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(nodes_); ar & BOOST_SERIALIZATION_NVP(roots_); } +#endif /// @} diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index a50c4bec9..976d1a7f2 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -199,6 +199,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -213,6 +214,7 @@ namespace gtsam { } ar & BOOST_SERIALIZATION_NVP(children); } +#endif /// @} diff --git a/gtsam/inference/Conditional.h b/gtsam/inference/Conditional.h index ba7b6897e..9f08e5623 100644 --- a/gtsam/inference/Conditional.h +++ b/gtsam/inference/Conditional.h @@ -213,12 +213,14 @@ namespace gtsam { // Cast to derived type (const) (casts down to derived conditional type, then up to factor type) const FACTOR& asFactor() const { return static_cast(static_cast(*this)); } +#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(nrFrontals_); } +#endif /// @} diff --git a/gtsam/inference/Factor.h b/gtsam/inference/Factor.h index 74baa4508..e357a9c88 100644 --- a/gtsam/inference/Factor.h +++ b/gtsam/inference/Factor.h @@ -21,7 +21,9 @@ #pragma once +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include @@ -190,16 +192,16 @@ namespace gtsam { /// @} private: - +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// @name Serialization /// @{ - /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_NVP(keys_); } +#endif /// @} diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 62259dd31..caaa13cae 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -30,8 +30,10 @@ #include // for Eigen::aligned_allocator #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include +#endif #include #include @@ -433,12 +435,14 @@ class FactorGraph { inline bool exists(size_t idx) const { return idx < size() && at(idx); } 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(factors_); } +#endif /// @} }; // FactorGraph diff --git a/gtsam/inference/LabeledSymbol.h b/gtsam/inference/LabeledSymbol.h index 5aee4a0e2..5a7a98c1d 100644 --- a/gtsam/inference/LabeledSymbol.h +++ b/gtsam/inference/LabeledSymbol.h @@ -112,6 +112,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -120,6 +121,7 @@ private: ar & BOOST_SERIALIZATION_NVP(label_); ar & BOOST_SERIALIZATION_NVP(j_); } +#endif }; // \class LabeledSymbol /** Create a symbol key from a character, label and index, i.e. xA5. */ diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 5841203fb..ad41aa5bb 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -256,12 +256,14 @@ private: static GTSAM_EXPORT Ordering ColamdConstrained( const VariableIndex& variableIndex, std::vector& cmember); +#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 }; /// traits diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 017d5134a..6ae5188cf 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -21,7 +21,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include @@ -122,6 +124,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -129,6 +132,7 @@ private: ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(j_); } +#endif }; /** Create a symbol key from a character and index, i.e. x5. */ diff --git a/gtsam/inference/VariableIndex.h b/gtsam/inference/VariableIndex.h index 9573f5988..207ded0ce 100644 --- a/gtsam/inference/VariableIndex.h +++ b/gtsam/inference/VariableIndex.h @@ -190,6 +190,7 @@ protected: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -198,6 +199,7 @@ private: ar & BOOST_SERIALIZATION_NVP(nFactors_); ar & BOOST_SERIALIZATION_NVP(nEntries_); } +#endif /// @} }; diff --git a/gtsam/linear/GaussianBayesNet.h b/gtsam/linear/GaussianBayesNet.h index ee9377eea..39528b810 100644 --- a/gtsam/linear/GaussianBayesNet.h +++ b/gtsam/linear/GaussianBayesNet.h @@ -256,12 +256,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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 1bc70d69a..f99006831 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -274,6 +274,7 @@ namespace gtsam { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -281,6 +282,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional); } +#endif }; // GaussianConditional /// traits diff --git a/gtsam/linear/GaussianFactor.h b/gtsam/linear/GaussianFactor.h index 4e7e92b74..3304829e2 100644 --- a/gtsam/linear/GaussianFactor.h +++ b/gtsam/linear/GaussianFactor.h @@ -163,12 +163,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_BASE_OBJECT_NVP(Base); } +#endif }; // GaussianFactor diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index f8a24245d..d517de77b 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -403,12 +403,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_BASE_OBJECT_NVP(Base); } +#endif }; /** diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index 0d67030d7..eb1fe2de2 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -363,6 +363,7 @@ namespace gtsam { friend class NonlinearFactorGraph; friend class NonlinearClusterTree; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -370,6 +371,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor); ar & BOOST_SERIALIZATION_NVP(info_); } +#endif }; /** diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index 40b109b11..375e82698 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -24,8 +24,10 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include +#endif namespace gtsam { @@ -413,6 +415,7 @@ namespace gtsam { // be very selective on who can access these private methods: template friend class ExpressionFactor; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -450,6 +453,7 @@ namespace gtsam { } BOOST_SERIALIZATION_SPLIT_MEMBER() +#endif }; // JacobianFactor /// traits template<> @@ -458,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 c84ea68fe..70166d97e 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -23,12 +23,14 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include #include #include #include #include +#endif namespace gtsam { namespace noiseModel { @@ -126,12 +128,14 @@ class GTSAM_EXPORT Base { void reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const; 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(reweight_); } +#endif }; /** "Null" robust loss function, equivalent to a Gaussian pdf noise model, or @@ -156,12 +160,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) @@ -188,6 +194,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 @@ -195,6 +202,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). @@ -221,6 +229,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 @@ -228,6 +237,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). @@ -259,6 +269,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 @@ -267,6 +278,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). @@ -293,6 +305,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 @@ -300,6 +313,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). @@ -326,6 +340,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 @@ -334,6 +349,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). @@ -363,6 +379,7 @@ class GTSAM_EXPORT GemanMcClure : public Base { double c_; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -370,6 +387,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 @@ -401,6 +419,7 @@ class GTSAM_EXPORT DCS : public Base { double c_; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -408,6 +427,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 @@ -439,6 +459,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 @@ -446,6 +467,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 645584e2d..72069f9f4 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -24,10 +24,12 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include #include #include +#endif #include @@ -139,12 +141,14 @@ namespace gtsam { virtual double weight(const Vector& v) const { return 1.0; } 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(dim_); } +#endif }; //--------------------------------------------------------------------------------------- @@ -263,6 +267,7 @@ namespace gtsam { virtual Matrix covariance() const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -270,7 +275,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(sqrt_information_); } - +#endif }; // Gaussian //--------------------------------------------------------------------------------------- @@ -356,6 +361,7 @@ namespace gtsam { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -364,6 +370,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(sigmas_); ar & BOOST_SERIALIZATION_NVP(invsigmas_); } +#endif }; // Diagonal //--------------------------------------------------------------------------------------- @@ -499,6 +506,7 @@ namespace gtsam { shared_ptr unit() const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -506,6 +514,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal); ar & BOOST_SERIALIZATION_NVP(mu_); } +#endif }; // Constrained @@ -567,6 +576,7 @@ namespace gtsam { inline double sigma() const { return sigma_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -575,6 +585,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(sigma_); ar & BOOST_SERIALIZATION_NVP(invsigma_); } +#endif }; @@ -616,12 +627,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 }; /** @@ -705,6 +718,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 @@ -713,6 +727,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 a9a407a1c..97d681547 100644 --- a/gtsam/linear/SubgraphBuilder.cpp +++ b/gtsam/linear/SubgraphBuilder.cpp @@ -27,7 +27,9 @@ #include #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include @@ -91,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()); @@ -108,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 925fdef33..fe8f704dc 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -21,8 +21,10 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include #include +#endif #include #include @@ -49,12 +51,14 @@ class GTSAM_EXPORT Subgraph { friend std::ostream &operator<<(std::ostream &os, const Edge &edge); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive &ar, const unsigned int /*version*/) { ar &BOOST_SERIALIZATION_NVP(index); ar &BOOST_SERIALIZATION_NVP(weight); } +#endif }; typedef std::vector Edges; @@ -80,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/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 29cea3976..bb5bbc794 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -368,12 +368,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(values_); } +#endif }; // VectorValues definition /// traits diff --git a/gtsam/linear/tests/CMakeLists.txt b/gtsam/linear/tests/CMakeLists.txt index d1aafb4ea..a99a5eb42 100644 --- a/gtsam/linear/tests/CMakeLists.txt +++ b/gtsam/linear/tests/CMakeLists.txt @@ -1,6 +1,15 @@ -gtsamAddTestsGlob(linear "test*.cpp" "" "gtsam") - -if(MSVC) - set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationLinear.cpp" - APPEND PROPERTY COMPILE_FLAGS "/bigobj") +# 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 "testSerializationLinear.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(linear "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") + +# Set properties to serialization target if Boost serialization is enabled and MSVC +if (GTSAM_ENABLE_BOOST_SERIALIZATION AND MSVC) + set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationLinear.cpp" + APPEND PROPERTY COMPILE_FLAGS "/bigobj") endif() diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index bf7ef56b0..05439bafc 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -120,6 +120,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -128,6 +129,7 @@ private: ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(biasHat_); } +#endif }; class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN { @@ -206,6 +208,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -216,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 b412d4d26..d61db2166 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -63,6 +63,7 @@ public: return bRef_; } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -70,6 +71,7 @@ public: ar & boost::serialization::make_nvp("nZ_", nZ_); ar & boost::serialization::make_nvp("bRef_", bRef_); } +#endif }; /** @@ -130,6 +132,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -140,6 +143,7 @@ private: ar & boost::serialization::make_nvp("AttitudeFactor", boost::serialization::base_object(*this)); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW @@ -213,6 +217,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -223,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/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index c7cf939af..cf1c147bf 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -97,6 +97,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { }; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -107,6 +108,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { boost::serialization::base_object(*this)); ar& BOOST_SERIALIZATION_NVP(nT_); } +#endif }; } // namespace gtsam diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index e6dc6e675..1a0126107 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -21,7 +21,9 @@ **/ #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif /* External or standard includes */ #include diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 407bf9ace..94a37c2d2 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -101,6 +101,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -111,6 +112,7 @@ private: ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance); ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW @@ -223,6 +225,7 @@ public: /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -231,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 dbc164d1a..cd89dd464 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -97,6 +97,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -107,6 +108,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(nT_); } +#endif }; /** @@ -164,6 +166,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// Serialization function friend class boost::serialization::access; template @@ -174,6 +177,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(nT_); } +#endif }; } /// namespace gtsam diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 9e337028a..6df87eda6 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -20,7 +20,9 @@ #include #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif namespace gtsam { @@ -140,6 +142,7 @@ private: /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -147,6 +150,7 @@ private: ar & BOOST_SERIALIZATION_NVP(biasAcc_); ar & BOOST_SERIALIZATION_NVP(biasGyro_); } +#endif public: diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 3134a8916..59ff688af 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -146,6 +146,7 @@ public: #endif private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -154,6 +155,7 @@ public: ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); } +#endif }; /** @@ -246,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*/) { @@ -254,6 +257,7 @@ public: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); } +#endif }; // class ImuFactor diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index 45adb2383..ba9a08d78 100644 --- a/gtsam/navigation/MagPoseFactor.h +++ b/gtsam/navigation/MagPoseFactor.h @@ -132,6 +132,7 @@ class MagPoseFactor: public NoiseModelFactorN { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function. friend class boost::serialization::access; template @@ -144,6 +145,7 @@ class MagPoseFactor: public NoiseModelFactorN { ar & BOOST_SERIALIZATION_NVP(bias_); ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } +#endif }; // \class MagPoseFactor } /// namespace gtsam diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 0f71ec416..a8c97477b 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -113,6 +113,7 @@ public: /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -126,6 +127,7 @@ private: ar & BOOST_SERIALIZATION_NVP(delVdelBiasAcc_); ar & BOOST_SERIALIZATION_NVP(delVdelBiasOmega_); } +#endif }; } /// namespace gtsam diff --git a/gtsam/navigation/NavState.h b/gtsam/navigation/NavState.h index 5e44e16c2..f778a7123 100644 --- a/gtsam/navigation/NavState.h +++ b/gtsam/navigation/NavState.h @@ -190,6 +190,7 @@ public: private: /// @{ /// serialization +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -197,6 +198,7 @@ private: ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(v_); } +#endif /// @} }; diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 05489c5fb..c80399f14 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -60,6 +60,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { std::optional getBodyPSensor() const { return body_P_sensor; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -75,6 +76,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis); } } +#endif #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions @@ -179,6 +181,7 @@ class GTSAM_EXPORT PreintegratedRotation { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -188,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/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 1a5366c6c..e4a790b9d 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -173,6 +173,7 @@ class GTSAM_EXPORT PreintegrationBase { OptionalJacobian<9, 6> H5 = {}) const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -181,6 +182,7 @@ class GTSAM_EXPORT PreintegrationBase { ar & BOOST_SERIALIZATION_NVP(biasHat_); ar & BOOST_SERIALIZATION_NVP(deltaTij_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index ab32343b8..4350c7ebd 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -71,6 +71,7 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { protected: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -82,6 +83,7 @@ protected: ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); ar & BOOST_SERIALIZATION_NVP(n_gravity); } +#endif #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index d03df5cb8..e16ad9310 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -127,6 +127,7 @@ public: /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -137,6 +138,7 @@ private: ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_); ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/navigation/tests/CMakeLists.txt b/gtsam/navigation/tests/CMakeLists.txt index 0beca7769..a7212da34 100644 --- a/gtsam/navigation/tests/CMakeLists.txt +++ b/gtsam/navigation/tests/CMakeLists.txt @@ -24,4 +24,9 @@ else() endif() endif() +# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests +if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) + list(APPEND tests_excluded testSerializationNavigation.cpp) +endif() + gtsamAddTestsGlob(navigation "test*.cpp" "${tests_excluded}" "${test_link_libraries}") diff --git a/gtsam/nonlinear/CustomFactor.h b/gtsam/nonlinear/CustomFactor.h index 60dbcdaf2..d486e6f0d 100644 --- a/gtsam/nonlinear/CustomFactor.h +++ b/gtsam/nonlinear/CustomFactor.h @@ -90,6 +90,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -97,6 +98,7 @@ private: ar & boost::serialization::make_nvp("CustomFactor", boost::serialization::base_object(*this)); } +#endif }; } diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index f859b3d92..8c4e8ce86 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -198,6 +198,7 @@ protected: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// Save to an archive: just saves the base class template void save(Archive& ar, const unsigned int /*version*/) const { @@ -218,6 +219,7 @@ private: BOOST_SERIALIZATION_SPLIT_MEMBER() friend class boost::serialization::access; +#endif // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index de82da05f..128de5847 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -119,6 +119,7 @@ class FunctorizedFactor : public NoiseModelFactorN { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -129,6 +130,7 @@ class FunctorizedFactor : public NoiseModelFactorN { ar &BOOST_SERIALIZATION_NVP(measured_); ar &BOOST_SERIALIZATION_NVP(func_); } +#endif }; /// traits @@ -229,6 +231,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -239,6 +242,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { ar &BOOST_SERIALIZATION_NVP(measured_); ar &BOOST_SERIALIZATION_NVP(func_); } +#endif }; /// traits diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 8b48f2f7d..50c5058c2 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -340,6 +340,7 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { void updateDelta(bool forceFullSolve = false) const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -357,6 +358,7 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { ar & BOOST_SERIALIZATION_NVP(fixedVariables_); ar & BOOST_SERIALIZATION_NVP(update_count_); } +#endif }; // ISAM2 diff --git a/gtsam/nonlinear/ISAM2Clique.h b/gtsam/nonlinear/ISAM2Clique.h index 0b1d567d2..08b74ef26 100644 --- a/gtsam/nonlinear/ISAM2Clique.h +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -147,6 +147,7 @@ class GTSAM_EXPORT ISAM2Clique void restoreFromOriginals(const Vector& originalValues, VectorValues* delta) const; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -155,6 +156,7 @@ class GTSAM_EXPORT ISAM2Clique ar& BOOST_SERIALIZATION_NVP(cachedFactor_); ar& BOOST_SERIALIZATION_NVP(gradientContribution_); } +#endif }; // \struct ISAM2Clique /** diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index 0442f4780..dfbf221c3 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -163,6 +163,7 @@ public: void initializeLinearizationPoint(const Values& linearizationPoint); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -172,6 +173,7 @@ public: ar & BOOST_SERIALIZATION_NVP(factor_); ar & BOOST_SERIALIZATION_NVP(linearizationPoint_); } +#endif }; // \class LinearContainerFactor diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 022fb4523..c8ab0c2af 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -182,6 +182,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -194,6 +195,7 @@ private: ar & BOOST_SERIALIZATION_NVP(allow_error_); ar & BOOST_SERIALIZATION_NVP(error_gain_); } +#endif }; // \class NonlinearEquality @@ -273,6 +275,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -283,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 73255482c..d22409875 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -28,7 +28,9 @@ #include #include // boost::index_sequence +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include @@ -303,6 +305,7 @@ public: shared_ptr cloneWithNewNoiseModel(const SharedNoiseModel newNoise) const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -311,6 +314,7 @@ public: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(noiseModel_); } +#endif }; // \class NoiseModelFactor @@ -713,6 +717,7 @@ protected: } } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -720,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/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index 95b116ab6..92bfdaf20 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -253,6 +253,7 @@ namespace gtsam { std::shared_ptr linearizeToHessianFactor( const Values& values, const Scatter& scatter, const Dampen& dampen = nullptr) const; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -260,6 +261,7 @@ namespace gtsam { ar & boost::serialization::make_nvp("NonlinearFactorGraph", boost::serialization::base_object(*this)); } +#endif }; /// traits diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 808f66c5b..ab2a66a77 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -105,6 +105,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -114,6 +115,7 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(prior_); } +#endif // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 66e90a0b3..172bfba89 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -307,12 +307,14 @@ namespace gtsam { return filter(key_value.key) && (dynamic_cast*>(&key_value.value)); } +#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(values_); } +#endif }; diff --git a/gtsam/nonlinear/tests/CMakeLists.txt b/gtsam/nonlinear/tests/CMakeLists.txt index 69a3700f2..4dcd5f4e9 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(nonlinear "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/sam/BearingFactor.h b/gtsam/sam/BearingFactor.h index 68d6cbd48..01b2baf18 100644 --- a/gtsam/sam/BearingFactor.h +++ b/gtsam/sam/BearingFactor.h @@ -75,12 +75,14 @@ struct BearingFactor : public ExpressionFactorN { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); } +#endif }; // BearingFactor /// traits diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h index f4fcbf692..a1e6251b5 100644 --- a/gtsam/sam/BearingRangeFactor.h +++ b/gtsam/sam/BearingRangeFactor.h @@ -93,12 +93,14 @@ class BearingRangeFactor private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); } +#endif }; // BearingRangeFactor /// traits diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index fb7977d45..193a89a5a 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -80,12 +80,14 @@ class RangeFactor : public ExpressionFactorN { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); } +#endif }; // \ RangeFactor /// traits @@ -162,8 +164,9 @@ class RangeFactorWithTransform : public ExpressionFactorN { } private: - /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; + /** Serialization function */ template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { // **IMPORTANT** We need to (de)serialize parameters before the base class, @@ -173,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/sam/tests/CMakeLists.txt b/gtsam/sam/tests/CMakeLists.txt index 127c619ee..000ded774 100644 --- a/gtsam/sam/tests/CMakeLists.txt +++ b/gtsam/sam/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(sam "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 "testSerializationSam.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(sam "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/sfm/SfmData.h b/gtsam/sfm/SfmData.h index dbf0bd1e7..7161ab2f9 100644 --- a/gtsam/sfm/SfmData.h +++ b/gtsam/sfm/SfmData.h @@ -125,13 +125,16 @@ struct GTSAM_EXPORT SfmData { /// @name Serialization /// @{ - /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; + /** Serialization function */ template void serialize(Archive& ar, const unsigned int /*version*/) { ar& BOOST_SERIALIZATION_NVP(cameras); ar& BOOST_SERIALIZATION_NVP(tracks); } +#endif + /// @} }; diff --git a/gtsam/sfm/SfmTrack.h b/gtsam/sfm/SfmTrack.h index 60699bc31..6ef1f9512 100644 --- a/gtsam/sfm/SfmTrack.h +++ b/gtsam/sfm/SfmTrack.h @@ -161,6 +161,7 @@ struct GTSAM_EXPORT SfmTrack : SfmTrack2d { /// @name Serialization /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -172,6 +173,7 @@ struct GTSAM_EXPORT SfmTrack : SfmTrack2d { ar& BOOST_SERIALIZATION_NVP(measurements); ar& BOOST_SERIALIZATION_NVP(siftIndices); } +#endif /// @} }; diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index abbfa7fcb..a7289f759 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -80,11 +80,13 @@ class TranslationFactor : public NoiseModelFactorN { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); } +#endif }; // \ TranslationFactor } // namespace gtsam diff --git a/gtsam/slam/AntiFactor.h b/gtsam/slam/AntiFactor.h index f11575035..3b031b334 100644 --- a/gtsam/slam/AntiFactor.h +++ b/gtsam/slam/AntiFactor.h @@ -106,6 +106,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -114,6 +115,7 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(factor_); } +#endif }; // \class AntiFactor } /// namespace gtsam diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 36cea67a9..3e5b154e3 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -135,6 +135,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -144,6 +145,7 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 }; @@ -174,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 14aa96dbc..a496971e2 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -83,6 +83,7 @@ struct BoundingConstraint1: public NoiseModelFactorN { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -93,6 +94,7 @@ private: ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); } +#endif }; /** @@ -159,6 +161,7 @@ struct BoundingConstraint2: public NoiseModelFactorN { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -169,6 +172,7 @@ private: ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); } +#endif }; } // \namespace gtsam diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index c533ea04d..45e54aa5d 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -91,6 +91,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -101,6 +102,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measuredE_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 8046a210b..5605ad58e 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -37,7 +37,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include #include @@ -181,6 +183,7 @@ public: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -190,6 +193,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; template @@ -280,6 +284,7 @@ public: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -289,6 +294,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; template diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index 72c50d43f..8ce90988b 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -91,6 +91,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -100,6 +101,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; } // \namespace gtsam diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index 85e7a0fa4..c5257f45c 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -90,6 +90,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -99,6 +100,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 73ed85035..f40d8f5bb 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -188,6 +188,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -199,6 +200,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index 73952d3cc..0ae6ea88a 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -122,6 +122,7 @@ public: Key local_key() const { return this->key3(); } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -129,6 +130,7 @@ private: ar & boost::serialization::make_nvp("NonlinearFactor3", boost::serialization::base_object(*this)); } +#endif }; /// traits diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a5fc3be1a..80dde3563 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -30,7 +30,9 @@ #include #include +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #include +#endif #include namespace gtsam { @@ -443,6 +445,7 @@ protected: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION/// /// Serialization function friend class boost::serialization::access; template @@ -452,6 +455,7 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } +#endif }; // end class SmartFactorBase diff --git a/gtsam/slam/SmartFactorParams.h b/gtsam/slam/SmartFactorParams.h index 4f23c085d..4523d0e0e 100644 --- a/gtsam/slam/SmartFactorParams.h +++ b/gtsam/slam/SmartFactorParams.h @@ -118,6 +118,7 @@ struct SmartProjectionParams { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -129,6 +130,7 @@ private: ar & BOOST_SERIALIZATION_NVP(throwCheirality); ar & BOOST_SERIALIZATION_NVP(verboseCheirality); } +#endif }; } // \ namespace gtsam diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 1434993e2..c54efecc4 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -466,6 +466,7 @@ protected: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -475,6 +476,7 @@ protected: ar & BOOST_SERIALIZATION_NVP(result_); ar & BOOST_SERIALIZATION_NVP(cameraPosesTriangulation_); } +#endif } ; diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 6421b3013..b88c1c628 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -148,6 +148,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -155,6 +156,7 @@ public: ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; // end of class declaration diff --git a/gtsam/slam/SmartProjectionRigFactor.h b/gtsam/slam/SmartProjectionRigFactor.h index cf564cdda..0aa070ed0 100644 --- a/gtsam/slam/SmartProjectionRigFactor.h +++ b/gtsam/slam/SmartProjectionRigFactor.h @@ -352,6 +352,7 @@ class SmartProjectionRigFactor : public SmartProjectionFactor { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -361,6 +362,7 @@ class SmartProjectionRigFactor : public SmartProjectionFactor { // ar& BOOST_SERIALIZATION_NVP(cameraRig_); // ar& BOOST_SERIALIZATION_NVP(cameraIds_); } +#endif }; // end of class declaration diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index 8d25d6032..a2d428d11 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -170,6 +170,7 @@ public: inline bool throwCheirality() const { return throwCheirality_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -183,6 +184,7 @@ private: ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } +#endif }; /// traits diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index c71c94b20..6feaa7041 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -189,6 +189,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -199,6 +200,7 @@ private: ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } +#endif }; } // \ namespace gtsam diff --git a/gtsam/slam/tests/CMakeLists.txt b/gtsam/slam/tests/CMakeLists.txt index 1205388a1..223fa6501 100644 --- a/gtsam/slam/tests/CMakeLists.txt +++ b/gtsam/slam/tests/CMakeLists.txt @@ -1 +1,10 @@ -gtsamAddTestsGlob(slam "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 "testSerializationDataset.cpp" "testSerializationInSlam.cpp") + message(STATUS "Excluding tests: ${EXCLUDE_TESTS}") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(slam "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/symbolic/SymbolicBayesNet.h b/gtsam/symbolic/SymbolicBayesNet.h index 31b1bac33..f2c142762 100644 --- a/gtsam/symbolic/SymbolicBayesNet.h +++ b/gtsam/symbolic/SymbolicBayesNet.h @@ -104,12 +104,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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits diff --git a/gtsam/symbolic/SymbolicBayesTree.h b/gtsam/symbolic/SymbolicBayesTree.h index 0a6b6608e..4d5804b27 100644 --- a/gtsam/symbolic/SymbolicBayesTree.h +++ b/gtsam/symbolic/SymbolicBayesTree.h @@ -63,12 +63,14 @@ namespace gtsam { bool equals(const This& other, double tol = 1e-9) const; 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 }; /// traits diff --git a/gtsam/symbolic/SymbolicConditional.h b/gtsam/symbolic/SymbolicConditional.h index 1411ceafe..5cc4e9cfc 100644 --- a/gtsam/symbolic/SymbolicConditional.h +++ b/gtsam/symbolic/SymbolicConditional.h @@ -126,6 +126,7 @@ namespace gtsam { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -133,6 +134,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor); ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional); } +#endif }; /// traits diff --git a/gtsam/symbolic/SymbolicFactor.h b/gtsam/symbolic/SymbolicFactor.h index 86ebdffbf..0e9eb3d46 100644 --- a/gtsam/symbolic/SymbolicFactor.h +++ b/gtsam/symbolic/SymbolicFactor.h @@ -153,12 +153,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_BASE_OBJECT_NVP(Base); } +#endif }; // IndexFactor // Forward declarations diff --git a/gtsam/symbolic/SymbolicFactorGraph.h b/gtsam/symbolic/SymbolicFactorGraph.h index bb37b4436..01b532a5c 100644 --- a/gtsam/symbolic/SymbolicFactorGraph.h +++ b/gtsam/symbolic/SymbolicFactorGraph.h @@ -148,12 +148,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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits diff --git a/gtsam/symbolic/tests/CMakeLists.txt b/gtsam/symbolic/tests/CMakeLists.txt index 6bef7a109..65a7cf719 100644 --- a/gtsam/symbolic/tests/CMakeLists.txt +++ b/gtsam/symbolic/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(symbolic "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 "testSerializationSymbolic.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(symbolic "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index 89ae59f9c..0e0d9ae27 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -157,6 +157,7 @@ public: /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -164,6 +165,7 @@ private: ar & BOOST_SERIALIZATION_NVP(first); ar & BOOST_SERIALIZATION_NVP(second); } +#endif }; diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index ab06b32a4..9f2ec89d2 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -51,6 +51,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -59,6 +60,7 @@ private: ar & boost::serialization::make_nvp("NoiseModelFactor3", boost::serialization::base_object(*this)); } +#endif }; // \VelocityConstraint3 } diff --git a/gtsam_unstable/geometry/BearingS2.h b/gtsam_unstable/geometry/BearingS2.h index 59819c555..cb1d055df 100644 --- a/gtsam_unstable/geometry/BearingS2.h +++ b/gtsam_unstable/geometry/BearingS2.h @@ -90,6 +90,7 @@ private: /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION // // Serialization function friend class boost::serialization::access; template @@ -97,6 +98,7 @@ private: ar & BOOST_SERIALIZATION_NVP(azimuth_); ar & BOOST_SERIALIZATION_NVP(elevation_); } +#endif }; diff --git a/gtsam_unstable/geometry/InvDepthCamera3.h b/gtsam_unstable/geometry/InvDepthCamera3.h index 7f02984bf..eb9045dff 100644 --- a/gtsam_unstable/geometry/InvDepthCamera3.h +++ b/gtsam_unstable/geometry/InvDepthCamera3.h @@ -172,6 +172,7 @@ private: /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -179,6 +180,7 @@ private: ar & BOOST_SERIALIZATION_NVP(pose_); ar & BOOST_SERIALIZATION_NVP(k_); } +#endif /// @} }; // \class InvDepthCamera -} // \namesapce gtsam +} // \namespace gtsam diff --git a/gtsam_unstable/geometry/Pose3Upright.h b/gtsam_unstable/geometry/Pose3Upright.h index 1c205c7fb..a77715fc6 100644 --- a/gtsam_unstable/geometry/Pose3Upright.h +++ b/gtsam_unstable/geometry/Pose3Upright.h @@ -130,6 +130,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION // // Serialization function friend class boost::serialization::access; template @@ -137,6 +138,7 @@ private: ar & BOOST_SERIALIZATION_NVP(T_); ar & BOOST_SERIALIZATION_NVP(z_); } +#endif }; // \class Pose3Upright diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.h b/gtsam_unstable/nonlinear/LinearizedFactor.h index 5bf791089..689c97c3a 100644 --- a/gtsam_unstable/nonlinear/LinearizedFactor.h +++ b/gtsam_unstable/nonlinear/LinearizedFactor.h @@ -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 @@ -67,6 +68,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(lin_points_); } +#endif }; @@ -146,14 +148,16 @@ public: Vector error_vector(const Values& c) const; private: - /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; + /** Serialization function */ template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & boost::serialization::make_nvp("LinearizedJacobianFactor", boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(Ab_); } +#endif }; /// traits @@ -275,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*/) { @@ -282,6 +287,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(info_); } +#endif }; /// traits diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index f175e30b3..f1337c0e8 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -415,6 +415,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -424,6 +425,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; // \class BetweenFactorEM diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index f4d30c2f9..f2b669f4f 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -94,6 +94,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -103,6 +104,7 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; // \class BiasedGPSFactor } /// namespace gtsam diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index 05ba708aa..f62157845 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -706,6 +706,7 @@ public: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -713,6 +714,7 @@ private: ar & boost::serialization::make_nvp("NonlinearFactor2", boost::serialization::base_object(*this)); } +#endif diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 390b49faa..a94c95335 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -573,6 +573,7 @@ public: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -580,6 +581,7 @@ private: ar & boost::serialization::make_nvp("NonlinearFactor2", boost::serialization::base_object(*this)); } +#endif diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index 87389a40d..b91ed2afe 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -113,6 +113,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -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 */ diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index a4d69f1dd..91dba26e6 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -413,6 +413,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -420,6 +421,7 @@ private: ar & boost::serialization::make_nvp("NonlinearFactor2", boost::serialization::base_object(*this)); } +#endif }; // \class InertialNavFactor_GlobalVelocity diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index c10ff3b01..64a1366a2 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -113,6 +113,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -121,5 +122,6 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index 0774eaa87..23f8bd3e0 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -135,6 +135,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -143,6 +144,7 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index 18f866c56..63fcb4d8c 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -142,6 +142,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -151,6 +152,7 @@ private: ar & BOOST_SERIALIZATION_NVP(K_); ar & BOOST_SERIALIZATION_NVP(referencePoint_); } +#endif }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index 4f0ac58a6..22a725d47 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -139,6 +139,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -147,6 +148,7 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; /** @@ -269,14 +271,16 @@ public: private: - /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; + /// Serialization function template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/MultiProjectionFactor.h b/gtsam_unstable/slam/MultiProjectionFactor.h index 3adf227bc..8e2ea0cf7 100644 --- a/gtsam_unstable/slam/MultiProjectionFactor.h +++ b/gtsam_unstable/slam/MultiProjectionFactor.h @@ -213,6 +213,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -224,5 +225,6 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } +#endif }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index 6e29ca6d5..b70fe8b19 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -140,6 +140,7 @@ namespace gtsam { const std::vector& indices() const { return indices_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -151,6 +152,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(indices_); // ar & BOOST_SERIALIZATION_NVP(H_); } +#endif }; // \class PartialPriorFactor } /// namespace gtsam diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index 339407a3f..aa383967d 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -119,6 +119,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -127,6 +128,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; // \class PoseBetweenFactor } /// namespace gtsam diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index a5e5facbd..4a201ad89 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -101,6 +101,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -109,6 +110,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } +#endif }; } /// namespace gtsam diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index 62f681b2e..be454cb70 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -92,6 +92,7 @@ class PoseToPointFactor : public NoiseModelFactorN { const POINT& measured() const { return measured_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -102,6 +103,7 @@ class PoseToPointFactor : public NoiseModelFactorN { boost::serialization::base_object(*this)); ar& BOOST_SERIALIZATION_NVP(measured_); } +#endif }; // \class PoseToPointFactor diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index dea28528d..38467c6cc 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -171,6 +171,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -181,6 +182,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } +#endif }; /// traits diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index a3dd0850a..5b6a83a33 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -151,6 +151,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -160,6 +161,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } +#endif }; /// traits diff --git a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h index 938f20fd6..c5eb58f14 100644 --- a/gtsam_unstable/slam/ProjectionFactorRollingShutter.h +++ b/gtsam_unstable/slam/ProjectionFactorRollingShutter.h @@ -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 @@ -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 diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index db86ead96..d24415c3b 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -65,6 +65,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -74,6 +75,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; // RelativeElevationFactor diff --git a/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h b/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h index 0aac1e0fa..e2e71cc03 100644 --- a/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h +++ b/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h @@ -456,12 +456,14 @@ class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter } 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 }; // end of class declaration diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index c05bd1fd0..0893af75e 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -501,6 +501,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -509,6 +510,7 @@ private: ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality); ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality); } +#endif }; /// traits diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h b/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h index df5aed412..529a1dc10 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h @@ -288,6 +288,7 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -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 diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 3e8270b25..cce265ab7 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -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 @@ -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 diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h index e269e6506..2a257ff57 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h @@ -216,6 +216,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -224,6 +225,7 @@ namespace gtsam { boost::serialization::base_object(*this)); //ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; // \class TransformBtwRobotsUnaryFactor /// traits diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 315feac9c..c47cf3b7d 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -414,6 +414,7 @@ namespace gtsam { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -422,6 +423,7 @@ namespace gtsam { boost::serialization::base_object(*this)); //ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; // \class TransformBtwRobotsUnaryFactorEM /// traits diff --git a/tests/simulated2D.h b/tests/simulated2D.h index 5334cbf45..612dd1891 100644 --- a/tests/simulated2D.h +++ b/tests/simulated2D.h @@ -160,6 +160,7 @@ namespace simulated2D { /// Default constructor GenericPrior() { } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -167,6 +168,7 @@ namespace simulated2D { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; /** @@ -208,6 +210,7 @@ namespace simulated2D { /// Default constructor GenericOdometry() { } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -215,6 +218,7 @@ namespace simulated2D { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; /** @@ -257,6 +261,7 @@ namespace simulated2D { /// Default constructor GenericMeasurement() { } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -264,6 +269,7 @@ namespace simulated2D { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; /** Typedefs for regular use */ diff --git a/tests/testExpressionFactor.cpp b/tests/testExpressionFactor.cpp index 4f4891d8a..567e9df5d 100644 --- a/tests/testExpressionFactor.cpp +++ b/tests/testExpressionFactor.cpp @@ -695,6 +695,7 @@ public: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -704,6 +705,7 @@ private: boost::serialization::base_object(*this)); ar &BOOST_SERIALIZATION_NVP(measured_); } +#endif }; TEST(ExpressionFactor, variadicTemplate) {