clean up docstrings
parent
6e13456db4
commit
629b9cd955
|
@ -48,13 +48,9 @@ struct Keypoints
|
|||
};
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
// TODO: THIS CLASSNAME IS DUPLICATED in SfmTrack.h, conflicts
|
||||
// @param camera index
|
||||
// @param 2d measurement
|
||||
// Implemented as named tuple, instead of std::pair
|
||||
// Implemented as named tuple, instead of std::pair (like SfmMeasurement in SfmTrack.h)
|
||||
struct NamedSfmMeasurement
|
||||
{
|
||||
size_t i;
|
||||
|
@ -93,7 +89,7 @@ class SfmTrack2d
|
|||
|
||||
using MatchIndicesMap = std::map<ImagePair, CorrespondenceIndices>;
|
||||
using KeypointsList = std::vector<Keypoints>;
|
||||
using KeypointsVector = std::vector<Keypoints>; // TODO: prefer KeypointsSet?
|
||||
using KeypointsVector = std::vector<Keypoints>; // TODO(johnwlambert): prefer KeypointsSet?
|
||||
|
||||
|
||||
class DsfTrackGenerator
|
||||
|
@ -113,25 +109,20 @@ class DsfTrackGenerator
|
|||
{
|
||||
std::vector<SfmTrack2d> track_2d_list;
|
||||
|
||||
// TODO: put these checks into the Keypoints class.
|
||||
// check to ensure dimensions of coordinates are correct
|
||||
//dims_valid = all([kps.coordinates.ndim == 2 for kps in keypoints_list])
|
||||
//if not dims_valid:
|
||||
// raise Exception("Dimensions for Keypoint coordinates incorrect. Array needs to be 2D")
|
||||
|
||||
std::cout << "[SfmTrack2d] Starting Union-Find..." << std::endl;
|
||||
// Generate the DSF to form tracks
|
||||
// Generate the DSF to form tracks.
|
||||
DSFMapIndexPair dsf;
|
||||
|
||||
// for DSF finally
|
||||
// measurement_idxs represented by k's
|
||||
for (const auto& [pair_idxs, corr_idxs]: matches_dict) {
|
||||
// Image pair is (i1,i2).
|
||||
size_t i1 = pair_idxs.first;
|
||||
size_t i2 = pair_idxs.second;
|
||||
for (size_t k = 0; k < corr_idxs.rows(); k++)
|
||||
{
|
||||
// Measurement indices are found in a single matrix row, as (k1,k2).
|
||||
size_t k1 = corr_idxs(k,0);
|
||||
size_t k2 = corr_idxs(k,1);
|
||||
// Unique keys for the DSF are (i,k), representing keypoint index in an image.
|
||||
dsf.merge(IndexPair(i1, k1), IndexPair(i2, k2));
|
||||
}
|
||||
}
|
||||
|
@ -140,24 +131,23 @@ class DsfTrackGenerator
|
|||
const std::map<IndexPair, std::set<IndexPair> > key_sets = dsf.sets();
|
||||
|
||||
size_t erroneous_track_count = 0;
|
||||
// create a landmark map: a list of tracks
|
||||
// Each track will be represented as a list of (camera_idx, measurements)
|
||||
// Create a list of tracks.
|
||||
// Each track will be represented as a list of (camera_idx, measurements).
|
||||
for (const auto& [set_id, index_pair_set]: key_sets) {
|
||||
// Initialize track from measurements
|
||||
// Initialize track from measurements.
|
||||
SfmTrack2d track_2d;
|
||||
|
||||
for (const auto& index_pair: index_pair_set)
|
||||
{
|
||||
// camera_idx is represented by i
|
||||
// measurement_idx is represented by k
|
||||
// Camera index is represented by i, and measurement index is represented by k.
|
||||
size_t i = index_pair.i();
|
||||
size_t k = index_pair.j();
|
||||
// add measurement in this track
|
||||
// Add measurement to this track.
|
||||
track_2d.addMeasurement(NamedSfmMeasurement(i, keypoints_list[i].coordinates.row(k)));
|
||||
}
|
||||
|
||||
// Skip erroneous track that had repeated measurements within the same image
|
||||
// This is an expected result from an incorrect correspondence slipping through
|
||||
// Skip erroneous track that had repeated measurements within the same image.
|
||||
// This is an expected result from an incorrect correspondence slipping through.
|
||||
if (track_2d.validate_unique_cameras())
|
||||
{
|
||||
track_2d_list.emplace_back(track_2d);
|
||||
|
@ -167,11 +157,11 @@ class DsfTrackGenerator
|
|||
}
|
||||
|
||||
double erroneous_track_pct = key_sets.size() > 0 ? erroneous_track_count / key_sets.size() * 100 : std::nan("1");
|
||||
// TODO: restrict decimal places to 2 decimals.
|
||||
// TODO(johnwlambert): restrict decimal places to 2 decimals.
|
||||
std::cout << "DSF Union-Find: " << erroneous_track_pct;
|
||||
std::cout << "% of tracks discarded from multiple obs. in a single image." << std::endl;
|
||||
|
||||
// TODO: return the Transitivity failure percentage here.
|
||||
// TODO(johnwlambert): return the Transitivity failure percentage here.
|
||||
return track_2d_list;
|
||||
}
|
||||
};
|
||||
|
|
|
@ -16,19 +16,20 @@ class TestDsfTrackGenerator(GtsamTestCase):
|
|||
"""Tests for DsfTrackGenerator."""
|
||||
|
||||
def test_track_generation(self) -> None:
|
||||
""" """
|
||||
kps_i0 = Keypoints(coordinates=np.array([[0,0],[1,1]]))
|
||||
kps_i1 = Keypoints(coordinates=np.array([[2,2],[3,3],[4,4]]))
|
||||
kps_i2 = Keypoints(coordinates=np.array([[5,5],[6,6]]))
|
||||
"""Ensures that DSF generates two tracks from measurements in 3 images (H=200,W=400)."""
|
||||
kps_i0 = Keypoints(coordinates=np.array([[10.,20],[30,40]]))
|
||||
kps_i1 = Keypoints(coordinates=np.array([[50.,60],[70,80],[90,100]]))
|
||||
kps_i2 = Keypoints(coordinates=np.array([[110.,120],[130,140]]))
|
||||
|
||||
keypoints_list = KeypointsList()
|
||||
keypoints_list.append(kps_i0)
|
||||
keypoints_list.append(kps_i1)
|
||||
keypoints_list.append(kps_i2)
|
||||
|
||||
# For each image pair (i1,i2), we provide a (K,2) matrix of corresponding image indices (k1,k2).
|
||||
matches_dict = MatchIndicesMap()
|
||||
matches_dict[(0,0)] = np.array([[0,0],[1,1]])
|
||||
matches_dict[(1,1)] = np.array([[2,2],[3,3],[4,4]])
|
||||
matches_dict[(0,1)] = np.array([[0,0],[1,1]])
|
||||
matches_dict[(1,2)] = np.array([[2,0],[1,1]])
|
||||
import pdb; pdb.set_trace()
|
||||
|
||||
tracks = DsfTrackGenerator.generate_tracks_from_pairwise_matches(matches_dict, keypoints_list)
|
||||
|
|
Loading…
Reference in New Issue