gtsam compiles and tests run with and without boost serialization

release/4.3a0
kartik arcot 2023-01-18 15:25:07 -08:00 committed by Kartik Arcot
parent efacfb81a0
commit b63a8b9542
42 changed files with 134 additions and 19 deletions

View File

@ -113,7 +113,6 @@ private:
std::copy(this->begin(), this->end(), map.begin());
ar & BOOST_SERIALIZATION_NVP(map);
}
#endif
template<class Archive>
void load(Archive& ar, const unsigned int /*version*/)
{
@ -124,6 +123,7 @@ private:
this->insert(map.begin(), map.end());
}
BOOST_SERIALIZATION_SPLIT_MEMBER()
#endif
};
}

View File

@ -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

View File

@ -132,4 +132,6 @@ namespace gtsam {
} /* namespace gtsam */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
BOOST_SERIALIZATION_ASSUME_ABSTRACT(gtsam::Value)
#endif

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -23,6 +23,7 @@
#include <boost/version.hpp>
#include <memory>
#include <cstddef>
#include <string>

View File

@ -445,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>
@ -454,6 +455,7 @@ namespace gtsam {
ar& BOOST_SERIALIZATION_NVP(branches_);
ar& BOOST_SERIALIZATION_NVP(allSame_);
}
#endif
}; // Choice
/****************************************************************************/

View File

@ -378,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>

View File

@ -1,7 +1,7 @@
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
# create a semicolon seperated list of files to exclude
set(EXCLUDE_TESTS "testSerializationDiscrete.cpp")
set(EXCLUDE_TESTS "testSerializationDiscrete.cpp" "testDiscreteFactor.cpp")
else()
set(EXCLUDE_TESTS "")
endif()

View File

@ -156,8 +156,8 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
/// @name Advanced Interface
/// @{
/** Serialization function */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class Archive>
void serialize(Archive& ar, const unsigned int /*version*/) {

View File

@ -416,6 +416,7 @@ private:
/// @name Advanced Interface
/// @{
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
@ -424,6 +425,7 @@ private:
& boost::serialization::make_nvp("PinholeBase",
boost::serialization::base_object<PinholeBase>(*this));
}
#endif
/// @}
};

View File

@ -431,6 +431,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
@ -440,6 +441,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(K_);
}
#endif
public:
GTSAM_MAKE_ALIGNED_OPERATOR_NEW

View File

@ -99,6 +99,7 @@ template <>
GTSAM_EXPORT
Vector9 SO3::vec(OptionalJacobian<9, 3> H) const;
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
template <class Archive>
/** Serialization function */
void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {
@ -113,6 +114,7 @@ void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {
ar& boost::serialization::make_nvp("R32", M(2, 1));
ar& boost::serialization::make_nvp("R33", M(2, 2));
}
#endif
namespace so3 {

View File

@ -78,6 +78,7 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = {});
*/
GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = {});
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
template <class Archive>
/** Serialization function */
void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) {
@ -102,6 +103,7 @@ void serialize(Archive &ar, SO4 &Q, const unsigned int /*version*/) {
ar &boost::serialization::make_nvp("Q43", M(3, 2));
ar &boost::serialization::make_nvp("Q44", M(3, 3));
}
#endif
/*
* Define the traits. internal::LieGroup provides both Lie group and Testable

View File

@ -223,12 +223,14 @@ class GTSAM_EXPORT SphericalCamera {
static size_t Dim() { return 6; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class Archive>
void serialize(Archive& ar, const unsigned int /*version*/) {
ar& BOOST_SERIALIZATION_NVP(pose_);
}
#endif
public:
GTSAM_MAKE_ALIGNED_OPERATOR_NEW

View File

@ -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() {

View File

@ -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
/* ************************************************************************* */

View File

@ -676,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

View File

@ -435,7 +435,6 @@ namespace gtsam {
ar << BOOST_SERIALIZATION_NVP(model_);
}
}
#endif
template<class ARCHIVE>
void load(ARCHIVE & ar, const unsigned int version) {
@ -454,6 +453,7 @@ namespace gtsam {
}
BOOST_SERIALIZATION_SPLIT_MEMBER()
#endif
}; // JacobianFactor
/// traits
template<>
@ -462,7 +462,9 @@ struct traits<JacobianFactor> : public Testable<JacobianFactor> {
} // \ namespace gtsam
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
BOOST_CLASS_VERSION(gtsam::JacobianFactor, 1)
#endif
#include <gtsam/linear/JacobianFactor-inl.h>

View File

