diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 2f1810dbb..e9929227a 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -376,8 +376,8 @@ class Pose2 { Pose2(const gtsam::Rot2& r, const gtsam::Point2& t); Pose2(Vector v); - static boost::optional Align(const gtsam::Point2Pairs& abPointPairs); - static boost::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); + static std::optional Align(const gtsam::Point2Pairs& abPointPairs); + static std::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); // Testable void print(string s = "") const; @@ -440,8 +440,8 @@ class Pose3 { Pose3(const gtsam::Pose2& pose2); Pose3(Matrix mat); - static boost::optional Align(const gtsam::Point3Pairs& abPointPairs); - static boost::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); + static std::optional Align(const gtsam::Point3Pairs& abPointPairs); + static std::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); // Testable void print(string s = "") const; diff --git a/gtsam/navigation/navigation.i b/gtsam/navigation/navigation.i index 7bbef9fc5..8e6090e06 100644 --- a/gtsam/navigation/navigation.i +++ b/gtsam/navigation/navigation.i @@ -75,8 +75,8 @@ virtual class PreintegratedRotationParams { Matrix getGyroscopeCovariance() const; - boost::optional getOmegaCoriolis() const; - boost::optional getBodyPSensor() const; + std::optional getOmegaCoriolis() const; + std::optional getBodyPSensor() const; }; #include diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 80e87a5fa..3e3373f61 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -392,7 +392,7 @@ virtual class LinearContainerFactor : gtsam::NonlinearFactor { LinearContainerFactor(gtsam::GaussianFactor* factor); gtsam::GaussianFactor* factor() const; - // const boost::optional& linearizationPoint() const; + // const std::optional& linearizationPoint() const; bool isJacobian() const; gtsam::JacobianFactor* toJacobian() const; diff --git a/gtsam_unstable/gtsam_unstable.i b/gtsam_unstable/gtsam_unstable.i index d338b34aa..5cd7e0da2 100644 --- a/gtsam_unstable/gtsam_unstable.i +++ b/gtsam_unstable/gtsam_unstable.i @@ -179,7 +179,7 @@ class SimWall2D { gtsam::Point2 midpoint() const; bool intersects(const gtsam::SimWall2D& wall) const; - // bool intersects(const gtsam::SimWall2D& wall, boost::optional pt={}) const; + // bool intersects(const gtsam::SimWall2D& wall, gtsam::Point2* pt = nullptr) const; gtsam::Point2 norm() const; gtsam::Rot2 reflection(const gtsam::Point2& init, const gtsam::Point2& intersection) const;