Skip to content

Commit

Permalink
Merge pull request #292 from borglab/use-ransac-in-triangulation
Browse files Browse the repository at this point in the history
Enable RANSAC in triangulation
  • Loading branch information
johnwlambert authored Jan 25, 2022
2 parents c664810 + ba1af74 commit 185cb97
Show file tree
Hide file tree
Showing 10 changed files with 272 additions and 119 deletions.
24 changes: 12 additions & 12 deletions .github/workflows/benchmark.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,18 +12,18 @@ jobs:
matrix:
config_dataset_info:
[
# config dataset lookahead img-extension source loader max-res share-intrinsics
[sift_front_end, door-12, 12, JPG, test_data, olsson-loader, 1296, true],
[deep_front_end, door-12, 12, JPG, test_data, olsson-loader, 1296, true],
[sift_front_end, skydio-8, 8, jpg, gdrive , colmap-loader, 760, true],
[deep_front_end, skydio-8, 8, jpg, gdrive, colmap-loader, 760, true],
[sift_front_end, skydio-32, 32, jpg, gdrive, colmap-loader, 760, true],
[deep_front_end, skydio-32, 32, jpg, gdrive, colmap-loader, 760, true],
[deep_front_end, skydio-501, 15, jpg, wget, colmap-loader, 760, true],
[sift_front_end, palace-fine-arts-281, 25, jpg, wget, olsson-loader, 320, true],
[deep_front_end, notre-dame-20, 20, jpg, gdrive, colmap-loader, 760, false],
[sift_front_end, 2011205_rc3, 65, png, wget, astronet, 1024, true],
[deep_front_end, 2011205_rc3, 20, png, wget, astronet, 1024, true],
# config dataset lookahead img-extension source loader max-res share-intrinsics
[sift_front_end, door-12, 12, JPG, test_data, olsson-loader, 1296, true],
[deep_front_end, door-12, 12, JPG, test_data, olsson-loader, 1296, true],
[sift_front_end, skydio-8, 8, jpg, gdrive , colmap-loader, 760, true],
[deep_front_end, skydio-8, 8, jpg, gdrive, colmap-loader, 760, true],
[sift_front_end, skydio-32, 32, jpg, gdrive, colmap-loader, 760, true],
[deep_front_end, skydio-32, 32, jpg, gdrive, colmap-loader, 760, true],
[deep_front_end, skydio-501, 15, jpg, wget, colmap-loader, 760, true],
[sift_front_end, palace-fine-arts-281, 25, jpg, wget, olsson-loader, 320, true],
[deep_front_end, notre-dame-20, 20, jpg, gdrive, colmap-loader, 760, false],
[sift_front_end, 2011205_rc3, 65, png, wget, astronet, 1024, true],
[deep_front_end_astronet, 2011205_rc3, 20, png, wget, astronet, 1024, true],
]
defaults:
run:
Expand Down
12 changes: 7 additions & 5 deletions gtsfm/configs/deep_front_end.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,14 @@ SceneOptimizer:

data_association_module:
_target_: gtsfm.data_association.data_assoc.DataAssociation
reproj_error_thresh: 100
min_track_len: 2
mode:
_target_: gtsfm.data_association.data_assoc.TriangulationParam
value: 0 # 0 corresponds to NO_RANSAC
num_ransac_hypotheses: 20
triangulation_options:
_target_: gtsfm.data_association.point3d_initializer.TriangulationOptions
reproj_error_threshold: 10
mode:
_target_: gtsfm.data_association.point3d_initializer.TriangulationSamplingMode
value: RANSAC_SAMPLE_UNIFORM
max_num_hypotheses: 100
save_track_patches_viz: False

bundle_adjustment_module:
Expand Down
72 changes: 72 additions & 0 deletions gtsfm/configs/deep_front_end_astronet.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
# Relaxes triangulation RANSAC threshold to 100 (10x threshold of deep_front_end.yaml)

SceneOptimizer:
_target_: gtsfm.scene_optimizer.SceneOptimizer
save_gtsfm_data: True
save_two_view_correspondences_viz: False
save_3d_viz: True
pose_angular_error_thresh: 5 # degrees

feature_extractor:
_target_: gtsfm.feature_extractor.FeatureExtractor
detector_descriptor:
_target_: gtsfm.frontend.cacher.detector_descriptor_cacher.DetectorDescriptorCacher
detector_descriptor_obj:
_target_: gtsfm.frontend.detector_descriptor.superpoint.SuperPointDetectorDescriptor
max_keypoints: 5000

two_view_estimator:
_target_: gtsfm.two_view_estimator.TwoViewEstimator
bundle_adjust_2view: True
eval_threshold_px: 4 # in px
bundle_adjust_2view_maxiters: 100

matcher:
_target_: gtsfm.frontend.cacher.matcher_cacher.MatcherCacher
matcher_obj:
_target_: gtsfm.frontend.matcher.superglue_matcher.SuperGlueMatcher
use_outdoor_model: True

verifier:
_target_: gtsfm.frontend.verifier.ransac.Ransac
use_intrinsics_in_verification: True
estimation_threshold_px: 4 # for H/E/F estimators

inlier_support_processor:
_target_: gtsfm.two_view_estimator.InlierSupportProcessor
min_num_inliers_est_model: 15
min_inlier_ratio_est_model: 0.1

multiview_optimizer:
_target_: gtsfm.multi_view_optimizer.MultiViewOptimizer
view_graph_estimator:
_target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator
edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR

rot_avg_module:
_target_: gtsfm.averaging.rotation.shonan.ShonanRotationAveraging

