Skip to content

Commit

Permalink
Merge branch 'feature/shonan_mst_init' into feature/shonan_mst_on
Browse files Browse the repository at this point in the history
  • Loading branch information
ayushbaid committed May 26, 2024
2 parents 5a2643b + 35b3a7b commit 3e125c7
Show file tree
Hide file tree
Showing 14 changed files with 623 additions and 419 deletions.
56 changes: 56 additions & 0 deletions environment_v2_linux_cpuonly.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
name: gtsfm-v2
channels:
# for priority order, we prefer pytorch as the highest priority as it supplies
# latest stable packages for numerous deep learning based methods. conda-forge
# supplies higher versions of packages like opencv compared to the defaults
# channel.
- pytorch
- conda-forge
dependencies:
# python essentials
- python
- pip
# formatting and dev environment
- black
- coverage
- mypy
- pylint
- pytest
- flake8
- isort
# dask and related
- dask # same as dask[complete] pip distribution
- asyncssh
- python-graphviz
# core functionality and APIs
- matplotlib
- networkx
- numpy
- nodejs
- pandas
- pillow
- scikit-learn
- seaborn
- scipy
- hydra-core
- gtsam
# 3rd party algorithms for different modules
- cpuonly # replacement of cudatoolkit for cpu only machines
- pytorch
- torchvision
- kornia
- pycolmap
- opencv
# io
- h5py
- plotly
- tabulate
- simplejson
- open3d
- colour
- pydot
- trimesh
# testing
- parameterized
# - pip:
# - pydegensac
13 changes: 7 additions & 6 deletions gtsfm/averaging/rotation/rotation_averaging_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,13 @@ class RotationAveragingBase(GTSFMProcess):
rotations.
"""

@staticmethod
def get_ui_metadata() -> UiMetadata:
"""Returns data needed to display node and edge info for this process in the process graph."""

return UiMetadata(
display_name="Rotation Averaging",
input_products=("View-Graph Relative Rotations", "Relative Pose Priors"),
input_products=("View-Graph Relative Rotations", "Relative Pose Priors", "Verified Correspondences"),
output_products=("Global Rotations",),
parent_plate="Sparse Reconstruction",
)
Expand Down Expand Up @@ -64,17 +65,17 @@ def _run_rotation_averaging_base(
num_images: int,
i2Ri1_dict: Dict[Tuple[int, int], Optional[Rot3]],
i1Ti2_priors: Dict[Tuple[int, int], PosePrior],
wTi_gt: List[Optional[Pose3]],
v_corr_idxs: Dict[Tuple[int, int], np.ndarray],
wTi_gt: List[Optional[Pose3]],
) -> Tuple[List[Optional[Rot3]], GtsfmMetricsGroup]:
"""Runs rotation averaging and computes metrics.
Args:
num_images: Number of poses.
i2Ri1_dict: Relative rotations as dictionary (i1, i2): i2Ri1.
i1Ti2_priors: Priors on relative poses as dictionary(i1, i2): PosePrior on i1Ti2.
wTi_gt: Ground truth global rotations to compare against.
v_corr_idxs: Dict mapping image pair indices (i1, i2) to indices of verified correspondences.
wTi_gt: Ground truth global rotations to compare against.
Returns:
Global rotations for each camera pose, i.e. wRi, as a list. The number of entries in the list is
Expand Down Expand Up @@ -121,17 +122,17 @@ def create_computation_graph(
num_images: int,
i2Ri1_graph: Delayed,
i1Ti2_priors: Dict[Tuple[int, int], PosePrior],
gt_wTi_list: List[Optional[Pose3]],
v_corr_idxs: Dict[Tuple[int, int], np.ndarray],
gt_wTi_list: List[Optional[Pose3]],
) -> Tuple[Delayed, Delayed]:
"""Create the computation graph for performing rotation averaging.
Args:
num_images: Number of poses.
i2Ri1_graph: Dictionary of relative rotations as a delayed task.
i1Ti2_priors: Priors on relative poses as (i1, i2): PosePrior on i1Ti2.
gt_wTi_list: Ground truth poses, to be used for evaluation.
v_corr_idxs: Dict mapping image pair indices (i1, i2) to indices of verified correspondences.
gt_wTi_list: Ground truth poses, to be used for evaluation.
Returns:
Global rotations wrapped using dask.delayed.
Expand All @@ -141,8 +142,8 @@ def create_computation_graph(
num_images,
i2Ri1_dict=i2Ri1_graph,
i1Ti2_priors=i1Ti2_priors,
wTi_gt=gt_wTi_list,
v_corr_idxs=v_corr_idxs,
wTi_gt=gt_wTi_list,
)

return wRis, metrics
105 changes: 64 additions & 41 deletions gtsfm/averaging/rotation/shonan.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,7 @@
import gtsam
import numpy as np
from gtsam import (
BetweenFactorPose3,
BetweenFactorPose3s,
LevenbergMarquardtParams,
Pose3,
Rot3,
ShonanAveraging3,
ShonanAveragingParameters3,
Expand All @@ -31,6 +28,7 @@
from gtsfm.averaging.rotation.rotation_averaging_base import RotationAveragingBase
from gtsfm.common.pose_prior import PosePrior

ROT3_DOF = 3
POSE3_DOF = 6

logger = logger_utils.get_logger()
Expand All @@ -42,20 +40,26 @@ class ShonanRotationAveraging(RotationAveragingBase):
"""Performs Shonan rotation averaging."""

def __init__(
self, two_view_rotation_sigma: float = _DEFAULT_TWO_VIEW_ROTATION_SIGMA, use_mst_init: bool = True
self,
two_view_rotation_sigma: float = _DEFAULT_TWO_VIEW_ROTATION_SIGMA,
weight_by_inliers: bool = True,
use_mst_init: bool = True,
) -> None:
"""Initializes module.
Note: `p_min` and `p_max` describe the minimum and maximum relaxation rank.
Args:
two_view_rotation_sigma: Covariance to use (lower values -> more strictly adhere to input measurements).
weight_by_inliers: Whether to weight pairwise costs according to an uncertainty equal to the inverse number
of inlier correspondences per edge.
"""
super().__init__()
self._p_min = 3
self._p_max = 64
self._two_view_rotation_sigma = two_view_rotation_sigma
self._weight_by_inliers = weight_by_inliers
self._use_mst_init = use_mst_init
self._p_min = 5
self._p_max = 64

def __get_shonan_params(self) -> ShonanAveragingParameters3:
lm_params = LevenbergMarquardtParams.CeresDefaults()
Expand All @@ -64,30 +68,34 @@ def __get_shonan_params(self) -> ShonanAveragingParameters3:
shonan_params.setCertifyOptimality(True)
return shonan_params

def __between_factors_from_2view_relative_rotations(
self, i2Ri1_dict: Dict[Tuple[int, int], Rot3], old_to_new_idxs: Dict[int, int]
) -> BetweenFactorPose3s:
def __measurements_from_2view_relative_rotations(
self,
i2Ri1_dict: Dict[Tuple[int, int], Rot3],
num_correspondences_dict: Dict[Tuple[int, int], int],
) -> gtsam.BinaryMeasurementsRot3:
"""Create between factors from relative rotations computed by the 2-view estimator."""
# TODO: how to weight the noise model on relative rotations compared to priors?
noise_model = gtsam.noiseModel.Isotropic.Sigma(POSE3_DOF, self._two_view_rotation_sigma)

between_factors = BetweenFactorPose3s()
# Default noise model if `self._weight_by_inliers` is False, or zero correspondences on edge.
noise_model = gtsam.noiseModel.Isotropic.Sigma(ROT3_DOF, self._two_view_rotation_sigma)

measurements = gtsam.BinaryMeasurementsRot3()
for (i1, i2), i2Ri1 in i2Ri1_dict.items():
if i2Ri1 is not None:
if i2Ri1 is None:
continue
if self._weight_by_inliers and num_correspondences_dict[(i1, i2)] > 0:
# ignore translation during rotation averaging
i2Ti1 = Pose3(i2Ri1, np.zeros(3))
i2_ = old_to_new_idxs[i2]
i1_ = old_to_new_idxs[i1]
between_factors.append(BetweenFactorPose3(i2_, i1_, i2Ti1, noise_model))
noise_model = gtsam.noiseModel.Isotropic.Sigma(ROT3_DOF, 1 / num_correspondences_dict[(i1, i2)])

return between_factors
measurements.append(gtsam.BinaryMeasurementRot3(i2, i1, i2Ri1, noise_model))

def _between_factors_from_pose_priors(
return measurements

def _measurements_from_pose_priors(
self, i1Ti2_priors: Dict[Tuple[int, int], PosePrior], old_to_new_idxs: Dict[int, int]
) -> BetweenFactorPose3s:
) -> gtsam.BinaryMeasurementsRot3:
"""Create between factors from the priors on relative poses."""
between_factors = BetweenFactorPose3s()
measurements = gtsam.BinaryMeasurementsRot3()

def get_isotropic_noise_model_sigma(covariance: np.ndarray) -> float:
"""Get the sigma to be used for the isotropic noise model.
Expand All @@ -100,13 +108,13 @@ def get_isotropic_noise_model_sigma(covariance: np.ndarray) -> float:
i1_ = old_to_new_idxs[i1]
i2_ = old_to_new_idxs[i2]
noise_model_sigma = get_isotropic_noise_model_sigma(i1Ti2_prior.covariance)
noise_model = gtsam.noiseModel.Isotropic.Sigma(POSE3_DOF, noise_model_sigma)
between_factors.append(BetweenFactorPose3(i1_, i2_, i1Ti2_prior.value, noise_model))
noise_model = gtsam.noiseModel.Isotropic.Sigma(ROT3_DOF, noise_model_sigma)
measurements.append(gtsam.BinaryMeasurementRot3(i1_, i2_, i1Ti2_prior.value.rotation(), noise_model))

