Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enable RANSAC in triangulation #292

Merged
merged 34 commits into from
Jan 25, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
6089133
enabled RANSAC in triangulation, tested reprojection error threshold …
travisdriver Sep 13, 2021
acd4fdd
fix merge conflicts
travisdriver Oct 8, 2021
e04bbca
remove changes in config
travisdriver Oct 8, 2021
beaa85d
remove changes in config
travisdriver Oct 8, 2021
7febac4
Fixed merge conflicts
travisdriver Nov 27, 2021
742d250
Changed RANSAC threshold to 3 pixels
travisdriver Nov 27, 2021
998c446
Removed dashboard file
travisdriver Nov 27, 2021
c74954d
Merge branch 'master' of https://github.com/borglab/gtsfm into use-ra…
travisdriver Nov 28, 2021
613fecb
Reject RANSAC support if <3 measurements
travisdriver Nov 28, 2021
f194248
Increase RANSAC threshold to 10 pixels
travisdriver Nov 28, 2021
1a94590
Increase pixel threshold to 100
travisdriver Nov 29, 2021
d4fe8c7
Merge branch 'master' of https://github.com/borglab/gtsfm into use-ra…
travisdriver Dec 7, 2021
300e1b4
Decrease RANSAC threshold to 10 pixels
travisdriver Dec 7, 2021
30956c1
Decrease RANSAC threshold to 10 pixels
travisdriver Dec 7, 2021
1e8c9fd
Merge branch 'master' of https://github.com/borglab/gtsfm into use-ra…
Dec 9, 2021
9826848
Merge branch 'master' of https://github.com/borglab/gtsfm into use-ra…
travisdriver Dec 9, 2021
2946037
Merge branch 'master' of https://github.com/borglab/gtsfm into use-ra…
travisdriver Dec 14, 2021
4bc9a58
Added AstroNet config
travisdriver Dec 14, 2021
c90a98a
Testing confidence-based RANSAC
travisdriver Dec 15, 2021
70962db
Fixed other configs
travisdriver Dec 15, 2021
d0cc521
Change SIFT frontend threshold to 100 pixels
travisdriver Dec 15, 2021
0364627
Merge branch 'master' of https://github.com/borglab/gtsfm into use-ra…
travisdriver Jan 2, 2022
16eb600
Fixed unit tests
travisdriver Jan 3, 2022
5669c36
Fixed unit tests
travisdriver Jan 3, 2022
92d0381
Added unit tests, addressed comments
travisdriver Jan 3, 2022
7f61b42
Fixed bugs
travisdriver Jan 3, 2022
3fe2a08
Fix astronet config
travisdriver Jan 3, 2022
991e693
address Akshay comments
Jan 25, 2022
7de6481
rename param
Jan 25, 2022
6b15560
Merge pull request #433 from borglab/rename-triangulation-param-class
johnwlambert Jan 25, 2022
c0342a0
Merge branch 'master' of https://github.com/borglab/gtsfm into use-ra…
Jan 25, 2022
f4e3dd7
add ViewGraphEstimator to new config
johnwlambert Jan 25, 2022
b3e3e78
address Ayush comments
johnwlambert Jan 25, 2022
ba1af74
use str Enum inheritance for config readability
johnwlambert Jan 25, 2022
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can we name it something which mentions this attribute value being high instead of tagging it with a database?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree, I think this would improve clarity

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

AstroNet is the only dataset that uses the config by default, so it seems fitting to name it accordingly.


SceneOptimizer:
travisdriver marked this conversation as resolved.
Show resolved Hide resolved
_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
travisdriver marked this conversation as resolved.
Show resolved Hide resolved

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