Camera sets

release/4.3a0
Frank Dellaert 2022-05-11 00:27:50 -04:00
parent 8333c8f15c
commit 287ea28920
2 changed files with 9 additions and 3 deletions

View File

@ -1040,7 +1040,11 @@ class Similarity3 {
double scale() const;
};
template <T>
template <T = {gtsam::PinholeCameraCal3_S2,
gtsam::PinholeCameraCal3DS2,
gtsam::PinholeCameraCal3Bundler,
gtsam::PinholeCameraCal3Fisheye,
gtsam::PinholeCameraCal3Unified}>
class CameraSet {
CameraSet();
@ -1088,10 +1092,10 @@ class StereoCamera {
};
#include <gtsam/geometry/triangulation.h>
virtual class TriangulationResult : boost::optional<gtsam::Point3> {
class TriangulationResult {
enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT };
Status status;
const gtsam::Point3& get() const;
};
class TriangulationParameters {

View File

@ -21,6 +21,8 @@ py::bind_vector<std::vector<gtsam::Pose3Pair>>(m_, "Pose3Pairs");
py::bind_vector<std::vector<gtsam::Pose3>>(m_, "Pose3Vector");
py::bind_vector<gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3_S2>>>(
m_, "CameraSetCal3_S2");
py::bind_vector<gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3DS2>>>(
m_, "CameraSetCal3DS2");
py::bind_vector<gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3Bundler>>>(
m_, "CameraSetCal3Bundler");
py::bind_vector<gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3Unified>>>(