return between_factors
return measurements

def _run_with_consecutive_ordering(
self, num_connected_nodes: int, between_factors: BetweenFactorPose3s, initial: Optional[Values]
self, num_connected_nodes: int, measurements: gtsam.BinaryMeasurementsRot3, initial: Optional[Values]
) -> List[Optional[Rot3]]:
"""Run the rotation averaging on a connected graph w/ N keys ordered consecutively [0,...,N-1].
Expand All @@ -117,7 +125,7 @@ def _run_with_consecutive_ordering(
Args:
num_connected_nodes: Number of unique connected nodes (i.e. images) in the graph
(<= the number of images in the dataset)
between_factors: BetweenFactorPose3s created from relative rotations from 2-view estimator and the priors.
measurements: BinaryMeasurementsRot3 created from relative rotations from 2-view estimator and the priors.
Returns:
Global rotations for each **CONNECTED** camera pose, i.e. wRi, as a list. The number of entries in
Expand All @@ -127,10 +135,10 @@ def _run_with_consecutive_ordering(

logger.info(
"Running Shonan with %d constraints on %d nodes",
len(between_factors),
len(measurements),
num_connected_nodes,
)
shonan = ShonanAveraging3(between_factors, self.__get_shonan_params())
shonan = ShonanAveraging3(measurements, self.__get_shonan_params())

if initial is None:
logger.info("Using random initialization for Shonan")
Expand Down Expand Up @@ -192,36 +200,51 @@ def run_rotation_averaging(
return wRi_list

nodes_with_edges = sorted(list(self._nodes_with_edges(i2Ri1_dict, i1Ti2_priors)))
old_to_new_idxes = {old_idx: i for i, old_idx in enumerate(nodes_with_edges)}
old_to_new_idxs = {old_idx: i for i, old_idx in enumerate(nodes_with_edges)}

i2Ri1_dict_ = {(old_to_new_idxes[i1], old_to_new_idxes[i2]): i2Ri1 for (i1, i2), i2Ri1 in i2Ri1_dict.items()}
i2Ri1_dict_remapped = {
(old_to_new_idxs[i1], old_to_new_idxs[i2]): i2Ri1 for (i1, i2), i2Ri1 in i2Ri1_dict.items()
}
num_correspondences_dict: Dict[Tuple[int, int], int] = {
(old_to_new_idxes[i1], old_to_new_idxes[i2]): len(v_corr_idxs[(i1, i2)])
(old_to_new_idxs[i1], old_to_new_idxs[i2]): len(v_corr_idxs[(i1, i2)])
for (i1, i2) in v_corr_idxs.keys()
if (i1, i2) in i2Ri1_dict
}

# Use negative of the number of correspondences as the edge weight.
initial_values: Optional[Values] = None
if self._use_mst_init:
logger.info("Using MST initialization for Shonan")
wRi_initial_ = rotation_util.initialize_global_rotations_using_mst(
len(nodes_with_edges),
i2Ri1_dict_,
edge_weights={(i1, i2): -num_correspondences_dict.get((i1, i2), 0) for i1, i2 in i2Ri1_dict_.keys()},
i2Ri1_dict_remapped,
edge_weights={
(i1, i2): -num_correspondences_dict.get((i1, i2), 0) for i1, i2 in i2Ri1_dict_remapped.keys()
},
)
initial_values = Values()
for i, wRi in enumerate(wRi_initial_):
initial_values.insert(i, wRi)

between_factors: BetweenFactorPose3s = self.__between_factors_from_2view_relative_rotations(
i2Ri1_dict, old_to_new_idxes
)
between_factors.extend(self._between_factors_from_pose_priors(i1Ti2_priors, old_to_new_idxes))

wRi_list_subset = self._run_with_consecutive_ordering(
num_connected_nodes=len(nodes_with_edges), between_factors=between_factors, initial=initial_values
)

def _create_factors_and_run() -> List[Rot3]:
measurements: gtsam.BinaryMeasurementsRot3 = self.__measurements_from_2view_relative_rotations(
i2Ri1_dict=i2Ri1_dict_remapped, num_correspondences_dict=num_correspondences_dict
)
measurements.extend(self._measurements_from_pose_priors(i1Ti2_priors, old_to_new_idxs))
wRi_list_subset = self._run_with_consecutive_ordering(
num_connected_nodes=len(nodes_with_edges), measurements=measurements, initial=initial_values
)
return wRi_list_subset

try:
wRi_list_subset = _create_factors_and_run()
except RuntimeError:
logger.exception("Shonan failed")
if self._weight_by_inliers is True:
logger.info("Reattempting Shonan without inlier-weighted costs...")
# At times, Shonan's `SparseMinimumEigenValue` fails to compute minimum eigenvalue.
self._weight_by_inliers = False
wRi_list_subset = _create_factors_and_run()
wRi_list = [None] * num_images
for remapped_i, original_i in enumerate(nodes_with_edges):
wRi_list[original_i] = wRi_list_subset[remapped_i]
Expand Down
4 changes: 3 additions & 1 deletion gtsfm/configs/unified.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -65,15 +65,17 @@ SceneOptimizer:
# comment out to not run
view_graph_estimator:
_target_: gtsfm.view_graph_estimator.cycle_consistent_rotation_estimator.CycleConsistentRotationViewGraphEstimator
edge_error_aggregation_criterion: MEDIAN_EDGE_ERROR
edge_error_aggregation_criterion: MIN_EDGE_ERROR

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

trans_avg_module:
_target_: gtsfm.averaging.translation.averaging_1dsfm.TranslationAveraging1DSFM
robust_measurement_noise: True
projection_sampling_method: SAMPLE_INPUT_MEASUREMENTS
reject_outliers: True

data_association_module:
_target_: gtsfm.data_association.data_assoc.DataAssociation
Expand Down
6 changes: 6 additions & 0 deletions gtsfm/frontend/verifier/verifier_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,12 @@ def get_ui_metadata() -> UiMetadata:
parent_plate="Two-View Estimator",
)

def __repr__(self) -> str:
return (
f"{type(self).__name__}"
+ f"__use_intrinsics{self._use_intrinsics_in_verification}_{self._estimation_threshold_px}px"
)

def __init__(
self,
use_intrinsics_in_verification: bool,
Expand Down

0 comments on commit 3e125c7

Please sign in to comment.