replace #ifdef with #if for GTSAM_ENABLE_BOOST_SERIALIZATION

release/4.3a0
Varun Agrawal 2024-12-26 23:44:00 -05:00
parent 51f3c6dea3
commit ae213dd464
168 changed files with 247 additions and 247 deletions

View File

@ -48,7 +48,7 @@ using ConcurrentMapBase = gtsam::FastMap<KEY, VALUE>;
#endif #endif
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/split_member.hpp> #include <boost/serialization/split_member.hpp>
#endif #endif
@ -101,7 +101,7 @@ public:
#endif #endif
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -20,7 +20,7 @@
#include <gtsam/base/FastDefaultAllocator.h> #include <gtsam/base/FastDefaultAllocator.h>
#include <list> #include <list>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/version.hpp> #include <boost/serialization/version.hpp>
#if BOOST_VERSION >= 107400 #if BOOST_VERSION >= 107400
@ -79,7 +79,7 @@ public:
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -19,7 +19,7 @@
#pragma once #pragma once
#include <gtsam/base/FastDefaultAllocator.h> #include <gtsam/base/FastDefaultAllocator.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/map.hpp> #include <boost/serialization/map.hpp>
#endif #endif
@ -69,7 +69,7 @@ public:
bool exists(const KEY& e) const { return this->find(e) != this->end(); } bool exists(const KEY& e) const { return this->find(e) != this->end(); }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -20,7 +20,7 @@
#include <gtsam/config.h> #include <gtsam/config.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/version.hpp> #include <boost/version.hpp>
#if BOOST_VERSION >= 107400 #if BOOST_VERSION >= 107400
#include <boost/serialization/library_version_type.hpp> #include <boost/serialization/library_version_type.hpp>
@ -125,7 +125,7 @@ public:
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -173,7 +173,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -19,7 +19,7 @@
// \callgraph // \callgraph
// Defined only if boost serialization is enabled // Defined only if boost serialization is enabled
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#pragma once #pragma once
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>

View File

@ -21,7 +21,7 @@
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
#include <cassert> #include <cassert>
@ -386,7 +386,7 @@ namespace gtsam {
template<typename SymmetricBlockMatrixType> friend class SymmetricBlockMatrixBlockExpr; template<typename SymmetricBlockMatrixType> friend class SymmetricBlockMatrixBlockExpr;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -21,7 +21,7 @@
#include <gtsam/config.h> // Configuration from CMake #include <gtsam/config.h> // Configuration from CMake
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/assume_abstract.hpp> #include <boost/serialization/assume_abstract.hpp>
#endif #endif
@ -121,7 +121,7 @@ namespace gtsam {
* The last two links explain why these export lines have to be in the same source module that includes * 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. * any of the archive class headers.
* */ * */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & /*ar*/, const unsigned int /*version*/) { void serialize(ARCHIVE & /*ar*/, const unsigned int /*version*/) {
@ -132,6 +132,6 @@ namespace gtsam {
} /* namespace gtsam */ } /* namespace gtsam */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value) BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value)
#endif #endif

View File

@ -17,7 +17,7 @@
*/ */
// Defined only if boost serialization is enabled // Defined only if boost serialization is enabled
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#pragma once #pragma once
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>

View File

