Skip to content

Commit de4da7c

Browse files
author
Yann N.
committed
On-the-fly resection candidates
Instead of recomputing resection candidates from scratch, which has O(N2) for the entire processing (and takes up to 1-2 seconds on large projects), we instead keep track of candidates per images. This makes everything constant time instead. On helenenschacht (https://github.com/OpenDroneMap/odm_data_helenenschacht/tree/main) : BEFORE : around 120 ms 2025-08-15 13:01:55,007 INFO: Reconstruction now has 3 shots. 2025-08-15 13:01:55,138 INFO: ------------------------------------------------------- 2025-08-15 13:01:56,832 INFO: Reconstruction now has 4 shots. 2025-08-15 13:01:56,965 INFO: ------------------------------------------------------- 2025-08-15 13:01:57,359 INFO: Reconstruction now has 5 shots. 2025-08-15 13:01:57,492 INFO: ------------------------------------------------------- AFTER : constant < 1 ms 2025-08-15 13:10:39,368 INFO: Reconstruction now has 3 shots. 2025-08-15 13:10:39,368 INFO: ------------------------------------------------------- 2025-08-15 13:10:41,195 INFO: Reconstruction now has 4 shots. 2025-08-15 13:10:41,195 INFO: ------------------------------------------------------- 2025-08-15 13:10:41,706 INFO: Reconstruction now has 5 shots. 2025-08-15 13:10:41,706 INFO: ------------------------------------------------------- On 7K images datasets (https://github.com/zivillian/odm_ziegeleipark/tree/master), this takes up to 1-2 seconds after a few thousands images
1 parent d4ed1c2 commit de4da7c

1 file changed

Lines changed: 115 additions & 23 deletions

File tree

opensfm/reconstruction.py

Lines changed: 115 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -705,7 +705,7 @@ def resect(
705705
bs = np.array(bs)
706706
Xs = np.array(Xs)
707707
if len(bs) < 5:
708-
return False, set(), {"num_common_points": len(bs)}
708+
return False, set(), set(), {"num_common_points": len(bs)}
709709

710710
T = multiview.absolute_pose_ransac(bs, Xs, threshold, 1000, 0.999)
711711

@@ -736,15 +736,17 @@ def resect(
736736
triangulate_shot_features(
737737
tracks_manager, reconstruction, new_shots, data.config
738738
)
739+
tracks = set()
739740
for i, succeed in enumerate(inliers):
740741
if succeed:
741742
add_observation_to_reconstruction(
742743
tracks_manager, reconstruction, shot_id, ids[i]
743744
)
745+
tracks.add(ids[i])
744746
report["shots"] = list(new_shots)
745-
return True, new_shots, report
747+
return True, new_shots, tracks, report
746748
else:
747-
return False, set(), report
749+
return False, set(), set(), report
748750

749751

750752
def corresponding_tracks(
@@ -911,7 +913,7 @@ def triangulate_robust(
911913
min_ray_angle_degrees: float,
912914
min_depth: float,
913915
iterations: int,
914-
) -> None:
916+
) -> bool:
915917
"""Triangulate track in a RANSAC way and add point to reconstruction."""
916918
os, bs, ids = [], [], []
917919
for shot_id, obs in self.tracks_handler.get_observations(track).items():
@@ -923,7 +925,7 @@ def triangulate_robust(
923925
ids.append(shot_id)
924926

925927
if len(ids) < 2:
926-
return
928+
return False
927929

928930
os = np.array(os)
929931
bs = np.array(bs)
@@ -1003,6 +1005,7 @@ def triangulate_robust(
10031005
self.tracks_handler.store_track_coordinates(track, best_point)
10041006
for i in best_inliers:
10051007
self.tracks_handler.store_inliers_observation(track, ids[i])
1008+
return len(best_inliers) > 1
10061009

10071010
def triangulate(
10081011
self,
@@ -1011,7 +1014,7 @@ def triangulate(
10111014
min_ray_angle_degrees: float,
10121015
min_depth: float,
10131016
iterations: int,
1014-
) -> None:
1017+
) -> bool:
10151018
"""Triangulate track and add point to reconstruction."""
10161019
os, bs, ids = [], [], []
10171020
for shot_id, obs in self.tracks_handler.get_observations(track).items():
@@ -1039,6 +1042,9 @@ def triangulate(
10391042
self.tracks_handler.store_track_coordinates(track, X.tolist())
10401043
for shot_id in ids:
10411044
self.tracks_handler.store_inliers_observation(track, shot_id)
1045+
return True
1046+
1047+
return False
10421048

10431049
def triangulate_dlt(
10441050
self,
@@ -1047,7 +1053,7 @@ def triangulate_dlt(
10471053
min_ray_angle_degrees: float,
10481054
min_depth: float,
10491055
iterations: int,
1050-
) -> None:
1056+
) -> bool:
10511057
"""Triangulate track using DLT and add point to reconstruction."""
10521058
Rts, bs, os, ids = [], [], [], []
10531059
for shot_id, obs in self.tracks_handler.get_observations(track).items():
@@ -1075,6 +1081,8 @@ def triangulate_dlt(
10751081
self.tracks_handler.store_track_coordinates(track, X.tolist())
10761082
for shot_id in ids:
10771083
self.tracks_handler.store_inliers_observation(track, shot_id)
1084+
return True
1085+
return False
10781086

10791087
def _shot_origin(self, shot: pymap.Shot) -> NDArray:
10801088
if shot.id in self.origins:
@@ -1106,7 +1114,7 @@ def triangulate_shot_features(
11061114
reconstruction: types.Reconstruction,
11071115
shot_ids: Set[str],
11081116
config: Dict[str, Any],
1109-
) -> None:
1117+
) -> List[str]:
11101118
"""Reconstruct as many tracks seen in shot_id as possible."""
11111119
reproj_threshold = config["triangulation_threshold"]
11121120
min_ray_angle = config["triangulation_min_ray_angle"]
@@ -1124,24 +1132,29 @@ def triangulate_shot_features(
11241132
if s in all_shots_ids
11251133
for t in tracks_manager.get_shot_observations(s)
11261134
}
1135+
1136+
created_tracks = []
11271137
for track in tracks_ids:
11281138
if track not in reconstruction.points:
11291139
if config["triangulation_type"] == "ROBUST":
1130-
triangulator.triangulate_robust(
1140+
if(triangulator.triangulate_robust(
11311141
track,
11321142
reproj_threshold,
11331143
min_ray_angle,
11341144
min_depth,
11351145
refinement_iterations,
1136-
)
1146+
)):
1147+
created_tracks.append(track)
11371148
elif config["triangulation_type"] == "FULL":
1138-
triangulator.triangulate(
1149+
if(triangulator.triangulate(
11391150
track,
11401151
reproj_threshold,
11411152
min_ray_angle,
11421153
min_depth,
11431154
refinement_iterations,
1144-
)
1155+
)):
1156+
created_tracks.append(track)
1157+
return created_tracks
11451158

11461159

11471160
def retriangulate(
@@ -1214,7 +1227,7 @@ def remove_outliers(
12141227
reconstruction: types.Reconstruction,
12151228
config: Dict[str, Any],
12161229
points: Optional[Dict[str, pymap.Landmark]] = None,
1217-
) -> int:
1230+
) -> Tuple[List[Tuple[str, str]], Set[str]]:
12181231
"""Remove points with large reprojection error.
12191232
12201233
A list of point ids to be processed can be given in ``points``.
@@ -1236,14 +1249,16 @@ def remove_outliers(
12361249
reconstruction.map.remove_observation(shot_id, track)
12371250
track_ids.add(track)
12381251

1252+
removed_tracks = set()
12391253
for track in track_ids:
12401254
if track in reconstruction.points:
12411255
lm = reconstruction.points[track]
12421256
if lm.number_of_observations() < 2:
12431257
reconstruction.map.remove_landmark(lm)
1258+
removed_tracks.add(track)
12441259

12451260
logger.info("Removed outliers: {}".format(len(outliers)))
1246-
return len(outliers)
1261+
return outliers, removed_tracks
12471262

12481263

12491264
def shot_lla_and_compass(
@@ -1407,6 +1422,75 @@ def should(self) -> bool:
14071422
def done(self) -> None:
14081423
self.num_points_last = len(self.reconstruction.points)
14091424

1425+
class ResectionCandidates:
1426+
"""Helper to keep track of resection candidates."""
1427+
1428+
def __init__(self, tracks_manager: pymap.TracksManager, reconstruction: types.Reconstruction) -> None:
1429+
self.tracks_manager = tracks_manager
1430+
self.reconstruction = reconstruction
1431+
self.candidates: Dict[str, Set[str]] = {}
1432+
self.tracks = set()
1433+
1434+
def update(self, reconstruction: types.Reconstruction) -> None:
1435+
"""Update candidates based on a new reconstruction."""
1436+
self.reconstruction = reconstruction
1437+
rec_tracks = set(reconstruction.points.keys())
1438+
1439+
# add new tracks
1440+
for track_id in rec_tracks:
1441+
if track_id not in self.tracks:
1442+
self.tracks.add(track_id)
1443+
for shot_id in self.tracks_manager.get_track_observations(track_id):
1444+
if shot_id not in self.candidates:
1445+
self.candidates[shot_id] = set()
1446+
self.candidates[shot_id].add(track_id)
1447+
1448+
# remove tracks that are not in the reconstruction
1449+
to_remove = set()
1450+
for track_id in self.tracks:
1451+
if track_id not in rec_tracks:
1452+
for shot_id, shot_candidates in self.candidates.items():
1453+
if track_id in shot_candidates:
1454+
shot_candidates.remove(track_id)
1455+
to_remove.add(track_id)
1456+
1457+
for track_id in to_remove:
1458+
self.tracks.remove(track_id)
1459+
1460+
def add(self, shots: List[str], tracks: Set[str]) -> None:
1461+
"""Add newly resected tracks and the shots they belong to."""
1462+
for shot_id in shots:
1463+
if shot_id in self.candidates:
1464+
del self.candidates[shot_id]
1465+
1466+
for track_id in tracks:
1467+
self.tracks.add(track_id)
1468+
for shot_id in self.tracks_manager.get_track_observations(track_id):
1469+
if shot_id in self.reconstruction.shots:
1470+
continue
1471+
if shot_id not in self.candidates:
1472+
self.candidates[shot_id] = set()
1473+
self.candidates[shot_id].add(track_id)
1474+
1475+
def remove(self, outliers: List[Tuple[str, str]], removed_tracks: List[str]) -> None:
1476+
"""Remove outliers from candidates."""
1477+
for shot_id, track_id in outliers:
1478+
if shot_id in self.candidates and track_id in self.candidates[shot_id]:
1479+
self.candidates[shot_id].remove(track_id)
1480+
if not self.candidates[shot_id]:
1481+
del self.candidates[shot_id]
1482+
1483+
for track_id in removed_tracks:
1484+
for shot_id, shot_candidates in self.candidates.items():
1485+
if track_id in shot_candidates:
1486+
shot_candidates.remove(track_id)
1487+
self.tracks.remove(track_id)
1488+
1489+
1490+
def get_candidates(self, images: Set[str]) -> List[Tuple[str, int]]:
1491+
"""Get sorted candidates for resection."""
1492+
return [(k, len(v)) for k,v in filter(lambda x: x[0] in images, sorted(self.candidates.items(), key=lambda x: -len(x[1])))]
1493+
14101494

14111495
def grow_reconstruction(
14121496
data: DataSetBase,
@@ -1429,8 +1513,15 @@ def grow_reconstruction(
14291513
remove_outliers(reconstruction, config)
14301514
paint_reconstruction(data, tracks_manager, reconstruction)
14311515

1516+
resection_candidates = ResectionCandidates(tracks_manager, reconstruction)
14321517
should_bundle = ShouldBundle(data, reconstruction)
14331518
should_retriangulate = ShouldRetriangulate(data, reconstruction)
1519+
1520+
resection_candidates.add(
1521+
list(reconstruction.shots.keys()),
1522+
list(reconstruction.points.keys()),
1523+
)
1524+
14341525
while True:
14351526
if config["save_partial_reconstructions"]:
14361527
paint_reconstruction(data, tracks_manager, reconstruction)
@@ -1441,17 +1532,15 @@ def grow_reconstruction(
14411532
),
14421533
)
14431534

1444-
candidates = reconstructed_points_for_images(
1445-
tracks_manager, reconstruction, images
1446-
)
1535+
candidates = resection_candidates.get_candidates(images)
14471536
if not candidates:
14481537
break
14491538

14501539
logger.info("-------------------------------------------------------")
14511540
threshold = data.config["resection_threshold"]
14521541
min_inliers = data.config["resection_min_inliers"]
14531542
for image, _ in candidates:
1454-
ok, new_shots, resrep = resect(
1543+
ok, new_shots, resected_tracks, resrep = resect(
14551544
data,
14561545
tracks_manager,
14571546
reconstruction,
@@ -1470,6 +1559,7 @@ def grow_reconstruction(
14701559
rig_camera_priors,
14711560
data.config,
14721561
)
1562+
resection_candidates.add(new_shots, resected_tracks)
14731563

14741564
logger.info(f"Adding {' and '.join(new_shots)} to the reconstruction")
14751565
step: Dict[str, Union[List[int], List[str], int, List[int], Any]] = {
@@ -1480,7 +1570,8 @@ def grow_reconstruction(
14801570
report["steps"].append(step)
14811571

14821572
np_before = len(reconstruction.points)
1483-
triangulate_shot_features(tracks_manager, reconstruction, new_shots, config)
1573+
new_tracks = triangulate_shot_features(tracks_manager, reconstruction, new_shots, config)
1574+
resection_candidates.add([], new_tracks)
14841575
np_after = len(reconstruction.points)
14851576
step["triangulated_points"] = np_after - np_before
14861577

@@ -1491,10 +1582,11 @@ def grow_reconstruction(
14911582
reconstruction, camera_priors, rig_camera_priors, None, config
14921583
)
14931584
rrep = retriangulate(tracks_manager, reconstruction, config)
1585+
resection_candidates.update(reconstruction)
14941586
b2rep = bundle(
14951587
reconstruction, camera_priors, rig_camera_priors, None, config
14961588
)
1497-
remove_outliers(reconstruction, config)
1589+
resection_candidates.remove(*remove_outliers(reconstruction, config))
14981590
step["bundle"] = b1rep
14991591
step["retriangulation"] = rrep
15001592
step["bundle_after_retriangulation"] = b2rep
@@ -1505,7 +1597,7 @@ def grow_reconstruction(
15051597
brep = bundle(
15061598
reconstruction, camera_priors, rig_camera_priors, None, config
15071599
)
1508-
remove_outliers(reconstruction, config)
1600+
resection_candidates.remove(*remove_outliers(reconstruction, config))
15091601
step["bundle"] = brep
15101602
should_bundle.done()
15111603
elif config["local_bundle_radius"] > 0:
@@ -1517,7 +1609,7 @@ def grow_reconstruction(
15171609
image,
15181610
config,
15191611
)
1520-
remove_outliers(reconstruction, config, bundled_points)
1612+
resection_candidates.remove(*remove_outliers(reconstruction, config, bundled_points))
15211613
step["local_bundle"] = brep
15221614

15231615
logger.info(f"Reconstruction now has {len(reconstruction.shots)} shots.")
@@ -1536,7 +1628,7 @@ def grow_reconstruction(
15361628
config = overidden_config
15371629

15381630
bundle(reconstruction, camera_priors, rig_camera_priors, gcp, config)
1539-
remove_outliers(reconstruction, config)
1631+
resection_candidates.remove(*remove_outliers(reconstruction, config))
15401632
paint_reconstruction(data, tracks_manager, reconstruction)
15411633
return reconstruction, report
15421634

0 commit comments

Comments
 (0)