From 1ff0779a03549d3e82141c190a65cd7efba035ba Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Mon, 6 May 2024 16:34:23 -0400 Subject: [PATCH 1/2] Update two_view_estimator.py --- gtsfm/two_view_estimator.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/gtsfm/two_view_estimator.py b/gtsfm/two_view_estimator.py index 10b8da7a2..d237c4c64 100644 --- a/gtsfm/two_view_estimator.py +++ b/gtsfm/two_view_estimator.py @@ -330,9 +330,6 @@ def run_2view( ) post_ba_inlier_ratio_wrt_estimate = float(len(post_ba_v_corr_idxs)) / len(putative_corr_idxs) - # TODO: Remove this hack once we can handle the lower post_ba_inlier_ratio_wrt_estimate downstream. - post_ba_inlier_ratio_wrt_estimate = pre_ba_inlier_ratio_wrt_estimate - post_ba_report = self.__get_2view_report_from_results( i2Ri1_computed=post_ba_i2Ri1, i2Ui1_computed=post_ba_i2Ui1, From badefa87ac8b4bf5787c963a73fbf2f2f4c0c63d Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Mon, 6 May 2024 16:42:32 -0400 Subject: [PATCH 2/2] temporarily remove two view estimator cacher --- gtsfm/configs/unified.yaml | 45 +++++++++++++++++++------------------- 1 file changed, 22 insertions(+), 23 deletions(-) diff --git a/gtsfm/configs/unified.yaml b/gtsfm/configs/unified.yaml index 8fef52586..28af13e4e 100644 --- a/gtsfm/configs/unified.yaml +++ b/gtsfm/configs/unified.yaml @@ -35,29 +35,28 @@ SceneOptimizer: features: "superpoint" two_view_estimator: - _target_: gtsfm.two_view_estimator_cacher.TwoViewEstimatorCacher - two_view_estimator_obj: - _target_: gtsfm.two_view_estimator.TwoViewEstimator - bundle_adjust_2view: True - eval_threshold_px: 4 # in px - ba_reproj_error_thresholds: [0.5] - bundle_adjust_2view_maxiters: 100 - - verifier: - _target_: gtsfm.frontend.verifier.ransac.Ransac - use_intrinsics_in_verification: True - estimation_threshold_px: 4 # for H/E/F estimators - - triangulation_options: - _target_: gtsfm.data_association.point3d_initializer.TriangulationOptions - mode: - _target_: gtsfm.data_association.point3d_initializer.TriangulationSamplingMode - value: NO_RANSAC - - inlier_support_processor: - _target_: gtsfm.two_view_estimator.InlierSupportProcessor - min_num_inliers_est_model: 15 - min_inlier_ratio_est_model: 0.1 + # TODO: undo before merge. + _target_: gtsfm.two_view_estimator.TwoViewEstimator + bundle_adjust_2view: True + eval_threshold_px: 4 # in px + ba_reproj_error_thresholds: [0.5] + bundle_adjust_2view_maxiters: 100 + + verifier: + _target_: gtsfm.frontend.verifier.ransac.Ransac + use_intrinsics_in_verification: True + estimation_threshold_px: 4 # for H/E/F estimators + + triangulation_options: + _target_: gtsfm.data_association.point3d_initializer.TriangulationOptions + mode: + _target_: gtsfm.data_association.point3d_initializer.TriangulationSamplingMode + value: NO_RANSAC + + 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