rename KeypointsList -> KeypointsVector
parent
4d690efdeb
commit
4f406650f7
|
|
@ -57,7 +57,7 @@ struct Keypoints {
|
||||||
Keypoints(const gtsam::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none
|
Keypoints(const gtsam::KeypointCoordinates& coordinates): coordinates(coordinates) {}; // boost::none
|
||||||
};
|
};
|
||||||
|
|
||||||
using KeypointsList = std::vector<Keypoints>;
|
using KeypointsVector = std::vector<Keypoints>;
|
||||||
// Mapping from each image pair to (N,2) array representing indices of matching keypoints.
|
// Mapping from each image pair to (N,2) array representing indices of matching keypoints.
|
||||||
using MatchIndicesMap = std::map<IndexPair, CorrespondenceIndices>;
|
using MatchIndicesMap = std::map<IndexPair, CorrespondenceIndices>;
|
||||||
|
|
||||||
|
|
@ -143,7 +143,7 @@ class DsfTrackGenerator {
|
||||||
// @param Length-N list of keypoints, for N images/cameras.
|
// @param Length-N list of keypoints, for N images/cameras.
|
||||||
std::vector<SfmTrack2d> generate_tracks_from_pairwise_matches(
|
std::vector<SfmTrack2d> generate_tracks_from_pairwise_matches(
|
||||||
const MatchIndicesMap& matches_dict,
|
const MatchIndicesMap& matches_dict,
|
||||||
const KeypointsList& keypoints_list) {
|
const KeypointsVector& keypoints_list) {
|
||||||
std::vector<SfmTrack2d> track_2d_list;
|
std::vector<SfmTrack2d> track_2d_list;
|
||||||
|
|
||||||
std::cout << "[SfmTrack2d] Starting Union-Find..." << std::endl;
|
std::cout << "[SfmTrack2d] Starting Union-Find..." << std::endl;
|
||||||
|
|
|
||||||
|
|
@ -24,9 +24,9 @@ class Keypoints
|
||||||
}; // check if this should be a method
|
}; // check if this should be a method
|
||||||
|
|
||||||
|
|
||||||
class KeypointsList {
|
class KeypointsVector {
|
||||||
KeypointsList();
|
KeypointsVector();
|
||||||
KeypointsList(const gtsam::KeypointsList& other);
|
KeypointsVector(const gtsam::KeypointsVector& other);
|
||||||
void push_back(const gtsam::Keypoints& keypoints);
|
void push_back(const gtsam::Keypoints& keypoints);
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
bool empty() const;
|
bool empty() const;
|
||||||
|
|
@ -78,7 +78,7 @@ class DsfTrackGenerator {
|
||||||
DsfTrackGenerator();
|
DsfTrackGenerator();
|
||||||
const gtsam::SfmTrack2dVector generate_tracks_from_pairwise_matches(
|
const gtsam::SfmTrack2dVector generate_tracks_from_pairwise_matches(
|
||||||
const gtsam::MatchIndicesMap& matches_dict,
|
const gtsam::MatchIndicesMap& matches_dict,
|
||||||
const gtsam::KeypointsList& keypoints_list);
|
const gtsam::KeypointsVector& keypoints_list);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -53,7 +53,7 @@ set(ignore
|
||||||
gtsam::DiscreteKey
|
gtsam::DiscreteKey
|
||||||
gtsam::KeyPairDoubleMap
|
gtsam::KeyPairDoubleMap
|
||||||
gtsam::MatchIndicesMap
|
gtsam::MatchIndicesMap
|
||||||
gtsam::KeypointsList
|
gtsam::KeypointsVector
|
||||||
gtsam::SfmTrack2dVector
|
gtsam::SfmTrack2dVector
|
||||||
gtsam::NamedSfmMeasurementVector)
|
gtsam::NamedSfmMeasurementVector)
|
||||||
|
|
||||||
|
|
@ -154,7 +154,7 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON)
|
||||||
gtsam::CameraSetCal3Fisheye
|
gtsam::CameraSetCal3Fisheye
|
||||||
gtsam::KeyPairDoubleMap
|
gtsam::KeyPairDoubleMap
|
||||||
gtsam::MatchIndicesMap
|
gtsam::MatchIndicesMap
|
||||||
gtsam::KeypointsList
|
gtsam::KeypointsVector
|
||||||
gtsam::SfmTrack2dVector
|
gtsam::SfmTrack2dVector
|
||||||
gtsam::NamedSfmMeasurementVector)
|
gtsam::NamedSfmMeasurementVector)
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -22,7 +22,7 @@ py::bind_map<gtsam::MatchIndicesMap>(m_, "MatchIndicesMap");
|
||||||
|
|
||||||
py::bind_vector<
|
py::bind_vector<
|
||||||
std::vector<gtsam::Keypoints> >(
|
std::vector<gtsam::Keypoints> >(
|
||||||
m_, "KeypointsList");
|
m_, "KeypointsVector");
|
||||||
|
|
||||||
|
|
||||||
py::bind_vector<
|
py::bind_vector<
|
||||||
|
|
|
||||||
|
|
@ -12,7 +12,7 @@ from gtsam import (
|
||||||
DsfTrackGenerator,
|
DsfTrackGenerator,
|
||||||
IndexPair,
|
IndexPair,
|
||||||
Keypoints,
|
Keypoints,
|
||||||
KeypointsList,
|
KeypointsVector,
|
||||||
MatchIndicesMap,
|
MatchIndicesMap,
|
||||||
NamedSfmMeasurement,
|
NamedSfmMeasurement,
|
||||||
NamedSfmMeasurementVector,
|
NamedSfmMeasurementVector,
|
||||||
|
|
@ -30,7 +30,7 @@ class TestDsfTrackGenerator(GtsamTestCase):
|
||||||
kps_i1 = Keypoints(coordinates=np.array([[50.0, 60], [70, 80], [90, 100]]))
|
kps_i1 = Keypoints(coordinates=np.array([[50.0, 60], [70, 80], [90, 100]]))
|
||||||
kps_i2 = Keypoints(coordinates=np.array([[110.0, 120], [130, 140]]))
|
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_i0)
|
||||||
keypoints_list.append(kps_i1)
|
keypoints_list.append(kps_i1)
|
||||||
keypoints_list.append(kps_i2)
|
keypoints_list.append(kps_i2)
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue