diff --git a/examples/ISAM2Example_SmartFactor.cpp b/examples/ISAM2Example_SmartFactor.cpp index 7dbd8323b..a874efc9a 100644 --- a/examples/ISAM2Example_SmartFactor.cpp +++ b/examples/ISAM2Example_SmartFactor.cpp @@ -105,7 +105,7 @@ int main(int argc, char* argv[]) { Values currentEstimate = isam.calculateEstimate(); currentEstimate.print("Current estimate: "); - boost::optional pointEstimate = smartFactor->point(currentEstimate); + auto pointEstimate = smartFactor->point(currentEstimate); if (pointEstimate) { cout << *pointEstimate << endl; } else { diff --git a/examples/SFMExample_SmartFactor.cpp b/examples/SFMExample_SmartFactor.cpp index 86e6b8ae9..c3400a0f9 100644 --- a/examples/SFMExample_SmartFactor.cpp +++ b/examples/SFMExample_SmartFactor.cpp @@ -114,10 +114,10 @@ int main(int argc, char* argv[]) { // The graph stores Factor shared_ptrs, so we cast back to a SmartFactor first SmartFactor::shared_ptr smart = boost::dynamic_pointer_cast(graph[j]); if (smart) { - // The output of point() is in boost::optional, as sometimes + // The output of point() is in std::optional, as sometimes // the triangulation operation inside smart factor will encounter degeneracy. - boost::optional point = smart->point(result); - if (point) // ignore if boost::optional return nullptr + auto point = smart->point(result); + if (point) // ignore if std::optional return nullptr landmark_result.insert(j, *point); } } diff --git a/examples/SFMExample_SmartFactorPCG.cpp b/examples/SFMExample_SmartFactorPCG.cpp index 3f553efc6..2f03a4ef0 100644 --- a/examples/SFMExample_SmartFactorPCG.cpp +++ b/examples/SFMExample_SmartFactorPCG.cpp @@ -110,8 +110,8 @@ int main(int argc, char* argv[]) { for (size_t j = 0; j < points.size(); ++j) { auto smart = boost::dynamic_pointer_cast(graph[j]); if (smart) { - boost::optional point = smart->point(result); - if (point) // ignore if boost::optional return nullptr + std::optional point = smart->point(result); + if (point) // ignore if std::optional return nullptr landmark_result.insert(j, *point); } } diff --git a/examples/TriangulationLOSTExample.cpp b/examples/TriangulationLOSTExample.cpp index a862026e0..4bb280dd1 100644 --- a/examples/TriangulationLOSTExample.cpp +++ b/examples/TriangulationLOSTExample.cpp @@ -29,6 +29,7 @@ #include #include #include +#include using namespace std; using namespace gtsam; @@ -131,23 +132,23 @@ int main(int argc, char* argv[]) { AddNoiseToMeasurements(measurements, measurementSigma); auto lostStart = std::chrono::high_resolution_clock::now(); - boost::optional estimateLOST = triangulatePoint3( + auto estimateLOST = triangulatePoint3( cameras, noisyMeasurements, rank_tol, false, measurementNoise, true); durationLOST += std::chrono::high_resolution_clock::now() - lostStart; auto dltStart = std::chrono::high_resolution_clock::now(); - boost::optional estimateDLT = triangulatePoint3( + auto estimateDLT = triangulatePoint3( cameras, noisyMeasurements, rank_tol, false, measurementNoise, false); durationDLT += std::chrono::high_resolution_clock::now() - dltStart; auto dltOptStart = std::chrono::high_resolution_clock::now(); - boost::optional estimateDLTOpt = triangulatePoint3( + auto estimateDLTOpt = triangulatePoint3( cameras, noisyMeasurements, rank_tol, true, measurementNoise, false); durationDLTOpt += std::chrono::high_resolution_clock::now() - dltOptStart; - errorsLOST.row(i) = *estimateLOST - landmark; - errorsDLT.row(i) = *estimateDLT - landmark; - errorsDLTOpt.row(i) = *estimateDLTOpt - landmark; + errorsLOST.row(i) = estimateLOST - landmark; + errorsDLT.row(i) = estimateDLT - landmark; + errorsDLTOpt.row(i) = estimateDLTOpt - landmark; } PrintCovarianceStats(errorsLOST, "LOST"); PrintCovarianceStats(errorsDLT, "DLT"); diff --git a/gtsam/base/Lie.h b/gtsam/base/Lie.h index c4eba5deb..1b574816a 100644 --- a/gtsam/base/Lie.h +++ b/gtsam/base/Lie.h @@ -54,14 +54,14 @@ struct LieGroup { } Class compose(const Class& g, ChartJacobian H1, - ChartJacobian H2 = boost::none) const { + ChartJacobian H2 = {}) const { if (H1) *H1 = g.inverse().AdjointMap(); if (H2) *H2 = Eigen::Matrix::Identity(); return derived() * g; } Class between(const Class& g, ChartJacobian H1, - ChartJacobian H2 = boost::none) const { + ChartJacobian H2 = {}) const { Class result = derived().inverse() * g; if (H1) *H1 = - result.inverse().AdjointMap(); if (H2) *H2 = Eigen::Matrix::Identity(); @@ -87,7 +87,7 @@ struct LieGroup { /// expmap with optional derivatives Class expmap(const TangentVector& v, // - ChartJacobian H1, ChartJacobian H2 = boost::none) const { + ChartJacobian H1, ChartJacobian H2 = {}) const { Jacobian D_g_v; Class g = Class::Expmap(v,H2 ? &D_g_v : 0); Class h = compose(g); // derivatives inlined below @@ -98,7 +98,7 @@ struct LieGroup { /// logmap with optional derivatives TangentVector logmap(const Class& g, // - ChartJacobian H1, ChartJacobian H2 = boost::none) const { + ChartJacobian H1, ChartJacobian H2 = {}) const { Class h = between(g); // derivatives inlined below Jacobian D_v_h; TangentVector v = Class::Logmap(h, (H1 || H2) ? &D_v_h : 0); @@ -139,7 +139,7 @@ struct LieGroup { /// retract with optional derivatives Class retract(const TangentVector& v, // - ChartJacobian H1, ChartJacobian H2 = boost::none) const { + ChartJacobian H1, ChartJacobian H2 = {}) const { Jacobian D_g_v; Class g = Class::ChartAtOrigin::Retract(v, H2 ? &D_g_v : 0); Class h = compose(g); // derivatives inlined below @@ -150,7 +150,7 @@ struct LieGroup { /// localCoordinates with optional derivatives TangentVector localCoordinates(const Class& g, // - ChartJacobian H1, ChartJacobian H2 = boost::none) const { + ChartJacobian H1, ChartJacobian H2 = {}) const { Class h = between(g); // derivatives inlined below Jacobian D_v_h; TangentVector v = Class::ChartAtOrigin::Local(h, (H1 || H2) ? &D_v_h : 0); @@ -188,38 +188,38 @@ struct LieGroupTraits: GetDimensionImpl { typedef OptionalJacobian ChartJacobian; static TangentVector Local(const Class& origin, const Class& other, - ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) { + ChartJacobian Horigin = {}, ChartJacobian Hother = {}) { return origin.localCoordinates(other, Horigin, Hother); } static Class Retract(const Class& origin, const TangentVector& v, - ChartJacobian Horigin = boost::none, ChartJacobian Hv = boost::none) { + ChartJacobian Horigin = {}, ChartJacobian Hv = {}) { return origin.retract(v, Horigin, Hv); } /// @} /// @name Lie Group /// @{ - static TangentVector Logmap(const Class& m, ChartJacobian Hm = boost::none) { + static TangentVector Logmap(const Class& m, ChartJacobian Hm = {}) { return Class::Logmap(m, Hm); } - static Class Expmap(const TangentVector& v, ChartJacobian Hv = boost::none) { + static Class Expmap(const TangentVector& v, ChartJacobian Hv = {}) { return Class::Expmap(v, Hv); } static Class Compose(const Class& m1, const Class& m2, // - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { return m1.compose(m2, H1, H2); } static Class Between(const Class& m1, const Class& m2, // - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { return m1.between(m2, H1, H2); } static Class Inverse(const Class& m, // - ChartJacobian H = boost::none) { + ChartJacobian H = {}) { return m.inverse(H); } /// @} @@ -325,8 +325,8 @@ T expm(const Vector& x, int K=7) { */ template T interpolate(const T& X, const T& Y, double t, - typename MakeOptionalJacobian::type Hx = boost::none, - typename MakeOptionalJacobian::type Hy = boost::none) { + typename MakeOptionalJacobian::type Hx = {}, + typename MakeOptionalJacobian::type Hy = {}) { if (Hx || Hy) { typename MakeJacobian::type between_H_x, log_H, exp_H, compose_H_x; const T between = diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index cfedf6d8c..88714d6f6 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -459,8 +459,8 @@ struct MultiplyWithInverse { /// A.inverse() * b, with optional derivatives VectorN operator()(const MatrixN& A, const VectorN& b, - OptionalJacobian H1 = boost::none, - OptionalJacobian H2 = boost::none) const { + OptionalJacobian H1 = {}, + OptionalJacobian H2 = {}) const { const MatrixN invA = A.inverse(); const VectorN c = invA * b; // The derivative in A is just -[c[0]*invA c[1]*invA ... c[N-1]*invA] @@ -495,16 +495,16 @@ struct MultiplyWithInverseFunction { /// f(a).inverse() * b, with optional derivatives VectorN operator()(const T& a, const VectorN& b, - OptionalJacobian H1 = boost::none, - OptionalJacobian H2 = boost::none) const { + OptionalJacobian H1 = {}, + OptionalJacobian H2 = {}) const { MatrixN A; - phi_(a, b, boost::none, A); // get A = f(a) by calling f once + phi_(a, b, {}, A); // get A = f(a) by calling f once const MatrixN invA = A.inverse(); const VectorN c = invA * b; if (H1) { Eigen::Matrix H; - phi_(a, c, H, boost::none); // get derivative H of forward mapping + phi_(a, c, H, {}); // get derivative H of forward mapping *H1 = -invA* H; } if (H2) *H2 = invA; diff --git a/gtsam/base/OptionalJacobian.h b/gtsam/base/OptionalJacobian.h index 4bde4e5e7..22a17e131 100644 --- a/gtsam/base/OptionalJacobian.h +++ b/gtsam/base/OptionalJacobian.h @@ -18,23 +18,20 @@ */ #pragma once +#include +#include #include // Configuration from CMake #include +#include #include #include -#ifndef OPTIONALJACOBIAN_NOBOOST -#include -#endif - namespace gtsam { /** * OptionalJacobian is an Eigen::Ref like class that can take be constructed using * either a fixed size or dynamic Eigen matrix. In the latter case, the dynamic - * matrix will be resized. Finally, there is a constructor that takes - * boost::none, the default constructor acts like boost::none, and - * boost::optional is also supported for backwards compatibility. + * matrix will be resized. * Below this class, a dynamic version is also implemented. */ template @@ -66,11 +63,18 @@ private: public: - /// Default constructor acts like boost::none + /// Default constructor OptionalJacobian() : map_(nullptr) { } + /// Default constructor with nullptr_t + /// To guide the compiler when nullptr + /// is passed to args of the type OptionalJacobian + OptionalJacobian(std::nullptr_t /*unused*/) : + map_(nullptr) { + } + /// Constructor that will usurp data of a fixed-size matrix OptionalJacobian(Jacobian& fixed) : map_(nullptr) { @@ -116,26 +120,21 @@ public: "Expected: ") + "(" + std::to_string(Rows) + ", " + std::to_string(Cols) + ")"); } - } + } -#ifndef OPTIONALJACOBIAN_NOBOOST - - /// Constructor with boost::none just makes empty - OptionalJacobian(boost::none_t /*none*/) : + /// Constructor with std::nullopt just makes empty + OptionalJacobian(std::nullopt_t /*none*/) : map_(nullptr) { } /// Constructor compatible with old-style derivatives - OptionalJacobian(const boost::optional optional) : + OptionalJacobian(const std::optional> optional) : map_(nullptr) { if (optional) { - optional->resize(Rows, Cols); - usurp(optional->data()); + optional->get().resize(Rows, Cols); + usurp(optional->get().data()); } } - -#endif - /// Constructor that will usurp data of a block expression /// TODO(frank): unfortunately using a Map makes usurping non-contiguous memory impossible // template @@ -200,7 +199,7 @@ private: public: - /// Default constructor acts like boost::none + /// Default constructor OptionalJacobian() : pointer_(nullptr) { } @@ -211,21 +210,17 @@ public: /// Construct from refrence to dynamic matrix OptionalJacobian(Jacobian& dynamic) : pointer_(&dynamic) {} -#ifndef OPTIONALJACOBIAN_NOBOOST - - /// Constructor with boost::none just makes empty - OptionalJacobian(boost::none_t /*none*/) : + /// Constructor with std::nullopt just makes empty + OptionalJacobian(std::nullopt_t /*none*/) : pointer_(nullptr) { } - /// Constructor compatible with old-style derivatives - OptionalJacobian(const boost::optional optional) : + /// Constructor for optional matrix reference + OptionalJacobian(const std::optional> optional) : pointer_(nullptr) { - if (optional) pointer_ = &(*optional); + if (optional) pointer_ = &((*optional).get()); } -#endif - /// Return true if allocated, false if default constructor was used operator bool() const { return pointer_!=nullptr; diff --git a/gtsam/base/ProductLieGroup.h b/gtsam/base/ProductLieGroup.h index 6689c11d6..831968bc8 100644 --- a/gtsam/base/ProductLieGroup.h +++ b/gtsam/base/ProductLieGroup.h @@ -75,14 +75,14 @@ public: typedef OptionalJacobian ChartJacobian; ProductLieGroup retract(const TangentVector& v, // - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) const { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) const { if (H1||H2) throw std::runtime_error("ProductLieGroup::retract derivatives not implemented yet"); G g = traits::Retract(this->first, v.template head()); H h = traits::Retract(this->second, v.template tail()); return ProductLieGroup(g,h); } TangentVector localCoordinates(const ProductLieGroup& g, // - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) const { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) const { if (H1||H2) throw std::runtime_error("ProductLieGroup::localCoordinates derivatives not implemented yet"); typename traits::TangentVector v1 = traits::Local(this->first, g.first); typename traits::TangentVector v2 = traits::Local(this->second, g.second); @@ -101,7 +101,7 @@ protected: public: ProductLieGroup compose(const ProductLieGroup& other, ChartJacobian H1, - ChartJacobian H2 = boost::none) const { + ChartJacobian H2 = {}) const { Jacobian1 D_g_first; Jacobian2 D_h_second; G g = traits::Compose(this->first,other.first, H1 ? &D_g_first : 0); H h = traits::Compose(this->second,other.second, H1 ? &D_h_second : 0); @@ -114,7 +114,7 @@ public: return ProductLieGroup(g,h); } ProductLieGroup between(const ProductLieGroup& other, ChartJacobian H1, - ChartJacobian H2 = boost::none) const { + ChartJacobian H2 = {}) const { Jacobian1 D_g_first; Jacobian2 D_h_second; G g = traits::Between(this->first,other.first, H1 ? &D_g_first : 0); H h = traits::Between(this->second,other.second, H1 ? &D_h_second : 0); @@ -137,7 +137,7 @@ public: } return ProductLieGroup(g,h); } - static ProductLieGroup Expmap(const TangentVector& v, ChartJacobian Hv = boost::none) { + static ProductLieGroup Expmap(const TangentVector& v, ChartJacobian Hv = {}) { Jacobian1 D_g_first; Jacobian2 D_h_second; G g = traits::Expmap(v.template head(), Hv ? &D_g_first : 0); H h = traits::Expmap(v.template tail(), Hv ? &D_h_second : 0); @@ -148,7 +148,7 @@ public: } return ProductLieGroup(g,h); } - static TangentVector Logmap(const ProductLieGroup& p, ChartJacobian Hp = boost::none) { + static TangentVector Logmap(const ProductLieGroup& p, ChartJacobian Hp = {}) { Jacobian1 D_g_first; Jacobian2 D_h_second; typename traits::TangentVector v1 = traits::Logmap(p.first, Hp ? &D_g_first : 0); typename traits::TangentVector v2 = traits::Logmap(p.second, Hp ? &D_h_second : 0); @@ -161,7 +161,7 @@ public: } return v; } - static TangentVector LocalCoordinates(const ProductLieGroup& p, ChartJacobian Hp = boost::none) { + static TangentVector LocalCoordinates(const ProductLieGroup& p, ChartJacobian Hp = {}) { return Logmap(p, Hp); } ProductLieGroup expmap(const TangentVector& v) const { diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h index 638096c95..b5068ad95 100644 --- a/gtsam/base/TestableAssertions.h +++ b/gtsam/base/TestableAssertions.h @@ -20,7 +20,8 @@ #include #include -#include +#include +#include #include #include #include @@ -40,21 +41,21 @@ inline bool assert_equal(const Key& expected, const Key& actual, double tol = 0. } /** - * Comparisons for boost.optional objects that checks whether objects exist + * Comparisons for std.optional objects that checks whether objects exist * before comparing their values. First version allows for both to be - * boost::none, but the second, with expected given rather than optional + * std::nullopt, but the second, with expected given rather than optional * * Concept requirement: V is testable */ template -bool assert_equal(const boost::optional& expected, - const boost::optional& actual, double tol = 1e-9) { +bool assert_equal(const std::optional& expected, + const std::optional& actual, double tol = 1e-9) { if (!expected && actual) { - std::cout << "expected is boost::none, while actual is not" << std::endl; + std::cout << "expected is {}, while actual is not" << std::endl; return false; } if (expected && !actual) { - std::cout << "actual is boost::none, while expected is not" << std::endl; + std::cout << "actual is {}, while expected is not" << std::endl; return false; } if (!expected && !actual) @@ -63,21 +64,22 @@ bool assert_equal(const boost::optional& expected, } template -bool assert_equal(const V& expected, const boost::optional& actual, double tol = 1e-9) { +bool assert_equal(const V& expected, const std::optional& actual, double tol = 1e-9) { if (!actual) { - std::cout << "actual is boost::none" << std::endl; + std::cout << "actual is {}" << std::endl; return false; } return assert_equal(expected, *actual, tol); } template -bool assert_equal(const V& expected, const boost::optional& actual, double tol = 1e-9) { +bool assert_equal(const V& expected, + const std::optional>& actual, double tol = 1e-9) { if (!actual) { - std::cout << "actual is boost::none" << std::endl; + std::cout << "actual is std::nullopt" << std::endl; return false; } - return assert_equal(expected, *actual, tol); + return assert_equal(expected, *actual.get(), tol); } /** diff --git a/gtsam/base/ThreadsafeException.h b/gtsam/base/ThreadsafeException.h index 652dbd90f..57e37237f 100644 --- a/gtsam/base/ThreadsafeException.h +++ b/gtsam/base/ThreadsafeException.h @@ -21,11 +21,11 @@ #include // for GTSAM_USE_TBB -#include #include #include #include #include +#include #ifdef GTSAM_USE_TBB #include @@ -53,7 +53,7 @@ protected: protected: bool dynamic_; ///< Whether this object was moved - mutable boost::optional description_; ///< Optional description + mutable std::optional description_; ///< Optional description /// Default constructor is protected - may only be created from derived classes ThreadsafeException() : diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 697c4f3be..0d2c601cd 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -21,6 +21,7 @@ #include // Configuration from CMake #include +#include #include #include #include diff --git a/gtsam/base/Vector.cpp b/gtsam/base/Vector.cpp index 16d913a96..ce7aeba7b 100644 --- a/gtsam/base/Vector.cpp +++ b/gtsam/base/Vector.cpp @@ -18,7 +18,6 @@ */ #include -#include #include #include #include diff --git a/gtsam/base/VectorSpace.h b/gtsam/base/VectorSpace.h index f7809f596..9fbd581bb 100644 --- a/gtsam/base/VectorSpace.h +++ b/gtsam/base/VectorSpace.h @@ -32,7 +32,7 @@ struct VectorSpaceImpl { static int GetDimension(const Class&) { return N;} static TangentVector Local(const Class& origin, const Class& other, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = - Jacobian::Identity(); if (H2) *H2 = Jacobian::Identity(); Class v = other-origin; @@ -40,7 +40,7 @@ struct VectorSpaceImpl { } static Class Retract(const Class& origin, const TangentVector& v, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = Jacobian::Identity(); if (H2) *H2 = Jacobian::Identity(); return origin + v; @@ -51,31 +51,31 @@ struct VectorSpaceImpl { /// @name Lie Group /// @{ - static TangentVector Logmap(const Class& m, ChartJacobian Hm = boost::none) { + static TangentVector Logmap(const Class& m, ChartJacobian Hm = {}) { if (Hm) *Hm = Jacobian::Identity(); return m.vector(); } - static Class Expmap(const TangentVector& v, ChartJacobian Hv = boost::none) { + static Class Expmap(const TangentVector& v, ChartJacobian Hv = {}) { if (Hv) *Hv = Jacobian::Identity(); return Class(v); } - static Class Compose(const Class& v1, const Class& v2, ChartJacobian H1 = boost::none, - ChartJacobian H2 = boost::none) { + static Class Compose(const Class& v1, const Class& v2, ChartJacobian H1 = {}, + ChartJacobian H2 = {}) { if (H1) *H1 = Jacobian::Identity(); if (H2) *H2 = Jacobian::Identity(); return v1 + v2; } - static Class Between(const Class& v1, const Class& v2, ChartJacobian H1 = boost::none, - ChartJacobian H2 = boost::none) { + static Class Between(const Class& v1, const Class& v2, ChartJacobian H1 = {}, + ChartJacobian H2 = {}) { if (H1) *H1 = - Jacobian::Identity(); if (H2) *H2 = Jacobian::Identity(); return v2 - v1; } - static Class Inverse(const Class& v, ChartJacobian H = boost::none) { + static Class Inverse(const Class& v, ChartJacobian H = {}) { if (H) *H = - Jacobian::Identity(); return -v; } @@ -106,7 +106,7 @@ struct VectorSpaceImpl { } static TangentVector Local(const Class& origin, const Class& other, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = - Eye(origin); if (H2) *H2 = Eye(other); Class v = other-origin; @@ -114,7 +114,7 @@ struct VectorSpaceImpl { } static Class Retract(const Class& origin, const TangentVector& v, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = Eye(origin); if (H2) *H2 = Eye(origin); return origin + v; @@ -125,12 +125,12 @@ struct VectorSpaceImpl { /// @name Lie Group /// @{ - static TangentVector Logmap(const Class& m, ChartJacobian Hm = boost::none) { + static TangentVector Logmap(const Class& m, ChartJacobian Hm = {}) { if (Hm) *Hm = Eye(m); return m.vector(); } - static Class Expmap(const TangentVector& v, ChartJacobian Hv = boost::none) { + static Class Expmap(const TangentVector& v, ChartJacobian Hv = {}) { Class result(v); if (Hv) *Hv = Eye(v); @@ -138,14 +138,14 @@ struct VectorSpaceImpl { } static Class Compose(const Class& v1, const Class& v2, ChartJacobian H1, - ChartJacobian H2 = boost::none) { + ChartJacobian H2 = {}) { if (H1) *H1 = Eye(v1); if (H2) *H2 = Eye(v2); return v1 + v2; } static Class Between(const Class& v1, const Class& v2, ChartJacobian H1, - ChartJacobian H2 = boost::none) { + ChartJacobian H2 = {}) { if (H1) *H1 = - Eye(v1); if (H2) *H2 = Eye(v2); return v2 - v1; @@ -237,7 +237,7 @@ struct ScalarTraits : VectorSpaceImpl { typedef OptionalJacobian<1, 1> ChartJacobian; static TangentVector Local(Scalar origin, Scalar other, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) (*H1)[0] = -1.0; if (H2) (*H2)[0] = 1.0; TangentVector result; @@ -246,7 +246,7 @@ struct ScalarTraits : VectorSpaceImpl { } static Scalar Retract(Scalar origin, const TangentVector& v, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) (*H1)[0] = 1.0; if (H2) (*H2)[0] = 1.0; return origin + v[0]; @@ -255,12 +255,12 @@ struct ScalarTraits : VectorSpaceImpl { /// @name Lie Group /// @{ - static TangentVector Logmap(Scalar m, ChartJacobian H = boost::none) { + static TangentVector Logmap(Scalar m, ChartJacobian H = {}) { if (H) (*H)[0] = 1.0; return Local(0, m); } - static Scalar Expmap(const TangentVector& v, ChartJacobian H = boost::none) { + static Scalar Expmap(const TangentVector& v, ChartJacobian H = {}) { if (H) (*H)[0] = 1.0; return v[0]; } @@ -312,7 +312,7 @@ struct traits > : typedef OptionalJacobian ChartJacobian; static TangentVector Local(const Fixed& origin, const Fixed& other, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) (*H1) = -Jacobian::Identity(); if (H2) (*H2) = Jacobian::Identity(); TangentVector result; @@ -321,7 +321,7 @@ struct traits > : } static Fixed Retract(const Fixed& origin, const TangentVector& v, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) (*H1) = Jacobian::Identity(); if (H2) (*H2) = Jacobian::Identity(); return origin + Eigen::Map(v.data()); @@ -330,14 +330,14 @@ struct traits > : /// @name Lie Group /// @{ - static TangentVector Logmap(const Fixed& m, ChartJacobian H = boost::none) { + static TangentVector Logmap(const Fixed& m, ChartJacobian H = {}) { if (H) *H = Jacobian::Identity(); TangentVector result; Eigen::Map(result.data()) = m; return result; } - static Fixed Expmap(const TangentVector& v, ChartJacobian H = boost::none) { + static Fixed Expmap(const TangentVector& v, ChartJacobian H = {}) { Fixed m; m.setZero(); if (H) *H = Jacobian::Identity(); @@ -393,7 +393,7 @@ struct DynamicTraits { } static TangentVector Local(const Dynamic& m, const Dynamic& other, // - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = -Eye(m); if (H2) *H2 = Eye(m); TangentVector v(GetDimension(m)); @@ -402,7 +402,7 @@ struct DynamicTraits { } static Dynamic Retract(const Dynamic& m, const TangentVector& v, // - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = Eye(m); if (H2) *H2 = Eye(m); return m + Eigen::Map(v.data(), m.rows(), m.cols()); @@ -411,32 +411,32 @@ struct DynamicTraits { /// @name Lie Group /// @{ - static TangentVector Logmap(const Dynamic& m, ChartJacobian H = boost::none) { + static TangentVector Logmap(const Dynamic& m, ChartJacobian H = {}) { if (H) *H = Eye(m); TangentVector result(GetDimension(m)); Eigen::Map(result.data(), m.cols(), m.rows()) = m; return result; } - static Dynamic Expmap(const TangentVector& /*v*/, ChartJacobian H = boost::none) { + static Dynamic Expmap(const TangentVector& /*v*/, ChartJacobian H = {}) { static_cast(H); throw std::runtime_error("Expmap not defined for dynamic types"); } - static Dynamic Inverse(const Dynamic& m, ChartJacobian H = boost::none) { + static Dynamic Inverse(const Dynamic& m, ChartJacobian H = {}) { if (H) *H = -Eye(m); return -m; } static Dynamic Compose(const Dynamic& v1, const Dynamic& v2, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = Eye(v1); if (H2) *H2 = Eye(v1); return v1 + v2; } static Dynamic Between(const Dynamic& v1, const Dynamic& v2, - ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) { + ChartJacobian H1 = {}, ChartJacobian H2 = {}) { if (H1) *H1 = -Eye(v1); if (H2) *H2 = Eye(v1); return v2 - v1; diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index e4255bc63..8c9934d77 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -37,8 +37,8 @@ namespace gtsam { * for a function with one relevant param and an optional derivative: * Foo bar(const Obj& a, OptionalMatrixType H1) * Use boost.bind to restructure: - * std::bind(bar, std::placeholders::_1, boost::none) - * This syntax will fix the optional argument to boost::none, while using the first argument provided + * std::bind(bar, std::placeholders::_1, {}) + * This syntax will fix the optional argument to {}, while using the first argument provided * * For member functions, such as below, with an instantiated copy instanceOfSomeClass * Foo SomeClass::bar(const Obj& a) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index bb8574245..7aab743db 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -24,6 +24,7 @@ #include #include +#include #include #include diff --git a/gtsam/base/std_optional_serialization.h b/gtsam/base/std_optional_serialization.h new file mode 100644 index 000000000..d4ed4f53d --- /dev/null +++ b/gtsam/base/std_optional_serialization.h @@ -0,0 +1,95 @@ +// Functionality to serialize std::optional to boost::archive +// Following this: +// PR: https://github.com/boostorg/serialization/pull/148/files# + +#pragma once +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +/** A bunch of declarations to deal with gcc bug + * The compiler has a difficult time distinguisihing between: + * + * template