replace #ifdef with #if for GTSAM_ENABLE_BOOST_SERIALIZATION
parent
51f3c6dea3
commit
ae213dd464
|
@ -48,7 +48,7 @@ using ConcurrentMapBase = gtsam::FastMap<KEY, VALUE>;
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/split_member.hpp>
|
||||
#endif
|
||||
|
@ -101,7 +101,7 @@ public:
|
|||
#endif
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <gtsam/base/FastDefaultAllocator.h>
|
||||
#include <list>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/version.hpp>
|
||||
#if BOOST_VERSION >= 107400
|
||||
|
@ -79,7 +79,7 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <gtsam/base/FastDefaultAllocator.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#endif
|
||||
|
@ -69,7 +69,7 @@ public:
|
|||
bool exists(const KEY& e) const { return this->find(e) != this->end(); }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <gtsam/config.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/version.hpp>
|
||||
#if BOOST_VERSION >= 107400
|
||||
#include <boost/serialization/library_version_type.hpp>
|
||||
|
@ -125,7 +125,7 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -173,7 +173,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
// \callgraph
|
||||
|
||||
// Defined only if boost serialization is enabled
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Matrix.h>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/base/Matrix.h>
|
||||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <cassert>
|
||||
|
@ -386,7 +386,7 @@ namespace gtsam {
|
|||
template<typename SymmetricBlockMatrixType> friend class SymmetricBlockMatrixBlockExpr;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/config.h> // Configuration from CMake
|
||||
|
||||
#include <gtsam/base/Vector.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/assume_abstract.hpp>
|
||||
#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
|
||||
* any of the archive class headers.
|
||||
* */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & /*ar*/, const unsigned int /*version*/) {
|
||||
|
@ -132,6 +132,6 @@ namespace gtsam {
|
|||
|
||||
} /* namespace gtsam */
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value)
|
||||
#endif
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
*/
|
||||
|
||||
// Defined only if boost serialization is enabled
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Vector.h>
|
||||
|
|
|
@ -221,7 +221,7 @@ namespace gtsam {
|
|||
friend class SymmetricBlockMatrix;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include <gtsam/config.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
|
||||
#include <Eigen/Core>
|
||||
#include <fstream>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include <gtsam/config.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
|
||||
#include <iostream>
|
||||
#include <sstream>
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
#pragma once
|
||||
|
||||
// Defined only if boost serialization is enabled
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <optional>
|
||||
#include <boost/config.hpp>
|
||||
|
||||
|
|
|
@ -144,7 +144,7 @@ namespace gtsam {
|
|||
private:
|
||||
using Base = DecisionTree<L, Y>::Node;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -471,7 +471,7 @@ namespace gtsam {
|
|||
private:
|
||||
using Base = DecisionTree<L, Y>::Node;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/discrete/Assignment.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <memory>
|
||||
|
@ -132,7 +132,7 @@ namespace gtsam {
|
|||
virtual bool isLeaf() const = 0;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -440,7 +440,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -310,7 +310,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -147,7 +147,7 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet<DiscreteConditional> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -275,7 +275,7 @@ class GTSAM_EXPORT DiscreteConditional
|
|||
bool forceComplete) const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -163,7 +163,7 @@ class GTSAM_EXPORT DiscreteFactor : public Factor {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/global_includes.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/vector.hpp>
|
||||
#endif
|
||||
#include <map>
|
||||
|
@ -87,7 +87,7 @@ namespace gtsam {
|
|||
/// Check equality to another DiscreteKeys object.
|
||||
bool equals(const DiscreteKeys& other, double tol = 0) const;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -123,7 +123,7 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet<DiscreteLookupTable> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/base/Manifold.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/OptionalJacobian.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <iostream>
|
||||
|
@ -148,7 +148,7 @@ public:
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// Serialization function
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||
|
|
|
@ -184,7 +184,7 @@ class GTSAM_EXPORT Cal3 {
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -145,7 +145,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3f {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -104,7 +104,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -156,7 +156,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -184,7 +184,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -138,7 +138,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -132,7 +132,7 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 {
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -143,7 +143,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -118,7 +118,7 @@ class GTSAM_EXPORT Cal3f : public Cal3 {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#include <gtsam/base/Manifold.h>
|
||||
#include <gtsam/base/ThreadsafeException.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
|
@ -230,7 +230,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -406,7 +406,7 @@ private:
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -472,7 +472,7 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -180,7 +180,7 @@ class EssentialMatrix {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -324,7 +324,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -212,7 +212,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -425,7 +425,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -64,7 +64,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <gtsam/base/VectorSpace.h>
|
||||
#include <gtsam/base/std_optional_serialization.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include <gtsam/base/Vector.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
#include <gtsam/base/VectorSerialization.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <numeric>
|
||||
|
|
|
@ -339,7 +339,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION //
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION //
|
||||
// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -406,7 +406,7 @@ public:
|
|||
friend std::ostream &operator<<(std::ostream &os, const Pose3& p);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -213,7 +213,7 @@ namespace gtsam {
|
|||
static Rot2 ClosestTo(const Matrix2& M);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -532,7 +532,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -98,7 +98,7 @@ template <>
|
|||
GTSAM_EXPORT
|
||||
Vector9 SO3::vec(OptionalJacobian<9, 3> H) const;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
template <class Archive>
|
||||
/** Serialization function */
|
||||
void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {
|
||||
|
|
|
@ -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 = {});
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
template <class Archive>
|
||||
/** Serialization function */
|
||||
void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) {
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include <gtsam/dllexport.h>
|
||||
#include <Eigen/Core>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
|
@ -326,7 +326,7 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
|
|||
/// @name Serialization
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
template <class Archive>
|
||||
friend void save(Archive&, SO&, const unsigned int);
|
||||
template <class Archive>
|
||||
|
@ -380,7 +380,7 @@ template <>
|
|||
GTSAM_EXPORT
|
||||
typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
template<class Archive>
|
||||
void serialize(
|
||||
|
|
|
@ -203,7 +203,7 @@ class GTSAM_EXPORT Similarity3 : public LieGroup<Similarity3, 7> {
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/Unit3.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
|
@ -54,7 +54,7 @@ class GTSAM_EXPORT EmptyCal {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -223,7 +223,7 @@ class GTSAM_EXPORT SphericalCamera {
|
|||
static size_t Dim() { return 6; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -177,7 +177,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive & ar, const unsigned int /*version*/) {
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/VectorSpace.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
|
@ -150,7 +150,7 @@ private:
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -198,7 +198,7 @@ private:
|
|||
|
||||
/// @name Advanced Interface
|
||||
/// @{
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -56,7 +56,7 @@ TEST(BearingRange, 3D) {
|
|||
EXPECT(assert_equal(expected, actual));
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
using namespace serializationTestHelpers;
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingRange, Serialization2D) {
|
||||
|
|
|
@ -499,7 +499,7 @@ TEST(Unit3, CopyAssign) {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
TEST(actualH, Serialization) {
|
||||
Unit3 p(0, 1, 0);
|
||||
EXPECT(serializationTestHelpers::equalsObj(p));
|
||||
|
|
|
@ -622,7 +622,7 @@ struct GTSAM_EXPORT TriangulationParameters {
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -687,7 +687,7 @@ class TriangulationResult : public std::optional<Point3> {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -268,7 +268,7 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -115,7 +115,7 @@ class GTSAM_EXPORT HybridBayesTree : public BayesTree<HybridBayesTreeClique> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -217,7 +217,7 @@ class GTSAM_EXPORT HybridConditional
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -140,7 +140,7 @@ class GTSAM_EXPORT HybridFactor : public Factor {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -253,7 +253,7 @@ class GTSAM_EXPORT HybridGaussianConditional
|
|||
/// Check whether `given` has values for all frontal keys.
|
||||
bool allFrontalsGiven(const VectorValues &given) const;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -176,7 +176,7 @@ class GTSAM_EXPORT HybridGaussianFactor : public HybridFactor {
|
|||
// Private constructor using ConstructorHelper above.
|
||||
HybridGaussianFactor(const ConstructorHelper &helper);
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -119,7 +119,7 @@ class GTSAM_EXPORT HybridGaussianProductFactor
|
|||
///@}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
|
|
@ -262,7 +262,7 @@ namespace gtsam {
|
|||
template<class BAYESTREE, class GRAPH> friend class EliminatableClusterTree;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -208,7 +208,7 @@ namespace gtsam {
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -233,7 +233,7 @@ 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<const FACTOR&>(static_cast<const DERIVEDCONDITIONAL&>(*this)); }
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <gtsam/base/FastVector.h>
|
||||
|
@ -193,7 +193,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// @name Serialization
|
||||
/// @{
|
||||
/** Serialization function */
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
|
||||
#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/vector.hpp>
|
||||
#endif
|
||||
|
@ -420,7 +420,7 @@ class FactorGraph {
|
|||
inline bool exists(size_t idx) const { return idx < size() && at(idx); }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -142,7 +142,7 @@ class GTSAM_EXPORT LabeledSymbol {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -252,7 +252,7 @@ private:
|
|||
static Ordering ColamdConstrained(
|
||||
const VariableIndex& variableIndex, std::vector<int>& cmember);
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <cstdint>
|
||||
|
@ -124,7 +124,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -192,7 +192,7 @@ protected:
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -267,7 +267,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -278,7 +278,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
|
|
@ -179,7 +179,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -400,7 +400,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -370,7 +370,7 @@ namespace gtsam {
|
|||
friend class NonlinearFactorGraph;
|
||||
friend class NonlinearClusterTree;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include <gtsam/global_includes.h>
|
||||
#include <gtsam/inference/VariableSlots.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/version.hpp>
|
||||
#include <boost/serialization/split_member.hpp>
|
||||
#endif
|
||||
|
@ -421,7 +421,7 @@ namespace gtsam {
|
|||
// be very selective on who can access these private methods:
|
||||
template<typename T> friend class ExpressionFactor;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -468,7 +468,7 @@ struct traits<JacobianFactor> : public Testable<JacobianFactor> {
|
|||
|
||||
} // \ namespace gtsam
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
BOOST_CLASS_VERSION(gtsam::JacobianFactor, 1)
|
||||
#endif
|
||||
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include <gtsam/base/Testable.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/nvp.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;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -161,7 +161,7 @@ class GTSAM_EXPORT Null : public Base {
|
|||
static shared_ptr Create();
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -195,7 +195,7 @@ class GTSAM_EXPORT Fair : public Base {
|
|||
double modelParameter() const { return c_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -230,7 +230,7 @@ class GTSAM_EXPORT Huber : public Base {
|
|||
double modelParameter() const { return k_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -270,7 +270,7 @@ class GTSAM_EXPORT Cauchy : public Base {
|
|||
double modelParameter() const { return k_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -306,7 +306,7 @@ class GTSAM_EXPORT Tukey : public Base {
|
|||
double modelParameter() const { return c_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -341,7 +341,7 @@ class GTSAM_EXPORT Welsch : public Base {
|
|||
double modelParameter() const { return c_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -380,7 +380,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
|
|||
double c_;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -420,7 +420,7 @@ class GTSAM_EXPORT DCS : public Base {
|
|||
double c_;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -460,7 +460,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base {
|
|||
double modelParameter() const { return k_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -496,7 +496,7 @@ class GTSAM_EXPORT AsymmetricTukey : public Base {
|
|||
double modelParameter() const { return c_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -532,7 +532,7 @@ class GTSAM_EXPORT AsymmetricCauchy : public Base {
|
|||
double modelParameter() const { return k_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -577,7 +577,7 @@ class GTSAM_EXPORT Custom : public Base {
|
|||
inline Custom() = default;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include <gtsam/dllexport.h>
|
||||
#include <gtsam/linear/LossFunctions.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/extended_type_info.hpp>
|
||||
#include <boost/serialization/singleton.hpp>
|
||||
|
@ -141,7 +141,7 @@ namespace gtsam {
|
|||
virtual double weight(const Vector& v) const { return 1.0; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -280,7 +280,7 @@ namespace gtsam {
|
|||
double negLogConstant() const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -375,7 +375,7 @@ namespace gtsam {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -520,7 +520,7 @@ namespace gtsam {
|
|||
shared_ptr unit() const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -593,7 +593,7 @@ namespace gtsam {
|
|||
inline double sigma() const { return sigma_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -648,7 +648,7 @@ namespace gtsam {
|
|||
void unwhitenInPlace(Eigen::Block<Vector>& /*v*/) const override {}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -739,7 +739,7 @@ namespace gtsam {
|
|||
const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#include <gtsam/linear/SubgraphBuilder.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_oarchive.hpp>
|
||||
#include <boost/serialization/vector.hpp>
|
||||
|
@ -71,7 +71,7 @@ vector<size_t> Subgraph::edgeIndices() const {
|
|||
return eid;
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/****************************************************************************/
|
||||
void Subgraph::save(const std::string &fn) const {
|
||||
std::ofstream os(fn.c_str());
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/version.hpp>
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
@ -51,7 +51,7 @@ class GTSAM_EXPORT Subgraph {
|
|||
friend std::ostream &operator<<(std::ostream &os, const Edge &edge);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
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);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
void serialize(Archive &ar, const unsigned int /*version*/) {
|
||||
|
|
|
@ -371,7 +371,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -120,7 +120,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -208,7 +208,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -73,7 +73,7 @@ class AttitudeFactor {
|
|||
const Unit3& bRef() const { return bMeasured_; }
|
||||
#endif
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -138,7 +138,7 @@ class GTSAM_EXPORT Rot3AttitudeFactor : public NoiseModelFactorN<Rot3>,
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -220,7 +220,7 @@ class GTSAM_EXPORT Pose3AttitudeFactor : public NoiseModelFactorN<Pose3>,
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -97,7 +97,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
**/
|
||||
|
||||
#include <gtsam/navigation/CombinedImuFactor.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/export.hpp>
|
||||
#endif
|
||||
|
||||
|
|
|
@ -169,7 +169,7 @@ class GTSAM_EXPORT PreintegratedCombinedMeasurements
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -281,7 +281,7 @@ class GTSAM_EXPORT CombinedImuFactor
|
|||
OptionalMatrixType H6) const override;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -97,7 +97,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -166,7 +166,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
#include <gtsam/base/OptionalJacobian.h>
|
||||
#include <gtsam/base/VectorSpace.h>
|
||||
#include <iosfwd>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
|
@ -142,7 +142,7 @@ private:
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -142,7 +142,7 @@ public:
|
|||
#endif
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -244,7 +244,7 @@ public:
|
|||
|
||||
private:
|
||||
/** Serialization function */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
|
@ -316,7 +316,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -132,7 +132,7 @@ class MagPoseFactor: public NoiseModelFactorN<POSE> {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function.
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -113,7 +113,7 @@ public:
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -269,7 +269,7 @@ public:
|
|||
private:
|
||||
/// @{
|
||||
/// serialization
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
|
|
|
@ -85,7 +85,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams {
|
|||
std::optional<Pose3> getBodyPSensor() const { return body_P_sensor; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -227,7 +227,7 @@ class GTSAM_EXPORT PreintegratedRotation {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -173,7 +173,7 @@ class GTSAM_EXPORT PreintegrationBase {
|
|||
OptionalJacobian<9, 6> H5 = {}) const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -84,7 +84,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {
|
|||
const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
|
@ -71,7 +71,7 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams {
|
|||
|
||||
protected:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -127,7 +127,7 @@ public:
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -88,7 +88,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
@ -200,7 +200,7 @@ protected:
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// Save to an archive: just saves the base class
|
||||
template <class Archive>
|
||||
void save(Archive& ar, const unsigned int /*version*/) const {
|
||||
|
@ -287,7 +287,7 @@ private:
|
|||
return expression(keys);
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
|
||||
|
|
|
@ -119,7 +119,7 @@ class FunctorizedFactor : public NoiseModelFactorN<T> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -231,7 +231,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue