diff --git a/gtsam/sfm/DsfTrackGenerator.h b/gtsam/sfm/DsfTrackGenerator.h index 05ad61390..a16ed3522 100644 --- a/gtsam/sfm/DsfTrackGenerator.h +++ b/gtsam/sfm/DsfTrackGenerator.h @@ -57,7 +57,7 @@ struct Keypoints { Keypoints(const gtsam::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none }; -using KeypointsList = std::vector; +using KeypointsVector = std::vector; // Mapping from each image pair to (N,2) array representing indices of matching keypoints. using MatchIndicesMap = std::map; @@ -143,7 +143,7 @@ class DsfTrackGenerator { // @param Length-N list of keypoints, for N images/cameras. std::vector generate_tracks_from_pairwise_matches( const MatchIndicesMap& matches_dict, - const KeypointsList& keypoints_list) { + const KeypointsVector& keypoints_list) { std::vector track_2d_list; std::cout << "[SfmTrack2d] Starting Union-Find..." << std::endl; diff --git a/gtsam/sfm/sfm.i b/gtsam/sfm/sfm.i index 6fd380b3c..9613410a7 100644 --- a/gtsam/sfm/sfm.i +++ b/gtsam/sfm/sfm.i @@ -24,9 +24,9 @@ class Keypoints }; // check if this should be a method -class KeypointsList { - KeypointsList(); - KeypointsList(const gtsam::KeypointsList& other); +class KeypointsVector { + KeypointsVector(); + KeypointsVector(const gtsam::KeypointsVector& other); void push_back(const gtsam::Keypoints& keypoints); size_t size() const; bool empty() const; @@ -78,7 +78,7 @@ class DsfTrackGenerator { DsfTrackGenerator(); const gtsam::SfmTrack2dVector generate_tracks_from_pairwise_matches( const gtsam::MatchIndicesMap& matches_dict, - const gtsam::KeypointsList& keypoints_list); + const gtsam::KeypointsVector& keypoints_list); }; diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 21f9f951d..600aeecc9 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -53,7 +53,7 @@ set(ignore gtsam::DiscreteKey gtsam::KeyPairDoubleMap gtsam::MatchIndicesMap - gtsam::KeypointsList + gtsam::KeypointsVector gtsam::SfmTrack2dVector gtsam::NamedSfmMeasurementVector) @@ -154,7 +154,7 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON) gtsam::CameraSetCal3Fisheye gtsam::KeyPairDoubleMap gtsam::MatchIndicesMap - gtsam::KeypointsList + gtsam::KeypointsVector gtsam::SfmTrack2dVector gtsam::NamedSfmMeasurementVector) diff --git a/python/gtsam/specializations/sfm.h b/python/gtsam/specializations/sfm.h index 1bbb93570..63f7f1a48 100644 --- a/python/gtsam/specializations/sfm.h +++ b/python/gtsam/specializations/sfm.h @@ -22,7 +22,7 @@ py::bind_map(m_, "MatchIndicesMap"); py::bind_vector< std::vector >( - m_, "KeypointsList"); + m_, "KeypointsVector"); py::bind_vector< diff --git a/python/gtsam/tests/test_DsfTrackGenerator.py b/python/gtsam/tests/test_DsfTrackGenerator.py index 3d4188284..563a01165 100644 --- a/python/gtsam/tests/test_DsfTrackGenerator.py +++ b/python/gtsam/tests/test_DsfTrackGenerator.py @@ -12,7 +12,7 @@ from gtsam import ( DsfTrackGenerator, IndexPair, Keypoints, - KeypointsList, + KeypointsVector, MatchIndicesMap, NamedSfmMeasurement, NamedSfmMeasurementVector, @@ -30,7 +30,7 @@ class TestDsfTrackGenerator(GtsamTestCase): kps_i1 = Keypoints(coordinates=np.array([[50.0, 60], [70, 80], [90, 100]])) kps_i2 = Keypoints(coordinates=np.array([[110.0, 120], [130, 140]])) - keypoints_list = KeypointsList() + keypoints_list = KeypointsVector() keypoints_list.append(kps_i0) keypoints_list.append(kps_i1) keypoints_list.append(kps_i2)