From 4b235103cfcfda1c3e5bd9cf50c28cd47648f8c4 Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Wed, 18 Jan 2023 11:36:21 -0800 Subject: [PATCH 1/9] ifdefs for gtsam folder on serialize --- gtsam/base/ConcurrentMap.h | 2 ++ gtsam/base/FastList.h | 2 ++ gtsam/base/FastMap.h | 2 ++ gtsam/base/FastSet.h | 2 ++ gtsam/base/GenericValue.h | 2 ++ gtsam/base/SymmetricBlockMatrix.h | 2 ++ gtsam/base/Value.h | 2 ++ gtsam/base/VerticalBlockMatrix.h | 2 ++ gtsam/discrete/DecisionTree-inl.h | 2 ++ gtsam/discrete/DecisionTree.h | 2 ++ gtsam/discrete/DecisionTreeFactor.h | 2 ++ gtsam/discrete/DiscreteBayesNet.h | 2 ++ gtsam/discrete/DiscreteConditional.h | 2 ++ gtsam/discrete/DiscreteKey.h | 2 ++ gtsam/discrete/DiscreteLookupDAG.h | 2 ++ gtsam/geometry/BearingRange.h | 2 ++ gtsam/geometry/Cal3.h | 2 ++ gtsam/geometry/Cal3Bundler.h | 2 ++ gtsam/geometry/Cal3DS2.h | 2 ++ gtsam/geometry/Cal3DS2_Base.h | 2 ++ gtsam/geometry/Cal3Fisheye.h | 2 ++ gtsam/geometry/Cal3Unified.h | 2 ++ gtsam/geometry/Cal3_S2.h | 2 ++ gtsam/geometry/Cal3_S2Stereo.h | 2 ++ gtsam/geometry/CalibratedCamera.h | 2 ++ gtsam/geometry/CameraSet.h | 2 ++ gtsam/geometry/EssentialMatrix.h | 2 ++ gtsam/geometry/PinholeCamera.h | 2 ++ gtsam/geometry/PinholePose.h | 2 ++ gtsam/geometry/PinholeSet.h | 2 ++ gtsam/geometry/Pose2.h | 2 ++ gtsam/geometry/Pose3.h | 2 ++ gtsam/geometry/Rot2.h | 2 ++ gtsam/geometry/Rot3.h | 2 ++ gtsam/geometry/SOn.h | 4 ++++ gtsam/geometry/SphericalCamera.h | 2 ++ gtsam/geometry/StereoCamera.h | 2 ++ gtsam/geometry/StereoPoint2.h | 2 ++ gtsam/geometry/Unit3.h | 2 ++ gtsam/geometry/triangulation.h | 2 ++ gtsam/hybrid/GaussianMixture.h | 2 ++ gtsam/hybrid/GaussianMixtureFactor.h | 2 ++ gtsam/hybrid/HybridBayesNet.h | 2 ++ gtsam/hybrid/HybridBayesTree.h | 2 ++ gtsam/hybrid/HybridConditional.h | 2 ++ gtsam/hybrid/HybridFactor.h | 2 ++ gtsam/inference/BayesTree.h | 2 ++ gtsam/inference/BayesTreeCliqueBase.h | 2 ++ gtsam/inference/Conditional.h | 2 ++ gtsam/inference/Factor.h | 2 ++ gtsam/inference/FactorGraph.h | 2 ++ gtsam/inference/LabeledSymbol.h | 2 ++ gtsam/inference/Ordering.h | 2 ++ gtsam/inference/Symbol.h | 2 ++ gtsam/inference/VariableIndex.h | 2 ++ gtsam/linear/GaussianBayesNet.h | 2 ++ gtsam/linear/GaussianConditional.h | 2 ++ gtsam/linear/GaussianFactor.h | 2 ++ gtsam/linear/GaussianFactorGraph.h | 2 ++ gtsam/linear/HessianFactor.h | 2 ++ gtsam/linear/JacobianFactor.h | 2 ++ gtsam/linear/LossFunctions.h | 2 ++ gtsam/linear/NoiseModel.h | 2 ++ gtsam/linear/SubgraphBuilder.h | 2 ++ gtsam/linear/VectorValues.h | 2 ++ gtsam/navigation/AHRSFactor.h | 2 ++ gtsam/navigation/AttitudeFactor.h | 2 ++ gtsam/navigation/BarometricFactor.h | 2 ++ gtsam/navigation/CombinedImuFactor.h | 2 ++ gtsam/navigation/GPSFactor.h | 2 ++ gtsam/navigation/ImuBias.h | 2 ++ gtsam/navigation/ImuFactor.h | 2 ++ gtsam/navigation/MagPoseFactor.h | 2 ++ gtsam/navigation/ManifoldPreintegration.h | 2 ++ gtsam/navigation/NavState.h | 2 ++ gtsam/navigation/PreintegratedRotation.h | 2 ++ gtsam/navigation/PreintegrationBase.h | 2 ++ gtsam/navigation/PreintegrationParams.h | 2 ++ gtsam/navigation/TangentPreintegration.h | 2 ++ gtsam/nonlinear/CustomFactor.h | 2 ++ gtsam/nonlinear/ExpressionFactor.h | 2 ++ gtsam/nonlinear/FunctorizedFactor.h | 2 ++ gtsam/nonlinear/ISAM2.h | 2 ++ gtsam/nonlinear/ISAM2Clique.h | 2 ++ gtsam/nonlinear/LinearContainerFactor.h | 2 ++ gtsam/nonlinear/NonlinearEquality.h | 2 ++ gtsam/nonlinear/NonlinearFactor.h | 2 ++ gtsam/nonlinear/NonlinearFactorGraph.h | 2 ++ gtsam/nonlinear/PriorFactor.h | 2 ++ gtsam/nonlinear/Values.h | 2 ++ gtsam/sam/BearingFactor.h | 2 ++ gtsam/sam/BearingRangeFactor.h | 2 ++ gtsam/sam/RangeFactor.h | 2 ++ gtsam/sfm/SfmData.h | 3 +++ gtsam/sfm/SfmTrack.h | 2 ++ gtsam/sfm/TranslationFactor.h | 2 ++ gtsam/slam/AntiFactor.h | 2 ++ gtsam/slam/BetweenFactor.h | 2 ++ gtsam/slam/BoundingConstraint.h | 2 ++ gtsam/slam/EssentialMatrixConstraint.h | 2 ++ gtsam/slam/GeneralSFMFactor.h | 2 ++ gtsam/slam/PoseRotationPrior.h | 2 ++ gtsam/slam/PoseTranslationPrior.h | 2 ++ gtsam/slam/ProjectionFactor.h | 2 ++ gtsam/slam/ReferenceFrameFactor.h | 2 ++ gtsam/slam/SmartFactorBase.h | 2 ++ gtsam/slam/SmartFactorParams.h | 2 ++ gtsam/slam/SmartProjectionFactor.h | 2 ++ gtsam/slam/SmartProjectionPoseFactor.h | 2 ++ gtsam/slam/SmartProjectionRigFactor.h | 2 ++ gtsam/slam/StereoFactor.h | 2 ++ gtsam/slam/TriangulationFactor.h | 2 ++ gtsam/symbolic/SymbolicBayesNet.h | 2 ++ gtsam/symbolic/SymbolicBayesTree.h | 2 ++ gtsam/symbolic/SymbolicConditional.h | 2 ++ gtsam/symbolic/SymbolicFactor.h | 2 ++ gtsam/symbolic/SymbolicFactorGraph.h | 2 ++ 117 files changed, 237 insertions(+) diff --git a/gtsam/base/ConcurrentMap.h b/gtsam/base/ConcurrentMap.h index 8d5f56675..196636c4e 100644 --- a/gtsam/base/ConcurrentMap.h +++ b/gtsam/base/ConcurrentMap.h @@ -101,6 +101,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void save(Archive& ar, const unsigned int /*version*/) const @@ -110,6 +111,7 @@ private: std::copy(this->begin(), this->end(), map.begin()); ar & BOOST_SERIALIZATION_NVP(map); } +#endif template void load(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/base/FastList.h b/gtsam/base/FastList.h index 29ecd7dbc..d6549ce2e 100644 --- a/gtsam/base/FastList.h +++ b/gtsam/base/FastList.h @@ -77,11 +77,13 @@ public: 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_BASE_OBJECT_NVP(Base); } +#endif }; diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index 1f68c8d28..4aadb6577 100644 --- a/gtsam/base/FastMap.h +++ b/gtsam/base/FastMap.h @@ -68,11 +68,13 @@ public: 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_BASE_OBJECT_NVP(Base); } +#endif }; } diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index 1fceebad5..b1c95ad84 100644 --- a/gtsam/base/FastSet.h +++ b/gtsam/base/FastSet.h @@ -122,11 +122,13 @@ public: 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_BASE_OBJECT_NVP(Base); } +#endif }; } diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index f83a067fb..537cf3a54 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -176,6 +176,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index 302a1ec34..f245db163 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -399,6 +399,7 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -410,6 +411,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..fde769829 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -119,10 +119,12 @@ 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 }; diff --git a/gtsam/base/VerticalBlockMatrix.h b/gtsam/base/VerticalBlockMatrix.h index ef6691cac..459d2902c 100644 --- a/gtsam/base/VerticalBlockMatrix.h +++ b/gtsam/base/VerticalBlockMatrix.h @@ -220,6 +220,7 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -229,6 +230,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(rowEnd_); ar & BOOST_SERIALIZATION_NVP(blockStart_); } +#endif }; } diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index da72bf71f..eb50197a6 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -155,6 +155,7 @@ namespace gtsam { using Base = DecisionTree::Node; /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -162,6 +163,7 @@ namespace gtsam { ar& BOOST_SERIALIZATION_NVP(constant_); ar& BOOST_SERIALIZATION_NVP(nrAssignments_); } +#endif }; // Leaf /****************************************************************************/ diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index af6101296..f4b64f36f 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -118,9 +118,11 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) {} +#endif }; /** ------------------------ Node base class --------------------------- */ diff --git a/gtsam/discrete/DecisionTreeFactor.h b/gtsam/discrete/DecisionTreeFactor.h index 9150c459a..61a14e13f 100644 --- a/gtsam/discrete/DecisionTreeFactor.h +++ b/gtsam/discrete/DecisionTreeFactor.h @@ -254,6 +254,7 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -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..226550b13 100644 --- a/gtsam/discrete/DiscreteBayesNet.h +++ b/gtsam/discrete/DiscreteBayesNet.h @@ -151,11 +151,13 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet { 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_BASE_OBJECT_NVP(Base); } +#endif }; // traits diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 854f5f43d..8af7cbcf2 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -269,12 +269,14 @@ class GTSAM_EXPORT DiscreteConditional 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_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..6f1768e17 100644 --- a/gtsam/discrete/DiscreteKey.h +++ b/gtsam/discrete/DiscreteKey.h @@ -80,6 +80,7 @@ namespace gtsam { bool equals(const DiscreteKeys& other, double tol = 0) const; /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -87,6 +88,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..8d72d221d 100644 --- a/gtsam/discrete/DiscreteLookupDAG.h +++ b/gtsam/discrete/DiscreteLookupDAG.h @@ -127,11 +127,13 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet { 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_BASE_OBJECT_NVP(Base); } +#endif }; // traits diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index ca767c1f1..0175af5b0 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -154,6 +154,7 @@ private: ar& boost::serialization::make_nvp("range", range_); } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; /// @} @@ -162,6 +163,7 @@ private: enum { NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0 }; +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; diff --git a/gtsam/geometry/Cal3.h b/gtsam/geometry/Cal3.h index a55010ce0..3c5989b9f 100644 --- a/gtsam/geometry/Cal3.h +++ b/gtsam/geometry/Cal3.h @@ -185,6 +185,7 @@ class GTSAM_EXPORT Cal3 { private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { @@ -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..8da57d50d 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -157,6 +157,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { @@ -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..e989e661c 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -105,12 +105,14 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { /// @{ /** 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( "Cal3DS2", boost::serialization::base_object(*this)); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h index 185521b77..539813cb0 100644 --- a/gtsam/geometry/Cal3DS2_Base.h +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -157,6 +157,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 { /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { @@ -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..775c6b46e 100644 --- a/gtsam/geometry/Cal3Fisheye.h +++ b/gtsam/geometry/Cal3Fisheye.h @@ -185,6 +185,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 { /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { @@ -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..74ad72fb2 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -139,6 +139,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { @@ -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..1b39e76e3 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -133,12 +133,14 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 { 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( "Cal3_S2", boost::serialization::base_object(*this)); } +#endif /// @} }; diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index 39ca1b099..fcc6b68ee 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -144,6 +144,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { @@ -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..0aef92352 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -229,11 +229,13 @@ public: 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_NVP(pose_); } +#endif }; // end of class PinholeBase diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 4521cbb82..f5b887ae9 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -466,11 +466,13 @@ class CameraSet : public std::vector> { private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// 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..7b8268d4d 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -181,6 +181,7 @@ class EssentialMatrix { /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..a77f5f220 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -327,6 +327,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { @@ -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..490ef63a9 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -218,6 +218,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { @@ -225,6 +226,7 @@ private: & boost::serialization::make_nvp("PinholeBase", boost::serialization::base_object(*this)); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h index 7541f886b..15d0ce473 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -65,11 +65,13 @@ public: 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_BASE_OBJECT_NVP(Base); } +#endif }; template diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index c106cb4d4..d92ce91d8 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -327,12 +327,14 @@ public: 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_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 3dd9e6b9f..42b9a8e57 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -393,12 +393,14 @@ public: 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_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..91c6d5d53 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -214,12 +214,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_NVP(c_); ar & BOOST_SERIALIZATION_NVP(s_); } +#endif }; diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index b98c03dce..fd110fe85 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -529,6 +529,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -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/SOn.h b/gtsam/geometry/SOn.h index b8b9deb3b..069aae833 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -323,6 +323,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 +332,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 /// @} }; @@ -376,6 +378,7 @@ GTSAM_EXPORT typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const; /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template void serialize( Archive& ar, SOn& Q, @@ -384,6 +387,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..76c0d86a1 100644 --- a/gtsam/geometry/SphericalCamera.h +++ b/gtsam/geometry/SphericalCamera.h @@ -53,12 +53,14 @@ class GTSAM_EXPORT EmptyCal { 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( "EmptyCal", boost::serialization::base_object(*this)); } +#endif }; /** 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..ae59c2b9d 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -147,6 +147,7 @@ private: /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -154,6 +155,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 8f629786d..db4f94085 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -207,11 +207,13 @@ private: /// @name Advanced Interface /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 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/triangulation.h b/gtsam/geometry/triangulation.h index 160ab0480..5ba324b4f 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -612,6 +612,7 @@ struct GTSAM_EXPORT TriangulationParameters { private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { @@ -620,6 +621,7 @@ private: ar & BOOST_SERIALIZATION_NVP(landmarkDistanceThreshold); ar & BOOST_SERIALIZATION_NVP(dynamicOutlierRejectionThreshold); } +#endif }; /** diff --git a/gtsam/hybrid/GaussianMixture.h b/gtsam/hybrid/GaussianMixture.h index 5b4bc0f74..cd65c0829 100644 --- a/gtsam/hybrid/GaussianMixture.h +++ b/gtsam/hybrid/GaussianMixture.h @@ -256,6 +256,7 @@ class GTSAM_EXPORT GaussianMixture bool allFrontalsGiven(const VectorValues &given) const; /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive &ar, const unsigned int /*version*/) { @@ -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..1233ccec9 100644 --- a/gtsam/hybrid/HybridBayesNet.h +++ b/gtsam/hybrid/HybridBayesNet.h @@ -229,11 +229,13 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet { void updateDiscreteConditionals(const DecisionTreeFactor &prunedDecisionTree); /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 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..66211d8a0 100644 --- a/gtsam/hybrid/HybridBayesTree.h +++ b/gtsam/hybrid/HybridBayesTree.h @@ -115,11 +115,13 @@ class GTSAM_EXPORT HybridBayesTree : public BayesTree { 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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index b38942bf5..80efd89c6 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -205,6 +205,7 @@ class GTSAM_EXPORT HybridConditional private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { @@ -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..9e243c4ec 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -138,6 +138,7 @@ class GTSAM_EXPORT HybridFactor : public Factor { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { @@ -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/inference/BayesTree.h b/gtsam/inference/BayesTree.h index d9450e107..b09e90223 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -260,12 +260,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_NVP(nodes_); ar & BOOST_SERIALIZATION_NVP(roots_); } +#endif /// @} diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index a50c4bec9..2ceb0577e 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -200,6 +200,7 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..2e75eceff 100644 --- a/gtsam/inference/Conditional.h +++ b/gtsam/inference/Conditional.h @@ -214,11 +214,13 @@ namespace gtsam { const FACTOR& asFactor() const { return static_cast(static_cast(*this)); } /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 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..af1e0858a 100644 --- a/gtsam/inference/Factor.h +++ b/gtsam/inference/Factor.h @@ -195,11 +195,13 @@ namespace gtsam { /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 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..2e3f5567f 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -434,11 +434,13 @@ class FactorGraph { 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_NVP(factors_); } +#endif /// @} }; // FactorGraph diff --git a/gtsam/inference/LabeledSymbol.h b/gtsam/inference/LabeledSymbol.h index 5aee4a0e2..2b61842ff 100644 --- a/gtsam/inference/LabeledSymbol.h +++ b/gtsam/inference/LabeledSymbol.h @@ -113,6 +113,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..7797a0a8e 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -257,11 +257,13 @@ private: const VariableIndex& variableIndex, std::vector& cmember); /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 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..3a61d9951 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -123,12 +123,14 @@ public: 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_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..bbb7e0443 100644 --- a/gtsam/inference/VariableIndex.h +++ b/gtsam/inference/VariableIndex.h @@ -191,6 +191,7 @@ protected: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..cdf5da241 100644 --- a/gtsam/linear/GaussianBayesNet.h +++ b/gtsam/linear/GaussianBayesNet.h @@ -257,11 +257,13 @@ 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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 1bc70d69a..62b47214b 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -275,12 +275,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_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..a4cb00f35 100644 --- a/gtsam/linear/GaussianFactor.h +++ b/gtsam/linear/GaussianFactor.h @@ -164,11 +164,13 @@ 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_BASE_OBJECT_NVP(Base); } +#endif }; // GaussianFactor diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index f8a24245d..f822640c3 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -404,11 +404,13 @@ 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_BASE_OBJECT_NVP(Base); } +#endif }; /** diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index 0d67030d7..a18e1b3c1 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -364,12 +364,14 @@ namespace gtsam { friend class NonlinearClusterTree; /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { 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..0ca99a070 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -414,6 +414,7 @@ namespace gtsam { template friend class ExpressionFactor; /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void save(ARCHIVE & ar, const unsigned int version) const { @@ -432,6 +433,7 @@ namespace gtsam { ar << BOOST_SERIALIZATION_NVP(model_); } } +#endif template void load(ARCHIVE & ar, const unsigned int version) { diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 04bb089ae..497fab1ef 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -129,11 +129,13 @@ class GTSAM_EXPORT Base { 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_NVP(reweight_); } +#endif }; /** "Null" robust loss function, equivalent to a Gaussian pdf noise model, or diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 863213ff2..4d0c84941 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -140,11 +140,13 @@ 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_NVP(dim_); } +#endif }; //--------------------------------------------------------------------------------------- diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 925fdef33..62fa76356 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -49,12 +49,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; diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 29cea3976..54afcd1e0 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -369,11 +369,13 @@ 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_NVP(values_); } +#endif }; // VectorValues definition /// traits diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index bf7ef56b0..f3262dd97 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -121,6 +121,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -128,6 +129,7 @@ private: ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(biasHat_); } +#endif }; class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN { diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index b412d4d26..1d12d8831 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -64,12 +64,14 @@ public: } /** 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("nZ_", nZ_); ar & boost::serialization::make_nvp("bRef_", bRef_); } +#endif }; /** diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index c7cf939af..af15bccb2 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -98,6 +98,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -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.h b/gtsam/navigation/CombinedImuFactor.h index 407bf9ace..5908989d1 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -102,6 +102,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -111,6 +112,7 @@ private: ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance); ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index dbc164d1a..76373a959 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -98,6 +98,7 @@ public: private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -107,6 +108,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(nT_); } +#endif }; /** diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 9e337028a..eb5205763 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -141,12 +141,14 @@ 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_NVP(biasAcc_); ar & BOOST_SERIALIZATION_NVP(biasGyro_); } +#endif public: diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 3134a8916..8431c31e9 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -147,6 +147,7 @@ public: private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -154,6 +155,7 @@ public: ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); } +#endif }; /** diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index 45adb2383..96ca15ba2 100644 --- a/gtsam/navigation/MagPoseFactor.h +++ b/gtsam/navigation/MagPoseFactor.h @@ -133,6 +133,7 @@ class MagPoseFactor: public NoiseModelFactorN { private: /// Serialization function. +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..7fb2b06ee 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -114,6 +114,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..84dbc4661 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -61,6 +61,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -75,6 +76,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis); } } +#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..8ca085fe7 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -174,6 +174,7 @@ class GTSAM_EXPORT PreintegrationBase { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..3d60eaf47 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -72,6 +72,7 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { protected: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..a756dd781 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -128,6 +128,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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/nonlinear/CustomFactor.h b/gtsam/nonlinear/CustomFactor.h index 60dbcdaf2..b6837473a 100644 --- a/gtsam/nonlinear/CustomFactor.h +++ b/gtsam/nonlinear/CustomFactor.h @@ -91,12 +91,14 @@ public: 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("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..7047a84f2 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -120,6 +120,7 @@ class FunctorizedFactor : public NoiseModelFactorN { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { @@ -129,6 +130,7 @@ class FunctorizedFactor : 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..d13cfbbef 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -341,6 +341,7 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..915ae8ce1 100644 --- a/gtsam/nonlinear/ISAM2Clique.h +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -148,6 +148,7 @@ class GTSAM_EXPORT ISAM2Clique VectorValues* delta) const; /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -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..0065368e2 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -164,6 +164,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..40d58298c 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -183,6 +183,7 @@ public: private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -194,6 +195,7 @@ private: ar & BOOST_SERIALIZATION_NVP(allow_error_); ar & BOOST_SERIALIZATION_NVP(error_gain_); } +#endif }; // \class NonlinearEquality diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 73255482c..83841bdc7 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -304,6 +304,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -311,6 +312,7 @@ public: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(noiseModel_); } +#endif }; // \class NoiseModelFactor diff --git a/gtsam/nonlinear/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index 95b116ab6..2d533ca46 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -254,12 +254,14 @@ namespace gtsam { const Values& values, const Scatter& scatter, const Dampen& dampen = nullptr) const; /** 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("NonlinearFactorGraph", boost::serialization::base_object(*this)); } +#endif }; /// traits diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 808f66c5b..f5bca7e0d 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -106,6 +106,7 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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 7c08dc338..88dfe1b97 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -350,11 +350,13 @@ namespace gtsam { } /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_NVP(values_); } +#endif static ConstKeyValuePair make_const_deref_pair(const KeyValueMap::const_iterator::value_type& key_value) { return ConstKeyValuePair(key_value.first, *key_value.second); } 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..9c97fb384 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 diff --git a/gtsam/sfm/SfmData.h b/gtsam/sfm/SfmData.h index dbf0bd1e7..3aca3e3b4 100644 --- a/gtsam/sfm/SfmData.h +++ b/gtsam/sfm/SfmData.h @@ -126,12 +126,15 @@ struct GTSAM_EXPORT SfmData { /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; 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..27a5164b0 100644 --- a/gtsam/sfm/SfmTrack.h +++ b/gtsam/sfm/SfmTrack.h @@ -162,6 +162,7 @@ struct GTSAM_EXPORT SfmTrack : SfmTrack2d { /// @{ /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -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..da77509ca 100644 --- a/gtsam/slam/AntiFactor.h +++ b/gtsam/slam/AntiFactor.h @@ -107,6 +107,7 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..b3bd80a7e 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -136,6 +136,7 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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 }; diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 14aa96dbc..aeda10c22 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -84,6 +84,7 @@ struct BoundingConstraint1: public NoiseModelFactorN { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -93,6 +94,7 @@ private: ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); } +#endif }; /** diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index c533ea04d..6d4833178 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -92,6 +92,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..b408f9bb6 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -182,6 +182,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { @@ -190,6 +191,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..ac21d7cf3 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -92,6 +92,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..6e57952d0 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -91,6 +91,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..2f1b59076 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -189,6 +189,7 @@ namespace gtsam { private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -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..837719cea 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -123,12 +123,14 @@ public: 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("NonlinearFactor3", boost::serialization::base_object(*this)); } +#endif }; /// traits diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index a5fc3be1a..560bf41dd 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -444,6 +444,7 @@ protected: private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION/// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -452,6 +453,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..d8eaf238f 100644 --- a/gtsam/slam/SmartFactorParams.h +++ b/gtsam/slam/SmartFactorParams.h @@ -119,6 +119,7 @@ struct SmartProjectionParams { private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { @@ -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..8091198a7 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -467,6 +467,7 @@ protected: private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { @@ -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..3745b7d8e 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -149,12 +149,14 @@ public: 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_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..70bafba65 100644 --- a/gtsam/slam/SmartProjectionRigFactor.h +++ b/gtsam/slam/SmartProjectionRigFactor.h @@ -353,6 +353,7 @@ class SmartProjectionRigFactor : public SmartProjectionFactor { private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { @@ -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..f9955ff1a 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -171,6 +171,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { @@ -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..38d1abcfb 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -190,6 +190,7 @@ public: private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -199,6 +200,7 @@ private: ar & BOOST_SERIALIZATION_NVP(throwCheirality_); ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); } +#endif }; } // \ namespace gtsam diff --git a/gtsam/symbolic/SymbolicBayesNet.h b/gtsam/symbolic/SymbolicBayesNet.h index 31b1bac33..a1c4c3d72 100644 --- a/gtsam/symbolic/SymbolicBayesNet.h +++ b/gtsam/symbolic/SymbolicBayesNet.h @@ -105,11 +105,13 @@ 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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits diff --git a/gtsam/symbolic/SymbolicBayesTree.h b/gtsam/symbolic/SymbolicBayesTree.h index 0a6b6608e..a30af3d68 100644 --- a/gtsam/symbolic/SymbolicBayesTree.h +++ b/gtsam/symbolic/SymbolicBayesTree.h @@ -64,11 +64,13 @@ 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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits diff --git a/gtsam/symbolic/SymbolicConditional.h b/gtsam/symbolic/SymbolicConditional.h index 1411ceafe..06f6121bc 100644 --- a/gtsam/symbolic/SymbolicConditional.h +++ b/gtsam/symbolic/SymbolicConditional.h @@ -127,12 +127,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_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..9ea8d4ed1 100644 --- a/gtsam/symbolic/SymbolicFactor.h +++ b/gtsam/symbolic/SymbolicFactor.h @@ -154,11 +154,13 @@ 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_BASE_OBJECT_NVP(Base); } +#endif }; // IndexFactor // Forward declarations diff --git a/gtsam/symbolic/SymbolicFactorGraph.h b/gtsam/symbolic/SymbolicFactorGraph.h index bb37b4436..ef719609d 100644 --- a/gtsam/symbolic/SymbolicFactorGraph.h +++ b/gtsam/symbolic/SymbolicFactorGraph.h @@ -149,11 +149,13 @@ 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_BASE_OBJECT_NVP(Base); } +#endif }; /// traits From a5b6968cbf7f690a30c07b918ff3d2cfaff7d1c9 Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Wed, 18 Jan 2023 11:53:38 -0800 Subject: [PATCH 2/9] serialization function comment moved --- CMakeLists.txt | 8 ++++++++ gtsam/base/ConcurrentMap.h | 2 +- gtsam/base/FastList.h | 2 +- gtsam/base/FastMap.h | 2 +- gtsam/base/FastSet.h | 2 +- gtsam/base/GenericValue.h | 2 +- gtsam/base/SymmetricBlockMatrix.h | 2 +- gtsam/base/VerticalBlockMatrix.h | 2 +- gtsam/discrete/DecisionTree-inl.h | 2 +- gtsam/discrete/DecisionTree.h | 2 +- gtsam/discrete/DecisionTreeFactor.h | 2 +- gtsam/discrete/DiscreteBayesNet.h | 2 +- gtsam/discrete/DiscreteConditional.h | 2 +- gtsam/discrete/DiscreteKey.h | 2 +- gtsam/discrete/DiscreteLookupDAG.h | 2 +- gtsam/geometry/BearingRange.h | 2 +- gtsam/geometry/Cal3.h | 2 +- gtsam/geometry/Cal3DS2.h | 2 +- gtsam/geometry/Cal3DS2_Base.h | 2 +- gtsam/geometry/Cal3Fisheye.h | 2 +- gtsam/geometry/Cal3Unified.h | 2 +- gtsam/geometry/Cal3_S2.h | 2 +- gtsam/geometry/Cal3_S2Stereo.h | 2 +- gtsam/geometry/CalibratedCamera.h | 2 +- gtsam/geometry/CameraSet.h | 2 +- gtsam/geometry/EssentialMatrix.h | 2 +- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 2 +- gtsam/geometry/PinholeSet.h | 2 +- gtsam/geometry/Pose2.h | 2 +- gtsam/geometry/Pose3.h | 2 +- gtsam/geometry/Rot2.h | 2 +- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/SO3.h | 2 +- gtsam/geometry/SO4.h | 2 +- gtsam/geometry/SOn.h | 2 +- gtsam/geometry/SphericalCamera.h | 2 +- gtsam/geometry/StereoPoint2.h | 2 +- gtsam/geometry/Unit3.h | 2 +- gtsam/geometry/triangulation.h | 2 +- gtsam/hybrid/GaussianMixture.h | 2 +- gtsam/hybrid/HybridBayesNet.h | 2 +- gtsam/hybrid/HybridBayesTree.h | 2 +- gtsam/hybrid/HybridConditional.h | 2 +- gtsam/hybrid/HybridFactor.h | 2 +- gtsam/inference/BayesTree.h | 2 +- gtsam/inference/BayesTreeCliqueBase.h | 2 +- gtsam/inference/Conditional.h | 2 +- gtsam/inference/Factor.h | 4 +--- gtsam/inference/FactorGraph.h | 2 +- gtsam/inference/LabeledSymbol.h | 2 +- gtsam/inference/Ordering.h | 2 +- gtsam/inference/Symbol.h | 2 +- gtsam/inference/VariableIndex.h | 2 +- gtsam/linear/GaussianBayesNet.h | 2 +- gtsam/linear/GaussianConditional.h | 2 +- gtsam/linear/GaussianFactor.h | 2 +- gtsam/linear/GaussianFactorGraph.h | 2 +- gtsam/linear/HessianFactor.h | 2 +- gtsam/linear/JacobianFactor.h | 2 +- gtsam/linear/LossFunctions.h | 2 +- gtsam/linear/NoiseModel.h | 2 +- gtsam/linear/VectorValues.h | 2 +- gtsam/navigation/AHRSFactor.h | 2 +- gtsam/navigation/AttitudeFactor.h | 2 +- gtsam/navigation/BarometricFactor.h | 2 +- gtsam/navigation/CombinedImuFactor.h | 2 +- gtsam/navigation/GPSFactor.h | 2 +- gtsam/navigation/ImuBias.h | 2 +- gtsam/navigation/ImuFactor.h | 2 +- gtsam/navigation/MagPoseFactor.h | 2 +- gtsam/navigation/ManifoldPreintegration.h | 2 +- gtsam/navigation/PreintegratedRotation.h | 2 +- gtsam/navigation/PreintegrationBase.h | 2 +- gtsam/navigation/PreintegrationParams.h | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- gtsam/nonlinear/CustomFactor.h | 2 +- gtsam/nonlinear/FunctorizedFactor.h | 2 +- gtsam/nonlinear/ISAM2.h | 2 +- gtsam/nonlinear/ISAM2Clique.h | 2 +- gtsam/nonlinear/LinearContainerFactor.h | 2 +- gtsam/nonlinear/NonlinearEquality.h | 2 +- gtsam/nonlinear/NonlinearFactor.h | 2 +- gtsam/nonlinear/NonlinearFactorGraph.h | 2 +- gtsam/nonlinear/PriorFactor.h | 2 +- gtsam/nonlinear/Values.h | 2 +- gtsam/sam/RangeFactor.h | 2 +- gtsam/sfm/SfmData.h | 2 +- gtsam/sfm/SfmTrack.h | 2 +- gtsam/slam/AntiFactor.h | 2 +- gtsam/slam/BetweenFactor.h | 2 +- gtsam/slam/BoundingConstraint.h | 2 +- gtsam/slam/EssentialMatrixConstraint.h | 2 +- gtsam/slam/GeneralSFMFactor.h | 2 +- gtsam/slam/PoseRotationPrior.h | 2 +- gtsam/slam/PoseTranslationPrior.h | 2 +- gtsam/slam/ProjectionFactor.h | 2 +- gtsam/slam/ReferenceFrameFactor.h | 2 +- gtsam/slam/SmartFactorBase.h | 2 +- gtsam/slam/SmartFactorParams.h | 2 +- gtsam/slam/SmartProjectionFactor.h | 2 +- gtsam/slam/SmartProjectionPoseFactor.h | 2 +- gtsam/slam/SmartProjectionRigFactor.h | 2 +- gtsam/slam/StereoFactor.h | 2 +- gtsam/slam/TriangulationFactor.h | 2 +- gtsam/symbolic/SymbolicBayesNet.h | 2 +- gtsam/symbolic/SymbolicBayesTree.h | 2 +- gtsam/symbolic/SymbolicConditional.h | 2 +- gtsam/symbolic/SymbolicFactor.h | 2 +- gtsam/symbolic/SymbolicFactorGraph.h | 2 +- 110 files changed, 117 insertions(+), 111 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 52b34101f..eb79600e1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -48,6 +48,14 @@ if(${GTSAM_SOURCE_DIR} STREQUAL ${GTSAM_BINARY_DIR}) message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ") endif() +# TODO(kartikarcot): Determine a proper home for this option +# a flag to enable or disable serialization with GTSAM_ENABLE_BOOST_SERIALIZATION +option(GTSAM_ENABLE_BOOST_SERIALIZATION "Enable Boost serialization" ON) +# set a compiler flag to enable or disable serialization with GTSAM_DISABLE_BOOST_SERIALIZATION +if(GTSAM_ENABLE_BOOST_SERIALIZATION) + add_definitions(-DGTSAM_ENABLE_BOOST_SERIALIZATION) +endif() + include(cmake/HandleGeneralOptions.cmake) # CMake build options # Libraries: diff --git a/gtsam/base/ConcurrentMap.h b/gtsam/base/ConcurrentMap.h index 196636c4e..5d35cacec 100644 --- a/gtsam/base/ConcurrentMap.h +++ b/gtsam/base/ConcurrentMap.h @@ -100,8 +100,8 @@ public: #endif private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void save(Archive& ar, const unsigned int /*version*/) const diff --git a/gtsam/base/FastList.h b/gtsam/base/FastList.h index d6549ce2e..f7fd38986 100644 --- a/gtsam/base/FastList.h +++ b/gtsam/base/FastList.h @@ -76,8 +76,8 @@ public: } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index 4aadb6577..3b764c34c 100644 --- a/gtsam/base/FastMap.h +++ b/gtsam/base/FastMap.h @@ -67,8 +67,8 @@ public: bool exists(const KEY& e) const { return this->find(e) != this->end(); } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index b1c95ad84..f60e69a23 100644 --- a/gtsam/base/FastSet.h +++ b/gtsam/base/FastSet.h @@ -121,8 +121,8 @@ public: } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 537cf3a54..bbf0f57ad 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -175,8 +175,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/base/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index f245db163..ccf726853 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -398,8 +398,8 @@ namespace gtsam { template friend class SymmetricBlockMatrixBlockExpr; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/base/VerticalBlockMatrix.h b/gtsam/base/VerticalBlockMatrix.h index 459d2902c..777441300 100644 --- a/gtsam/base/VerticalBlockMatrix.h +++ b/gtsam/base/VerticalBlockMatrix.h @@ -219,8 +219,8 @@ namespace gtsam { friend class SymmetricBlockMatrix; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index eb50197a6..4d68bc525 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -154,8 +154,8 @@ namespace gtsam { private: using Base = DecisionTree::Node; - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index f4b64f36f..4d70c3d93 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -117,8 +117,8 @@ namespace gtsam { virtual bool isLeaf() const = 0; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) {} diff --git a/gtsam/discrete/DecisionTreeFactor.h b/gtsam/discrete/DecisionTreeFactor.h index 61a14e13f..74899b729 100644 --- a/gtsam/discrete/DecisionTreeFactor.h +++ b/gtsam/discrete/DecisionTreeFactor.h @@ -253,8 +253,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/discrete/DiscreteBayesNet.h b/gtsam/discrete/DiscreteBayesNet.h index 226550b13..9005f975f 100644 --- a/gtsam/discrete/DiscreteBayesNet.h +++ b/gtsam/discrete/DiscreteBayesNet.h @@ -150,8 +150,8 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 8af7cbcf2..183cf8561 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -268,8 +268,8 @@ class GTSAM_EXPORT DiscreteConditional bool forceComplete) const; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/discrete/DiscreteKey.h b/gtsam/discrete/DiscreteKey.h index 6f1768e17..c224b74db 100644 --- a/gtsam/discrete/DiscreteKey.h +++ b/gtsam/discrete/DiscreteKey.h @@ -79,8 +79,8 @@ namespace gtsam { /// Check equality to another DiscreteKeys object. bool equals(const DiscreteKeys& other, double tol = 0) const; - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/discrete/DiscreteLookupDAG.h b/gtsam/discrete/DiscreteLookupDAG.h index 8d72d221d..d3fd65ebe 100644 --- a/gtsam/discrete/DiscreteLookupDAG.h +++ b/gtsam/discrete/DiscreteLookupDAG.h @@ -126,8 +126,8 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index 0175af5b0..0c7d4a577 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -147,8 +147,8 @@ public: /// @{ private: - /// Serialization function template + /// Serialization function void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp("bearing", bearing_); ar& boost::serialization::make_nvp("range", range_); diff --git a/gtsam/geometry/Cal3.h b/gtsam/geometry/Cal3.h index 3c5989b9f..1b66eb336 100644 --- a/gtsam/geometry/Cal3.h +++ b/gtsam/geometry/Cal3.h @@ -184,8 +184,8 @@ class GTSAM_EXPORT Cal3 { /// @{ private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index e989e661c..a7ca08afc 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -104,8 +104,8 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h index 539813cb0..b0ef0368b 100644 --- a/gtsam/geometry/Cal3DS2_Base.h +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -156,8 +156,8 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 { /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Cal3Fisheye.h b/gtsam/geometry/Cal3Fisheye.h index 775c6b46e..3f1cac148 100644 --- a/gtsam/geometry/Cal3Fisheye.h +++ b/gtsam/geometry/Cal3Fisheye.h @@ -184,8 +184,8 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 { /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index 74ad72fb2..309b6dca1 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -138,8 +138,8 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index 1b39e76e3..885be614f 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -132,8 +132,8 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 { /// @{ private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index fcc6b68ee..4fee1a022 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -143,8 +143,8 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 { /// @{ private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 0aef92352..c2683596e 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -228,8 +228,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index f5b887ae9..1db86cfde 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -465,8 +465,8 @@ class CameraSet : public std::vector> { } private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index 7b8268d4d..d514c4f19 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -180,8 +180,8 @@ class EssentialMatrix { /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index a77f5f220..23b595c84 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -326,8 +326,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 490ef63a9..96c691242 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -217,8 +217,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h index 15d0ce473..55269f9d6 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -64,8 +64,8 @@ public: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index d92ce91d8..e3ff1416c 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -326,8 +326,8 @@ public: private: - // Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION // + // Serialization function friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 42b9a8e57..3f0d3e0e0 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -392,8 +392,8 @@ public: friend std::ostream &operator<<(std::ostream &os, const Pose3& p); private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 91c6d5d53..63b914434 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -213,8 +213,8 @@ namespace gtsam { static Rot2 ClosestTo(const Matrix2& M); private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index fd110fe85..0b3798baa 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -528,8 +528,8 @@ class GTSAM_EXPORT Rot3 : public LieGroup { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 6f78bed4e..421619d19 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -99,8 +99,8 @@ template <> GTSAM_EXPORT Vector9 SO3::vec(OptionalJacobian<9, 3> H) const; -/** Serialization function */ 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)); diff --git a/gtsam/geometry/SO4.h b/gtsam/geometry/SO4.h index 529935006..f1c6815cc 100644 --- a/gtsam/geometry/SO4.h +++ b/gtsam/geometry/SO4.h @@ -78,8 +78,8 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = {}); */ GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {}); -/** Serialization function */ 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)); diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 069aae833..7a0babbcb 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -377,8 +377,8 @@ template <> GTSAM_EXPORT typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const; -/** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +/** Serialization function */ template void serialize( Archive& ar, SOn& Q, diff --git a/gtsam/geometry/SphericalCamera.h b/gtsam/geometry/SphericalCamera.h index 76c0d86a1..6c17c5962 100644 --- a/gtsam/geometry/SphericalCamera.h +++ b/gtsam/geometry/SphericalCamera.h @@ -52,8 +52,8 @@ class GTSAM_EXPORT EmptyCal { } private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index ae59c2b9d..a12957f17 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -146,8 +146,8 @@ private: /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index db4f94085..82a85b081 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -206,8 +206,8 @@ private: /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 5ba324b4f..f71ad76da 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -611,8 +611,8 @@ struct GTSAM_EXPORT TriangulationParameters { private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { diff --git a/gtsam/hybrid/GaussianMixture.h b/gtsam/hybrid/GaussianMixture.h index cd65c0829..2d715c6e3 100644 --- a/gtsam/hybrid/GaussianMixture.h +++ b/gtsam/hybrid/GaussianMixture.h @@ -255,8 +255,8 @@ class GTSAM_EXPORT GaussianMixture /// Check whether `given` has values for all frontal keys. bool allFrontalsGiven(const VectorValues &given) const; - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive &ar, const unsigned int /*version*/) { diff --git a/gtsam/hybrid/HybridBayesNet.h b/gtsam/hybrid/HybridBayesNet.h index 1233ccec9..2b0042b8d 100644 --- a/gtsam/hybrid/HybridBayesNet.h +++ b/gtsam/hybrid/HybridBayesNet.h @@ -228,8 +228,8 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet { */ void updateDiscreteConditionals(const DecisionTreeFactor &prunedDecisionTree); - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { diff --git a/gtsam/hybrid/HybridBayesTree.h b/gtsam/hybrid/HybridBayesTree.h index 66211d8a0..e0e6db98e 100644 --- a/gtsam/hybrid/HybridBayesTree.h +++ b/gtsam/hybrid/HybridBayesTree.h @@ -114,8 +114,8 @@ class GTSAM_EXPORT HybridBayesTree : public BayesTree { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/hybrid/HybridConditional.h b/gtsam/hybrid/HybridConditional.h index 80efd89c6..64bdcb2c1 100644 --- a/gtsam/hybrid/HybridConditional.h +++ b/gtsam/hybrid/HybridConditional.h @@ -204,8 +204,8 @@ class GTSAM_EXPORT HybridConditional /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index 9e243c4ec..8fa23b1f9 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -137,8 +137,8 @@ class GTSAM_EXPORT HybridFactor : public Factor { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index b09e90223..85bc710b1 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -259,8 +259,8 @@ namespace gtsam { template friend class EliminatableClusterTree; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index 2ceb0577e..976d1a7f2 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -199,8 +199,8 @@ namespace gtsam { private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/Conditional.h b/gtsam/inference/Conditional.h index 2e75eceff..9f08e5623 100644 --- a/gtsam/inference/Conditional.h +++ b/gtsam/inference/Conditional.h @@ -213,8 +213,8 @@ 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)); } - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/Factor.h b/gtsam/inference/Factor.h index af1e0858a..3b8cc94bf 100644 --- a/gtsam/inference/Factor.h +++ b/gtsam/inference/Factor.h @@ -190,12 +190,10 @@ namespace gtsam { /// @} private: - +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// @name Serialization /// @{ - /** Serialization function */ -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 2e3f5567f..43664ac7c 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -433,8 +433,8 @@ class FactorGraph { inline bool exists(size_t idx) const { return idx < size() && at(idx); } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/LabeledSymbol.h b/gtsam/inference/LabeledSymbol.h index 2b61842ff..5a7a98c1d 100644 --- a/gtsam/inference/LabeledSymbol.h +++ b/gtsam/inference/LabeledSymbol.h @@ -112,8 +112,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 7797a0a8e..ad41aa5bb 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -256,8 +256,8 @@ private: static GTSAM_EXPORT Ordering ColamdConstrained( const VariableIndex& variableIndex, std::vector& cmember); - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 3a61d9951..3238a1949 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -122,8 +122,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/inference/VariableIndex.h b/gtsam/inference/VariableIndex.h index bbb7e0443..207ded0ce 100644 --- a/gtsam/inference/VariableIndex.h +++ b/gtsam/inference/VariableIndex.h @@ -190,8 +190,8 @@ protected: } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/GaussianBayesNet.h b/gtsam/linear/GaussianBayesNet.h index cdf5da241..39528b810 100644 --- a/gtsam/linear/GaussianBayesNet.h +++ b/gtsam/linear/GaussianBayesNet.h @@ -256,8 +256,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 62b47214b..f99006831 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -274,8 +274,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/GaussianFactor.h b/gtsam/linear/GaussianFactor.h index a4cb00f35..3304829e2 100644 --- a/gtsam/linear/GaussianFactor.h +++ b/gtsam/linear/GaussianFactor.h @@ -163,8 +163,8 @@ namespace gtsam { } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index f822640c3..d517de77b 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -403,8 +403,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index a18e1b3c1..eb1fe2de2 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -363,8 +363,8 @@ namespace gtsam { friend class NonlinearFactorGraph; friend class NonlinearClusterTree; - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index 0ca99a070..acfeb45a3 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -413,8 +413,8 @@ namespace gtsam { // be very selective on who can access these private methods: template friend class ExpressionFactor; - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void save(ARCHIVE & ar, const unsigned int version) const { diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 497fab1ef..d91843206 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -128,8 +128,8 @@ class GTSAM_EXPORT Base { void reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 4d0c84941..821d57b01 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -139,8 +139,8 @@ namespace gtsam { virtual double weight(const Vector& v) const { return 1.0; } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 54afcd1e0..bb5bbc794 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -368,8 +368,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index f3262dd97..d163394bf 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -120,8 +120,8 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 1d12d8831..dfd8b3287 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -63,8 +63,8 @@ public: return bRef_; } - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index af15bccb2..cf1c147bf 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -97,8 +97,8 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { }; private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 5908989d1..25b72034c 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -101,8 +101,8 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index 76373a959..518a11358 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -97,8 +97,8 @@ public: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index eb5205763..818540aae 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -140,8 +140,8 @@ private: /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 8431c31e9..2c2ca5f80 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -146,8 +146,8 @@ public: #endif private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/MagPoseFactor.h b/gtsam/navigation/MagPoseFactor.h index 96ca15ba2..ba9a08d78 100644 --- a/gtsam/navigation/MagPoseFactor.h +++ b/gtsam/navigation/MagPoseFactor.h @@ -132,8 +132,8 @@ class MagPoseFactor: public NoiseModelFactorN { } private: - /// Serialization function. #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function. friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 7fb2b06ee..a8c97477b 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -113,8 +113,8 @@ public: /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 84dbc4661..c4b2caa9b 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -60,8 +60,8 @@ struct GTSAM_EXPORT PreintegratedRotationParams { std::optional getBodyPSensor() const { return body_P_sensor; } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 8ca085fe7..e4a790b9d 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -173,8 +173,8 @@ class GTSAM_EXPORT PreintegrationBase { OptionalJacobian<9, 6> H5 = {}) const; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 3d60eaf47..4350c7ebd 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -71,8 +71,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { protected: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index a756dd781..e16ad9310 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -127,8 +127,8 @@ public: /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/CustomFactor.h b/gtsam/nonlinear/CustomFactor.h index b6837473a..d486e6f0d 100644 --- a/gtsam/nonlinear/CustomFactor.h +++ b/gtsam/nonlinear/CustomFactor.h @@ -90,8 +90,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 7047a84f2..7c4a0097c 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -119,8 +119,8 @@ class FunctorizedFactor : public NoiseModelFactorN { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index d13cfbbef..50c5058c2 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -340,8 +340,8 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { void updateDelta(bool forceFullSolve = false) const; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/ISAM2Clique.h b/gtsam/nonlinear/ISAM2Clique.h index 915ae8ce1..08b74ef26 100644 --- a/gtsam/nonlinear/ISAM2Clique.h +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -147,8 +147,8 @@ class GTSAM_EXPORT ISAM2Clique void restoreFromOriginals(const Vector& originalValues, VectorValues* delta) const; - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index 0065368e2..dfbf221c3 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -163,8 +163,8 @@ public: void initializeLinearizationPoint(const Values& linearizationPoint); private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 40d58298c..ddf275f38 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -182,8 +182,8 @@ public: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 83841bdc7..6a1222c5d 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -303,8 +303,8 @@ public: shared_ptr cloneWithNewNoiseModel(const SharedNoiseModel newNoise) const; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index 2d533ca46..92bfdaf20 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -253,8 +253,8 @@ namespace gtsam { std::shared_ptr linearizeToHessianFactor( const Values& values, const Scatter& scatter, const Dampen& dampen = nullptr) const; - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index f5bca7e0d..ab2a66a77 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -105,8 +105,8 @@ namespace gtsam { private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 88dfe1b97..d5b6348cc 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -349,8 +349,8 @@ namespace gtsam { return filter(key_value.key) && (dynamic_cast*>(&key_value.value)); } - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index 9c97fb384..bfc766857 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -164,8 +164,8 @@ class RangeFactorWithTransform : public ExpressionFactorN { } private: - /** Serialization function */ 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, diff --git a/gtsam/sfm/SfmData.h b/gtsam/sfm/SfmData.h index 3aca3e3b4..7161ab2f9 100644 --- a/gtsam/sfm/SfmData.h +++ b/gtsam/sfm/SfmData.h @@ -125,9 +125,9 @@ 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); diff --git a/gtsam/sfm/SfmTrack.h b/gtsam/sfm/SfmTrack.h index 27a5164b0..6ef1f9512 100644 --- a/gtsam/sfm/SfmTrack.h +++ b/gtsam/sfm/SfmTrack.h @@ -161,8 +161,8 @@ struct GTSAM_EXPORT SfmTrack : SfmTrack2d { /// @name Serialization /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/AntiFactor.h b/gtsam/slam/AntiFactor.h index da77509ca..3b031b334 100644 --- a/gtsam/slam/AntiFactor.h +++ b/gtsam/slam/AntiFactor.h @@ -106,8 +106,8 @@ namespace gtsam { private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index b3bd80a7e..7be202194 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -135,8 +135,8 @@ namespace gtsam { private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index aeda10c22..405c0d4a6 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -83,8 +83,8 @@ struct BoundingConstraint1: public NoiseModelFactorN { private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 6d4833178..45e54aa5d 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -91,8 +91,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index b408f9bb6..e2b07f62e 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -181,8 +181,8 @@ public: } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index ac21d7cf3..8ce90988b 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -91,8 +91,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index 6e57952d0..c5257f45c 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -90,8 +90,8 @@ public: private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 2f1b59076..f40d8f5bb 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -188,8 +188,8 @@ namespace gtsam { private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index 837719cea..0ae6ea88a 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -122,8 +122,8 @@ public: Key local_key() const { return this->key3(); } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 560bf41dd..cda34119a 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -443,8 +443,8 @@ protected: private: -/// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION/// +/// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/SmartFactorParams.h b/gtsam/slam/SmartFactorParams.h index d8eaf238f..4523d0e0e 100644 --- a/gtsam/slam/SmartFactorParams.h +++ b/gtsam/slam/SmartFactorParams.h @@ -118,8 +118,8 @@ struct SmartProjectionParams { private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 8091198a7..c54efecc4 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -466,8 +466,8 @@ protected: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 3745b7d8e..b88c1c628 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -148,8 +148,8 @@ public: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/SmartProjectionRigFactor.h b/gtsam/slam/SmartProjectionRigFactor.h index 70bafba65..0aa070ed0 100644 --- a/gtsam/slam/SmartProjectionRigFactor.h +++ b/gtsam/slam/SmartProjectionRigFactor.h @@ -352,8 +352,8 @@ class SmartProjectionRigFactor : public SmartProjectionFactor { } private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index f9955ff1a..a2d428d11 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -170,8 +170,8 @@ public: inline bool throwCheirality() const { return throwCheirality_; } private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 38d1abcfb..6feaa7041 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -189,8 +189,8 @@ public: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/symbolic/SymbolicBayesNet.h b/gtsam/symbolic/SymbolicBayesNet.h index a1c4c3d72..f2c142762 100644 --- a/gtsam/symbolic/SymbolicBayesNet.h +++ b/gtsam/symbolic/SymbolicBayesNet.h @@ -104,8 +104,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/symbolic/SymbolicBayesTree.h b/gtsam/symbolic/SymbolicBayesTree.h index a30af3d68..4d5804b27 100644 --- a/gtsam/symbolic/SymbolicBayesTree.h +++ b/gtsam/symbolic/SymbolicBayesTree.h @@ -63,8 +63,8 @@ namespace gtsam { bool equals(const This& other, double tol = 1e-9) const; private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/symbolic/SymbolicConditional.h b/gtsam/symbolic/SymbolicConditional.h index 06f6121bc..5cc4e9cfc 100644 --- a/gtsam/symbolic/SymbolicConditional.h +++ b/gtsam/symbolic/SymbolicConditional.h @@ -126,8 +126,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int /*version*/) { diff --git a/gtsam/symbolic/SymbolicFactor.h b/gtsam/symbolic/SymbolicFactor.h index 9ea8d4ed1..0e9eb3d46 100644 --- a/gtsam/symbolic/SymbolicFactor.h +++ b/gtsam/symbolic/SymbolicFactor.h @@ -153,8 +153,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { diff --git a/gtsam/symbolic/SymbolicFactorGraph.h b/gtsam/symbolic/SymbolicFactorGraph.h index ef719609d..01b532a5c 100644 --- a/gtsam/symbolic/SymbolicFactorGraph.h +++ b/gtsam/symbolic/SymbolicFactorGraph.h @@ -148,8 +148,8 @@ namespace gtsam { /// @} private: - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { From 3250cf49ca78b31641017e3db0df8c737c1e105a Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Wed, 18 Jan 2023 12:03:30 -0800 Subject: [PATCH 3/9] gtsam_unstable, test folders ifdefs --- gtsam_unstable/dynamics/PoseRTV.h | 2 ++ gtsam_unstable/dynamics/VelocityConstraint3.h | 2 ++ gtsam_unstable/geometry/BearingS2.h | 2 ++ gtsam_unstable/geometry/InvDepthCamera3.h | 4 +++- gtsam_unstable/geometry/Pose3Upright.h | 2 ++ gtsam_unstable/nonlinear/LinearizedFactor.h | 4 +++- gtsam_unstable/slam/BetweenFactorEM.h | 2 ++ gtsam_unstable/slam/BiasedGPSFactor.h | 2 ++ gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h | 2 ++ gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h | 2 ++ gtsam_unstable/slam/GaussMarkov1stOrderFactor.h | 2 ++ gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h | 2 ++ gtsam_unstable/slam/InvDepthFactor3.h | 2 ++ gtsam_unstable/slam/InvDepthFactorVariant1.h | 2 ++ gtsam_unstable/slam/InvDepthFactorVariant2.h | 2 ++ gtsam_unstable/slam/InvDepthFactorVariant3.h | 4 +++- gtsam_unstable/slam/MultiProjectionFactor.h | 2 ++ gtsam_unstable/slam/PartialPriorFactor.h | 2 ++ gtsam_unstable/slam/PoseBetweenFactor.h | 2 ++ gtsam_unstable/slam/PosePriorFactor.h | 2 ++ gtsam_unstable/slam/PoseToPointFactor.h | 2 ++ gtsam_unstable/slam/ProjectionFactorPPP.h | 2 ++ gtsam_unstable/slam/ProjectionFactorPPPC.h | 2 ++ gtsam_unstable/slam/ProjectionFactorRollingShutter.h | 2 ++ gtsam_unstable/slam/RelativeElevationFactor.h | 2 ++ gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h | 2 ++ gtsam_unstable/slam/SmartStereoProjectionFactor.h | 2 ++ gtsam_unstable/slam/SmartStereoProjectionFactorPP.h | 2 ++ gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h | 2 ++ gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h | 2 ++ gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h | 2 ++ tests/simulated2D.h | 2 ++ tests/testExpressionFactor.cpp | 2 ++ 33 files changed, 69 insertions(+), 3 deletions(-) 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..f050676e5 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,8 +148,8 @@ public: Vector error_vector(const Values& c) const; private: - /** Serialization function */ friend class boost::serialization::access; + /** Serialization function */ template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & boost::serialization::make_nvp("LinearizedJacobianFactor", 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..fb4588955 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -140,6 +140,7 @@ public: private: /// Serialization function +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -147,6 +148,7 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; /** @@ -269,8 +271,8 @@ public: private: - /// Serialization function friend class boost::serialization::access; + /// Serialization function template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); 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..f00b35617 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 }; /** 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) { From ded460035383e7915ff95d328e203856cef7beaa Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Wed, 18 Jan 2023 13:04:28 -0800 Subject: [PATCH 4/9] removed boost serialization headers --- gtsam/base/ConcurrentMap.h | 2 ++ gtsam/base/FastList.h | 3 ++- gtsam/base/FastMap.h | 2 ++ gtsam/base/FastSet.h | 2 ++ gtsam/base/SymmetricBlockMatrix.h | 2 ++ gtsam/base/Value.h | 2 ++ gtsam/discrete/DecisionTree.h | 2 ++ gtsam/discrete/DiscreteKey.h | 2 ++ gtsam/geometry/BearingRange.h | 8 +++++--- gtsam/geometry/CalibratedCamera.h | 2 ++ gtsam/geometry/Point2.h | 2 ++ gtsam/geometry/Point3.h | 2 ++ gtsam/geometry/SOn.h | 2 ++ gtsam/geometry/SphericalCamera.h | 2 ++ gtsam/geometry/StereoPoint2.h | 2 ++ gtsam/inference/Factor.h | 2 ++ gtsam/inference/FactorGraph.h | 2 ++ gtsam/inference/Symbol.h | 2 ++ gtsam/linear/JacobianFactor.h | 2 ++ gtsam/linear/LossFunctions.h | 2 ++ gtsam/linear/NoiseModel.h | 2 ++ gtsam/linear/SubgraphBuilder.cpp | 2 ++ gtsam/linear/SubgraphBuilder.h | 2 ++ gtsam/navigation/CombinedImuFactor.cpp | 2 ++ gtsam/navigation/ImuBias.h | 2 ++ gtsam/nonlinear/NonlinearFactor.h | 2 ++ gtsam/slam/GeneralSFMFactor.h | 2 ++ gtsam/slam/SmartFactorBase.h | 2 ++ 28 files changed, 59 insertions(+), 4 deletions(-) diff --git a/gtsam/base/ConcurrentMap.h b/gtsam/base/ConcurrentMap.h index 5d35cacec..e88f6eed9 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 diff --git a/gtsam/base/FastList.h b/gtsam/base/FastList.h index f7fd38986..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 { diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index 3b764c34c..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 { diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index f60e69a23..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 diff --git a/gtsam/base/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index ccf726853..bb2c650c3 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 diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index fde769829..69f578156 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 { diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index 4d70c3d93..1589d5c4d 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 diff --git a/gtsam/discrete/DiscreteKey.h b/gtsam/discrete/DiscreteKey.h index c224b74db..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 diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index 0c7d4a577..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,15 +149,16 @@ public: /// @{ private: - template +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// Serialization function + template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& boost::serialization::make_nvp("bearing", bearing_); ar& boost::serialization::make_nvp("range", range_); } -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; +#endif /// @} @@ -163,7 +166,6 @@ private: enum { NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0 }; -#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index c2683596e..6a030fa6f 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 { diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 6d5940584..38abef733 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/SOn.h b/gtsam/geometry/SOn.h index 7a0babbcb..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 diff --git a/gtsam/geometry/SphericalCamera.h b/gtsam/geometry/SphericalCamera.h index 6c17c5962..8d10b4efe 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 { diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index a12957f17..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 { diff --git a/gtsam/inference/Factor.h b/gtsam/inference/Factor.h index 3b8cc94bf..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 diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 43664ac7c..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 diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 3238a1949..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 diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index acfeb45a3..e315f902a 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 { diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index d91843206..9710e2cb7 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 { diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 821d57b01..63e22f9ad 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 diff --git a/gtsam/linear/SubgraphBuilder.cpp b/gtsam/linear/SubgraphBuilder.cpp index a9a407a1c..ebca21dbe 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 diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 62fa76356..506183a72 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 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/ImuBias.h b/gtsam/navigation/ImuBias.h index 818540aae..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 { diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 6a1222c5d..d56bceb7d 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 diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index e2b07f62e..5f9d02819 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 diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index cda34119a..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 { From efacfb81a024ae9f364b3d60ede41344c496d29b Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Wed, 18 Jan 2023 13:27:10 -0800 Subject: [PATCH 5/9] cmake lists changes --- gtsam/base/tests/CMakeLists.txt | 10 +++++++++- gtsam/discrete/tests/CMakeLists.txt | 10 +++++++++- gtsam/geometry/tests/CMakeLists.txt | 10 +++++++++- gtsam/hybrid/tests/CMakeLists.txt | 10 +++++++++- gtsam/linear/tests/CMakeLists.txt | 19 ++++++++++++++----- gtsam/navigation/tests/CMakeLists.txt | 5 +++++ gtsam/sam/tests/CMakeLists.txt | 10 +++++++++- gtsam/slam/tests/CMakeLists.txt | 10 +++++++++- gtsam/symbolic/tests/CMakeLists.txt | 10 +++++++++- 9 files changed, 82 insertions(+), 12 deletions(-) diff --git a/gtsam/base/tests/CMakeLists.txt b/gtsam/base/tests/CMakeLists.txt index 8e99ef5ba..d8d79f912 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(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/discrete/tests/CMakeLists.txt b/gtsam/discrete/tests/CMakeLists.txt index e968fac91..cff0bb6fc 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") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/geometry/tests/CMakeLists.txt b/gtsam/geometry/tests/CMakeLists.txt index b1499ee9d..0e2da2a93 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(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/hybrid/tests/CMakeLists.txt b/gtsam/hybrid/tests/CMakeLists.txt index 06ad2c505..9c8bc74cb 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(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") 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/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/sam/tests/CMakeLists.txt b/gtsam/sam/tests/CMakeLists.txt index 127c619ee..10a03e073 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(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/slam/tests/CMakeLists.txt b/gtsam/slam/tests/CMakeLists.txt index 1205388a1..7208ef65d 100644 --- a/gtsam/slam/tests/CMakeLists.txt +++ b/gtsam/slam/tests/CMakeLists.txt @@ -1 +1,9 @@ -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 "testSerializationDatataset.cpp" "testSerializationInSlam.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/symbolic/tests/CMakeLists.txt b/gtsam/symbolic/tests/CMakeLists.txt index 6bef7a109..95e610593 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(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") From b63a8b9542250f31485ed947603d7de4124c85a8 Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Wed, 18 Jan 2023 15:25:07 -0800 Subject: [PATCH 6/9] gtsam compiles and tests run with and without boost serialization --- gtsam/base/ConcurrentMap.h | 2 +- gtsam/base/MatrixSerialization.h | 3 +++ gtsam/base/Value.h | 2 ++ gtsam/base/VectorSerialization.h | 3 +++ gtsam/base/serializationTestHelpers.h | 2 ++ gtsam/base/std_optional_serialization.h | 4 +++- gtsam/base/timing.h | 1 + gtsam/discrete/DecisionTree-inl.h | 2 ++ gtsam/discrete/DecisionTree.h | 2 ++ gtsam/discrete/tests/CMakeLists.txt | 2 +- gtsam/geometry/Cal3Bundler.h | 2 +- gtsam/geometry/CalibratedCamera.h | 2 ++ gtsam/geometry/PinholePose.h | 2 ++ gtsam/geometry/SO3.h | 2 ++ gtsam/geometry/SO4.h | 2 ++ gtsam/geometry/SphericalCamera.h | 2 ++ gtsam/geometry/tests/testBearingRange.cpp | 18 ++++++++++-------- gtsam/geometry/tests/testUnit3.cpp | 2 ++ gtsam/geometry/triangulation.h | 2 ++ gtsam/linear/JacobianFactor.h | 4 +++- gtsam/linear/LossFunctions.h | 18 ++++++++++++++++++ gtsam/linear/NoiseModel.h | 13 ++++++++++++- gtsam/linear/SubgraphBuilder.cpp | 2 ++ gtsam/linear/SubgraphBuilder.h | 6 ++++-- gtsam/navigation/AHRSFactor.h | 2 ++ gtsam/navigation/AttitudeFactor.h | 4 ++++ gtsam/navigation/CombinedImuFactor.h | 2 ++ gtsam/navigation/GPSFactor.h | 2 ++ gtsam/navigation/ImuFactor.h | 2 ++ gtsam/navigation/PreintegratedRotation.h | 2 ++ gtsam/nonlinear/FunctorizedFactor.h | 2 ++ gtsam/nonlinear/NonlinearEquality.h | 2 ++ gtsam/nonlinear/NonlinearFactor.h | 2 ++ gtsam/nonlinear/tests/CMakeLists.txt | 10 +++++++++- gtsam/sam/RangeFactor.h | 2 ++ gtsam/slam/BetweenFactor.h | 2 ++ gtsam/slam/BoundingConstraint.h | 2 ++ gtsam/slam/GeneralSFMFactor.h | 2 ++ gtsam/slam/tests/CMakeLists.txt | 3 ++- gtsam_unstable/nonlinear/LinearizedFactor.h | 4 ++++ gtsam_unstable/slam/InvDepthFactorVariant3.h | 4 +++- tests/simulated2D.h | 4 ++++ 42 files changed, 134 insertions(+), 19 deletions(-) diff --git a/gtsam/base/ConcurrentMap.h b/gtsam/base/ConcurrentMap.h index e88f6eed9..66d06d324 100644 --- a/gtsam/base/ConcurrentMap.h +++ b/gtsam/base/ConcurrentMap.h @@ -113,7 +113,6 @@ private: std::copy(this->begin(), this->end(), map.begin()); ar & BOOST_SERIALIZATION_NVP(map); } -#endif template void load(Archive& ar, const unsigned int /*version*/) { @@ -124,6 +123,7 @@ private: this->insert(map.begin(), map.end()); } BOOST_SERIALIZATION_SPLIT_MEMBER() +#endif }; } diff --git a/gtsam/base/MatrixSerialization.h b/gtsam/base/MatrixSerialization.h index f79d7b27f..9cf730230 100644 --- a/gtsam/base/MatrixSerialization.h +++ b/gtsam/base/MatrixSerialization.h @@ -18,6 +18,8 @@ // \callgraph +// Defined only if boost serialization is enabled +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include @@ -87,3 +89,4 @@ void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) { } // namespace serialization } // namespace boost +#endif diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 69f578156..c36de42ab 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -132,4 +132,6 @@ namespace gtsam { } /* namespace gtsam */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value) +#endif diff --git a/gtsam/base/VectorSerialization.h b/gtsam/base/VectorSerialization.h index 97df02a75..7acf108f4 100644 --- a/gtsam/base/VectorSerialization.h +++ b/gtsam/base/VectorSerialization.h @@ -16,6 +16,8 @@ * @date February 2022 */ +// Defined only if boost serialization is enabled +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include @@ -63,3 +65,4 @@ BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector2) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector3) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector6) +#endif diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 7aab743db..09b36cdc8 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -17,6 +17,7 @@ * @date Feb 7, 2012 */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include @@ -175,3 +176,4 @@ bool equalsDereferencedBinary(const T& input = T()) { } // \namespace serializationTestHelpers } // \namespace gtsam +#endif diff --git a/gtsam/base/std_optional_serialization.h b/gtsam/base/std_optional_serialization.h index f59c71cd3..07a02c228 100644 --- a/gtsam/base/std_optional_serialization.h +++ b/gtsam/base/std_optional_serialization.h @@ -9,6 +9,8 @@ * Inspired from this PR: https://github.com/boostorg/serialization/pull/163 * ---------------------------------------------------------------------------- */ +// Defined only if boost serialization is enabled +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #pragma once #include #include @@ -97,4 +99,4 @@ void serialize(Archive& ar, std::optional& t, const unsigned int version) { } // namespace serialization } // namespace boost - +#endif diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index 33236d8e1..52e6adff7 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -23,6 +23,7 @@ #include +#include #include #include diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 4d68bc525..f17786056 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -445,6 +445,7 @@ namespace gtsam { private: using Base = DecisionTree::Node; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -454,6 +455,7 @@ namespace gtsam { ar& BOOST_SERIALIZATION_NVP(branches_); ar& BOOST_SERIALIZATION_NVP(allSame_); } +#endif }; // Choice /****************************************************************************/ diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index 1589d5c4d..f3949b512 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -378,12 +378,14 @@ namespace gtsam { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { ar& BOOST_SERIALIZATION_NVP(root_); } +#endif }; // DecisionTree template diff --git a/gtsam/discrete/tests/CMakeLists.txt b/gtsam/discrete/tests/CMakeLists.txt index cff0bb6fc..3067e54be 100644 --- a/gtsam/discrete/tests/CMakeLists.txt +++ b/gtsam/discrete/tests/CMakeLists.txt @@ -1,7 +1,7 @@ # if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) # create a semicolon seperated list of files to exclude - set(EXCLUDE_TESTS "testSerializationDiscrete.cpp") + set(EXCLUDE_TESTS "testSerializationDiscrete.cpp" "testDiscreteFactor.cpp") else() set(EXCLUDE_TESTS "") endif() diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 8da57d50d..725c1481f 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -156,8 +156,8 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { /// @name Advanced Interface /// @{ - /** Serialization function */ #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 6a030fa6f..277c865c5 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -416,6 +416,7 @@ private: /// @name Advanced Interface /// @{ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -424,6 +425,7 @@ private: & boost::serialization::make_nvp("PinholeBase", boost::serialization::base_object(*this)); } +#endif /// @} }; diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 96c691242..7670e1e88 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -431,6 +431,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -440,6 +441,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 421619d19..cd67bfb8c 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -99,6 +99,7 @@ template <> GTSAM_EXPORT Vector9 SO3::vec(OptionalJacobian<9, 3> H) const; +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template /** Serialization function */ void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) { @@ -113,6 +114,7 @@ void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) { ar& boost::serialization::make_nvp("R32", M(2, 1)); ar& boost::serialization::make_nvp("R33", M(2, 2)); } +#endif namespace so3 { diff --git a/gtsam/geometry/SO4.h b/gtsam/geometry/SO4.h index f1c6815cc..834cab746 100644 --- a/gtsam/geometry/SO4.h +++ b/gtsam/geometry/SO4.h @@ -78,6 +78,7 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = {}); */ GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {}); +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION template /** Serialization function */ void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) { @@ -102,6 +103,7 @@ void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) { ar &boost::serialization::make_nvp("Q43", M(3, 2)); ar &boost::serialization::make_nvp("Q44", M(3, 3)); } +#endif /* * Define the traits. internal::LieGroup provides both Lie group and Testable diff --git a/gtsam/geometry/SphericalCamera.h b/gtsam/geometry/SphericalCamera.h index 8d10b4efe..a9c38cd69 100644 --- a/gtsam/geometry/SphericalCamera.h +++ b/gtsam/geometry/SphericalCamera.h @@ -223,12 +223,14 @@ class GTSAM_EXPORT SphericalCamera { static size_t Dim() { return 6; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive& ar, const unsigned int /*version*/) { ar& BOOST_SERIALIZATION_NVP(pose_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/geometry/tests/testBearingRange.cpp b/gtsam/geometry/tests/testBearingRange.cpp index 8c5d2208e..1216a6396 100644 --- a/gtsam/geometry/tests/testBearingRange.cpp +++ b/gtsam/geometry/tests/testBearingRange.cpp @@ -25,7 +25,6 @@ using namespace std; using namespace gtsam; -using namespace serializationTestHelpers; typedef BearingRange BearingRange2D; BearingRange2D br2D(1, 2); @@ -45,13 +44,6 @@ TEST(BearingRange, 2D) { EXPECT(assert_equal(expected, actual)); } -/* ************************************************************************* */ -TEST(BearingRange, Serialization2D) { - EXPECT(equalsObj(br2D)); - EXPECT(equalsXML(br2D)); - EXPECT(equalsBinary(br2D)); -} - //****************************************************************************** TEST(BearingRange3D, Concept) { BOOST_CONCEPT_ASSERT((IsManifold)); @@ -64,12 +56,22 @@ TEST(BearingRange, 3D) { EXPECT(assert_equal(expected, actual)); } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +using namespace serializationTestHelpers; +/* ************************************************************************* */ +TEST(BearingRange, Serialization2D) { + EXPECT(equalsObj(br2D)); + EXPECT(equalsXML(br2D)); + EXPECT(equalsBinary(br2D)); +} + /* ************************************************************************* */ TEST(BearingRange, Serialization3D) { EXPECT(equalsObj(br3D)); EXPECT(equalsXML(br3D)); EXPECT(equalsBinary(br3D)); } +#endif /* ************************************************************************* */ int main() { diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 29d4aee5e..0c4c2c725 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -499,12 +499,14 @@ TEST(Unit3, CopyAssign) { } /* ************************************************************************* */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION TEST(actualH, Serialization) { Unit3 p(0, 1, 0); EXPECT(serializationTestHelpers::equalsObj(p)); EXPECT(serializationTestHelpers::equalsXML(p)); EXPECT(serializationTestHelpers::equalsBinary(p)); } +#endif /* ************************************************************************* */ diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index f71ad76da..24bc94d80 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -676,12 +676,14 @@ class TriangulationResult : public std::optional { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int version) { ar& BOOST_SERIALIZATION_NVP(status); } +#endif }; /// triangulateSafe: extensive checking of the outcome diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index e315f902a..375e82698 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -435,7 +435,6 @@ namespace gtsam { ar << BOOST_SERIALIZATION_NVP(model_); } } -#endif template void load(ARCHIVE & ar, const unsigned int version) { @@ -454,6 +453,7 @@ namespace gtsam { } BOOST_SERIALIZATION_SPLIT_MEMBER() +#endif }; // JacobianFactor /// traits template<> @@ -462,7 +462,9 @@ struct traits : public Testable { } // \ namespace gtsam +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION BOOST_CLASS_VERSION(gtsam::JacobianFactor, 1) +#endif #include diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 9710e2cb7..5b4c58fe3 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -162,12 +162,14 @@ class GTSAM_EXPORT Null : public Base { static shared_ptr Create(); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE &ar, const unsigned int /*version*/) { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); } +#endif }; /** Implementation of the "Fair" robust error model (Zhang97ivc) @@ -194,6 +196,7 @@ class GTSAM_EXPORT Fair : public Base { double modelParameter() const { return c_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -201,6 +204,7 @@ class GTSAM_EXPORT Fair : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** The "Huber" robust error model (Zhang97ivc). @@ -227,6 +231,7 @@ class GTSAM_EXPORT Huber : public Base { double modelParameter() const { return k_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -234,6 +239,7 @@ class GTSAM_EXPORT Huber : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(k_); } +#endif }; /** Implementation of the "Cauchy" robust error model (Lee2013IROS). @@ -265,6 +271,7 @@ class GTSAM_EXPORT Cauchy : public Base { double modelParameter() const { return k_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -273,6 +280,7 @@ class GTSAM_EXPORT Cauchy : public Base { ar &BOOST_SERIALIZATION_NVP(k_); ar &BOOST_SERIALIZATION_NVP(ksquared_); } +#endif }; /** Implementation of the "Tukey" robust error model (Zhang97ivc). @@ -299,6 +307,7 @@ class GTSAM_EXPORT Tukey : public Base { double modelParameter() const { return c_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -306,6 +315,7 @@ class GTSAM_EXPORT Tukey : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** Implementation of the "Welsch" robust error model (Zhang97ivc). @@ -332,6 +342,7 @@ class GTSAM_EXPORT Welsch : public Base { double modelParameter() const { return c_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -340,6 +351,7 @@ class GTSAM_EXPORT Welsch : public Base { ar &BOOST_SERIALIZATION_NVP(c_); ar &BOOST_SERIALIZATION_NVP(csquared_); } +#endif }; /** Implementation of the "Geman-McClure" robust error model (Zhang97ivc). @@ -369,6 +381,7 @@ class GTSAM_EXPORT GemanMcClure : public Base { double c_; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -376,6 +389,7 @@ class GTSAM_EXPORT GemanMcClure : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** DCS implements the Dynamic Covariance Scaling robust error model @@ -407,6 +421,7 @@ class GTSAM_EXPORT DCS : public Base { double c_; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -414,6 +429,7 @@ class GTSAM_EXPORT DCS : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(c_); } +#endif }; /** L2WithDeadZone implements a standard L2 penalty, but with a dead zone of @@ -445,6 +461,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base { double modelParameter() const { return k_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -452,6 +469,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base { ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar &BOOST_SERIALIZATION_NVP(k_); } +#endif }; } // namespace mEstimator diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 63e22f9ad..ccc0a321e 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -267,6 +267,7 @@ namespace gtsam { virtual Matrix covariance() const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -274,7 +275,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(sqrt_information_); } - +#endif }; // Gaussian //--------------------------------------------------------------------------------------- @@ -362,6 +363,7 @@ namespace gtsam { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -370,6 +372,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(sigmas_); ar & BOOST_SERIALIZATION_NVP(invsigmas_); } +#endif }; // Diagonal //--------------------------------------------------------------------------------------- @@ -517,6 +520,7 @@ namespace gtsam { shared_ptr unit() const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -524,6 +528,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal); ar & BOOST_SERIALIZATION_NVP(mu_); } +#endif }; // Constrained @@ -585,6 +590,7 @@ namespace gtsam { inline double sigma() const { return sigma_; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -593,6 +599,7 @@ namespace gtsam { ar & BOOST_SERIALIZATION_NVP(sigma_); ar & BOOST_SERIALIZATION_NVP(invsigma_); } +#endif }; @@ -634,12 +641,14 @@ namespace gtsam { void unwhitenInPlace(Eigen::Block& /*v*/) const override {} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Isotropic); } +#endif }; /** @@ -727,6 +736,7 @@ namespace gtsam { const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -735,6 +745,7 @@ namespace gtsam { ar & boost::serialization::make_nvp("robust_", const_cast(robust_)); ar & boost::serialization::make_nvp("noise_", const_cast(noise_)); } +#endif }; // Helper function diff --git a/gtsam/linear/SubgraphBuilder.cpp b/gtsam/linear/SubgraphBuilder.cpp index ebca21dbe..97d681547 100644 --- a/gtsam/linear/SubgraphBuilder.cpp +++ b/gtsam/linear/SubgraphBuilder.cpp @@ -93,6 +93,7 @@ vector Subgraph::edgeIndices() const { return eid; } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /****************************************************************************/ void Subgraph::save(const std::string &fn) const { std::ofstream os(fn.c_str()); @@ -110,6 +111,7 @@ Subgraph Subgraph::load(const std::string &fn) { is.close(); return subgraph; } +#endif /****************************************************************************/ ostream &operator<<(ostream &os, const Subgraph::Edge &edge) { diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 506183a72..fe8f704dc 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -84,16 +84,18 @@ class GTSAM_EXPORT Subgraph { iterator end() { return edges_.end(); } const_iterator end() const { return edges_.end(); } - void save(const std::string &fn) const; - static Subgraph load(const std::string &fn); friend std::ostream &operator<<(std::ostream &os, const Subgraph &subgraph); private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(Archive &ar, const unsigned int /*version*/) { ar &BOOST_SERIALIZATION_NVP(edges_); } + void save(const std::string &fn) const; + static Subgraph load(const std::string &fn); +#endif }; /****************************************************************************/ diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index d163394bf..05439bafc 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -208,6 +208,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -218,6 +219,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); } +#endif }; // AHRSFactor diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index dfd8b3287..d61db2166 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -132,6 +132,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -142,6 +143,7 @@ private: ar & boost::serialization::make_nvp("AttitudeFactor", boost::serialization::base_object(*this)); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW @@ -215,6 +217,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -225,6 +228,7 @@ private: ar & boost::serialization::make_nvp("AttitudeFactor", boost::serialization::base_object(*this)); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 25b72034c..94a37c2d2 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -225,6 +225,7 @@ public: /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -233,6 +234,7 @@ public: ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index 518a11358..cd89dd464 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -166,6 +166,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// Serialization function friend class boost::serialization::access; template @@ -176,6 +177,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(nT_); } +#endif }; } /// namespace gtsam diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 2c2ca5f80..59ff688af 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -248,6 +248,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -256,6 +257,7 @@ public: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); } +#endif }; // class ImuFactor diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index c4b2caa9b..c80399f14 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -181,6 +181,7 @@ class GTSAM_EXPORT PreintegratedRotation { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -190,6 +191,7 @@ class GTSAM_EXPORT PreintegratedRotation { ar& BOOST_SERIALIZATION_NVP(deltaRij_); ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); } +#endif #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 7c4a0097c..128de5847 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -231,6 +231,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { /// @} private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -241,6 +242,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN { ar &BOOST_SERIALIZATION_NVP(measured_); ar &BOOST_SERIALIZATION_NVP(func_); } +#endif }; /// traits diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index ddf275f38..c8ab0c2af 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -275,6 +275,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -285,6 +286,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(value_); } +#endif }; // \NonlinearEquality1 diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index d56bceb7d..d22409875 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -717,6 +717,7 @@ protected: } } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -724,6 +725,7 @@ protected: ar& boost::serialization::make_nvp( "NoiseModelFactor", boost::serialization::base_object(*this)); } +#endif public: /// @name Shortcut functions `key1()` -> `key<1>()` diff --git a/gtsam/nonlinear/tests/CMakeLists.txt b/gtsam/nonlinear/tests/CMakeLists.txt index 69a3700f2..4f098275a 100644 --- a/gtsam/nonlinear/tests/CMakeLists.txt +++ b/gtsam/nonlinear/tests/CMakeLists.txt @@ -1 +1,9 @@ -gtsamAddTestsGlob(nonlinear "test*.cpp" "" "gtsam") +# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests +if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) + # create a semicolon seperated list of files to exclude + set(EXCLUDE_TESTS "testSerializationNonlinear.cpp") +else() + set(EXCLUDE_TESTS "") +endif() + +gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index bfc766857..193a89a5a 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -164,6 +164,7 @@ class RangeFactorWithTransform : public ExpressionFactorN { } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; /** Serialization function */ template @@ -175,6 +176,7 @@ class RangeFactorWithTransform : public ExpressionFactorN { ar& boost::serialization::make_nvp( "Base", boost::serialization::base_object(*this)); } +#endif }; // \ RangeFactorWithTransform /// traits diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 7be202194..3e5b154e3 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -176,12 +176,14 @@ namespace gtsam { private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & boost::serialization::make_nvp("BetweenFactor", boost::serialization::base_object >(*this)); } +#endif }; // \class BetweenConstraint /// traits diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 405c0d4a6..a496971e2 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -161,6 +161,7 @@ struct BoundingConstraint2: public NoiseModelFactorN { private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -171,6 +172,7 @@ private: ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); } +#endif }; } // \namespace gtsam diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 5f9d02819..5605ad58e 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -284,6 +284,7 @@ public: } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -293,6 +294,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; template diff --git a/gtsam/slam/tests/CMakeLists.txt b/gtsam/slam/tests/CMakeLists.txt index 7208ef65d..e5dd0830e 100644 --- a/gtsam/slam/tests/CMakeLists.txt +++ b/gtsam/slam/tests/CMakeLists.txt @@ -1,7 +1,8 @@ # if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION) # create a semicolon seperated list of files to exclude - set(EXCLUDE_TESTS "testSerializationDatataset.cpp" "testSerializationInSlam.cpp") + set(EXCLUDE_TESTS "testSerializationDataset.cpp" "testSerializationInSlam.cpp") + message(STATUS "Excluding tests: ${EXCLUDE_TESTS}") else() set(EXCLUDE_TESTS "") endif() diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.h b/gtsam_unstable/nonlinear/LinearizedFactor.h index f050676e5..689c97c3a 100644 --- a/gtsam_unstable/nonlinear/LinearizedFactor.h +++ b/gtsam_unstable/nonlinear/LinearizedFactor.h @@ -148,6 +148,7 @@ public: Vector error_vector(const Values& c) const; private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; /** Serialization function */ template @@ -156,6 +157,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(Ab_); } +#endif }; /// traits @@ -277,6 +279,7 @@ public: private: /** Serialization function */ +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -284,6 +287,7 @@ private: boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(info_); } +#endif }; /// traits diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index fb4588955..22a725d47 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -139,8 +139,8 @@ public: private: - /// Serialization function #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// + /// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { @@ -271,6 +271,7 @@ public: private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION friend class boost::serialization::access; /// Serialization function template @@ -279,6 +280,7 @@ private: ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(K_); } +#endif }; } // \ namespace gtsam diff --git a/tests/simulated2D.h b/tests/simulated2D.h index f00b35617..612dd1891 100644 --- a/tests/simulated2D.h +++ b/tests/simulated2D.h @@ -210,6 +210,7 @@ namespace simulated2D { /// Default constructor GenericOdometry() { } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -217,6 +218,7 @@ namespace simulated2D { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; /** @@ -259,6 +261,7 @@ namespace simulated2D { /// Default constructor GenericMeasurement() { } +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// /// Serialization function friend class boost::serialization::access; template @@ -266,6 +269,7 @@ namespace simulated2D { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); } +#endif }; /** Typedefs for regular use */ From 06bdd66ed76fb7ef0f51adc56e9ae9c2ff966f3b Mon Sep 17 00:00:00 2001 From: Kartik Arcot Date: Sun, 22 Jan 2023 22:53:11 -0800 Subject: [PATCH 7/9] cassert --- gtsam/base/treeTraversal-inst.h | 1 + 1 file changed, 1 insertion(+) 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 { From b2134d1d12a008964f6642ad389b5de16938be6a Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Mon, 23 Jan 2023 14:21:24 -0800 Subject: [PATCH 8/9] move the option to enable boost serialization to a different file --- CMakeLists.txt | 8 -------- cmake/HandleGeneralOptions.cmake | 1 + gtsam/config.h.in | 3 +++ 3 files changed, 4 insertions(+), 8 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index eb79600e1..52b34101f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -48,14 +48,6 @@ if(${GTSAM_SOURCE_DIR} STREQUAL ${GTSAM_BINARY_DIR}) message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ") endif() -# TODO(kartikarcot): Determine a proper home for this option -# a flag to enable or disable serialization with GTSAM_ENABLE_BOOST_SERIALIZATION -option(GTSAM_ENABLE_BOOST_SERIALIZATION "Enable Boost serialization" ON) -# set a compiler flag to enable or disable serialization with GTSAM_DISABLE_BOOST_SERIALIZATION -if(GTSAM_ENABLE_BOOST_SERIALIZATION) - add_definitions(-DGTSAM_ENABLE_BOOST_SERIALIZATION) -endif() - include(cmake/HandleGeneralOptions.cmake) # CMake build options # Libraries: diff --git a/cmake/HandleGeneralOptions.cmake b/cmake/HandleGeneralOptions.cmake index 64fa6b407..266da7ca1 100644 --- a/cmake/HandleGeneralOptions.cmake +++ b/cmake/HandleGeneralOptions.cmake @@ -29,6 +29,7 @@ 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) if(NOT MSVC AND NOT XCODE_VERSION) option(GTSAM_BUILD_WITH_CCACHE "Use ccache compiler cache" ON) endif() diff --git a/gtsam/config.h.in b/gtsam/config.h.in index 7f8936d1e..fd71f5d89 100644 --- a/gtsam/config.h.in +++ b/gtsam/config.h.in @@ -83,3 +83,6 @@ // Toggle switch for BetweenFactor jacobian computation #cmakedefine GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR + +// Toggle Boost serialization definitions +#cmakedefine GTSAM_ENABLE_BOOST_SERIALIZATION From 1d7181be101d9035b7936b8dfb2443355e4781af Mon Sep 17 00:00:00 2001 From: kartik arcot Date: Mon, 23 Jan 2023 15:56:33 -0800 Subject: [PATCH 9/9] fix CI issue --- cmake/HandleGeneralOptions.cmake | 6 ++++++ examples/CMakeLists.txt | 8 ++++++++ gtsam/base/tests/CMakeLists.txt | 2 +- gtsam/config.h.in | 3 --- gtsam/geometry/tests/CMakeLists.txt | 2 +- gtsam/hybrid/tests/CMakeLists.txt | 2 +- gtsam/nonlinear/tests/CMakeLists.txt | 2 +- gtsam/sam/tests/CMakeLists.txt | 2 +- gtsam/slam/tests/CMakeLists.txt | 2 +- gtsam/symbolic/tests/CMakeLists.txt | 2 +- 10 files changed, 21 insertions(+), 10 deletions(-) diff --git a/cmake/HandleGeneralOptions.cmake b/cmake/HandleGeneralOptions.cmake index 266da7ca1..83cf9bbb9 100644 --- a/cmake/HandleGeneralOptions.cmake +++ b/cmake/HandleGeneralOptions.cmake @@ -30,6 +30,12 @@ option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissecti 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/tests/CMakeLists.txt b/gtsam/base/tests/CMakeLists.txt index d8d79f912..ae8a12581 100644 --- a/gtsam/base/tests/CMakeLists.txt +++ b/gtsam/base/tests/CMakeLists.txt @@ -6,4 +6,4 @@ else() set(EXCLUDE_TESTS "") endif() -gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") +gtsamAddTestsGlob(base "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/config.h.in b/gtsam/config.h.in index fd71f5d89..7f8936d1e 100644 --- a/gtsam/config.h.in +++ b/gtsam/config.h.in @@ -83,6 +83,3 @@ // Toggle switch for BetweenFactor jacobian computation #cmakedefine GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR - -// Toggle Boost serialization definitions -#cmakedefine GTSAM_ENABLE_BOOST_SERIALIZATION diff --git a/gtsam/geometry/tests/CMakeLists.txt b/gtsam/geometry/tests/CMakeLists.txt index 0e2da2a93..97b41c1fd 100644 --- a/gtsam/geometry/tests/CMakeLists.txt +++ b/gtsam/geometry/tests/CMakeLists.txt @@ -6,4 +6,4 @@ else() set(EXCLUDE_TESTS "") endif() -gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") +gtsamAddTestsGlob(geometry "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/hybrid/tests/CMakeLists.txt b/gtsam/hybrid/tests/CMakeLists.txt index 9c8bc74cb..ddb5ff640 100644 --- a/gtsam/hybrid/tests/CMakeLists.txt +++ b/gtsam/hybrid/tests/CMakeLists.txt @@ -6,4 +6,4 @@ else() set(EXCLUDE_TESTS "") endif() -gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") +gtsamAddTestsGlob(hybrid "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/nonlinear/tests/CMakeLists.txt b/gtsam/nonlinear/tests/CMakeLists.txt index 4f098275a..4dcd5f4e9 100644 --- a/gtsam/nonlinear/tests/CMakeLists.txt +++ b/gtsam/nonlinear/tests/CMakeLists.txt @@ -6,4 +6,4 @@ else() set(EXCLUDE_TESTS "") endif() -gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") +gtsamAddTestsGlob(nonlinear "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/sam/tests/CMakeLists.txt b/gtsam/sam/tests/CMakeLists.txt index 10a03e073..000ded774 100644 --- a/gtsam/sam/tests/CMakeLists.txt +++ b/gtsam/sam/tests/CMakeLists.txt @@ -6,4 +6,4 @@ else() set(EXCLUDE_TESTS "") endif() -gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") +gtsamAddTestsGlob(sam "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/slam/tests/CMakeLists.txt b/gtsam/slam/tests/CMakeLists.txt index e5dd0830e..223fa6501 100644 --- a/gtsam/slam/tests/CMakeLists.txt +++ b/gtsam/slam/tests/CMakeLists.txt @@ -7,4 +7,4 @@ else() set(EXCLUDE_TESTS "") endif() -gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") +gtsamAddTestsGlob(slam "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") diff --git a/gtsam/symbolic/tests/CMakeLists.txt b/gtsam/symbolic/tests/CMakeLists.txt index 95e610593..65a7cf719 100644 --- a/gtsam/symbolic/tests/CMakeLists.txt +++ b/gtsam/symbolic/tests/CMakeLists.txt @@ -6,4 +6,4 @@ else() set(EXCLUDE_TESTS "") endif() -gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam") +gtsamAddTestsGlob(symbolic "test*.cpp" "${EXCLUDE_TESTS}" "gtsam")