diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 96249b6e0..1e9444b02 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -1040,7 +1040,11 @@ class Similarity3 { double scale() const; }; -template +template class CameraSet { CameraSet(); @@ -1088,10 +1092,10 @@ class StereoCamera { }; #include - -virtual class TriangulationResult : boost::optional { +class TriangulationResult { enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT }; Status status; + const gtsam::Point3& get() const; }; class TriangulationParameters { diff --git a/python/gtsam/specializations/geometry.h b/python/gtsam/specializations/geometry.h index 5a0ea35ef..99f40253f 100644 --- a/python/gtsam/specializations/geometry.h +++ b/python/gtsam/specializations/geometry.h @@ -21,6 +21,8 @@ py::bind_vector>(m_, "Pose3Pairs"); py::bind_vector>(m_, "Pose3Vector"); py::bind_vector>>( m_, "CameraSetCal3_S2"); +py::bind_vector>>( + m_, "CameraSetCal3DS2"); py::bind_vector>>( m_, "CameraSetCal3Bundler"); py::bind_vector>>(