added utility functions and code cleanup
parent
77b6595998
commit
2e39433469
|
@ -497,9 +497,6 @@ TriangulationResult triangulateSafe(const CameraSet<CAMERA>& cameras,
|
|||
}
|
||||
|
||||
// Vector of Cameras - used by the Python/MATLAB wrapper
|
||||
//typedef CameraSet<PinholeCamera<Cal3Bundler>> CameraSetCal3Bundler;
|
||||
//typedef CameraSet<PinholeCamera<Cal3_S2>> CameraSetCal3_S2;
|
||||
|
||||
using CameraSetCal3Bundler = CameraSet<PinholeCamera<Cal3Bundler>>;
|
||||
using CameraSetCal3_S2 = CameraSet<PinholeCamera<Cal3_S2>>;
|
||||
|
||||
|
|
|
@ -1068,18 +1068,18 @@ typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
|
|||
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
|
||||
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
|
||||
|
||||
template<T = {gtsam::PinholeCameraCal3Bundler, gtsam::PinholeCameraCal3_S2}>
|
||||
template<T>
|
||||
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<gtsam::PinholeCameraCal3_S2> CameraSetCal3_S2;
|
||||
|
|
|
@ -10,5 +10,3 @@ PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Pose3>);
|
|||
PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > >);
|
||||
PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > >);
|
||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::IndexPair>);
|
||||
//PYBIND11_MAKE_OPAQUE(gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3Bundler> >);
|
||||
//PYBIND11_MAKE_OPAQUE(gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3_S2> >);
|
||||
|
|
|
@ -13,5 +13,3 @@ py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(m_, "Bina
|
|||
py::bind_map<gtsam::IndexPairSetMap>(m_, "IndexPairSetMap");
|
||||
py::bind_vector<gtsam::IndexPairVector>(m_, "IndexPairVector");
|
||||
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
|
||||
// py::bind_vector<gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3_S2> > >(m_, "CameraSetCal3_S2");
|
||||
// py::bind_vector<gtsam::CameraSet<gtsam::PinholeCamera<gtsam::Cal3Bundler> > >(m_, "CameraSetCal3Bundler");
|
||||
|
|
|
@ -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)
|
||||
|
|
Loading…
Reference in New Issue