From b5e9dc04fd478c12bca67ba02f0b6e8216958db8 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 10 May 2022 22:56:55 -0400 Subject: [PATCH] Make status a public field --- gtsam/geometry/triangulation.h | 66 ++++++++++++++-------------------- 1 file changed, 26 insertions(+), 40 deletions(-) diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 49b5aef04..401fd2d0b 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -23,6 +23,7 @@ #include #include #include +#include #include #include #include @@ -510,18 +511,18 @@ private: }; /** - * TriangulationResult is an optional point, along with the reasons why it is invalid. + * TriangulationResult is an optional point, along with the reasons why it is + * invalid. */ -class TriangulationResult: public boost::optional { - enum Status { - VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT - }; - Status status_; - TriangulationResult(Status s) : - status_(s) { - } -public: +class TriangulationResult : public boost::optional { + public: + enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT }; + Status status; + private: + TriangulationResult(Status s) : status(s) {} + + public: /** * Default constructor, only for serialization */ @@ -530,54 +531,38 @@ public: /** * Constructor */ - TriangulationResult(const Point3& p) : - status_(VALID) { - reset(p); - } + TriangulationResult(const Point3& p) : status(VALID) { reset(p); } static TriangulationResult Degenerate() { return TriangulationResult(DEGENERATE); } - static TriangulationResult Outlier() { - return TriangulationResult(OUTLIER); - } + static TriangulationResult Outlier() { return TriangulationResult(OUTLIER); } static TriangulationResult FarPoint() { return TriangulationResult(FAR_POINT); } static TriangulationResult BehindCamera() { return TriangulationResult(BEHIND_CAMERA); } - bool valid() const { - return status_ == VALID; - } - bool degenerate() const { - return status_ == DEGENERATE; - } - bool outlier() const { - return status_ == OUTLIER; - } - bool farPoint() const { - return status_ == FAR_POINT; - } - bool behindCamera() const { - return status_ == BEHIND_CAMERA; - } + bool valid() const { return status == VALID; } + bool degenerate() const { return status == DEGENERATE; } + bool outlier() const { return status == OUTLIER; } + bool farPoint() const { return status == FAR_POINT; } + bool behindCamera() const { return status == BEHIND_CAMERA; } // stream to output - friend std::ostream &operator<<(std::ostream &os, - const TriangulationResult& result) { + friend std::ostream& operator<<(std::ostream& os, + const TriangulationResult& result) { if (result) os << "point = " << *result << std::endl; else - os << "no point, status = " << result.status_ << std::endl; + os << "no point, status = " << result.status << std::endl; return os; } -private: - + private: /// Serialization function friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int version) { - ar & BOOST_SERIALIZATION_NVP(status_); + template + void serialize(ARCHIVE& ar, const unsigned int version) { + ar& BOOST_SERIALIZATION_NVP(status); } }; @@ -644,6 +629,7 @@ TriangulationResult triangulateSafe(const CameraSet& cameras, // Vector of Cameras - used by the Python/MATLAB wrapper using CameraSetCal3Bundler = CameraSet>; using CameraSetCal3_S2 = CameraSet>; +using CameraSetCal3DS2 = CameraSet>; using CameraSetCal3Fisheye = CameraSet>; using CameraSetCal3Unified = CameraSet>; using CameraSetSpherical = CameraSet;