release/4.3a0
kartik arcot 2023-01-13 14:12:15 -08:00
parent 9329bddd8a
commit 607a30a08e
4 changed files with 8 additions and 8 deletions

View File

@ -376,8 +376,8 @@ class Pose2 {
Pose2(const gtsam::Rot2& r, const gtsam::Point2& t); Pose2(const gtsam::Rot2& r, const gtsam::Point2& t);
Pose2(Vector v); Pose2(Vector v);
static boost::optional<gtsam::Pose2> Align(const gtsam::Point2Pairs& abPointPairs); static std::optional<gtsam::Pose2> Align(const gtsam::Point2Pairs& abPointPairs);
static boost::optional<gtsam::Pose2> Align(const gtsam::Matrix& a, const gtsam::Matrix& b); static std::optional<gtsam::Pose2> Align(const gtsam::Matrix& a, const gtsam::Matrix& b);
// Testable // Testable
void print(string s = "") const; void print(string s = "") const;
@ -440,8 +440,8 @@ class Pose3 {
Pose3(const gtsam::Pose2& pose2); Pose3(const gtsam::Pose2& pose2);
Pose3(Matrix mat); Pose3(Matrix mat);
static boost::optional<gtsam::Pose3> Align(const gtsam::Point3Pairs& abPointPairs); static std::optional<gtsam::Pose3> Align(const gtsam::Point3Pairs& abPointPairs);
static boost::optional<gtsam::Pose3> Align(const gtsam::Matrix& a, const gtsam::Matrix& b); static std::optional<gtsam::Pose3> Align(const gtsam::Matrix& a, const gtsam::Matrix& b);
// Testable // Testable
void print(string s = "") const; void print(string s = "") const;

View File

@ -75,8 +75,8 @@ virtual class PreintegratedRotationParams {
Matrix getGyroscopeCovariance() const; Matrix getGyroscopeCovariance() const;
boost::optional<Vector> getOmegaCoriolis() const; std::optional<Vector> getOmegaCoriolis() const;
boost::optional<gtsam::Pose3> getBodyPSensor() const; std::optional<gtsam::Pose3> getBodyPSensor() const;
}; };
#include <gtsam/navigation/PreintegrationParams.h> #include <gtsam/navigation/PreintegrationParams.h>

View File

@ -392,7 +392,7 @@ virtual class LinearContainerFactor : gtsam::NonlinearFactor {
LinearContainerFactor(gtsam::GaussianFactor* factor); LinearContainerFactor(gtsam::GaussianFactor* factor);
gtsam::GaussianFactor* factor() const; gtsam::GaussianFactor* factor() const;
// const boost::optional<Values>& linearizationPoint() const; // const std::optional<Values>& linearizationPoint() const;
bool isJacobian() const; bool isJacobian() const;
gtsam::JacobianFactor* toJacobian() const; gtsam::JacobianFactor* toJacobian() const;

View File

@ -179,7 +179,7 @@ class SimWall2D {
gtsam::Point2 midpoint() const; gtsam::Point2 midpoint() const;
bool intersects(const gtsam::SimWall2D& wall) const; bool intersects(const gtsam::SimWall2D& wall) const;
// bool intersects(const gtsam::SimWall2D& wall, boost::optional<gtsam::Point2&> pt={}) const; // bool intersects(const gtsam::SimWall2D& wall, gtsam::Point2* pt = nullptr) const;
gtsam::Point2 norm() const; gtsam::Point2 norm() const;
gtsam::Rot2 reflection(const gtsam::Point2& init, const gtsam::Point2& intersection) const; gtsam::Rot2 reflection(const gtsam::Point2& init, const gtsam::Point2& intersection) const;