Skip to content

Commit

Permalink
save post ba two-view reports
Browse files Browse the repository at this point in the history
  • Loading branch information
akshay-krishnan committed May 20, 2024
1 parent 509fa02 commit 8481689
Show file tree
Hide file tree
Showing 3 changed files with 81 additions and 26 deletions.
25 changes: 20 additions & 5 deletions gtsfm/runner/gtsfm_runner_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -344,8 +344,8 @@ def run(self) -> GtsfmData:
)
two_view_estimation_duration_sec = time.time() - two_view_estimation_start_time

i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict, _, two_view_reports_dict = unzip_two_view_results(
two_view_results_dict
i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict, _, post_ba_two_view_reports_dict, two_view_reports_dict = (
unzip_two_view_results(two_view_results_dict)
)

if self.scene_optimizer._save_two_view_correspondences_viz:
Expand All @@ -364,7 +364,11 @@ def run(self) -> GtsfmData:
f"{i1}_{i2}__{image_i1.file_name}_{image_i2.file_name}.jpg",
),
)

two_view_agg_metrics_post_ba = two_view_estimator.aggregate_frontend_metrics(
two_view_reports_dict=post_ba_two_view_reports_dict,
angular_err_threshold_deg=self.scene_optimizer._pose_angular_error_thresh,
metric_group_name="verifier_summary_{}".format(two_view_estimator.POST_BA_REPORT_TAG),
)
two_view_agg_metrics = two_view_estimator.aggregate_frontend_metrics(
two_view_reports_dict=two_view_reports_dict,
angular_err_threshold_deg=self.scene_optimizer._pose_angular_error_thresh,
Expand All @@ -376,14 +380,15 @@ def run(self) -> GtsfmData:
two_view_agg_metrics.add_metric(
GtsfmMetric("total_two_view_estimation_duration_sec", two_view_estimation_duration_sec)
)
all_metrics_groups = [retriever_metrics, two_view_agg_metrics]
all_metrics_groups = [retriever_metrics, two_view_agg_metrics, two_view_agg_metrics_post_ba]

delayed_sfm_result, delayed_io, delayed_mvo_metrics_groups = self.scene_optimizer.create_computation_graph(
keypoints_list=keypoints_list,
i2Ri1_dict=i2Ri1_dict,
i2Ui1_dict=i2Ui1_dict,
v_corr_idxs_dict=v_corr_idxs_dict,
two_view_reports=two_view_reports_dict,
post_ba_two_view_reports=post_ba_two_view_reports_dict,
num_images=len(self.loader),
images=self.loader.create_computation_graph_for_images(),
camera_intrinsics=intrinsics,
Expand Down Expand Up @@ -420,12 +425,14 @@ def unzip_two_view_results(two_view_results: Dict[Tuple[int, int], TWO_VIEW_OUTP
Dict[Tuple[int, int], np.ndarray],
Dict[Tuple[int, int], TwoViewEstimationReport],
Dict[Tuple[int, int], TwoViewEstimationReport],
Dict[Tuple[int, int], TwoViewEstimationReport],
]:
"""Unzip the tuple TWO_VIEW_OUTPUT into 1 dictionary for 1 element in the tuple."""
i2Ri1_dict: Dict[Tuple[int, int], Rot3] = {}
i2Ui1_dict: Dict[Tuple[int, int], Unit3] = {}
v_corr_idxs_dict: Dict[Tuple[int, int], np.ndarray] = {}
pre_ba_two_view_reports_dict: Dict[Tuple[int, int], TwoViewEstimationReport] = {}
post_ba_two_view_reports_dict: Dict[Tuple[int, int], TwoViewEstimationReport] = {}
post_isp_two_view_reports_dict: Dict[Tuple[int, int], TwoViewEstimationReport] = {}

for (i1, i2), two_view_output in two_view_results.items():
Expand All @@ -441,9 +448,17 @@ def unzip_two_view_results(two_view_results: Dict[Tuple[int, int], TWO_VIEW_OUTP
i2Ui1_dict[(i1, i2)] = i2Ui1
v_corr_idxs_dict[(i1, i2)] = two_view_output[2]
pre_ba_two_view_reports_dict[(i1, i2)] = two_view_output[3]
post_ba_two_view_reports_dict[(i1, i2)] = two_view_output[4]
post_isp_two_view_reports_dict[(i1, i2)] = two_view_output[5]

return i2Ri1_dict, i2Ui1_dict, v_corr_idxs_dict, pre_ba_two_view_reports_dict, post_isp_two_view_reports_dict
return (
i2Ri1_dict,
i2Ui1_dict,
v_corr_idxs_dict,
pre_ba_two_view_reports_dict,
post_ba_two_view_reports_dict,
post_isp_two_view_reports_dict,
)


def save_metrics_reports(metrics_group_list: List[GtsfmMetricsGroup], metrics_path: str) -> None:
Expand Down
12 changes: 12 additions & 0 deletions gtsfm/scene_optimizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
from gtsfm.retriever.retriever_base import ImageMatchingRegime
from gtsfm.two_view_estimator import (
POST_ISP_REPORT_TAG,
POST_BA_REPORT_TAG,
VIEWGRAPH_REPORT_TAG,
TwoViewEstimationReport,
TwoViewEstimator,
Expand Down Expand Up @@ -135,6 +136,7 @@ def create_computation_graph(
i2Ui1_dict: Dict[Tuple[int, int], Unit3],
v_corr_idxs_dict: Dict[Tuple[int, int], np.ndarray],
two_view_reports: Dict[Tuple[int, int], TwoViewEstimationReport],
post_ba_two_view_reports: Dict[Tuple[int, int], TwoViewEstimationReport],
num_images: int,
images: List[Delayed],
camera_intrinsics: List[Optional[gtsfm_types.CALIBRATION_TYPE]],
Expand Down Expand Up @@ -192,6 +194,16 @@ def create_computation_graph(
plot_base_path=self._plot_base_path,
)
)
delayed_results.append(
dask.delayed(save_full_frontend_metrics)(
two_view_reports,
images,
filename="post_ba_two_view_report_{}.json".format(POST_BA_REPORT_TAG),
save_retrieval_metrics=save_retrieval_metrics,
metrics_path=self._metrics_path,
plot_base_path=self._plot_base_path,
)
)

# TODO(Ayush): pass only image name instead of the whole image. And delete images from memory.
delayed_results.append(
Expand Down
70 changes: 49 additions & 21 deletions gtsfm/two_view_estimator.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
Authors: Ayush Baid, John Lambert
"""

import dataclasses
import logging
import timeit
Expand All @@ -26,6 +27,7 @@
from gtsfm.evaluation.metrics import GtsfmMetric, GtsfmMetricsGroup
from gtsfm.frontend.inlier_support_processor import InlierSupportProcessor
from gtsfm.frontend.verifier.verifier_base import VerifierBase
from gtsfm.utils import tracks as track_utils

logger = logger_utils.get_logger()

Expand Down Expand Up @@ -190,7 +192,12 @@ def bundle_adjust(
logger.debug("Triangulated %d correspondences out of %d.", len(triangulated_tracks), len(verified_corr_idxs))

if len(triangulated_tracks) == 0:
return i2Ti1_initial.rotation(), Unit3(i2Ti1_initial.translation()), np.zeros(shape=(0, 2), dtype=np.int32)
return (
i2Ti1_initial.rotation(),
Unit3(i2Ti1_initial.translation()),
np.zeros(shape=(0, 2), dtype=np.int32),
None,
)

# Build BA inputs.
start_time = timeit.default_timer()
Expand All @@ -213,8 +220,16 @@ def bundle_adjust(
return i2Ri1_initial, i2Ui1_initial, valid_corr_idxs
i2Ti1_optimized = wTi2.between(wTi1)
logger.debug("Performed 2-view BA in %.6f seconds.", timeit.default_timer() - start_time)
points3d = [t.point3() for t in ba_output.get_tracks()]
triangulation_angles = [track_utils.get_max_triangulation_angle(t, cameras) for t in ba_output.get_tracks()]
logger.info(
"triangulation angles %d %d %d",
np.mean(triangulation_angles),
np.max(triangulation_angles),
np.median(triangulation_angles),
)

return i2Ti1_optimized.rotation(), Unit3(i2Ti1_optimized.translation()), valid_corr_idxs
return i2Ti1_optimized.rotation(), Unit3(i2Ti1_optimized.translation()), valid_corr_idxs, np.array(points3d)

def __get_2view_report_from_results(
self,
Expand Down Expand Up @@ -331,15 +346,15 @@ 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_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,
keypoints_i1=keypoints_i1,
keypoints_i2=keypoints_i2,
verified_corr_idxs=post_ba_v_corr_idxs,
inlier_ratio_wrt_estimate=post_ba_inlier_ratio_wrt_estimate,
inlier_ratio_wrt_estimate=pre_ba_inlier_ratio_wrt_estimate,
gt_camera_i1=gt_camera_i1,
gt_camera_i2=gt_camera_i2,
gt_scene_mesh=gt_scene_mesh,
Expand All @@ -349,15 +364,26 @@ def run_2view(
post_ba_i2Ui1 = pre_ba_i2Ui1
post_ba_v_corr_idxs = pre_ba_v_corr_idxs
post_ba_report = dataclasses.replace(pre_ba_report)
post_ba_inlier_ratio_wrt_estimate = pre_ba_inlier_ratio_wrt_estimate
points3d = None

(
post_isp_i2Ri1,
post_isp_i2Ui1,
post_isp_v_corr_idxs,
post_isp_report,
) = self.processor.run_inlier_support(post_ba_i2Ri1, post_ba_i2Ui1, post_ba_v_corr_idxs, post_ba_report)
post_ba_report.inlier_ratio_est_model = post_ba_inlier_ratio_wrt_estimate

return post_isp_i2Ri1, post_isp_i2Ui1, post_isp_v_corr_idxs, pre_ba_report, post_ba_report, post_isp_report
return (
post_isp_i2Ri1,
post_isp_i2Ui1,
post_isp_v_corr_idxs,
pre_ba_report,
post_ba_report,
post_isp_report,
points3d,
)


def generate_two_view_report(
Expand Down Expand Up @@ -625,24 +651,26 @@ def round_fn(x: Optional[float]) -> Optional[float]:
"i2_filename": images[i2].file_name,
"rotation_angular_error": round_fn(report.R_error_deg),
"translation_angular_error": round_fn(report.U_error_deg),
"num_inliers_gt_model": int(report.num_inliers_gt_model)
if report.num_inliers_gt_model is not None
else None,
"num_inliers_gt_model": (
int(report.num_inliers_gt_model) if report.num_inliers_gt_model is not None else None
),
"inlier_ratio_gt_model": round_fn(report.inlier_ratio_gt_model),
"inlier_avg_reproj_error_gt_model": round_fn(
np.nanmean(report.reproj_error_gt_model[report.v_corr_idxs_inlier_mask_gt])
)
if report.reproj_error_gt_model is not None and report.v_corr_idxs_inlier_mask_gt is not None
else None,
"outlier_avg_reproj_error_gt_model": round_fn(
np.nanmean(report.reproj_error_gt_model[np.logical_not(report.v_corr_idxs_inlier_mask_gt)])
)
if report.reproj_error_gt_model is not None and report.v_corr_idxs_inlier_mask_gt is not None
else None,
"inlier_avg_reproj_error_gt_model": (
round_fn(np.nanmean(report.reproj_error_gt_model[report.v_corr_idxs_inlier_mask_gt]))
if report.reproj_error_gt_model is not None and report.v_corr_idxs_inlier_mask_gt is not None
else None
),
"outlier_avg_reproj_error_gt_model": (
round_fn(
np.nanmean(report.reproj_error_gt_model[np.logical_not(report.v_corr_idxs_inlier_mask_gt)])
)
if report.reproj_error_gt_model is not None and report.v_corr_idxs_inlier_mask_gt is not None
else None
),
"inlier_ratio_est_model": round_fn(report.inlier_ratio_est_model),
"num_inliers_est_model": int(report.num_inliers_est_model)
if report.num_inliers_est_model is not None
else None,
"num_inliers_est_model": (
int(report.num_inliers_est_model) if report.num_inliers_est_model is not None else None
),
}
)
return metrics_list

0 comments on commit 8481689

Please sign in to comment.