diff --git a/gtsam/sfm/DsfTrackGenerator.h b/gtsam/sfm/DsfTrackGenerator.h index 960f1622c..47578d6ea 100644 --- a/gtsam/sfm/DsfTrackGenerator.h +++ b/gtsam/sfm/DsfTrackGenerator.h @@ -30,6 +30,8 @@ namespace gtsam { +namespace gtsfm { + typedef DSFMap DSFMapIndexPair; typedef Eigen::MatrixX2i CorrespondenceIndices; // N x 2 array @@ -54,7 +56,7 @@ struct Keypoints { /// Optional confidences/responses for each detection, of shape N. boost::optional responses; - Keypoints(const gtsam::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none + Keypoints(const gtsam::gtsfm::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none }; using KeypointsVector = std::vector; @@ -119,7 +121,7 @@ class SfmTrack2d { } }; -using SfmTrack2dVector = std::vector; +using SfmTrack2dVector = std::vector; using NamedSfmMeasurementVector = std::vector; @@ -216,5 +218,7 @@ class DsfTrackGenerator { } }; +}///\namespace gtsfm + } // namespace gtsam diff --git a/gtsam/sfm/sfm.i b/gtsam/sfm/sfm.i index ce840a1a9..984955d23 100644 --- a/gtsam/sfm/sfm.i +++ b/gtsam/sfm/sfm.i @@ -4,34 +4,36 @@ namespace gtsam { +namespace gtsfm { + #include class MatchIndicesMap { MatchIndicesMap(); - MatchIndicesMap(const gtsam::MatchIndicesMap& other); + MatchIndicesMap(const gtsam::gtsfm::MatchIndicesMap& other); size_t size() const; bool empty() const; void clear(); - gtsam::CorrespondenceIndices at(const pair& keypair) const; + gtsam::gtsfm::CorrespondenceIndices at(const pair& keypair) const; }; class Keypoints { - Keypoints(const gtsam::KeypointCoordinates& coordinates); - gtsam::KeypointCoordinates coordinates; + Keypoints(const gtsam::gtsfm::KeypointCoordinates& coordinates); + gtsam::gtsfm::KeypointCoordinates coordinates; }; // check if this should be a method class KeypointsVector { KeypointsVector(); - KeypointsVector(const gtsam::KeypointsVector& other); - void push_back(const gtsam::Keypoints& keypoints); + KeypointsVector(const gtsam::gtsfm::KeypointsVector& other); + void push_back(const gtsam::gtsfm::Keypoints& keypoints); size_t size() const; bool empty() const; void clear(); - gtsam::Keypoints at(const size_t& index) const; + gtsam::gtsfm::Keypoints at(const size_t& index) const; }; @@ -44,44 +46,44 @@ class NamedSfmMeasurement class NamedSfmMeasurementVector { NamedSfmMeasurementVector(); - NamedSfmMeasurementVector(const gtsam::NamedSfmMeasurementVector& other); - void push_back(const gtsam::NamedSfmMeasurement& measurement); + NamedSfmMeasurementVector(const gtsam::gtsfm::NamedSfmMeasurementVector& other); + void push_back(const gtsam::gtsfm::NamedSfmMeasurement& measurement); size_t size() const; bool empty() const; void clear(); - gtsam::NamedSfmMeasurement at(const size_t& index) const; + gtsam::gtsfm::NamedSfmMeasurement at(const size_t& index) const; }; class SfmTrack2d { SfmTrack2d(); - SfmTrack2d(std::vector &measurements); + SfmTrack2d(std::vector &measurements); size_t numberMeasurements() const; - void addMeasurement(const gtsam::NamedSfmMeasurement &m); - std::vector measurements(); - gtsam::NamedSfmMeasurement measurement(size_t idx) const; + void addMeasurement(const gtsam::gtsfm::NamedSfmMeasurement &m); + std::vector measurements(); + gtsam::gtsfm::NamedSfmMeasurement measurement(size_t idx) const; bool hasUniqueCameras(); }; class SfmTrack2dVector { SfmTrack2dVector(); - SfmTrack2dVector(const gtsam::SfmTrack2dVector& other); - void push_back(const gtsam::SfmTrack2d& track); + SfmTrack2dVector(const gtsam::gtsfm::SfmTrack2dVector& other); + void push_back(const gtsam::gtsfm::SfmTrack2d& track); size_t size() const; bool empty() const; void clear(); - gtsam::SfmTrack2d at(const size_t& index) const; + gtsam::gtsfm::SfmTrack2d at(const size_t& index) const; }; class DsfTrackGenerator { DsfTrackGenerator(); - const gtsam::SfmTrack2dVector generate_tracks_from_pairwise_matches( - const gtsam::MatchIndicesMap& matches_dict, - const gtsam::KeypointsVector& keypoints_list, + const gtsam::gtsfm::SfmTrack2dVector generate_tracks_from_pairwise_matches( + const gtsam::gtsfm::MatchIndicesMap& matches_dict, + const gtsam::gtsfm::KeypointsVector& keypoints_list, bool verbose = false); }; - +}///\namespace gtsfm #include #include diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 600aeecc9..398ee2788 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -52,10 +52,10 @@ set(ignore gtsam::BinaryMeasurementsRot3 gtsam::DiscreteKey gtsam::KeyPairDoubleMap - gtsam::MatchIndicesMap - gtsam::KeypointsVector - gtsam::SfmTrack2dVector - gtsam::NamedSfmMeasurementVector) + gtsam::gtsfm::MatchIndicesMap + gtsam::gtsfm::KeypointsVector + gtsam::gtsfm::SfmTrack2dVector + gtsam::gtsfm::NamedSfmMeasurementVector) set(interface_headers ${PROJECT_SOURCE_DIR}/gtsam/gtsam.i @@ -153,10 +153,10 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON) gtsam::CameraSetCal3Unified gtsam::CameraSetCal3Fisheye gtsam::KeyPairDoubleMap - gtsam::MatchIndicesMap - gtsam::KeypointsVector - gtsam::SfmTrack2dVector - gtsam::NamedSfmMeasurementVector) + gtsam::gtsfm::MatchIndicesMap + gtsam::gtsfm::KeypointsVector + gtsam::gtsfm::SfmTrack2dVector + gtsam::gtsfm::NamedSfmMeasurementVector) pybind_wrap(${GTSAM_PYTHON_UNSTABLE_TARGET} # target diff --git a/python/gtsam/preamble/sfm.h b/python/gtsam/preamble/sfm.h index 91c9fc418..067dd8801 100644 --- a/python/gtsam/preamble/sfm.h +++ b/python/gtsam/preamble/sfm.h @@ -24,7 +24,7 @@ PYBIND11_MAKE_OPAQUE( PYBIND11_MAKE_OPAQUE( std::vector>); PYBIND11_MAKE_OPAQUE( - std::vector); -PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap); + std::vector); +PYBIND11_MAKE_OPAQUE(gtsam::gtsfm::MatchIndicesMap); PYBIND11_MAKE_OPAQUE( - std::vector); \ No newline at end of file + std::vector); \ No newline at end of file diff --git a/python/gtsam/specializations/sfm.h b/python/gtsam/specializations/sfm.h index 63f7f1a48..10fb1a0ab 100644 --- a/python/gtsam/specializations/sfm.h +++ b/python/gtsam/specializations/sfm.h @@ -18,29 +18,25 @@ py::bind_vector > >( py::bind_vector > >( m_, "BinaryMeasurementsRot3"); py::bind_map(m_, "KeyPairDoubleMap"); -py::bind_map(m_, "MatchIndicesMap"); - -py::bind_vector< - std::vector >( - m_, "KeypointsVector"); - - py::bind_vector< std::vector >( m_, "SfmTracks"); - py::bind_vector< std::vector >( m_, "SfmCameras"); - py::bind_vector< std::vector>>( m_, "SfmMeasurementVector" ); -py::bind_vector< - std::vector >( - m_, "SfmTrack2dVector"); py::bind_vector< - std::vector >( + std::vector >( + m_, "SfmTrack2dVector"); +py::bind_vector< + std::vector >( m_, "NamedSfmMeasurementVector"); +py::bind_map(m_, "MatchIndicesMap"); + +py::bind_vector< + std::vector >( + m_, "KeypointsVector"); diff --git a/python/gtsam/tests/test_DsfTrackGenerator.py b/python/gtsam/tests/test_DsfTrackGenerator.py index 721584cff..f1851c221 100644 --- a/python/gtsam/tests/test_DsfTrackGenerator.py +++ b/python/gtsam/tests/test_DsfTrackGenerator.py @@ -8,14 +8,11 @@ import unittest import numpy as np import gtsam -from gtsam import ( +from gtsam import IndexPair, KeypointsVector, MatchIndicesMap, NamedSfmMeasurementVector +from gtsam.gtsam.gtsfm import ( DsfTrackGenerator, - IndexPair, Keypoints, - KeypointsVector, - MatchIndicesMap, NamedSfmMeasurement, - NamedSfmMeasurementVector, SfmTrack2d, ) from gtsam.utils.test_case import GtsamTestCase