From 50cbe3e96229d144705d40b4639b8e835627510e Mon Sep 17 00:00:00 2001 From: Ayush Baid Date: Sat, 7 Oct 2023 15:40:37 -0700 Subject: [PATCH] Require min 500 tracks for batch triangulation task --- gtsfm/data_association/data_assoc.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsfm/data_association/data_assoc.py b/gtsfm/data_association/data_assoc.py index c75dee6bd..3761d6f6f 100644 --- a/gtsfm/data_association/data_assoc.py +++ b/gtsfm/data_association/data_assoc.py @@ -37,6 +37,7 @@ # Heuristically set to limit the number of delayed tasks, as recommended by Dask: # https://docs.dask.org/en/stable/delayed-best-practices.html#avoid-too-many-tasks MAX_DELAYED_TRIANGULATION_CALLS = 1e3 +MIN_TRACKS_PER_BATCH = 500 @dataclass(frozen=True) @@ -242,7 +243,7 @@ def triangulate_batch( point3d_initializer = Point3dInitializer(cameras, self.triangulation_options) # Loop through tracks and and generate delayed triangulation tasks. - batch_size = int(np.ceil(len(tracks_2d) / MAX_DELAYED_TRIANGULATION_CALLS)) + batch_size = max(int(np.ceil(len(tracks_2d) / MAX_DELAYED_TRIANGULATION_CALLS)), MIN_TRACKS_PER_BATCH) triangulation_results = [] if batch_size == 1: for track_2d in tracks_2d: