Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
2 changes: 1 addition & 1 deletion environment_linux.yml
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ dependencies:
- pydegensac
- colour
- trimesh[easy]
- gtsam-develop==4.3a1.dev202603090403
- gtsam-develop==4.3a1.dev202604240153
- pydot
# dust3r/mast3r
- roma
Expand Down
2 changes: 1 addition & 1 deletion environment_linux_cpuonly.yml
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ dependencies:
- pydegensac
- colour
- trimesh[easy]
- gtsam-develop==4.3a1.dev202603090403
- gtsam-develop==4.3a1.dev202604240153
- pydot
- roma
- tqdm
Expand Down
2 changes: 1 addition & 1 deletion environment_mac.yml
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ dependencies:
- pydegensac
- colour
- trimesh[easy]
- gtsam-develop==4.3a1.dev202603090403
- gtsam-develop==4.3a1.dev202604240153
- pydot
# dust3r/mast3r
- roma
Expand Down
23 changes: 4 additions & 19 deletions gtsfm/averaging/translation/averaging_1dsfm.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
from gtsfm.evaluation.metrics import GtsfmMetric, GtsfmMetricsGroup
from gtsfm.products.visibility_graph import AnnotatedGraph, ImageIndexPair, ImageIndexPairs
from gtsfm.utils import align, transform
from gtsfm.utils.tracks import compute_world_directions

# Hyperparameters for 1D-SFM
# maximum number of times 1dsfm will project the Unit3's to a 1d subspace for outlier rejection
Expand Down Expand Up @@ -416,25 +417,9 @@ def _get_landmark_directions(
Returns:
Dictionary of unit directions from camera to track in world frame indexed by (track_id, camera_id).
"""
landmark_directions = {}
for track_id, track in enumerate(tracks_2d):
for j in range(track.number_measurements()):
measurement = track.measurement(j)
cam_idx = measurement.i

# TODO(akshay-krishnan): consider changing input type and checking elsewhere
intrinsics_i = intrinsics[cam_idx]
wRi = wRi_list[cam_idx]
assert wRi is not None, "Camera must have valid rotation to use tracks for averaging."
assert intrinsics_i is not None, "Camera must be calibrated to use tracks for averaging."

measurement_xy = intrinsics_i.calibrate(measurement.uv)
measurement_homogeneous = Point3(measurement_xy[0], measurement_xy[1], 1.0)
w_cam_U_track = Unit3(wRi.rotate(Unit3(measurement_homogeneous).point3()))

# Direction starts at camera, but first index is track_id.
landmark_directions[(track_id, cam_idx)] = w_cam_U_track
return landmark_directions
observations = compute_world_directions(tracks_2d, intrinsics, wRi_list)
return {(track_id, cam_idx): Unit3(Point3(*direction))
for track_id, cam_idx, direction in observations}

def __run_averaging(
self,
Expand Down
128 changes: 128 additions & 0 deletions gtsfm/configs/sift_global_positioner.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
# MegaLoc + SIFT + Global Positioner with Single partition.
# Based on unified_megaloc.yaml with SIFT detector/matcher swap + GP.

# @package _global_
_target_: gtsfm.scene_optimizer.SceneOptimizer

loader:
_target_: gtsfm.loader.Olsson

image_pairs_generator:
_target_: gtsfm.retriever.image_pairs_generator.ImagePairsGenerator
global_descriptor:
_target_: gtsfm.frontend.cacher.global_descriptor_cacher.GlobalDescriptorCacher
global_descriptor_obj:
_target_: gtsfm.frontend.global_descriptor.MegaLoc
retriever:
_target_: gtsfm.retriever.Similarity
num_matched: 100
min_score: 0.15
use_diffusion_preprocessing: false
use_mst_augmentation: false
batch_size: 16

graph_partitioner:
_target_: gtsfm.graph_partitioner.Single

cluster_optimizer:
_target_: gtsfm.cluster_optimizer.Multiview

correspondence_generator:
_target_: gtsfm.frontend.correspondence_generator.det_desc_correspondence_generator.DetDescCorrespondenceGenerator

detector_descriptor:
_target_: gtsfm.frontend.cacher.detector_descriptor_cacher.DetectorDescriptorCacher
detector_descriptor_obj:
_target_: gtsfm.frontend.detector_descriptor.colmap_sift.ColmapSIFTDetectorDescriptor
max_keypoints: 8192

matcher:
_target_: gtsfm.frontend.cacher.matcher_cacher.MatcherCacher
matcher_obj:
_target_: gtsfm.frontend.matcher.twoway_matcher.TwoWayMatcher
ratio_test_threshold: 0.8

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
ba_reproj_error_thresholds: [0.5]
bundle_adjust_2view_maxiters: 100

verifier:
_target_: gtsfm.frontend.verifier.poselib_verifier.PoseLibVerifier
estimation_threshold_px: 2

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: 30
min_inlier_ratio_est_model: 0.15
save_gtsfm_data: True
save_3d_viz: False
save_two_view_viz: False
pose_angular_error_thresh: 5
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: MIN_EDGE_ERROR
error_threshold: 7.0

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: False
use_all_tracks_for_averaging: True
use_relative_camera_poses: True

data_association_module:
_target_: gtsfm.data_association.data_assoc.DataAssociation
min_track_len: 3
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

global_positioner:
_target_: gtsfm.global_positioner.global_positioner.GlobalPositioner
noise_sigma: 0.01
huber_loss_scale: 0.1
max_iterations: 50
min_track_measurements: 3
max_reproj_error: 10.0
save_iteration_visualization: True

run_view_graph_calibration: true
rotation_outlier_threshold_deg: 0

bundle_adjustment_module:
_target_: gtsfm.bundle.bundle_adjustment.BundleAdjustmentOptimizer
reproj_error_thresholds: [10, 5, 3]
robust_ba_mode: "HUBER"
shared_calib: False
cam_pose3_prior_noise_sigma: 0.1
calibration_prior_focal_sigma: 200.0
measurement_noise_sigma: 1.0
use_calibration_prior: true

dense_multiview_optimizer: null
gaussian_splatting_optimizer: null

1 change: 1 addition & 0 deletions gtsfm/global_positioner/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
"""Global positioner module — joint camera + point estimation using bearing constraints."""
Loading
Loading