Skip to content

Commit

Permalink
Merge branch 'master' of https://github.com/borglab/gtsfm into avg-co…
Browse files Browse the repository at this point in the history
…ord-nms
  • Loading branch information
senselessdev1 committed Sep 27, 2023
2 parents d8a04fc + eecbb3f commit cd41a97
Show file tree
Hide file tree
Showing 39 changed files with 436 additions and 323 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/benchmark-self-hosted.yml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ jobs:
PYTHON_VERSION: 3.8

steps:
- uses: actions/checkout@v4.0.0
- uses: actions/checkout@v4.1.0
- name: Cache frontend
uses: actions/cache@v3
env:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/benchmark.yml
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ jobs:
PYTHON_VERSION: 3.8

steps:
- uses: actions/checkout@v4.0.0
- uses: actions/checkout@v4.1.0
- name: Cache frontend
uses: actions/cache@v3
env:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/build-wheels.yml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ jobs:
shell: bash -l {0}

steps:
- uses: actions/checkout@v4.0.0
- uses: actions/checkout@v4.1.0
- uses: conda-incubator/setup-miniconda@v2
with:
mamba-version: "*"
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test-python.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ jobs:
PYTHON_VERSION: 3.8

steps:
- uses: actions/checkout@v4.0.0
- uses: actions/checkout@v4.1.0
- uses: conda-incubator/setup-miniconda@v2
with:
mamba-version: "*"
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test-reproducibility.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ jobs:
PYTHON_VERSION: 3.8