trans_avg_module:
_target_: gtsfm.averaging.translation.averaging_1dsfm.TranslationAveraging1DSFM
robust_measurement_noise: True

data_association_module:
_target_: gtsfm.data_association.data_assoc.DataAssociation
min_track_len: 2
triangulation_options:
_target_: gtsfm.data_association.point3d_initializer.TriangulationOptions
reproj_error_threshold: 100
mode:
_target_: gtsfm.data_association.point3d_initializer.TriangulationSamplingMode
value: RANSAC_SAMPLE_UNIFORM
max_num_hypotheses: 100
save_track_patches_viz: False

bundle_adjustment_module:
_target_: gtsfm.bundle.bundle_adjustment.BundleAdjustmentOptimizer
output_reproj_error_thresh: 3 # for post-optimization filtering
robust_measurement_noise: True
shared_calib: False

dense_multiview_optimizer:
_target_: gtsfm.densify.mvs_patchmatchnet.MVSPatchmatchNet
13 changes: 7 additions & 6 deletions gtsfm/configs/scene_optimizer_unit_test_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ SceneOptimizer:
detector_descriptor:
_target_: gtsfm.frontend.detector_descriptor.sift.SIFTDetectorDescriptor


two_view_estimator:
_target_: gtsfm.two_view_estimator.TwoViewEstimator
bundle_adjust_2view: True
Expand Down Expand Up @@ -44,12 +43,14 @@ SceneOptimizer:

data_association_module:
_target_: gtsfm.data_association.data_assoc.DataAssociation
reproj_error_thresh: 100
min_track_len: 2
mode:
_target_: gtsfm.data_association.data_assoc.TriangulationParam
value: 0 # 0 corresponds to NO_RANSAC
num_ransac_hypotheses: 20
triangulation_options:
_target_: gtsfm.data_association.point3d_initializer.TriangulationOptions
reproj_error_threshold: 10
mode:
_target_: gtsfm.data_association.point3d_initializer.TriangulationSamplingMode
value: NO_RANSAC
max_num_hypotheses: 20
save_track_patches_viz: False

bundle_adjustment_module:
Expand Down
12 changes: 7 additions & 5 deletions gtsfm/configs/sift_front_end.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,14 @@ SceneOptimizer:

data_association_module:
_target_: gtsfm.data_association.data_assoc.DataAssociation
reproj_error_thresh: 100
min_track_len: 2
mode:
_target_: gtsfm.data_association.data_assoc.TriangulationParam
value: 0 # 0 corresponds to NO_RANSAC
num_ransac_hypotheses: 20
triangulation_options:
_target_: gtsfm.data_association.point3d_initializer.TriangulationOptions
reproj_error_threshold: 100
mode:
_target_: gtsfm.data_association.point3d_initializer.TriangulationSamplingMode
value: RANSAC_SAMPLE_UNIFORM
max_num_hypotheses: 100
save_track_patches_viz: False

bundle_adjustment_module:
Expand Down
27 changes: 9 additions & 18 deletions gtsfm/data_association/data_assoc.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from gtsfm.common.sfm_track import SfmTrack2d
from gtsfm.data_association.point3d_initializer import (
Point3dInitializer,
TriangulationParam,
TriangulationOptions,
TriangulationExitCode,
)
from gtsfm.common.image import Image
Expand All @@ -40,17 +40,14 @@ class DataAssociation(NamedTuple):
"""Class to form feature tracks; for each track, call LandmarkInitializer.
Args:
reproj_error_thresh: the maximum reprojection error allowed.
min_track_len: min length required for valid feature track / min nb of supporting views required for a landmark
to be valid.
mode: triangulation mode, which dictates whether or not to use robust estimation.
num_ransac_hypotheses (optional): number of hypothesis for RANSAC-based triangulation.
triangulation_options: options for triangulating points.
save_track_patches_viz: whether to save a mosaic of individual patches associated with each track.
"""

reproj_error_thresh: float
min_track_len: int
mode: TriangulationParam
num_ransac_hypotheses: Optional[int] = None
triangulation_options: TriangulationOptions
save_track_patches_viz: Optional[bool] = False

def __validate_track(self, sfm_track: Optional[SfmTrack]) -> bool:
Expand Down Expand Up @@ -91,16 +88,8 @@ def run(
logger.debug("[Data association] input number of tracks: %s", len(tracks_2d))
logger.debug("[Data association] input avg. track length: %s", np.mean(track_lengths_2d))

# initializer of 3D landmark for each track
point3d_initializer = Point3dInitializer(
cameras,
self.mode,
self.reproj_error_thresh,
self.num_ransac_hypotheses,
)

per_accepted_track_avg_errors = []
per_rejected_track_avg_errors = []
# Initialize 3D landmark for each track
point3d_initializer = Point3dInitializer(cameras, self.triangulation_options)

# form GtsfmData object after triangulation
triangulated_data = GtsfmData(num_images)
Expand All @@ -113,8 +102,10 @@ def run(
if cameras_gt is not None:
exit_codes_wrt_gt = track_utils.classify_tracks2d_with_gt_cameras(tracks=tracks_2d, cameras_gt=cameras_gt)

exit_codes_wrt_computed: List[TriangulationExitCode] = []
# add valid tracks where triangulation is successful
exit_codes_wrt_computed: List[TriangulationExitCode] = []
per_accepted_track_avg_errors = []
per_rejected_track_avg_errors = []
for track_2d in tracks_2d:
# triangulate and filter based on reprojection error
sfm_track, avg_track_reproj_error, triangulation_exit_code = point3d_initializer.triangulate(track_2d)
Expand Down
Loading

0 comments on commit 185cb97

Please sign in to comment.