@ -221,7 +221,7 @@ namespace gtsam {
friend class SymmetricBlockMatrix; friend class SymmetricBlockMatrix;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -21,7 +21,7 @@
#include <gtsam/config.h> #include <gtsam/config.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <Eigen/Core> #include <Eigen/Core>
#include <fstream> #include <fstream>

View File

@ -21,7 +21,7 @@
#include <gtsam/config.h> #include <gtsam/config.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <iostream> #include <iostream>
#include <sstream> #include <sstream>

View File

@ -11,7 +11,7 @@
#pragma once #pragma once
// Defined only if boost serialization is enabled // Defined only if boost serialization is enabled
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <optional> #include <optional>
#include <boost/config.hpp> #include <boost/config.hpp>

View File

@ -144,7 +144,7 @@ namespace gtsam {
private: private:
using Base = DecisionTree<L, Y>::Node; using Base = DecisionTree<L, Y>::Node;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -471,7 +471,7 @@ namespace gtsam {
private: private:
using Base = DecisionTree<L, Y>::Node; using Base = DecisionTree<L, Y>::Node;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -23,7 +23,7 @@
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <gtsam/discrete/Assignment.h> #include <gtsam/discrete/Assignment.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
#include <memory> #include <memory>
@ -132,7 +132,7 @@ namespace gtsam {
virtual bool isLeaf() const = 0; virtual bool isLeaf() const = 0;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -440,7 +440,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -310,7 +310,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -147,7 +147,7 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet<DiscreteConditional> {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -275,7 +275,7 @@ class GTSAM_EXPORT DiscreteConditional
bool forceComplete) const; bool forceComplete) const;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -163,7 +163,7 @@ class GTSAM_EXPORT DiscreteFactor : public Factor {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -21,7 +21,7 @@
#include <gtsam/global_includes.h> #include <gtsam/global_includes.h>
#include <gtsam/inference/Key.h> #include <gtsam/inference/Key.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/vector.hpp> #include <boost/serialization/vector.hpp>
#endif #endif
#include <map> #include <map>
@ -87,7 +87,7 @@ namespace gtsam {
/// Check equality to another DiscreteKeys object. /// Check equality to another DiscreteKeys object.
bool equals(const DiscreteKeys& other, double tol = 0) const; bool equals(const DiscreteKeys& other, double tol = 0) const;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -123,7 +123,7 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet<DiscreteLookupTable> {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -21,7 +21,7 @@
#include <gtsam/base/Manifold.h> #include <gtsam/base/Manifold.h>
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/OptionalJacobian.h> #include <gtsam/base/OptionalJacobian.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
#include <iostream> #include <iostream>
@ -148,7 +148,7 @@ public:
/// @{ /// @{
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/// Serialization function /// Serialization function
template <class ARCHIVE> template <class ARCHIVE>
void serialize(ARCHIVE& ar, const unsigned int /*version*/) { void serialize(ARCHIVE& ar, const unsigned int /*version*/) {

View File

@ -184,7 +184,7 @@ class GTSAM_EXPORT Cal3 {
/// @{ /// @{
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -145,7 +145,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3f {
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -104,7 +104,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -156,7 +156,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -184,7 +184,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -138,7 +138,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -132,7 +132,7 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 {
/// @{ /// @{
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -143,7 +143,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
/// @{ /// @{
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -118,7 +118,7 @@ class GTSAM_EXPORT Cal3f : public Cal3 {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -25,7 +25,7 @@
#include <gtsam/base/Manifold.h> #include <gtsam/base/Manifold.h>
#include <gtsam/base/ThreadsafeException.h> #include <gtsam/base/ThreadsafeException.h>
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
@ -230,7 +230,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
@ -406,7 +406,7 @@ private:
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -472,7 +472,7 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -180,7 +180,7 @@ class EssentialMatrix {
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -324,7 +324,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -212,7 +212,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
@ -425,7 +425,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -64,7 +64,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -19,7 +19,7 @@
#include <gtsam/base/VectorSpace.h> #include <gtsam/base/VectorSpace.h>
#include <gtsam/base/std_optional_serialization.h> #include <gtsam/base/std_optional_serialization.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif

View File

@ -26,7 +26,7 @@
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#include <gtsam/base/VectorSerialization.h> #include <gtsam/base/VectorSerialization.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
#include <numeric> #include <numeric>

View File

@ -339,7 +339,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION // #if GTSAM_ENABLE_BOOST_SERIALIZATION //
// Serialization function // Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -406,7 +406,7 @@ public:
friend std::ostream &operator<<(std::ostream &os, const Pose3& p); friend std::ostream &operator<<(std::ostream &os, const Pose3& p);
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -213,7 +213,7 @@ namespace gtsam {
static Rot2 ClosestTo(const Matrix2& M); static Rot2 ClosestTo(const Matrix2& M);
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -532,7 +532,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -98,7 +98,7 @@ template <>
GTSAM_EXPORT GTSAM_EXPORT
Vector9 SO3::vec(OptionalJacobian<9, 3> H) const; Vector9 SO3::vec(OptionalJacobian<9, 3> H) const;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
template <class Archive> template <class Archive>
/** Serialization function */ /** Serialization function */
void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) { void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {

View File

@ -78,7 +78,7 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = {});
*/ */
GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {}); GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {});
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
template <class Archive> template <class Archive>
/** Serialization function */ /** Serialization function */
void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) { void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) {

View File

@ -24,7 +24,7 @@
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#include <Eigen/Core> #include <Eigen/Core>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
@ -326,7 +326,7 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
/// @name Serialization /// @name Serialization
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
template <class Archive> template <class Archive>
friend void save(Archive&, SO&, const unsigned int); friend void save(Archive&, SO&, const unsigned int);
template <class Archive> template <class Archive>
@ -380,7 +380,7 @@ template <>
GTSAM_EXPORT GTSAM_EXPORT
typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const; typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
template<class Archive> template<class Archive>
void serialize( void serialize(

View File

@ -203,7 +203,7 @@ class GTSAM_EXPORT Similarity3 : public LieGroup<Similarity3, 7> {
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -26,7 +26,7 @@
#include <gtsam/geometry/Pose3.h> #include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Unit3.h> #include <gtsam/geometry/Unit3.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
@ -54,7 +54,7 @@ class GTSAM_EXPORT EmptyCal {
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>
@ -223,7 +223,7 @@ class GTSAM_EXPORT SphericalCamera {
static size_t Dim() { return 6; } static size_t Dim() { return 6; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -177,7 +177,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>
void serialize(Archive & ar, const unsigned int /*version*/) { void serialize(Archive & ar, const unsigned int /*version*/) {

View File

@ -20,7 +20,7 @@
#include <gtsam/geometry/Point2.h> #include <gtsam/geometry/Point2.h>
#include <gtsam/base/VectorSpace.h> #include <gtsam/base/VectorSpace.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
@ -150,7 +150,7 @@ private:
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -198,7 +198,7 @@ private:
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -56,7 +56,7 @@ TEST(BearingRange, 3D) {
EXPECT(assert_equal(expected, actual)); EXPECT(assert_equal(expected, actual));
} }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
using namespace serializationTestHelpers; using namespace serializationTestHelpers;
/* ************************************************************************* */ /* ************************************************************************* */
TEST(BearingRange, Serialization2D) { TEST(BearingRange, Serialization2D) {

View File

@ -499,7 +499,7 @@ TEST(Unit3, CopyAssign) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
TEST(actualH, Serialization) { TEST(actualH, Serialization) {
Unit3 p(0, 1, 0); Unit3 p(0, 1, 0);
EXPECT(serializationTestHelpers::equalsObj(p)); EXPECT(serializationTestHelpers::equalsObj(p));

View File

@ -622,7 +622,7 @@ struct GTSAM_EXPORT TriangulationParameters {
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -687,7 +687,7 @@ class TriangulationResult : public std::optional<Point3> {
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -268,7 +268,7 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -115,7 +115,7 @@ class GTSAM_EXPORT HybridBayesTree : public BayesTree<HybridBayesTreeClique> {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -217,7 +217,7 @@ class GTSAM_EXPORT HybridConditional
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -140,7 +140,7 @@ class GTSAM_EXPORT HybridFactor : public Factor {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -253,7 +253,7 @@ class GTSAM_EXPORT HybridGaussianConditional
/// Check whether `given` has values for all frontal keys. /// Check whether `given` has values for all frontal keys.
bool allFrontalsGiven(const VectorValues &given) const; bool allFrontalsGiven(const VectorValues &given) const;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -176,7 +176,7 @@ class GTSAM_EXPORT HybridGaussianFactor : public HybridFactor {
// Private constructor using ConstructorHelper above. // Private constructor using ConstructorHelper above.
HybridGaussianFactor(const ConstructorHelper &helper); HybridGaussianFactor(const ConstructorHelper &helper);
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -119,7 +119,7 @@ class GTSAM_EXPORT HybridGaussianProductFactor
///@} ///@}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>

View File

@ -262,7 +262,7 @@ namespace gtsam {
template<class BAYESTREE, class GRAPH> friend class EliminatableClusterTree; template<class BAYESTREE, class GRAPH> friend class EliminatableClusterTree;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -208,7 +208,7 @@ namespace gtsam {
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -233,7 +233,7 @@ namespace gtsam {
// Cast to derived type (const) (casts down to derived conditional type, then up to factor type) // Cast to derived type (const) (casts down to derived conditional type, then up to factor type)
const FACTOR& asFactor() const { return static_cast<const FACTOR&>(static_cast<const DERIVEDCONDITIONAL&>(*this)); } const FACTOR& asFactor() const { return static_cast<const FACTOR&>(static_cast<const DERIVEDCONDITIONAL&>(*this)); }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -21,7 +21,7 @@
#pragma once #pragma once
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
#include <gtsam/base/FastVector.h> #include <gtsam/base/FastVector.h>
@ -193,7 +193,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/// @name Serialization /// @name Serialization
/// @{ /// @{
/** Serialization function */ /** Serialization function */

View File

@ -29,7 +29,7 @@
#include <Eigen/Core> // for Eigen::aligned_allocator #include <Eigen/Core> // for Eigen::aligned_allocator
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/vector.hpp> #include <boost/serialization/vector.hpp>
#endif #endif
@ -420,7 +420,7 @@ class FactorGraph {
inline bool exists(size_t idx) const { return idx < size() && at(idx); } inline bool exists(size_t idx) const { return idx < size() && at(idx); }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -142,7 +142,7 @@ class GTSAM_EXPORT LabeledSymbol {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -252,7 +252,7 @@ private:
static Ordering ColamdConstrained( static Ordering ColamdConstrained(
const VariableIndex& variableIndex, std::vector<int>& cmember); const VariableIndex& variableIndex, std::vector<int>& cmember);
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -21,7 +21,7 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/inference/Key.h> #include <gtsam/inference/Key.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
#include <cstdint> #include <cstdint>
@ -124,7 +124,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -192,7 +192,7 @@ protected:
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -267,7 +267,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -278,7 +278,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class Archive> template<class Archive>

View File

@ -179,7 +179,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -400,7 +400,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -370,7 +370,7 @@ namespace gtsam {
friend class NonlinearFactorGraph; friend class NonlinearFactorGraph;
friend class NonlinearClusterTree; friend class NonlinearClusterTree;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -24,7 +24,7 @@
#include <gtsam/global_includes.h> #include <gtsam/global_includes.h>
#include <gtsam/inference/VariableSlots.h> #include <gtsam/inference/VariableSlots.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/version.hpp> #include <boost/serialization/version.hpp>
#include <boost/serialization/split_member.hpp> #include <boost/serialization/split_member.hpp>
#endif #endif
@ -421,7 +421,7 @@ namespace gtsam {
// be very selective on who can access these private methods: // be very selective on who can access these private methods:
template<typename T> friend class ExpressionFactor; template<typename T> friend class ExpressionFactor;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -468,7 +468,7 @@ struct traits<JacobianFactor> : public Testable<JacobianFactor> {
} // \ namespace gtsam } // \ namespace gtsam
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
BOOST_CLASS_VERSION(gtsam::JacobianFactor, 1) BOOST_CLASS_VERSION(gtsam::JacobianFactor, 1)
#endif #endif

View File

@ -24,7 +24,7 @@
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/extended_type_info.hpp> #include <boost/serialization/extended_type_info.hpp>
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/version.hpp> #include <boost/serialization/version.hpp>
@ -129,7 +129,7 @@ class GTSAM_EXPORT Base {
void reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const; void reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -161,7 +161,7 @@ class GTSAM_EXPORT Null : public Base {
static shared_ptr Create(); static shared_ptr Create();
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -195,7 +195,7 @@ class GTSAM_EXPORT Fair : public Base {
double modelParameter() const { return c_; } double modelParameter() const { return c_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -230,7 +230,7 @@ class GTSAM_EXPORT Huber : public Base {
double modelParameter() const { return k_; } double modelParameter() const { return k_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -270,7 +270,7 @@ class GTSAM_EXPORT Cauchy : public Base {
double modelParameter() const { return k_; } double modelParameter() const { return k_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -306,7 +306,7 @@ class GTSAM_EXPORT Tukey : public Base {
double modelParameter() const { return c_; } double modelParameter() const { return c_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -341,7 +341,7 @@ class GTSAM_EXPORT Welsch : public Base {
double modelParameter() const { return c_; } double modelParameter() const { return c_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -380,7 +380,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
double c_; double c_;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -420,7 +420,7 @@ class GTSAM_EXPORT DCS : public Base {
double c_; double c_;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -460,7 +460,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base {
double modelParameter() const { return k_; } double modelParameter() const { return k_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -496,7 +496,7 @@ class GTSAM_EXPORT AsymmetricTukey : public Base {
double modelParameter() const { return c_; } double modelParameter() const { return c_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -532,7 +532,7 @@ class GTSAM_EXPORT AsymmetricCauchy : public Base {
double modelParameter() const { return k_; } double modelParameter() const { return k_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -577,7 +577,7 @@ class GTSAM_EXPORT Custom : public Base {
inline Custom() = default; inline Custom() = default;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -24,7 +24,7 @@
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#include <gtsam/linear/LossFunctions.h> #include <gtsam/linear/LossFunctions.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/serialization/extended_type_info.hpp> #include <boost/serialization/extended_type_info.hpp>
#include <boost/serialization/singleton.hpp> #include <boost/serialization/singleton.hpp>
@ -141,7 +141,7 @@ namespace gtsam {
virtual double weight(const Vector& v) const { return 1.0; } virtual double weight(const Vector& v) const { return 1.0; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -280,7 +280,7 @@ namespace gtsam {
double negLogConstant() const; double negLogConstant() const;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -375,7 +375,7 @@ namespace gtsam {
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -520,7 +520,7 @@ namespace gtsam {
shared_ptr unit() const; shared_ptr unit() const;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -593,7 +593,7 @@ namespace gtsam {
inline double sigma() const { return sigma_; } inline double sigma() const { return sigma_; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -648,7 +648,7 @@ namespace gtsam {
void unwhitenInPlace(Eigen::Block<Vector>& /*v*/) const override {} void unwhitenInPlace(Eigen::Block<Vector>& /*v*/) const override {}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -739,7 +739,7 @@ namespace gtsam {
const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise);
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -25,7 +25,7 @@
#include <gtsam/linear/SubgraphBuilder.h> #include <gtsam/linear/SubgraphBuilder.h>
#include <gtsam/base/kruskal.h> #include <gtsam/base/kruskal.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/archive/text_iarchive.hpp> #include <boost/archive/text_iarchive.hpp>
#include <boost/archive/text_oarchive.hpp> #include <boost/archive/text_oarchive.hpp>
#include <boost/serialization/vector.hpp> #include <boost/serialization/vector.hpp>
@ -71,7 +71,7 @@ vector<size_t> Subgraph::edgeIndices() const {
return eid; return eid;
} }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/****************************************************************************/ /****************************************************************************/
void Subgraph::save(const std::string &fn) const { void Subgraph::save(const std::string &fn) const {
std::ofstream os(fn.c_str()); std::ofstream os(fn.c_str());

View File

@ -21,7 +21,7 @@
#include <gtsam/base/types.h> #include <gtsam/base/types.h>
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/version.hpp> #include <boost/serialization/version.hpp>
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
@ -51,7 +51,7 @@ class GTSAM_EXPORT Subgraph {
friend std::ostream &operator<<(std::ostream &os, const Edge &edge); friend std::ostream &operator<<(std::ostream &os, const Edge &edge);
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>
void serialize(Archive &ar, const unsigned int /*version*/) { void serialize(Archive &ar, const unsigned int /*version*/) {
@ -87,7 +87,7 @@ class GTSAM_EXPORT Subgraph {
friend std::ostream &operator<<(std::ostream &os, const Subgraph &subgraph); friend std::ostream &operator<<(std::ostream &os, const Subgraph &subgraph);
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access; friend class boost::serialization::access;
template <class Archive> template <class Archive>
void serialize(Archive &ar, const unsigned int /*version*/) { void serialize(Archive &ar, const unsigned int /*version*/) {

View File

@ -371,7 +371,7 @@ namespace gtsam {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -120,7 +120,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -208,7 +208,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -73,7 +73,7 @@ class AttitudeFactor {
const Unit3& bRef() const { return bMeasured_; } const Unit3& bRef() const { return bMeasured_; }
#endif #endif
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -138,7 +138,7 @@ class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN<Rot3>,
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -220,7 +220,7 @@ class GTSAM_EXPORT Pose3AttitudeFactor : public NoiseModelFactorN<Pose3>,
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -97,7 +97,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -21,7 +21,7 @@
**/ **/
#include <gtsam/navigation/CombinedImuFactor.h> #include <gtsam/navigation/CombinedImuFactor.h>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/export.hpp> #include <boost/serialization/export.hpp>
#endif #endif

View File

@ -169,7 +169,7 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -281,7 +281,7 @@ class GTSAM_EXPORT CombinedImuFactor
OptionalMatrixType H6) const override; OptionalMatrixType H6) const override;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -97,7 +97,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -166,7 +166,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -20,7 +20,7 @@
#include <gtsam/base/OptionalJacobian.h> #include <gtsam/base/OptionalJacobian.h>
#include <gtsam/base/VectorSpace.h> #include <gtsam/base/VectorSpace.h>
#include <iosfwd> #include <iosfwd>
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#endif #endif
@ -142,7 +142,7 @@ private:
/// @name Advanced Interface /// @name Advanced Interface
/// @{ /// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -142,7 +142,7 @@ public:
#endif #endif
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function /// Serialization function
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -244,7 +244,7 @@ public:
private: private:
/** Serialization function */ /** Serialization function */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
@ -316,7 +316,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -132,7 +132,7 @@ class MagPoseFactor: public NoiseModelFactorN<POSE> {
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function. /// Serialization function.
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -113,7 +113,7 @@ public:
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -269,7 +269,7 @@ public:
private: private:
/// @{ /// @{
/// serialization /// serialization
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// #if GTSAM_ENABLE_BOOST_SERIALIZATION ///
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) { void serialize(ARCHIVE & ar, const unsigned int /*version*/) {

View File

@ -85,7 +85,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams {
std::optional<Pose3> getBodyPSensor() const { return body_P_sensor; } std::optional<Pose3> getBodyPSensor() const { return body_P_sensor; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
@ -227,7 +227,7 @@ class GTSAM_EXPORT PreintegratedRotation {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -173,7 +173,7 @@ class GTSAM_EXPORT PreintegrationBase {
OptionalJacobian<9, 6> H5 = {}) const; OptionalJacobian<9, 6> H5 = {}) const;
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -84,7 +84,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {
const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; } const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

View File

@ -71,7 +71,7 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams {
protected: protected:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -127,7 +127,7 @@ public:
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -88,7 +88,7 @@ public:
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>

View File

@ -200,7 +200,7 @@ protected:
} }
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/// Save to an archive: just saves the base class /// Save to an archive: just saves the base class
template <class Archive> template <class Archive>
void save(Archive& ar, const unsigned int /*version*/) const { void save(Archive& ar, const unsigned int /*version*/) const {
@ -287,7 +287,7 @@ private:
return expression(keys); return expression(keys);
} }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
void serialize(ARCHIVE &ar, const unsigned int /*version*/) { void serialize(ARCHIVE &ar, const unsigned int /*version*/) {

View File

@ -119,7 +119,7 @@ class FunctorizedFactor : public NoiseModelFactorN<T> {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>
@ -231,7 +231,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
/// @} /// @}
private: private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION #if GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */ /** Serialization function */
friend class boost::serialization::access; friend class boost::serialization::access;
template <class ARCHIVE> template <class ARCHIVE>

Some files were not shown because too many files have changed in this diff Show More