steps:
- uses: actions/checkout@v4.0.0
- uses: actions/checkout@v4.1.0
- uses: conda-incubator/setup-miniconda@v2
with:
mamba-version: "*"
Expand Down
25 changes: 12 additions & 13 deletions gtsfm/common/keypoints.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@ def __init__(
"""Initializes the attributes.
Args:
coordinates: the (x, y) coordinates of the features, of shape Nx2.
scales: optional scale of the detections, of shape N.
responses: optional confidences/responses for each detection, of shape N.
coordinates: The (x, y) coordinates of the features, of shape Nx2.
scales: Optional scale of the detections, of shape N.
responses: Optional confidences/responses for each detection, of shape N.
"""
self.coordinates = coordinates
self.scales = scales
Expand All @@ -61,10 +61,10 @@ def __eq__(self, other: object) -> bool:
if not isinstance(other, Keypoints):
return False

# equality check on coordinates
# Equality check on coordinates.
coordinates_eq = np.array_equal(self.coordinates, other.coordinates)

# equality check on scales
# Equality check on scales.
if self.scales is None and other.scales is None:
scales_eq = True
elif self.scales is not None and other.scales is not None:
Expand Down Expand Up @@ -93,10 +93,10 @@ def get_top_k(self, k: int) -> Tuple["Keypoints", np.ndarray]:
If k keypoints are requested, and only n < k are available, then returning n keypoints is the expected behavior.
Args:
k: max number of keypoints to return.
k: Maximum number of keypoints to return.
Returns:
subset of current keypoints.
Subset of current keypoints.
"""
if k >= len(self):
return copy.deepcopy(self), np.arange(self.__len__())
Expand All @@ -114,7 +114,7 @@ def filter_by_mask(self, mask: np.ndarray) -> Tuple["Keypoints", np.ndarray]:
Args:
mask: (H, W) array of 0's and 1's corresponding to valid portions of the original image.
keypoints: detected keypoints with length M.
keypoints: Detected keypoints with length M.
descriptors: (M, D) array of descriptors D is the dimension of each descriptor.
Returns:
Expand Down Expand Up @@ -148,7 +148,7 @@ def cast_to_float(self) -> "Keypoints":
"""Cast all attributes which are numpy arrays to float.
Returns:
keypoints with the type-casted attributes.
Keypoints with the type-casted attributes.
"""
return Keypoints(
coordinates=None if self.coordinates is None else self.coordinates.astype(np.float32),
Expand All @@ -166,7 +166,7 @@ def cast_to_opencv_keypoints(self) -> List[cv.KeyPoint]:
List of OpenCV's keypoints with the same information as input keypoints.
"""

# cast input attributed to floating point numpy arrays.
# Cast input attributed to floating point numpy arrays.
keypoints = self.cast_to_float()

opencv_keypoints = []
Expand Down Expand Up @@ -216,14 +216,13 @@ def extract_indices(self, indices: np.ndarray) -> "Keypoints":
"""Form subset with the given indices.
Args:
indices: indices to extract, as a 1-D vector.
indices: Indices to extract, as a 1-D vector.
Returns:
Subset of data at the given indices.
"""

if indices.size == 0:
return Keypoints(coordinates=np.array([]))
return Keypoints(coordinates=np.zeros(shape=(0, 2)))

return Keypoints(
self.coordinates[indices],
Expand Down
18 changes: 10 additions & 8 deletions gtsfm/data_association/cpp_dsf_tracks_estimator.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,15 @@ def run(self, matches_dict: Dict[Tuple[int, int], np.ndarray], keypoints_list: L
# 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, but found "
f"{[kps.coordinates.shape for kps in keypoints_list]}"
error_str = " ".join(
[
f"i={i}: shape={kps.coordinates.shape},"
for i, kps in enumerate(keypoints_list)
if kps.coordinates.ndim != 2
]
)
raise ValueError(
f"Dimensions for Keypoint coordinates incorrect. Array needs to be 2D, but found {error_str}"
)

# For each image pair (i1,i2), we provide a (K,2) matrix of corresponding keypoint indices (k1,k2).
Expand All @@ -65,11 +71,7 @@ def run(self, matches_dict: Dict[Tuple[int, int], np.ndarray], keypoints_list: L
for keypoint in keypoints_list:
keypoints_vector.append(gtsam.gtsfm.Keypoints(keypoint.coordinates))

tracks = gtsam.gtsfm.tracksFromPairwiseMatches(
matches_map,
keypoints_vector,
verbose=True,
)
tracks = gtsam.gtsfm.tracksFromPairwiseMatches(matches_map, keypoints_vector, verbose=True)

track_2d_list = []
for track in tracks:
Expand Down
69 changes: 36 additions & 33 deletions gtsfm/data_association/point3d_initializer.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,15 +69,15 @@ class TriangulationOptions(NamedTuple):
See the following slides for a derivation of the #req'd samples: http://www.cse.psu.edu/~rtc12/CSE486/lecture15.pdf
Args:
mode: triangulation mode, which dictates whether or not to use robust estimation.
reproj_error_threshold: the maximum reprojection error allowed.
min_triangulation_angle: threshold for the minimum angle (in degrees) subtended at the triangulated track from 2
mode: Triangulation mode, which dictates whether or not to use robust estimation.
reproj_error_threshold: The maximum reprojection error allowed.
min_triangulation_angle: Threshold for the minimum angle (in degrees) subtended at the triangulated track from 2
cameras. Tracks for which the maximum angle at any two cameras is less then this threshold will be rejected.
min_inlier_ratio: a priori assumed minimum probability that a point is an inlier.
confidence: desired confidence that at least one hypothesis is outlier free.
min_inlier_ratio: A priori assumed minimum probability that a point is an inlier.
confidence: Desired confidence that at least one hypothesis is outlier free.
dyn_num_hypotheses_multiplier: multiplication factor for dynamically computed hyptheses based on confidence.
min_num_hypotheses: minimum number of hypotheses.
max_num_hypotheses: maximum number of hypotheses.
min_num_hypotheses: Minimum number of hypotheses.
max_num_hypotheses: Maximum number of hypotheses.
"""

mode: TriangulationSamplingMode
Expand Down Expand Up @@ -123,15 +123,18 @@ class Point3dInitializer:
Args:
track_cameras: Dict of cameras and their indices.
mode: triangulation mode, which dictates whether or not to use robust estimation.
reproj_error_thresh: threshold on reproj errors for inliers.
num_ransac_hypotheses (optional): desired number of RANSAC hypotheses.
mode: Triangulation mode, which dictates whether or not to use robust estimation.
reproj_error_thresh: Threshold on reproj errors for inliers.
num_ransac_hypotheses (optional): Desired number of RANSAC hypotheses.
"""

def __init__(self, track_camera_dict: Dict[int, gtsfm_types.CAMERA_TYPE], options: TriangulationOptions) -> None:
self.track_camera_dict = track_camera_dict
self.options = options

if len(track_camera_dict) == 0:
raise ValueError("No camera positions were estimated, so triangulation is not feasible.")

sample_camera = list(self.track_camera_dict.values())[0]
self._camera_set_class = (
CameraSetCal3Bundler if isinstance(sample_camera, PinholeCameraCal3Bundler) else CameraSetCal3Fisheye
Expand All @@ -142,23 +145,23 @@ def execute_ransac_variant(self, track_2d: SfmTrack2d) -> np.ndarray:
RANSAC chooses one of 3 different sampling schemes to execute.
Args:
track: feature track with N 2d measurements in separate images
track: Feature track with N 2d measurements in separate images
Returns:
best_inliers: boolean array of length N. Indices of measurements
are set to true if they correspond to the best RANSAC hypothesis
best_inliers: Boolean array of length N. Indices of measurements
are set to true if they correspond to the best RANSAC hypothesis.
"""

# Generate all possible matches
# Generate all possible matches.
measurement_pairs = generate_measurement_pairs(track_2d)

# limit the number of samples to the number of available pairs
# Limit the number of samples to the number of available pairs.
num_hypotheses = min(self.options.num_ransac_hypotheses(), len(measurement_pairs))

# Sampling
# Sampling.
samples = self.sample_ransac_hypotheses(track_2d, measurement_pairs, num_hypotheses)

# Initialize the best output containers
# Initialize the best output containers.
best_num_votes = 0
best_error = MAX_TRACK_REPROJ_ERROR
best_inliers = np.zeros(len(track_2d.measurements), dtype=bool)
Expand All @@ -168,7 +171,7 @@ def execute_ransac_variant(self, track_2d: SfmTrack2d) -> np.ndarray:
i1, uv1 = track_2d.measurements[k1]
i2, uv2 = track_2d.measurements[k2]

# check for unestimated cameras
# Check for unestimated cameras.
if self.track_camera_dict.get(i1) is None or self.track_camera_dict.get(i2) is None:
logger.warning("Unestimated cameras found at indices %d or %d. Skipping them.", i1, i2)
continue
Expand All @@ -181,7 +184,7 @@ def execute_ransac_variant(self, track_2d: SfmTrack2d) -> np.ndarray:
img_measurements.append(uv1)
img_measurements.append(uv2)

# triangulate point for track
# Triangulate point for track.
try:
triangulated_pt = gtsam.triangulatePoint3(
camera_estimates,
Expand All @@ -204,11 +207,11 @@ def execute_ransac_variant(self, track_2d: SfmTrack2d) -> np.ndarray:
# If the inlier number are the same, check the average error of inliers
is_inlier = errors < self.options.reproj_error_threshold

# tally the number of votes
# Tally the number of votes.
inlier_errors = errors[is_inlier]

if inlier_errors.size > 0:
# only tally error over the inlier measurements
# Only tally error over the inlier measurements.
avg_error = inlier_errors.mean()
num_votes = is_inlier.astype(int).sum()

Expand All @@ -223,7 +226,7 @@ def triangulate(self, track_2d: SfmTrack2d) -> Tuple[Optional[SfmTrack], Optiona
"""Triangulates 3D point according to the configured triangulation mode.
Args:
track: feature track from which measurements are to be extracted
track: Feature track from which measurements are to be extracted.
Returns:
track with inlier measurements and 3D landmark. None returned if triangulation fails or has high error.
Expand Down Expand Up @@ -300,11 +303,12 @@ def sample_ransac_hypotheses(
"""Sample a list of hypotheses (camera pairs) to use during triangulation.
Args:
track: feature track from which measurements are to be extracted
measurement_pairs: all possible indices of pairs of measurements in a given track
num_hypotheses: desired number of samples
track: Feature track from which measurements are to be extracted.
measurement_pairs: All possible indices of pairs of measurements in a given track.
num_hypotheses: Desired number of samples.
Returns:
Indices of selected match
Indices of selected match.
"""
# Initialize scores as uniform distribution
scores = np.ones(len(measurement_pairs), dtype=float)
Expand All @@ -320,10 +324,10 @@ def sample_ransac_hypotheses(
wTc1 = self.track_camera_dict[i1].pose()
wTc2 = self.track_camera_dict[i2].pose()

# rough approximation approximation of baseline between the 2 cameras
# Rough approximation approximation of baseline between the 2 cameras
scores[k] = np.linalg.norm(wTc1.inverse().compose(wTc2).translation())

# Check the validity of scores
# Check the validity of scores.
if sum(scores) <= 0.0:
raise Exception("Sum of scores cannot be zero (or smaller than zero)! It must a bug somewhere")

Expand Down Expand Up @@ -351,7 +355,7 @@ def extract_measurements(
Returns None, None if less than 2 measurements were found with estimated camera poses after averaging.
Args:
track: feature track from which measurements are to be extracted.
track: Feature track from which measurements are to be extracted.
Returns:
Vector of individual camera calibrations pertaining to track
Expand All @@ -377,14 +381,13 @@ def extract_measurements(


def generate_measurement_pairs(track: SfmTrack2d) -> List[Tuple[int, ...]]:
"""
Extract all possible measurement pairs in a track for triangulation.
"""Extract all possible measurement pairs in a track for triangulation.
Args:
track: feature track from which measurements are to be extracted
track: Feature track from which measurements are to be extracted.
Returns:
measurement_idxs: all possible matching measurement indices in a given track
measurement_idxs: All possible matching measurement indices in a given track
"""
num_track_measurements = track.number_measurements()
all_measurement_idxs = range(num_track_measurements)
Expand Down
11 changes: 6 additions & 5 deletions gtsfm/evaluation/compare_metrics.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,16 +24,17 @@ def compute_metrics_from_txt(
"""Calculate metrics from pipeline outputs parsed from COLMAP txt format.
Args:
cameras: dictionary of COLMAP-formatted Cameras
images: dictionary of COLMAP-formatted Images
points3D: dictionary of COLMAP-formatted Point3Ds
cameras: Dictionary of COLMAP-formatted Cameras.
images: Dictionary of COLMAP-formatted Images.
points3D: Dictionary of COLMAP-formatted Point3Ds.
reproj_error_threshold: Reprojection error threshold for filtering tracks.
Returns:
other_pipeline_metrics: A dictionary of metrics from another pipeline that are comparable with GTSfM
"""
image_files, images, cameras, sfmtracks = io_utils.colmap2gtsfm(cameras, images, points3d, load_sfmtracks=True)
num_cameras = len(cameras)
_, _, intrinsics_gtsfm, sfmtracks, _, _, _ = io_utils.colmap2gtsfm(cameras, images, points3d, load_sfmtracks=True)

num_cameras = len(intrinsics_gtsfm)
unfiltered_track_lengths = []
image_id_num_measurements = {}
for track in sfmtracks:
Expand Down
8 changes: 4 additions & 4 deletions gtsfm/evaluation/metrics.py
Original file line number Diff line number Diff line change
Expand Up @@ -89,9 +89,9 @@ def __init__(

self._name = name
if data is not None:
# Cast to a numpy array
# Cast to a numpy array.
if isinstance(data, list):
# Replace None with NaN
# Replace None with NaN.
data = [x if x is not None else np.NaN for x in data]
if all(isinstance(x, int) for x in data):
data = np.array(data, dtype=np.int32)
Expand All @@ -113,7 +113,7 @@ def __init__(
else:
raise ValueError("Unsupported plot type for the data dimension")

# Create a summary if the data is a 1D distribution
# Create a summary if the data is a 1D distribution.
if self._dim == 1:
self._summary = self._create_summary(data)

Expand All @@ -123,7 +123,7 @@ def __init__(
else:
self._data = None
else:
# Metrics created from summary alone are 1D distribution metrics
# Metrics created from summary alone are 1D distribution metrics.
self._dim = 1
self._summary = summary
self._plot_type = self.PlotType.HISTOGRAM if "histogram" in summary else self.PlotType.BOX
Expand Down
Loading

0 comments on commit cd41a97

Please sign in to comment.