Merge pull request #1409 from kartikarcot/verdant/boost-serialization
commit
dd95757229
|
@ -29,6 +29,13 @@ option(GTSAM_ALLOW_DEPRECATED_SINCE_V43 "Allow use of methods/functions depr
|
|||
option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON)
|
||||
option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" ON)
|
||||
option(GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR "Use the slower but correct version of BetweenFactor" OFF)
|
||||
option(GTSAM_ENABLE_BOOST_SERIALIZATION "Enable Boost serialization" ON)
|
||||
|
||||
#TODO(kartikarcot) defining it in config.h.in did not work
|
||||
if (GTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
add_definitions(-DGTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
endif()
|
||||
|
||||
if(NOT MSVC AND NOT XCODE_VERSION)
|
||||
option(GTSAM_BUILD_WITH_CCACHE "Use ccache compiler cache" ON)
|
||||
endif()
|
||||
|
|
|
@ -2,4 +2,12 @@ set (excluded_examples
|
|||
elaboratePoint2KalmanFilter.cpp
|
||||
)
|
||||
|
||||
# if GTSAM_ENABLE_BOOST_SERIALIZATION is not set then SolverComparer.cpp will not compile
|
||||
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
set (excluded_examples
|
||||
${excluded_examples}
|
||||
SolverComparer.cpp
|
||||
)
|
||||
endif()
|
||||
|
||||
gtsamAddExamplesGlob("*.cpp" "${excluded_examples}" "gtsam;gtsam_unstable;${Boost_PROGRAM_OPTIONS_LIBRARY}")
|
||||
|
|
|
@ -48,8 +48,10 @@ using ConcurrentMapBase = gtsam::FastMap<KEY, VALUE>;
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/split_member.hpp>
|
||||
#endif
|
||||
#include <boost/static_assert.hpp>
|
||||
|
||||
#include <gtsam/base/FastVector.h>
|
||||
|
@ -100,6 +102,7 @@ public:
|
|||
#endif
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -120,6 +123,7 @@ private:
|
|||
this->insert(map.begin(), map.end());
|
||||
}
|
||||
BOOST_SERIALIZATION_SPLIT_MEMBER()
|
||||
#endif
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -21,10 +21,11 @@
|
|||
#include <gtsam/base/FastDefaultAllocator.h>
|
||||
#include <list>
|
||||
#include <boost/utility/enable_if.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/version.hpp>
|
||||
#include <boost/serialization/optional.hpp>
|
||||
#include <boost/serialization/list.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -76,12 +77,14 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -19,8 +19,10 @@
|
|||
#pragma once
|
||||
|
||||
#include <gtsam/base/FastDefaultAllocator.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/map.hpp>
|
||||
#endif
|
||||
#include <map>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -67,12 +69,14 @@ public:
|
|||
bool exists(const KEY& e) const { return this->find(e) != this->end(); }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -19,11 +19,13 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/version.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#if BOOST_VERSION >= 107400
|
||||
#include <boost/serialization/library_version_type.hpp>
|
||||
#endif
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/set.hpp>
|
||||
#endif
|
||||
#include <gtsam/base/FastDefaultAllocator.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
|
||||
|
@ -121,12 +123,14 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -175,6 +175,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -183,6 +184,7 @@ public:
|
|||
boost::serialization::base_object<Value>(*this));
|
||||
ar & boost::serialization::make_nvp("value", value_);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
|
||||
|
|
|
@ -18,6 +18,8 @@
|
|||
|
||||
// \callgraph
|
||||
|
||||
// Defined only if boost serialization is enabled
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Matrix.h>
|
||||
|
@ -87,3 +89,4 @@ void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) {
|
|||
|
||||
} // namespace serialization
|
||||
} // namespace boost
|
||||
#endif
|
||||
|
|
|
@ -21,7 +21,9 @@
|
|||
#include <gtsam/base/Matrix.h>
|
||||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <cassert>
|
||||
#include <stdexcept>
|
||||
#include <array>
|
||||
|
@ -384,6 +386,7 @@ namespace gtsam {
|
|||
template<typename SymmetricBlockMatrixType> friend class SymmetricBlockMatrixBlockExpr;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -396,6 +399,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_NVP(variableColOffsets_);
|
||||
ar & BOOST_SERIALIZATION_NVP(blockStart_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/// Foward declare exception class
|
||||
|
|
|
@ -21,8 +21,10 @@
|
|||
#include <gtsam/config.h> // Configuration from CMake
|
||||
|
||||
#include <gtsam/base/Vector.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/assume_abstract.hpp>
|
||||
#endif
|
||||
#include <memory>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -119,13 +121,17 @@ namespace gtsam {
|
|||
* The last two links explain why these export lines have to be in the same source module that includes
|
||||
* any of the archive class headers.
|
||||
* */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & /*ar*/, const unsigned int /*version*/) {
|
||||
}
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
} /* namespace gtsam */
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value)
|
||||
#endif
|
||||
|
|
|
@ -16,6 +16,8 @@
|
|||
* @date February 2022
|
||||
*/
|
||||
|
||||
// Defined only if boost serialization is enabled
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/base/Vector.h>
|
||||
|
@ -63,3 +65,4 @@ BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector)
|
|||
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector2)
|
||||
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector3)
|
||||
BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector6)
|
||||
#endif
|
||||
|
|
|
@ -219,6 +219,7 @@ namespace gtsam {
|
|||
friend class SymmetricBlockMatrix;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -229,6 +230,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_NVP(rowEnd_);
|
||||
ar & BOOST_SERIALIZATION_NVP(blockStart_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
* @date Feb 7, 2012
|
||||
*/
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#pragma once
|
||||
|
||||
#include <iostream>
|
||||
|
@ -175,3 +176,4 @@ bool equalsDereferencedBinary(const T& input = T()) {
|
|||
|
||||
} // \namespace serializationTestHelpers
|
||||
} // \namespace gtsam
|
||||
#endif
|
||||
|
|
|
@ -9,6 +9,8 @@
|
|||
* Inspired from this PR: https://github.com/boostorg/serialization/pull/163
|
||||
* ---------------------------------------------------------------------------- */
|
||||
|
||||
// Defined only if boost serialization is enabled
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#pragma once
|
||||
#include <optional>
|
||||
#include <boost/config.hpp>
|
||||
|
@ -97,4 +99,4 @@ void serialize(Archive& ar, std::optional<T>& t, const unsigned int version) {
|
|||
|
||||
} // namespace serialization
|
||||
} // namespace boost
|
||||
|
||||
#endif
|
||||
|
|
|
@ -1 +1,9 @@
|
|||
gtsamAddTestsGlob(base "test*.cpp" "" "gtsam")
|
||||
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
|
||||
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
# create a semicolon seperated list of files to exclude
|
||||
set(EXCLUDE_TESTS "testSerializationBase.cpp" "testStdOptionalSerialization.cpp")
|
||||
else()
|
||||
set(EXCLUDE_TESTS "")
|
||||
endif()
|
||||
|
||||
gtsamAddTestsGlob(base "test*.cpp" "${EXCLUDE_TESTS}" "gtsam")
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
|
||||
#include <boost/version.hpp>
|
||||
|
||||
#include <memory>
|
||||
#include <cstddef>
|
||||
#include <string>
|
||||
|
||||
|
|
|
@ -28,6 +28,7 @@
|
|||
#include <vector>
|
||||
#include <string>
|
||||
#include <memory>
|
||||
#include <cassert>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
|
|
@ -154,6 +154,7 @@ namespace gtsam {
|
|||
private:
|
||||
using Base = DecisionTree<L, Y>::Node;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -162,6 +163,7 @@ namespace gtsam {
|
|||
ar& BOOST_SERIALIZATION_NVP(constant_);
|
||||
ar& BOOST_SERIALIZATION_NVP(nrAssignments_);
|
||||
}
|
||||
#endif
|
||||
}; // Leaf
|
||||
|
||||
/****************************************************************************/
|
||||
|
@ -443,6 +445,7 @@ namespace gtsam {
|
|||
private:
|
||||
using Base = DecisionTree<L, Y>::Node;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -452,6 +455,7 @@ namespace gtsam {
|
|||
ar& BOOST_SERIALIZATION_NVP(branches_);
|
||||
ar& BOOST_SERIALIZATION_NVP(allSame_);
|
||||
}
|
||||
#endif
|
||||
}; // Choice
|
||||
|
||||
/****************************************************************************/
|
||||
|
|
|
@ -23,7 +23,9 @@
|
|||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/discrete/Assignment.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <memory>
|
||||
#include <functional>
|
||||
#include <iostream>
|
||||
|
@ -117,10 +119,12 @@ namespace gtsam {
|
|||
virtual bool isLeaf() const = 0;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {}
|
||||
#endif
|
||||
};
|
||||
/** ------------------------ Node base class --------------------------- */
|
||||
|
||||
|
@ -374,12 +378,14 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||
ar& BOOST_SERIALIZATION_NVP(root_);
|
||||
}
|
||||
#endif
|
||||
}; // DecisionTree
|
||||
|
||||
template <class L, class Y>
|
||||
|
|
|
@ -253,6 +253,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -261,6 +262,7 @@ namespace gtsam {
|
|||
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(ADT);
|
||||
ar& BOOST_SERIALIZATION_NVP(cardinalities_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
// traits
|
||||
|
|
|
@ -150,12 +150,14 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet<DiscreteConditional> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
// traits
|
||||
|
|
|
@ -268,6 +268,7 @@ class GTSAM_EXPORT DiscreteConditional
|
|||
bool forceComplete) const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -275,6 +276,7 @@ class GTSAM_EXPORT DiscreteConditional
|
|||
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor);
|
||||
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
// DiscreteConditional
|
||||
|
||||
|
|
|
@ -21,7 +21,9 @@
|
|||
#include <gtsam/global_includes.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/vector.hpp>
|
||||
#endif
|
||||
#include <map>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
@ -79,6 +81,7 @@ namespace gtsam {
|
|||
/// Check equality to another DiscreteKeys object.
|
||||
bool equals(const DiscreteKeys& other, double tol = 0) const;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -87,6 +90,7 @@ namespace gtsam {
|
|||
"DiscreteKeys",
|
||||
boost::serialization::base_object<std::vector<DiscreteKey>>(*this));
|
||||
}
|
||||
#endif
|
||||
|
||||
}; // DiscreteKeys
|
||||
|
||||
|
|
|
@ -126,12 +126,14 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet<DiscreteLookupTable> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
// traits
|
||||
|
|
|
@ -1 +1,9 @@
|
|||
gtsamAddTestsGlob(discrete "test*.cpp" "" "gtsam")
|
||||
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
|
||||
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
# create a semicolon seperated list of files to exclude
|
||||
set(EXCLUDE_TESTS "testSerializationDiscrete.cpp" "testDiscreteFactor.cpp")
|
||||
else()
|
||||
set(EXCLUDE_TESTS "")
|
||||
endif()
|
||||
|
||||
gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam")
|
||||
|
|
|
@ -22,7 +22,9 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/OptionalJacobian.h>
|
||||
#include <boost/concept/assert.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <iostream>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -147,6 +149,7 @@ public:
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// Serialization function
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||
|
@ -155,6 +158,7 @@ private:
|
|||
}
|
||||
|
||||
friend class boost::serialization::access;
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -184,6 +184,7 @@ class GTSAM_EXPORT Cal3 {
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -194,6 +195,7 @@ class GTSAM_EXPORT Cal3 {
|
|||
ar& BOOST_SERIALIZATION_NVP(u0_);
|
||||
ar& BOOST_SERIALIZATION_NVP(v0_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -156,6 +156,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -166,6 +167,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
|
|||
ar& BOOST_SERIALIZATION_NVP(k2_);
|
||||
ar& BOOST_SERIALIZATION_NVP(tol_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -104,6 +104,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -111,6 +112,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
|
|||
ar& boost::serialization::make_nvp(
|
||||
"Cal3DS2", boost::serialization::base_object<Cal3DS2_Base>(*this));
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -156,6 +156,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -168,6 +169,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
|
|||
ar& BOOST_SERIALIZATION_NVP(p2_);
|
||||
ar& BOOST_SERIALIZATION_NVP(tol_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -184,6 +184,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -195,6 +196,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
|
|||
ar& BOOST_SERIALIZATION_NVP(k3_);
|
||||
ar& BOOST_SERIALIZATION_NVP(k4_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -138,6 +138,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -146,6 +147,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
|
|||
"Cal3Unified", boost::serialization::base_object<Cal3DS2_Base>(*this));
|
||||
ar& BOOST_SERIALIZATION_NVP(xi_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
template <>
|
||||
|
|
|
@ -132,6 +132,7 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 {
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -139,6 +140,7 @@ class GTSAM_EXPORT Cal3_S2 : public Cal3 {
|
|||
ar& boost::serialization::make_nvp(
|
||||
"Cal3_S2", boost::serialization::base_object<Cal3>(*this));
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -143,6 +143,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
|
|||
/// @{
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -151,6 +152,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
|
|||
"Cal3_S2", boost::serialization::base_object<Cal3_S2>(*this));
|
||||
ar& BOOST_SERIALIZATION_NVP(b_);
|
||||
}
|
||||
#endif
|
||||
/// @}
|
||||
};
|
||||
|
||||
|
|
|
@ -25,7 +25,9 @@
|
|||
#include <gtsam/base/Manifold.h>
|
||||
#include <gtsam/base/ThreadsafeException.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -228,12 +230,14 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(pose_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
// end of class PinholeBase
|
||||
|
||||
|
@ -412,6 +416,7 @@ private:
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -420,6 +425,7 @@ private:
|
|||
& boost::serialization::make_nvp("PinholeBase",
|
||||
boost::serialization::base_object<PinholeBase>(*this));
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -465,12 +465,14 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||
ar&(*this);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
|
@ -180,6 +180,7 @@ class EssentialMatrix {
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -197,6 +198,7 @@ class EssentialMatrix {
|
|||
ar & boost::serialization::make_nvp("E32", E_(2, 1));
|
||||
ar & boost::serialization::make_nvp("E33", E_(2, 2));
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -326,6 +326,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -335,6 +336,7 @@ private:
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(K_);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
|
@ -217,6 +217,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -225,6 +226,7 @@ private:
|
|||
& boost::serialization::make_nvp("PinholeBase",
|
||||
boost::serialization::base_object<PinholeBase>(*this));
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
@ -429,6 +431,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -438,6 +441,7 @@ private:
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(K_);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
|
@ -64,12 +64,14 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
template<class CAMERA>
|
||||
|
|
|
@ -19,7 +19,9 @@
|
|||
|
||||
#include <gtsam/base/VectorSpace.h>
|
||||
#include <gtsam/base/std_optional_serialization.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
#include <optional>
|
||||
|
||||
|
|
|
@ -26,7 +26,9 @@
|
|||
#include <gtsam/base/Vector.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
#include <gtsam/base/VectorSerialization.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <numeric>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -326,6 +326,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION //
|
||||
// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -333,6 +334,7 @@ public:
|
|||
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||
ar & BOOST_SERIALIZATION_NVP(r_);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
// Align for Point2, which is either derived from, or is typedef, of Vector2
|
||||
|
|
|
@ -389,6 +389,7 @@ public:
|
|||
friend std::ostream &operator<<(std::ostream &os, const Pose3& p);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -396,6 +397,7 @@ public:
|
|||
ar & BOOST_SERIALIZATION_NVP(R_);
|
||||
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||
}
|
||||
#endif
|
||||
/// @}
|
||||
|
||||
#ifdef GTSAM_USE_QUATERNIONS
|
||||
|
|
|
@ -213,6 +213,7 @@ namespace gtsam {
|
|||
static Rot2 ClosestTo(const Matrix2& M);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -220,6 +221,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_NVP(c_);
|
||||
ar & BOOST_SERIALIZATION_NVP(s_);
|
||||
}
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -528,6 +528,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -550,6 +551,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
|
|||
ar& boost::serialization::make_nvp("z", quaternion_.z());
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef GTSAM_USE_QUATERNIONS
|
||||
// only align if quaternion, Matrix3 has no alignment requirements
|
||||
|
|
|
@ -99,8 +99,9 @@ template <>
|
|||
GTSAM_EXPORT
|
||||
Vector9 SO3::vec(OptionalJacobian<9, 3> H) const;
|
||||
|
||||
/** Serialization function */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
template <class Archive>
|
||||
/** Serialization function */
|
||||
void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {
|
||||
Matrix3& M = R.matrix_;
|
||||
ar& boost::serialization::make_nvp("R11", M(0, 0));
|
||||
|
@ -113,6 +114,7 @@ void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {
|
|||
ar& boost::serialization::make_nvp("R32", M(2, 1));
|
||||
ar& boost::serialization::make_nvp("R33", M(2, 2));
|
||||
}
|
||||
#endif
|
||||
|
||||
namespace so3 {
|
||||
|
||||
|
|
|
@ -78,8 +78,9 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = {});
|
|||
*/
|
||||
GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {});
|
||||
|
||||
/** Serialization function */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
template <class Archive>
|
||||
/** Serialization function */
|
||||
void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) {
|
||||
Matrix4 &M = Q.matrix_;
|
||||
ar &boost::serialization::make_nvp("Q11", M(0, 0));
|
||||
|
@ -102,6 +103,7 @@ void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) {
|
|||
ar &boost::serialization::make_nvp("Q43", M(3, 2));
|
||||
ar &boost::serialization::make_nvp("Q44", M(3, 3));
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Define the traits. internal::LieGroup provides both Lie group and Testable
|
||||
|
|
|
@ -24,7 +24,9 @@
|
|||
#include <gtsam/dllexport.h>
|
||||
#include <Eigen/Core>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
#include <iostream> // TODO(frank): how to avoid?
|
||||
#include <string>
|
||||
|
@ -323,6 +325,7 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
|
|||
/// @name Serialization
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
template <class Archive>
|
||||
friend void save(Archive&, SO&, const unsigned int);
|
||||
template <class Archive>
|
||||
|
@ -331,6 +334,7 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
|
|||
friend void serialize(Archive&, SO&, const unsigned int);
|
||||
friend class boost::serialization::access;
|
||||
friend class Rot3; // for serialize
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
@ -375,6 +379,7 @@ template <>
|
|||
GTSAM_EXPORT
|
||||
typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
template<class Archive>
|
||||
void serialize(
|
||||
|
@ -384,6 +389,7 @@ void serialize(
|
|||
Matrix& M = Q.matrix_;
|
||||
ar& BOOST_SERIALIZATION_NVP(M);
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Define the traits. internal::LieGroup provides both Lie group and Testable
|
||||
|
|
|
@ -26,7 +26,9 @@
|
|||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/Unit3.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -52,6 +54,7 @@ class GTSAM_EXPORT EmptyCal {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -59,6 +62,7 @@ class GTSAM_EXPORT EmptyCal {
|
|||
ar& boost::serialization::make_nvp(
|
||||
"EmptyCal", boost::serialization::base_object<EmptyCal>(*this));
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -219,12 +223,14 @@ class GTSAM_EXPORT SphericalCamera {
|
|||
static size_t Dim() { return 6; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
void serialize(Archive& ar, const unsigned int /*version*/) {
|
||||
ar& BOOST_SERIALIZATION_NVP(pose_);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
|
@ -179,12 +179,14 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(leftCamPose_);
|
||||
ar & BOOST_SERIALIZATION_NVP(K_);
|
||||
}
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -20,7 +20,9 @@
|
|||
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/VectorSpace.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -146,6 +148,7 @@ private:
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -154,6 +157,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(uR_);
|
||||
ar & BOOST_SERIALIZATION_NVP(v_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -199,12 +199,14 @@ private:
|
|||
|
||||
/// @name Advanced Interface
|
||||
/// @{
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(p_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -1 +1,9 @@
|
|||
gtsamAddTestsGlob(geometry "test*.cpp" "" "gtsam")
|
||||
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
|
||||
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
# create a semicolon seperated list of files to exclude
|
||||
set(EXCLUDE_TESTS "testSerializationGeometry.cpp")
|
||||
else()
|
||||
set(EXCLUDE_TESTS "")
|
||||
endif()
|
||||
|
||||
gtsamAddTestsGlob(geometry "test*.cpp" "${EXCLUDE_TESTS}" "gtsam")
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace serializationTestHelpers;
|
||||
|
||||
typedef BearingRange<Pose2, Point2> BearingRange2D;
|
||||
BearingRange2D br2D(1, 2);
|
||||
|
@ -45,13 +44,6 @@ TEST(BearingRange, 2D) {
|
|||
EXPECT(assert_equal(expected, actual));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingRange, Serialization2D) {
|
||||
EXPECT(equalsObj<BearingRange2D>(br2D));
|
||||
EXPECT(equalsXML<BearingRange2D>(br2D));
|
||||
EXPECT(equalsBinary<BearingRange2D>(br2D));
|
||||
}
|
||||
|
||||
//******************************************************************************
|
||||
TEST(BearingRange3D, Concept) {
|
||||
BOOST_CONCEPT_ASSERT((IsManifold<BearingRange3D>));
|
||||
|
@ -64,12 +56,22 @@ TEST(BearingRange, 3D) {
|
|||
EXPECT(assert_equal(expected, actual));
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
using namespace serializationTestHelpers;
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingRange, Serialization2D) {
|
||||
EXPECT(equalsObj<BearingRange2D>(br2D));
|
||||
EXPECT(equalsXML<BearingRange2D>(br2D));
|
||||
EXPECT(equalsBinary<BearingRange2D>(br2D));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingRange, Serialization3D) {
|
||||
EXPECT(equalsObj<BearingRange3D>(br3D));
|
||||
EXPECT(equalsXML<BearingRange3D>(br3D));
|
||||
EXPECT(equalsBinary<BearingRange3D>(br3D));
|
||||
}
|
||||
#endif
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() {
|
||||
|
|
|
@ -499,12 +499,14 @@ TEST(Unit3, CopyAssign) {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
TEST(actualH, Serialization) {
|
||||
Unit3 p(0, 1, 0);
|
||||
EXPECT(serializationTestHelpers::equalsObj(p));
|
||||
EXPECT(serializationTestHelpers::equalsXML(p));
|
||||
EXPECT(serializationTestHelpers::equalsBinary(p));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -611,6 +611,7 @@ struct GTSAM_EXPORT TriangulationParameters {
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -620,6 +621,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(landmarkDistanceThreshold);
|
||||
ar & BOOST_SERIALIZATION_NVP(dynamicOutlierRejectionThreshold);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -674,12 +676,14 @@ class TriangulationResult : public std::optional<Point3> {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int version) {
|
||||
ar& BOOST_SERIALIZATION_NVP(status);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/// triangulateSafe: extensive checking of the outcome
|
||||
|
|
|
@ -255,6 +255,7 @@ class GTSAM_EXPORT GaussianMixture
|
|||
/// Check whether `given` has values for all frontal keys.
|
||||
bool allFrontalsGiven(const VectorValues &given) const;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -263,6 +264,7 @@ class GTSAM_EXPORT GaussianMixture
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
|
||||
ar &BOOST_SERIALIZATION_NVP(conditionals_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/// Return the DiscreteKey vector as a set.
|
||||
|
|
|
@ -152,6 +152,7 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -159,6 +160,7 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor {
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar &BOOST_SERIALIZATION_NVP(factors_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
// traits
|
||||
|
|
|
@ -228,12 +228,14 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
|
|||
*/
|
||||
void updateDiscreteConditionals(const DecisionTreeFactor &prunedDecisionTree);
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
|
||||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/// traits
|
||||
|
|
|
@ -114,12 +114,14 @@ class GTSAM_EXPORT HybridBayesTree : public BayesTree<HybridBayesTreeClique> {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/// traits
|
||||
|
|
|
@ -204,6 +204,7 @@ class GTSAM_EXPORT HybridConditional
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
|
@ -225,6 +226,7 @@ class GTSAM_EXPORT HybridConditional
|
|||
static_cast<GaussianMixture*>(NULL), static_cast<Factor*>(NULL));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
}; // HybridConditional
|
||||
|
||||
|
|
|
@ -137,6 +137,7 @@ class GTSAM_EXPORT HybridFactor : public Factor {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -148,6 +149,7 @@ class GTSAM_EXPORT HybridFactor : public Factor {
|
|||
ar &BOOST_SERIALIZATION_NVP(discreteKeys_);
|
||||
ar &BOOST_SERIALIZATION_NVP(continuousKeys_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
// HybridFactor
|
||||
|
||||
|
|
|
@ -1 +1,9 @@
|
|||
gtsamAddTestsGlob(hybrid "test*.cpp" "" "gtsam")
|
||||
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
|
||||
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
# create a semicolon seperated list of files to exclude
|
||||
set(EXCLUDE_TESTS "testSerializationHybrid.cpp")
|
||||
else()
|
||||
set(EXCLUDE_TESTS "")
|
||||
endif()
|
||||
|
||||
gtsamAddTestsGlob(hybrid "test*.cpp" "${EXCLUDE_TESTS}" "gtsam")
|
||||
|
|
|
@ -259,6 +259,7 @@ namespace gtsam {
|
|||
template<class BAYESTREE, class GRAPH> friend class EliminatableClusterTree;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -266,6 +267,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_NVP(nodes_);
|
||||
ar & BOOST_SERIALIZATION_NVP(roots_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -199,6 +199,7 @@ namespace gtsam {
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -213,6 +214,7 @@ namespace gtsam {
|
|||
}
|
||||
ar & BOOST_SERIALIZATION_NVP(children);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -213,12 +213,14 @@ namespace gtsam {
|
|||
// Cast to derived type (const) (casts down to derived conditional type, then up to factor type)
|
||||
const FACTOR& asFactor() const { return static_cast<const FACTOR&>(static_cast<const DERIVEDCONDITIONAL&>(*this)); }
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(nrFrontals_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -21,7 +21,9 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <memory>
|
||||
|
||||
#include <gtsam/base/types.h>
|
||||
|
@ -190,16 +192,16 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// @name Serialization
|
||||
/// @{
|
||||
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(keys_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -30,8 +30,10 @@
|
|||
#include <Eigen/Core> // for Eigen::aligned_allocator
|
||||
|
||||
#include <boost/assign/list_inserter.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/vector.hpp>
|
||||
#endif
|
||||
|
||||
#include <string>
|
||||
#include <type_traits>
|
||||
|
@ -433,12 +435,14 @@ class FactorGraph {
|
|||
inline bool exists(size_t idx) const { return idx < size() && at(idx); }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||
ar& BOOST_SERIALIZATION_NVP(factors_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
}; // FactorGraph
|
||||
|
|
|
@ -112,6 +112,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -120,6 +121,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(label_);
|
||||
ar & BOOST_SERIALIZATION_NVP(j_);
|
||||
}
|
||||
#endif
|
||||
}; // \class LabeledSymbol
|
||||
|
||||
/** Create a symbol key from a character, label and index, i.e. xA5. */
|
||||
|
|
|
@ -256,12 +256,14 @@ private:
|
|||
static GTSAM_EXPORT Ordering ColamdConstrained(
|
||||
const VariableIndex& variableIndex, std::vector<int>& cmember);
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/// traits
|
||||
|
|
|
@ -21,7 +21,9 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <cstdint>
|
||||
#include <functional>
|
||||
|
||||
|
@ -122,6 +124,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -129,6 +132,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(c_);
|
||||
ar & BOOST_SERIALIZATION_NVP(j_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** Create a symbol key from a character and index, i.e. x5. */
|
||||
|
|
|
@ -190,6 +190,7 @@ protected:
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -198,6 +199,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(nFactors_);
|
||||
ar & BOOST_SERIALIZATION_NVP(nEntries_);
|
||||
}
|
||||
#endif
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
|
|
@ -256,12 +256,14 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/// traits
|
||||
|
|
|
@ -274,6 +274,7 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
|
@ -281,6 +282,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor);
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
|
||||
}
|
||||
#endif
|
||||
}; // GaussianConditional
|
||||
|
||||
/// traits
|
||||
|
|
|
@ -163,12 +163,14 @@ namespace gtsam {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
|
||||
}; // GaussianFactor
|
||||
|
||||
|
|
|
@ -403,12 +403,14 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -363,6 +363,7 @@ namespace gtsam {
|
|||
friend class NonlinearFactorGraph;
|
||||
friend class NonlinearClusterTree;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -370,6 +371,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor);
|
||||
ar & BOOST_SERIALIZATION_NVP(info_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -24,8 +24,10 @@
|
|||
#include <gtsam/global_includes.h>
|
||||
#include <gtsam/inference/VariableSlots.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/version.hpp>
|
||||
#include <boost/serialization/split_member.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -413,6 +415,7 @@ namespace gtsam {
|
|||
// be very selective on who can access these private methods:
|
||||
template<typename T> friend class ExpressionFactor;
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -450,6 +453,7 @@ namespace gtsam {
|
|||
}
|
||||
|
||||
BOOST_SERIALIZATION_SPLIT_MEMBER()
|
||||
#endif
|
||||
}; // JacobianFactor
|
||||
/// traits
|
||||
template<>
|
||||
|
@ -458,7 +462,9 @@ struct traits<JacobianFactor> : public Testable<JacobianFactor> {
|
|||
|
||||
} // \ namespace gtsam
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
BOOST_CLASS_VERSION(gtsam::JacobianFactor, 1)
|
||||
#endif
|
||||
|
||||
#include <gtsam/linear/JacobianFactor-inl.h>
|
||||
|
||||
|
|
|
@ -23,12 +23,14 @@
|
|||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/extended_type_info.hpp>
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/version.hpp>
|
||||
#include <boost/serialization/optional.hpp>
|
||||
#include <boost/serialization/shared_ptr.hpp>
|
||||
#include <boost/serialization/singleton.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
namespace noiseModel {
|
||||
|
@ -126,12 +128,14 @@ class GTSAM_EXPORT Base {
|
|||
void reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
|
||||
ar &BOOST_SERIALIZATION_NVP(reweight_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** "Null" robust loss function, equivalent to a Gaussian pdf noise model, or
|
||||
|
@ -156,12 +160,14 @@ class GTSAM_EXPORT Null : public Base {
|
|||
static shared_ptr Create();
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
|
||||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** Implementation of the "Fair" robust error model (Zhang97ivc)
|
||||
|
@ -188,6 +194,7 @@ class GTSAM_EXPORT Fair : public Base {
|
|||
double modelParameter() const { return c_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -195,6 +202,7 @@ class GTSAM_EXPORT Fair : public Base {
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar &BOOST_SERIALIZATION_NVP(c_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** The "Huber" robust error model (Zhang97ivc).
|
||||
|
@ -221,6 +229,7 @@ class GTSAM_EXPORT Huber : public Base {
|
|||
double modelParameter() const { return k_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -228,6 +237,7 @@ class GTSAM_EXPORT Huber : public Base {
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar &BOOST_SERIALIZATION_NVP(k_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** Implementation of the "Cauchy" robust error model (Lee2013IROS).
|
||||
|
@ -259,6 +269,7 @@ class GTSAM_EXPORT Cauchy : public Base {
|
|||
double modelParameter() const { return k_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -267,6 +278,7 @@ class GTSAM_EXPORT Cauchy : public Base {
|
|||
ar &BOOST_SERIALIZATION_NVP(k_);
|
||||
ar &BOOST_SERIALIZATION_NVP(ksquared_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** Implementation of the "Tukey" robust error model (Zhang97ivc).
|
||||
|
@ -293,6 +305,7 @@ class GTSAM_EXPORT Tukey : public Base {
|
|||
double modelParameter() const { return c_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -300,6 +313,7 @@ class GTSAM_EXPORT Tukey : public Base {
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar &BOOST_SERIALIZATION_NVP(c_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** Implementation of the "Welsch" robust error model (Zhang97ivc).
|
||||
|
@ -326,6 +340,7 @@ class GTSAM_EXPORT Welsch : public Base {
|
|||
double modelParameter() const { return c_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -334,6 +349,7 @@ class GTSAM_EXPORT Welsch : public Base {
|
|||
ar &BOOST_SERIALIZATION_NVP(c_);
|
||||
ar &BOOST_SERIALIZATION_NVP(csquared_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** Implementation of the "Geman-McClure" robust error model (Zhang97ivc).
|
||||
|
@ -363,6 +379,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
|
|||
double c_;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -370,6 +387,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar &BOOST_SERIALIZATION_NVP(c_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** DCS implements the Dynamic Covariance Scaling robust error model
|
||||
|
@ -401,6 +419,7 @@ class GTSAM_EXPORT DCS : public Base {
|
|||
double c_;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -408,6 +427,7 @@ class GTSAM_EXPORT DCS : public Base {
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar &BOOST_SERIALIZATION_NVP(c_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/** L2WithDeadZone implements a standard L2 penalty, but with a dead zone of
|
||||
|
@ -439,6 +459,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base {
|
|||
double modelParameter() const { return k_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -446,6 +467,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base {
|
|||
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar &BOOST_SERIALIZATION_NVP(k_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
} // namespace mEstimator
|
||||
|
|
|
@ -24,10 +24,12 @@
|
|||
#include <gtsam/dllexport.h>
|
||||
#include <gtsam/linear/LossFunctions.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#include <boost/serialization/extended_type_info.hpp>
|
||||
#include <boost/serialization/singleton.hpp>
|
||||
#include <boost/serialization/shared_ptr.hpp>
|
||||
#endif
|
||||
|
||||
#include <optional>
|
||||
|
||||
|
@ -139,12 +141,14 @@ namespace gtsam {
|
|||
virtual double weight(const Vector& v) const { return 1.0; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(dim_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
//---------------------------------------------------------------------------------------
|
||||
|
@ -263,6 +267,7 @@ namespace gtsam {
|
|||
virtual Matrix covariance() const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -270,7 +275,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
ar & BOOST_SERIALIZATION_NVP(sqrt_information_);
|
||||
}
|
||||
|
||||
#endif
|
||||
}; // Gaussian
|
||||
|
||||
//---------------------------------------------------------------------------------------
|
||||
|
@ -356,6 +361,7 @@ namespace gtsam {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -364,6 +370,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_NVP(sigmas_);
|
||||
ar & BOOST_SERIALIZATION_NVP(invsigmas_);
|
||||
}
|
||||
#endif
|
||||
}; // Diagonal
|
||||
|
||||
//---------------------------------------------------------------------------------------
|
||||
|
@ -499,6 +506,7 @@ namespace gtsam {
|
|||
shared_ptr unit() const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -506,6 +514,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal);
|
||||
ar & BOOST_SERIALIZATION_NVP(mu_);
|
||||
}
|
||||
#endif
|
||||
|
||||
}; // Constrained
|
||||
|
||||
|
@ -567,6 +576,7 @@ namespace gtsam {
|
|||
inline double sigma() const { return sigma_; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -575,6 +585,7 @@ namespace gtsam {
|
|||
ar & BOOST_SERIALIZATION_NVP(sigma_);
|
||||
ar & BOOST_SERIALIZATION_NVP(invsigma_);
|
||||
}
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
|
@ -616,12 +627,14 @@ namespace gtsam {
|
|||
void unwhitenInPlace(Eigen::Block<Vector>& /*v*/) const override {}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Isotropic);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -705,6 +718,7 @@ namespace gtsam {
|
|||
const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -713,6 +727,7 @@ namespace gtsam {
|
|||
ar & boost::serialization::make_nvp("robust_", const_cast<RobustModel::shared_ptr&>(robust_));
|
||||
ar & boost::serialization::make_nvp("noise_", const_cast<NoiseModel::shared_ptr&>(noise_));
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
// Helper function
|
||||
|
|
|
@ -27,7 +27,9 @@
|
|||
#include <boost/algorithm/string.hpp>
|
||||
#include <boost/archive/text_iarchive.hpp>
|
||||
#include <boost/archive/text_oarchive.hpp>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/vector.hpp>
|
||||
#endif
|
||||
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
|
@ -91,6 +93,7 @@ vector<size_t> Subgraph::edgeIndices() const {
|
|||
return eid;
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/****************************************************************************/
|
||||
void Subgraph::save(const std::string &fn) const {
|
||||
std::ofstream os(fn.c_str());
|
||||
|
@ -108,6 +111,7 @@ Subgraph Subgraph::load(const std::string &fn) {
|
|||
is.close();
|
||||
return subgraph;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************/
|
||||
ostream &operator<<(ostream &os, const Subgraph::Edge &edge) {
|
||||
|
|
|
@ -21,8 +21,10 @@
|
|||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/dllexport.h>
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/version.hpp>
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
#include <memory>
|
||||
|
||||
#include <vector>
|
||||
|
@ -49,12 +51,14 @@ class GTSAM_EXPORT Subgraph {
|
|||
friend std::ostream &operator<<(std::ostream &os, const Edge &edge);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
void serialize(Archive &ar, const unsigned int /*version*/) {
|
||||
ar &BOOST_SERIALIZATION_NVP(index);
|
||||
ar &BOOST_SERIALIZATION_NVP(weight);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
typedef std::vector<Edge> Edges;
|
||||
|
@ -80,16 +84,18 @@ class GTSAM_EXPORT Subgraph {
|
|||
iterator end() { return edges_.end(); }
|
||||
const_iterator end() const { return edges_.end(); }
|
||||
|
||||
void save(const std::string &fn) const;
|
||||
static Subgraph load(const std::string &fn);
|
||||
friend std::ostream &operator<<(std::ostream &os, const Subgraph &subgraph);
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template <class Archive>
|
||||
void serialize(Archive &ar, const unsigned int /*version*/) {
|
||||
ar &BOOST_SERIALIZATION_NVP(edges_);
|
||||
}
|
||||
void save(const std::string &fn) const;
|
||||
static Subgraph load(const std::string &fn);
|
||||
#endif
|
||||
};
|
||||
|
||||
/****************************************************************************/
|
||||
|
|
|
@ -368,12 +368,14 @@ namespace gtsam {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
ar & BOOST_SERIALIZATION_NVP(values_);
|
||||
}
|
||||
#endif
|
||||
}; // VectorValues definition
|
||||
|
||||
/// traits
|
||||
|
|
|
@ -1,6 +1,15 @@
|
|||
gtsamAddTestsGlob(linear "test*.cpp" "" "gtsam")
|
||||
|
||||
if(MSVC)
|
||||
set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationLinear.cpp"
|
||||
APPEND PROPERTY COMPILE_FLAGS "/bigobj")
|
||||
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
|
||||
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
|
||||
# create a semicolon seperated list of files to exclude
|
||||
set(EXCLUDE_TESTS "testSerializationLinear.cpp")
|
||||
else()
|
||||
set(EXCLUDE_TESTS "")
|
||||
endif()
|
||||
|
||||
gtsamAddTestsGlob(linear "test*.cpp" "${EXCLUDE_TESTS}" "gtsam")
|
||||
|
||||
# Set properties to serialization target if Boost serialization is enabled and MSVC
|
||||
if (GTSAM_ENABLE_BOOST_SERIALIZATION AND MSVC)
|
||||
set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationLinear.cpp"
|
||||
APPEND PROPERTY COMPILE_FLAGS "/bigobj")
|
||||
endif()
|
||||
|
|
|
@ -120,6 +120,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -128,6 +129,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(p_);
|
||||
ar & BOOST_SERIALIZATION_NVP(biasHat_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN<Rot3, Rot3, Vector3> {
|
||||
|
@ -206,6 +208,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -216,6 +219,7 @@ private:
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(_PIM_);
|
||||
}
|
||||
#endif
|
||||
|
||||
};
|
||||
// AHRSFactor
|
||||
|
|
|
@ -63,6 +63,7 @@ public:
|
|||
return bRef_;
|
||||
}
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -70,6 +71,7 @@ public:
|
|||
ar & boost::serialization::make_nvp("nZ_", nZ_);
|
||||
ar & boost::serialization::make_nvp("bRef_", bRef_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -130,6 +132,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -140,6 +143,7 @@ private:
|
|||
ar & boost::serialization::make_nvp("AttitudeFactor",
|
||||
boost::serialization::base_object<AttitudeFactor>(*this));
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
@ -213,6 +217,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -223,6 +228,7 @@ private:
|
|||
ar & boost::serialization::make_nvp("AttitudeFactor",
|
||||
boost::serialization::base_object<AttitudeFactor>(*this));
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
|
@ -97,6 +97,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
|
|||
};
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -107,6 +108,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar& BOOST_SERIALIZATION_NVP(nT_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -21,7 +21,9 @@
|
|||
**/
|
||||
|
||||
#include <gtsam/navigation/CombinedImuFactor.h>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/export.hpp>
|
||||
#endif
|
||||
|
||||
/* External or standard includes */
|
||||
#include <ostream>
|
||||
|
|
|
@ -101,6 +101,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -111,6 +112,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance);
|
||||
ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
@ -223,6 +225,7 @@ public:
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -231,6 +234,7 @@ public:
|
|||
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
|
||||
ar& BOOST_SERIALIZATION_NVP(preintMeasCov_);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
|
@ -97,6 +97,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -107,6 +108,7 @@ private:
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(nT_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -164,6 +166,7 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -174,6 +177,7 @@ private:
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(nT_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
} /// namespace gtsam
|
||||
|
|
|
@ -20,7 +20,9 @@
|
|||
#include <gtsam/base/OptionalJacobian.h>
|
||||
#include <gtsam/base/VectorSpace.h>
|
||||
#include <iosfwd>
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
#include <boost/serialization/nvp.hpp>
|
||||
#endif
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -140,6 +142,7 @@ private:
|
|||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -147,6 +150,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(biasAcc_);
|
||||
ar & BOOST_SERIALIZATION_NVP(biasGyro_);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
public:
|
||||
|
|
|
@ -146,6 +146,7 @@ public:
|
|||
#endif
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -154,6 +155,7 @@ public:
|
|||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
|
||||
ar & BOOST_SERIALIZATION_NVP(preintMeasCov_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -246,6 +248,7 @@ public:
|
|||
|
||||
private:
|
||||
/** Serialization function */
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
|
@ -254,6 +257,7 @@ public:
|
|||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(_PIM_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
// class ImuFactor
|
||||
|
||||
|
|
|
@ -132,6 +132,7 @@ class MagPoseFactor: public NoiseModelFactorN<POSE> {
|
|||
}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
/// Serialization function.
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -144,6 +145,7 @@ class MagPoseFactor: public NoiseModelFactorN<POSE> {
|
|||
ar & BOOST_SERIALIZATION_NVP(bias_);
|
||||
ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
|
||||
}
|
||||
#endif
|
||||
}; // \class MagPoseFactor
|
||||
|
||||
} /// namespace gtsam
|
||||
|
|
|
@ -113,6 +113,7 @@ public:
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -126,6 +127,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(delVdelBiasAcc_);
|
||||
ar & BOOST_SERIALIZATION_NVP(delVdelBiasOmega_);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
} /// namespace gtsam
|
||||
|
|
|
@ -190,6 +190,7 @@ public:
|
|||
private:
|
||||
/// @{
|
||||
/// serialization
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
|
||||
|
@ -197,6 +198,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(t_);
|
||||
ar & BOOST_SERIALIZATION_NVP(v_);
|
||||
}
|
||||
#endif
|
||||
/// @}
|
||||
};
|
||||
|
||||
|
|
|
@ -60,6 +60,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams {
|
|||
std::optional<Pose3> getBodyPSensor() const { return body_P_sensor; }
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -75,6 +76,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams {
|
|||
ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef GTSAM_USE_QUATERNIONS
|
||||
// Align if we are using Quaternions
|
||||
|
@ -179,6 +181,7 @@ class GTSAM_EXPORT PreintegratedRotation {
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template <class ARCHIVE>
|
||||
|
@ -188,6 +191,7 @@ class GTSAM_EXPORT PreintegratedRotation {
|
|||
ar& BOOST_SERIALIZATION_NVP(deltaRij_);
|
||||
ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef GTSAM_USE_QUATERNIONS
|
||||
// Align if we are using Quaternions
|
||||
|
|
|
@ -173,6 +173,7 @@ class GTSAM_EXPORT PreintegrationBase {
|
|||
OptionalJacobian<9, 6> H5 = {}) const;
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -181,6 +182,7 @@ class GTSAM_EXPORT PreintegrationBase {
|
|||
ar & BOOST_SERIALIZATION_NVP(biasHat_);
|
||||
ar & BOOST_SERIALIZATION_NVP(deltaTij_);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
|
@ -71,6 +71,7 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams {
|
|||
|
||||
protected:
|
||||
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -82,6 +83,7 @@ protected:
|
|||
ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis);
|
||||
ar & BOOST_SERIALIZATION_NVP(n_gravity);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef GTSAM_USE_QUATERNIONS
|
||||
// Align if we are using Quaternions
|
||||
|
|
|
@ -127,6 +127,7 @@ public:
|
|||
/// @}
|
||||
|
||||
private:
|
||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
@ -137,6 +138,7 @@ private:
|
|||
ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_);
|
||||
ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_);
|
||||
}
|
||||
#endif
|
||||
|
||||
public:
|
||||
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue