diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 617d09da7..1df9efd22 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -497,9 +497,6 @@ TriangulationResult triangulateSafe(const CameraSet& cameras, } // Vector of Cameras - used by the Python/MATLAB wrapper -//typedef CameraSet> CameraSetCal3Bundler; -//typedef CameraSet> CameraSetCal3_S2; - using CameraSetCal3Bundler = CameraSet>; using CameraSetCal3_S2 = CameraSet>; diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 954d74f05..8596106e4 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -1068,18 +1068,18 @@ typedef gtsam::PinholeCamera PinholeCameraCal3DS2; typedef gtsam::PinholeCamera PinholeCameraCal3Unified; typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; -template +template class CameraSet { CameraSet(); - // // common STL methods - // size_t size() const; - // bool empty() const; - // void clear(); + // common STL methods + size_t size() const; + bool empty() const; + void clear(); - // // structure specific methods - // T at(size_t i) const; - // void push_back(const T& cam); + // structure specific methods + T at(size_t i) const; + void push_back(const T& cam); }; typedef gtsam::CameraSet CameraSetCal3_S2; diff --git a/python/gtsam/preamble.h b/python/gtsam/preamble.h index 92ad14797..6166f615e 100644 --- a/python/gtsam/preamble.h +++ b/python/gtsam/preamble.h @@ -10,5 +10,3 @@ PYBIND11_MAKE_OPAQUE(std::vector); PYBIND11_MAKE_OPAQUE(std::vector > >); PYBIND11_MAKE_OPAQUE(std::vector > >); PYBIND11_MAKE_OPAQUE(std::vector); -//PYBIND11_MAKE_OPAQUE(gtsam::CameraSet >); -//PYBIND11_MAKE_OPAQUE(gtsam::CameraSet >); diff --git a/python/gtsam/specializations.h b/python/gtsam/specializations.h index 8f97c2dae..cacad874c 100644 --- a/python/gtsam/specializations.h +++ b/python/gtsam/specializations.h @@ -13,5 +13,3 @@ py::bind_vector > >(m_, "Bina py::bind_map(m_, "IndexPairSetMap"); py::bind_vector(m_, "IndexPairVector"); py::bind_map(m_, "KeyPairDoubleMap"); -// py::bind_vector > >(m_, "CameraSetCal3_S2"); -// py::bind_vector > >(m_, "CameraSetCal3Bundler"); diff --git a/python/gtsam/tests/test_Triangulation.py b/python/gtsam/tests/test_Triangulation.py index a1adcd2c9..2a9851d04 100644 --- a/python/gtsam/tests/test_Triangulation.py +++ b/python/gtsam/tests/test_Triangulation.py @@ -75,8 +75,8 @@ class TestVisualISAMExample(GtsamTestCase): camera2 = PinholeCameraCal3_S2(self.pose2, K2) cameras = CameraSetCal3_S2() - cameras.append(camera1) - cameras.append(camera2) + cameras.push_back(camera1) + cameras.push_back(camera2) # Project two landmarks into two cameras and triangulate z1 = camera1.project(self.landmark) @@ -101,8 +101,8 @@ class TestVisualISAMExample(GtsamTestCase): camera2 = PinholeCameraCal3Bundler(self.pose2, K2) cameras = CameraSetCal3Bundler() - cameras.append(camera1) - cameras.append(camera2) + cameras.push_back(camera1) + cameras.push_back(camera2) # Project two landmarks into two cameras and triangulate z1 = camera1.project(self.landmark)