diff --git a/gtsam/base/std_optional_serialization.h b/gtsam/base/std_optional_serialization.h new file mode 100644 index 000000000..3dac79284 --- /dev/null +++ b/gtsam/base/std_optional_serialization.h @@ -0,0 +1,79 @@ +// A hack to serialize std::optional to boost::archive +// Don't know if it will work. Trying to follow this: +// PR: https://github.com/boostorg/serialization/pull/148/files# +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// function specializations must be defined in the appropriate +// namespace - boost::serialization +namespace boost { +namespace serialization { + +template +void save(Archive& ar, const std::optional& t, const unsigned int /*version*/ +) { + // It is an inherent limitation to the serialization of optional.hpp + // that the underlying type must be either a pointer or must have a + // default constructor. It's possible that this could change sometime + // in the future, but for now, one will have to work around it. This can + // be done by serialization the optional as optional + BOOST_STATIC_ASSERT(boost::serialization::detail::is_default_constructible::value || boost::is_pointer::value); + const bool tflag = t.has_value(); + ar << boost::serialization::make_nvp("initialized", tflag); + if (tflag) { + const boost::serialization::item_version_type item_version(version::value); +#if 0 + const boost::archive::library_version_type library_version( + ar.get_library_version() + }; + if(boost::archive::library_version_type(3) < library_version){ + ar << BOOST_SERIALIZATION_NVP(item_version); + } +#else + ar << BOOST_SERIALIZATION_NVP(item_version); +#endif + ar << boost::serialization::make_nvp("value", *t); + } +} + +template +void load(Archive& ar, std::optional& t, const unsigned int /*version*/ +) { + bool tflag; + ar >> boost::serialization::make_nvp("initialized", tflag); + if (!tflag) { + t.reset(); + return; + } + + boost::serialization::item_version_type item_version(0); + boost::archive::library_version_type library_version(ar.get_library_version()); + if (boost::archive::library_version_type(3) < library_version) { + ar >> BOOST_SERIALIZATION_NVP(item_version); + } + detail::stack_allocate tp; + ar >> boost::serialization::make_nvp("value", tp.reference()); + t = std::move(tp.reference()); + // hack because std::optional does not have get_ptr fn + ar.reset_object_address(&(t.value()), &tp.reference()); +} + +template +void serialize(Archive& ar, std::optional& t, const unsigned int version) { + boost::serialization::split_free(ar, t, version); +} + +} // namespace serialization +} // namespace boost + diff --git a/gtsam/base/tests/testSerializationBase.cpp b/gtsam/base/tests/testSerializationBase.cpp index d2f4d5f51..9387d9b59 100644 --- a/gtsam/base/tests/testSerializationBase.cpp +++ b/gtsam/base/tests/testSerializationBase.cpp @@ -28,6 +28,7 @@ #include #include +#include #include using namespace std; diff --git a/gtsam/slam/KarcherMeanFactor-inl.h b/gtsam/slam/KarcherMeanFactor-inl.h index 00f741705..e714f653b 100644 --- a/gtsam/slam/KarcherMeanFactor-inl.h +++ b/gtsam/slam/KarcherMeanFactor-inl.h @@ -20,6 +20,7 @@ #include #include #include +#include using namespace std; @@ -58,7 +59,7 @@ T FindKarcherMean(std::initializer_list&& rotations) { template template KarcherMeanFactor::KarcherMeanFactor(const CONTAINER &keys, int d, - boost::optional beta) + std::optional beta) : NonlinearFactor(keys), d_(static_cast(d)) { if (d <= 0) { throw std::invalid_argument( @@ -75,4 +76,4 @@ KarcherMeanFactor::KarcherMeanFactor(const CONTAINER &keys, int d, whitenedJacobian_ = boost::make_shared(terms, Vector::Zero(d)); } -} // namespace gtsam \ No newline at end of file +} // namespace gtsam diff --git a/gtsam/slam/KarcherMeanFactor.h b/gtsam/slam/KarcherMeanFactor.h index 964cd598f..2b230c2f2 100644 --- a/gtsam/slam/KarcherMeanFactor.h +++ b/gtsam/slam/KarcherMeanFactor.h @@ -22,6 +22,7 @@ #include #include +#include namespace gtsam { /** @@ -60,7 +61,7 @@ public: */ template KarcherMeanFactor(const CONTAINER &keys, int d = D, - boost::optional beta = boost::none); + std::optional beta = {}); /// Destructor ~KarcherMeanFactor() override {} diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index b263b4de6..3b60c8a5a 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -25,7 +25,7 @@ #include #include #include -#include +#include namespace gtsam { @@ -43,7 +43,7 @@ namespace gtsam { // Keep a copy of measurement and calibration for I/O Point2 measured_; ///< 2D measurement boost::shared_ptr K_; ///< shared pointer to calibration object - boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame + std::optional body_P_sensor_; ///< The pose of the sensor in the body frame // verbosity handling for Cheirality Exceptions bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) @@ -80,7 +80,7 @@ namespace gtsam { */ GenericProjectionFactor(const Point2& measured, const SharedNoiseModel& model, Key poseKey, Key pointKey, const boost::shared_ptr& K, - boost::optional body_P_sensor = boost::none) : + std::optional body_P_sensor = {}) : Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor), throwCheirality_(false), verboseCheirality_(false) {} @@ -99,7 +99,7 @@ namespace gtsam { GenericProjectionFactor(const Point2& measured, const SharedNoiseModel& model, Key poseKey, Key pointKey, const boost::shared_ptr& K, bool throwCheirality, bool verboseCheirality, - boost::optional body_P_sensor = boost::none) : + std::optional body_P_sensor = {}) : Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor), throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} @@ -176,7 +176,7 @@ namespace gtsam { } /** return the (optional) sensor pose with respect to the vehicle frame */ - const boost::optional& body_P_sensor() const { + const std::optional& body_P_sensor() const { return body_P_sensor_; } diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index b53235ab3..09627a68f 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -30,6 +30,7 @@ #include #include +#include #include #include #include @@ -78,7 +79,7 @@ protected: */ ZVector measured_; - boost::optional + std::optional body_P_sensor_; ///< Pose of the camera in the body frame // Cache for Fblocks, to avoid a malloc ever time we re-linearize @@ -98,7 +99,7 @@ protected: /// Construct with given noise model and optional arguments. SmartFactorBase(const SharedNoiseModel& sharedNoiseModel, - boost::optional body_P_sensor = boost::none, + std::optional body_P_sensor = {}, size_t expectedNumberCameras = 10) : body_P_sensor_(body_P_sensor), Fs(expectedNumberCameras) { diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index d09f42509..a38a8bd88 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include @@ -410,7 +410,7 @@ protected: * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. */ double totalReprojectionError(const Cameras& cameras, - boost::optional externalPoint = boost::none) const { + std::optional externalPoint = {}) const { if (externalPoint) result_ = TriangulationResult(*externalPoint); diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index e432cbfb1..ce84babed 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -86,7 +86,7 @@ public: SmartProjectionPoseFactor( const SharedNoiseModel& sharedNoiseModel, const boost::shared_ptr K, - const boost::optional body_P_sensor, + const std::optional body_P_sensor, const SmartProjectionParams& params = SmartProjectionParams()) : SmartProjectionPoseFactor(sharedNoiseModel, K, params) { this->body_P_sensor_ = body_P_sensor; diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index c0e3fd1b3..d52860776 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include @@ -34,7 +35,7 @@ private: // Keep a copy of measurement and calibration for I/O StereoPoint2 measured_; ///< the measurement Cal3_S2Stereo::shared_ptr K_; ///< shared pointer to calibration - boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame + std::optional body_P_sensor_; ///< The pose of the sensor in the body frame // verbosity handling for Cheirality Exceptions bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) @@ -68,7 +69,7 @@ public: */ GenericStereoFactor(const StereoPoint2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr& K, - boost::optional body_P_sensor = boost::none) : + std::optional body_P_sensor = {}) : Base(model, poseKey, landmarkKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor), throwCheirality_(false), verboseCheirality_(false) {} @@ -86,7 +87,7 @@ public: GenericStereoFactor(const StereoPoint2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr& K, bool throwCheirality, bool verboseCheirality, - boost::optional body_P_sensor = boost::none) : + std::optional body_P_sensor = {}) : Base(model, poseKey, landmarkKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor), throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index db79fcd3c..cfd7b8820 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -43,7 +43,7 @@ #include #include -#include +#include #include #include @@ -113,7 +113,7 @@ string createRewrittenFileName(const string &name) { // Type for parser functions used in parseLines below. template using Parser = - std::function(istream &is, const string &tag)>; + std::function(istream &is, const string &tag)>; // Parse a file by calling the parse(is, tag) function for every line. // The result of calling the function is ignored, so typically parse function @@ -141,7 +141,7 @@ map parseToMap(const string &filename, Parser> parse, if (!maxIndex || t->first <= maxIndex) result.emplace(*t); } - return boost::none; + return std::nullopt; }; parseLines(filename, emplace); return result; @@ -155,14 +155,14 @@ static vector parseToVector(const string &filename, Parser parse) { Parser add = [&result, parse](istream &is, const string &tag) { if (auto t = parse(is, tag)) result.push_back(*t); - return boost::none; + return std::nullopt; }; parseLines(filename, add); return result; } /* ************************************************************************* */ -boost::optional parseVertexPose(istream &is, const string &tag) { +std::optional parseVertexPose(istream &is, const string &tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { size_t id; double x, y, yaw; @@ -171,7 +171,7 @@ boost::optional parseVertexPose(istream &is, const string &tag) { } return IndexedPose(id, Pose2(x, y, yaw)); } else { - return boost::none; + return std::nullopt; } } @@ -182,7 +182,7 @@ GTSAM_EXPORT std::map parseVariables( } /* ************************************************************************* */ -boost::optional parseVertexLandmark(istream &is, +std::optional parseVertexLandmark(istream &is, const string &tag) { if (tag == "VERTEX_XY") { size_t id; @@ -193,7 +193,7 @@ boost::optional parseVertexLandmark(istream &is, } return IndexedLandmark(id, Point2(x, y)); } else { - return boost::none; + return std::nullopt; } } @@ -288,7 +288,7 @@ static SharedNoiseModel createNoiseModel( } /* ************************************************************************* */ -boost::optional parseEdge(istream &is, const string &tag) { +std::optional parseEdge(istream &is, const string &tag) { if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || (tag == "ODOMETRY")) { @@ -299,7 +299,7 @@ boost::optional parseEdge(istream &is, const string &tag) { } return IndexedEdge({id1, id2}, Pose2(x, y, yaw)); } else { - return boost::none; + return std::nullopt; } } @@ -315,13 +315,13 @@ template struct ParseFactor : ParseMeasurement { : ParseMeasurement(parent) {} // We parse a measurement then convert - typename boost::optional::shared_ptr> + typename std::optional::shared_ptr> operator()(istream &is, const string &tag) { if (auto m = ParseMeasurement::operator()(is, tag)) return boost::make_shared>( m->key1(), m->key2(), m->measured(), m->noiseModel()); else - return boost::none; + return std::nullopt; } }; @@ -341,11 +341,11 @@ template <> struct ParseMeasurement { SharedNoiseModel model; // The actual parser - boost::optional> operator()(istream &is, + std::optional> operator()(istream &is, const string &tag) { auto edge = parseEdge(is, tag); if (!edge) - return boost::none; + return std::nullopt; // parse noise model Vector6 v; @@ -355,7 +355,7 @@ template <> struct ParseMeasurement { size_t id1, id2; tie(id1, id2) = edge->first; if (maxIndex && (id1 > maxIndex || id2 > maxIndex)) - return boost::none; + return std::nullopt; // Get pose and optionally add noise Pose2 &pose = edge->second; @@ -446,10 +446,10 @@ template <> struct ParseMeasurement { size_t maxIndex; // The actual parser - boost::optional> + std::optional> operator()(istream &is, const string &tag) { if (tag != "BR" && tag != "LANDMARK") - return boost::none; + return std::nullopt; size_t id1, id2; is >> id1 >> id2; @@ -485,7 +485,7 @@ template <> struct ParseMeasurement { // optional filter if (maxIndex && id1 > maxIndex) - return boost::none; + return std::nullopt; // Create noise model auto measurementNoise = noiseModel::Diagonal::Sigmas( @@ -759,7 +759,7 @@ istream &operator>>(istream &is, Rot3 &R) { } /* ************************************************************************* */ -boost::optional> parseVertexPose3(istream &is, +std::optional> parseVertexPose3(istream &is, const string &tag) { if (tag == "VERTEX3") { size_t id; @@ -774,7 +774,7 @@ boost::optional> parseVertexPose3(istream &is, is >> id >> x >> y >> z >> q; return make_pair(id, Pose3(q, {x, y, z})); } else - return boost::none; + return std::nullopt; } template <> @@ -784,7 +784,7 @@ GTSAM_EXPORT std::map parseVariables( } /* ************************************************************************* */ -boost::optional> parseVertexPoint3(istream &is, +std::optional> parseVertexPoint3(istream &is, const string &tag) { if (tag == "VERTEX_TRACKXYZ") { size_t id; @@ -792,7 +792,7 @@ boost::optional> parseVertexPoint3(istream &is, is >> id >> x >> y >> z; return make_pair(id, Point3(x, y, z)); } else - return boost::none; + return std::nullopt; } template <> @@ -820,16 +820,16 @@ template <> struct ParseMeasurement { size_t maxIndex; // The actual parser - boost::optional> operator()(istream &is, + std::optional> operator()(istream &is, const string &tag) { if (tag != "EDGE3" && tag != "EDGE_SE3:QUAT") - return boost::none; + return std::nullopt; // parse ids and optionally filter size_t id1, id2; is >> id1 >> id2; if (maxIndex && (id1 > maxIndex || id2 > maxIndex)) - return boost::none; + return std::nullopt; Matrix6 m; if (tag == "EDGE3") { @@ -864,7 +864,7 @@ template <> struct ParseMeasurement { return BinaryMeasurement( id1, id2, T12, noiseModel::Gaussian::Information(mgtsam)); } else - return boost::none; + return std::nullopt; } }; diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 95e750674..875f23306 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -40,6 +40,7 @@ #include #include #include +#include namespace gtsam { @@ -118,7 +119,7 @@ typedef std::pair, Pose2> IndexedEdge; * @param is input stream * @param tag string parsed from input stream, will only parse if vertex type */ -GTSAM_EXPORT boost::optional parseVertexPose(std::istream& is, +GTSAM_EXPORT std::optional parseVertexPose(std::istream& is, const std::string& tag); /** @@ -126,7 +127,7 @@ GTSAM_EXPORT boost::optional parseVertexPose(std::istream& is, * @param is input stream * @param tag string parsed from input stream, will only parse if vertex type */ -GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& is, +GTSAM_EXPORT std::optional parseVertexLandmark(std::istream& is, const std::string& tag); /** @@ -134,7 +135,7 @@ GTSAM_EXPORT boost::optional parseVertexLandmark(std::istream& * @param is input stream * @param tag string parsed from input stream, will only parse if edge type */ -GTSAM_EXPORT boost::optional parseEdge(std::istream& is, +GTSAM_EXPORT std::optional parseEdge(std::istream& is, const std::string& tag); /// Return type for load functions, which return a graph and initial values. For @@ -227,7 +228,7 @@ using BinaryMeasurementsPoint3 = std::vector>; using BinaryMeasurementsRot3 = std::vector>; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 -inline boost::optional GTSAM_DEPRECATED +inline std::optional GTSAM_DEPRECATED parseVertex(std::istream& is, const std::string& tag) { return parseVertexPose(is, tag); } diff --git a/gtsam/slam/tests/PinholeFactor.h b/gtsam/slam/tests/PinholeFactor.h index 35500ca35..7266a4aea 100644 --- a/gtsam/slam/tests/PinholeFactor.h +++ b/gtsam/slam/tests/PinholeFactor.h @@ -35,7 +35,7 @@ class PinholeFactor : public SmartFactorBase > { typedef SmartFactorBase > Base; PinholeFactor() {} PinholeFactor(const SharedNoiseModel& sharedNoiseModel, - boost::optional body_P_sensor = boost::none, + std::optional body_P_sensor = {}, size_t expectedNumberCameras = 10) : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {} double error(const Values& values) const override { return 0.0; } diff --git a/gtsam/slam/tests/testSerializationInSlam.cpp b/gtsam/slam/tests/testSerializationInSlam.cpp index 08fb80c0a..f729f8ed6 100644 --- a/gtsam/slam/tests/testSerializationInSlam.cpp +++ b/gtsam/slam/tests/testSerializationInSlam.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #include diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index ba5a53bbb..2eb799663 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -138,7 +138,7 @@ TEST( SmartProjectionPoseFactor, noiseless ) { factor.triangulateAndComputeE(actualE, values); // get point - boost::optional point = factor.point(); + auto point = factor.point(); CHECK(point); // calculate numerical derivative with triangulated point @@ -366,7 +366,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { CHECK(smartFactor1->triangulateSafe(cameras)); CHECK(!smartFactor1->isDegenerate()); CHECK(!smartFactor1->isPointBehindCamera()); - boost::optional p = smartFactor1->point(); + auto p = smartFactor1->point(); CHECK(p); EXPECT(assert_equal(landmark1, *p)); diff --git a/gtsam/slam/tests/testSmartProjectionRigFactor.cpp b/gtsam/slam/tests/testSmartProjectionRigFactor.cpp index 6d39eb5b0..2fa6e7290 100644 --- a/gtsam/slam/tests/testSmartProjectionRigFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionRigFactor.cpp @@ -166,7 +166,7 @@ TEST(SmartProjectionRigFactor, noiseless) { factor.triangulateAndComputeE(actualE, values); // get point - boost::optional point = factor.point(); + auto point = factor.point(); CHECK(point); // calculate numerical derivative with triangulated point @@ -508,7 +508,7 @@ TEST(SmartProjectionRigFactor, Factors) { CHECK(smartFactor1->triangulateSafe(cameras)); CHECK(!smartFactor1->isDegenerate()); CHECK(!smartFactor1->isPointBehindCamera()); - boost::optional p = smartFactor1->point(); + auto p = smartFactor1->point(); CHECK(p); EXPECT(assert_equal(landmark1, *p)); diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index a9caf0c4c..9ebc9ba10 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -32,6 +32,8 @@ #include #include +#include +#include #include namespace gtsam { @@ -87,7 +89,7 @@ public: */ SmartStereoProjectionFactor(const SharedNoiseModel& sharedNoiseModel, const SmartStereoProjectionParams& params = SmartStereoProjectionParams(), - const boost::optional body_P_sensor = boost::none) : + const std::optional body_P_sensor = {}) : Base(sharedNoiseModel, body_P_sensor), // params_(params), // result_(TriangulationResult::Degenerate()) { @@ -415,7 +417,7 @@ public: * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. */ double totalReprojectionError(const Cameras& cameras, - boost::optional externalPoint = boost::none) const { + std::optional externalPoint = {}) const { if (externalPoint) result_ = TriangulationResult(*externalPoint); diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.cpp index c28cb25a1..4f6ef18ab 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.cpp @@ -26,7 +26,7 @@ namespace gtsam { SmartStereoProjectionPoseFactor::SmartStereoProjectionPoseFactor( const SharedNoiseModel& sharedNoiseModel, const SmartStereoProjectionParams& params, - const boost::optional& body_P_sensor) + const std::optional& body_P_sensor) : Base(sharedNoiseModel, params, body_P_sensor) {} void SmartStereoProjectionPoseFactor::add( diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index ad09cd207..7295413ca 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -69,7 +69,7 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor SmartStereoProjectionPoseFactor( const SharedNoiseModel& sharedNoiseModel, const SmartStereoProjectionParams& params = SmartStereoProjectionParams(), - const boost::optional& body_P_sensor = boost::none); + const std::optional& body_P_sensor = {}); /** Virtual destructor */ ~SmartStereoProjectionPoseFactor() override = default; diff --git a/tests/testSerializationSlam.cpp b/tests/testSerializationSlam.cpp index ea7038635..f986d812a 100644 --- a/tests/testSerializationSlam.cpp +++ b/tests/testSerializationSlam.cpp @@ -50,6 +50,7 @@ #include #include #include +#include #include #include