@ -162,12 +162,14 @@ class GTSAM_EXPORT Null : public Base {
static shared_ptr Create();
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <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)
@ -194,6 +196,7 @@ class GTSAM_EXPORT Fair : public Base {
double modelParameter() const { return c_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -201,6 +204,7 @@ class GTSAM_EXPORT Fair : public Base {
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar &BOOST_SERIALIZATION_NVP(c_);
}
#endif
};
/** The "Huber" robust error model (Zhang97ivc).
@ -227,6 +231,7 @@ class GTSAM_EXPORT Huber : public Base {
double modelParameter() const { return k_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -234,6 +239,7 @@ class GTSAM_EXPORT Huber : public Base {
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar &BOOST_SERIALIZATION_NVP(k_);
}
#endif
};
/** Implementation of the "Cauchy" robust error model (Lee2013IROS).
@ -265,6 +271,7 @@ class GTSAM_EXPORT Cauchy : public Base {
double modelParameter() const { return k_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -273,6 +280,7 @@ class GTSAM_EXPORT Cauchy : public Base {
ar &BOOST_SERIALIZATION_NVP(k_);
ar &BOOST_SERIALIZATION_NVP(ksquared_);
}
#endif
};
/** Implementation of the "Tukey" robust error model (Zhang97ivc).
@ -299,6 +307,7 @@ class GTSAM_EXPORT Tukey : public Base {
double modelParameter() const { return c_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -306,6 +315,7 @@ class GTSAM_EXPORT Tukey : public Base {
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar &BOOST_SERIALIZATION_NVP(c_);
}
#endif
};
/** Implementation of the "Welsch" robust error model (Zhang97ivc).
@ -332,6 +342,7 @@ class GTSAM_EXPORT Welsch : public Base {
double modelParameter() const { return c_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -340,6 +351,7 @@ class GTSAM_EXPORT Welsch : public Base {
ar &BOOST_SERIALIZATION_NVP(c_);
ar &BOOST_SERIALIZATION_NVP(csquared_);
}
#endif
};
/** Implementation of the "Geman-McClure" robust error model (Zhang97ivc).
@ -369,6 +381,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
double c_;
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -376,6 +389,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar &BOOST_SERIALIZATION_NVP(c_);
}
#endif
};
/** DCS implements the Dynamic Covariance Scaling robust error model
@ -407,6 +421,7 @@ class GTSAM_EXPORT DCS : public Base {
double c_;
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -414,6 +429,7 @@ class GTSAM_EXPORT DCS : public Base {
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar &BOOST_SERIALIZATION_NVP(c_);
}
#endif
};
/** L2WithDeadZone implements a standard L2 penalty, but with a dead zone of
@ -445,6 +461,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base {
double modelParameter() const { return k_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -452,6 +469,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base {
ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar &BOOST_SERIALIZATION_NVP(k_);
}
#endif
};
} // namespace mEstimator

View File

@ -267,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>
@ -274,7 +275,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(sqrt_information_);
}
#endif
}; // Gaussian
//---------------------------------------------------------------------------------------
@ -362,6 +363,7 @@ namespace gtsam {
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -370,6 +372,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(sigmas_);
ar & BOOST_SERIALIZATION_NVP(invsigmas_);
}
#endif
}; // Diagonal
//---------------------------------------------------------------------------------------
@ -517,6 +520,7 @@ namespace gtsam {
shared_ptr unit() const;
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -524,6 +528,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Diagonal);
ar & BOOST_SERIALIZATION_NVP(mu_);
}
#endif
}; // Constrained
@ -585,6 +590,7 @@ namespace gtsam {
inline double sigma() const { return sigma_; }
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -593,6 +599,7 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(sigma_);
ar & BOOST_SERIALIZATION_NVP(invsigma_);
}
#endif
};
@ -634,12 +641,14 @@ namespace gtsam {
void unwhitenInPlace(Eigen::Block<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
};
/**
@ -727,6 +736,7 @@ namespace gtsam {
const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise);
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -735,6 +745,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

View File

@ -93,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());
@ -110,6 +111,7 @@ Subgraph Subgraph::load(const std::string &fn) {
is.close();
return subgraph;
}
#endif
/****************************************************************************/
ostream &operator<<(ostream &os, const Subgraph::Edge &edge) {

View File

@ -84,16 +84,18 @@ class GTSAM_EXPORT Subgraph {
iterator end() { return edges_.end(); }
const_iterator end() const { return edges_.end(); }
void save(const std::string &fn) const;
static Subgraph load(const std::string &fn);
friend std::ostream &operator<<(std::ostream &os, const Subgraph &subgraph);
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access;
template <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
};
/****************************************************************************/

View File

@ -208,6 +208,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -218,6 +219,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(_PIM_);
}
#endif
};
// AHRSFactor

View File

@ -132,6 +132,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -142,6 +143,7 @@ private:
ar & boost::serialization::make_nvp("AttitudeFactor",
boost::serialization::base_object<AttitudeFactor>(*this));
}
#endif
public:
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
@ -215,6 +217,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -225,6 +228,7 @@ private:
ar & boost::serialization::make_nvp("AttitudeFactor",
boost::serialization::base_object<AttitudeFactor>(*this));
}
#endif
public:
GTSAM_MAKE_ALIGNED_OPERATOR_NEW

View File

@ -225,6 +225,7 @@ public:
/// @}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template <class ARCHIVE>
@ -233,6 +234,7 @@ public:
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
ar& BOOST_SERIALIZATION_NVP(preintMeasCov_);
}
#endif
public:
GTSAM_MAKE_ALIGNED_OPERATOR_NEW

View File

