Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use futures in triangulation #758

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
5 changes: 4 additions & 1 deletion gtsfm/data_association/data_assoc.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
import dask
import numpy as np
from dask.delayed import Delayed
from distributed.worker import get_client
from gtsam import SfmTrack

import gtsfm.common.types as gtsfm_types
Expand Down Expand Up @@ -239,7 +240,9 @@ def triangulate_batch(
return batch_results

# Initialize 3D landmark for each track.
client = get_client()
point3d_initializer = Point3dInitializer(cameras, self.triangulation_options)
future_point3d_initializer = client.scatter(point3d_initializer, broadcast=True)

# Loop through tracks and and generate delayed triangulation tasks.
batch_size = int(np.ceil(len(tracks_2d) / MAX_DELAYED_TRIANGULATION_CALLS))
Expand All @@ -250,7 +253,7 @@ def triangulate_batch(
else:
for j in range(0, len(tracks_2d), batch_size):
triangulation_results.append(
dask.delayed(triangulate_batch)(point3d_initializer, tracks_2d[j : j + batch_size])
dask.delayed(triangulate_batch)(future_point3d_initializer, tracks_2d[j : j + batch_size])
)

# Perform triangulation in parallel.
Expand Down
4 changes: 2 additions & 2 deletions gtsfm/multi_view_optimizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
from gtsfm.data_association.data_assoc import DataAssociation
from gtsfm.evaluation.metrics import GtsfmMetricsGroup
from gtsfm.view_graph_estimator.view_graph_estimator_base import ViewGraphEstimatorBase
from gtsfm.data_association.cpp_dsf_tracks_estimator import CppDsfTracksEstimator
from gtsfm.data_association.dsf_tracks_estimator import DsfTracksEstimator
from gtsfm.common.two_view_estimation_report import TwoViewEstimationReport


Expand Down Expand Up @@ -194,5 +194,5 @@ def init_cameras(
def get_2d_tracks(
corr_idxs_dict: Dict[Tuple[int, int], np.ndarray], keypoints_list: List[Keypoints]
) -> List[SfmTrack2d]:
tracks_estimator = CppDsfTracksEstimator()
tracks_estimator = DsfTracksEstimator()
return tracks_estimator.run(corr_idxs_dict, keypoints_list)
Loading