@ -166,6 +166,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -176,6 +177,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(nT_);
}
#endif
};
} /// namespace gtsam

View File

@ -248,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*/) {
@ -256,6 +257,7 @@ public:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(_PIM_);
}
#endif
};
// class ImuFactor

View File

@ -181,6 +181,7 @@ class GTSAM_EXPORT PreintegratedRotation {
/// @}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -190,6 +191,7 @@ class GTSAM_EXPORT PreintegratedRotation {
ar& BOOST_SERIALIZATION_NVP(deltaRij_);
ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_);
}
#endif
#ifdef GTSAM_USE_QUATERNIONS
// Align if we are using Quaternions

View File

@ -231,6 +231,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
/// @}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -241,6 +242,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
ar &BOOST_SERIALIZATION_NVP(measured_);
ar &BOOST_SERIALIZATION_NVP(func_);
}
#endif
};
/// traits

View File

@ -275,6 +275,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -285,6 +286,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(value_);
}
#endif
};
// \NonlinearEquality1

View File

@ -717,6 +717,7 @@ protected:
}
}
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template <class ARCHIVE>
@ -724,6 +725,7 @@ protected:
ar& boost::serialization::make_nvp(
"NoiseModelFactor", boost::serialization::base_object<Base>(*this));
}
#endif
public:
/// @name Shortcut functions `key1()` -> `key<1>()`

View File

@ -1 +1,9 @@
gtsamAddTestsGlob(nonlinear "test*.cpp" "" "gtsam")
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
# create a semicolon seperated list of files to exclude
set(EXCLUDE_TESTS "testSerializationNonlinear.cpp")
else()
set(EXCLUDE_TESTS "")
endif()
gtsamAddTestsGlob(discrete "test*.cpp" "${EXCLUDE_TESTS}" "gtsam")

View File

@ -164,6 +164,7 @@ class RangeFactorWithTransform : public ExpressionFactorN<T, A1, A2> {
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access;
/** Serialization function */
template <typename ARCHIVE>
@ -175,6 +176,7 @@ class RangeFactorWithTransform : public ExpressionFactorN<T, A1, A2> {
ar& boost::serialization::make_nvp(
"Base", boost::serialization::base_object<Base>(*this));
}
#endif
}; // \ RangeFactorWithTransform
/// traits

View File

@ -176,12 +176,14 @@ namespace gtsam {
private:
/** Serialization function */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
ar & boost::serialization::make_nvp("BetweenFactor",
boost::serialization::base_object<BetweenFactor<VALUE> >(*this));
}
#endif
}; // \class BetweenConstraint
/// traits

View File

@ -161,6 +161,7 @@ struct BoundingConstraint2: public NoiseModelFactorN<VALUE1, VALUE2> {
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -171,6 +172,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(threshold_);
ar & BOOST_SERIALIZATION_NVP(isGreaterThan_);
}
#endif
};
} // \namespace gtsam

View File

@ -284,6 +284,7 @@ public:
}
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
@ -293,6 +294,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
};
template<class CALIBRATION>

View File

@ -1,7 +1,8 @@
# if GTSAM_ENABLE_BOOST_SERIALIZATION is OFF then exclude some tests
if (NOT GTSAM_ENABLE_BOOST_SERIALIZATION)
# create a semicolon seperated list of files to exclude
set(EXCLUDE_TESTS "testSerializationDatataset.cpp" "testSerializationInSlam.cpp")
set(EXCLUDE_TESTS "testSerializationDataset.cpp" "testSerializationInSlam.cpp")
message(STATUS "Excluding tests: ${EXCLUDE_TESTS}")
else()
set(EXCLUDE_TESTS "")
endif()

View File

@ -148,6 +148,7 @@ public:
Vector error_vector(const Values& c) const;
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access;
/** Serialization function */
template<class ARCHIVE>
@ -156,6 +157,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(Ab_);
}
#endif
};
/// traits
@ -277,6 +279,7 @@ public:
private:
/** Serialization function */
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
@ -284,6 +287,7 @@ private:
boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(info_);
}
#endif
};
/// traits

View File

@ -139,8 +139,8 @@ public:
private:
/// Serialization function
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
@ -271,6 +271,7 @@ public:
private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
friend class boost::serialization::access;
/// Serialization function
template<class ARCHIVE>
@ -279,6 +280,7 @@ private:
ar & BOOST_SERIALIZATION_NVP(measured_);
ar & BOOST_SERIALIZATION_NVP(K_);
}
#endif
};
} // \ namespace gtsam

View File

@ -210,6 +210,7 @@ namespace simulated2D {
/// Default constructor
GenericOdometry() { }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -217,6 +218,7 @@ namespace simulated2D {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
};
/**
@ -259,6 +261,7 @@ namespace simulated2D {
/// Default constructor
GenericMeasurement() { }
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION ///
/// Serialization function
friend class boost::serialization::access;
template<class ARCHIVE>
@ -266,6 +269,7 @@ namespace simulated2D {
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
ar & BOOST_SERIALIZATION_NVP(measured_);
}
#endif
};
/** Typedefs for regular use */