Skip to content

Add Global Positioner module #1100

Merged
kathirgounder merged 11 commits intoborglab:masterfrom
kathirgounder:GlobalPositioner-v2
Apr 25, 2026
Merged

Add Global Positioner module #1100
kathirgounder merged 11 commits intoborglab:masterfrom
kathirgounder:GlobalPositioner-v2

Conversation

@kathirgounder
Copy link
Copy Markdown
Collaborator

@kathirgounder kathirgounder commented Apr 1, 2026

!Implemented a standalone Global Positioner Class in GTSAM to match SOTA Global SFM and now bringing those changes into GTSFM, this was fun :)!

GTSAM PR: borglab/gtsam#2495

Akshay had already implemented the BilinearAngleTranslationFactors in GTSAM and wired it in the TranslationRecovery class, but we were not combining Translation Averaging + Triangulation into one step like GLOMAP does. I scrolled through Slack for a couple of years and it seems like the furthest we went was we tried jointly estimating Translations and 3D Tracks, but we kept camera-camera constraints and threw away the estimated 3D points, and ran the triangulation step again to regenerate 3D points to initialize BA (data_association in gtsfm). Glomap's insight was that we didn't need to do manual triangulation after Translation Averaging anymore thanks to the GlobalPositioner

This PR replaces Translation Averaging + Triangulation completely with the GlobalPositioner and initializes BA that way. Here's a small table on our benchmarks. We've also reached parity with the SOTA on tough IMC datasets like British Museum and Brussels.

image

Some videos showing the GlobalPositioner in action:

Palace of Fine Arts:

convergence_palace_smooth.mp4

Brussels:

gp_convergence_brussels.mp4

South Building:

convergence_south.mp4

Gerrard Hall:

convergence_gerrard.mp4

Door:

convergence_native_api.mp4

@dellaert
Copy link
Copy Markdown
Member

dellaert commented Apr 4, 2026

Could you include the comparison with baseline in the PR comment?

@kathirgounder
Copy link
Copy Markdown
Collaborator Author

kathirgounder commented Apr 4, 2026

Could you include the comparison with baseline in the PR comment?

Hi Frank @dellaert, just added a screenshot of the metrics comparison and some videos.

The existing visualize_benchmark_comparison.py compares the same configs across two different CI runs (master vs branch) by matching artifact names, it wasn't built to compare two different configs and code paths within the same run since they have different artifact names and the script pairs by name (unified sift vs unified sift_global_positioner - both are identical besides the fact one does TA + Triangulation verus GlobalPositioning), the global positioner is a clean swap / drop in that replaces the two stages and I added separate configs for it and added it to the ci.yml, so I had claude write a quick script to pull down all the metrics and just compare the results between the two from the same CI Run.

@dellaert
Copy link
Copy Markdown
Member

dellaert commented Apr 4, 2026

Amazing! @akshay-krishnan whaddayathink? I’ll leave you to approve…

@kathirgounder
Copy link
Copy Markdown
Collaborator Author

Amazing! @akshay-krishnan whaddayathink? I’ll leave you to approve…

Will try to clean up and add more documentation on some of the things I added (Viz Script and optimizer logging) and also discuss with Akshay how to go about updating the default CI strategy before trying to merge this in

@kathirgounder
Copy link
Copy Markdown
Collaborator Author

Hey @dellaert @akshay-krishnan !

I was potentially thinking of adding a separate GTSAM class for the GlobalPositioner instead of using the TranslationRecovery class. The semantics are a bit misleading in comparison to how I am using it to express the Global Positioning Optimization. TranslationRecovery's documentation, variable names, and API all describe camera-to-camera translation directions. The current interface does not indicate anywhere that tracks are supported and assumes all measurements are camera-camera.

Our GTSFM code passes C(cam_idx) and L(track_idx) as keys, computes world-frame bearings from feature tracks, and maps results back to cameras+landmarks, all in Python wrapper code that a potential GTSAM user would have to reverse-engineer from our application to understand the GP use case. I think a dedicated class would make the camera+landmark formulation cleaner.

Additionally TranslationRecovery's addPrior method is designed specifically for Translation Averaging, where it tries fix the 4 degrees of freedom required for TA by pinning key1 to the origin and key2 to default scale * measured(). In GP, edges are camera-to-landmark, so key2 is a landmark. The scale prior pins the entire reconstruction's scale to one depth estimate for one landmark rather than establishing a baseline. In our tests the optimizer overcomes this since the prior is soft, but to match Glomaps GP formulation we would only add a prior to the first camera.

I think this will make both the GTSFM code and GTSAM code more explicit and separate. GTSAM already has the factor (BilinearAngleTranslationFactor) and the solver machinery, what's missing is the solve pipeline that makes GP as
easy to use and expressed as a first class citizen like ShonanAveraging and TranslationRecovery are for their respective problems!

I also wanted to learn how to contribute to GTSAM :)

Copy link
Copy Markdown
Collaborator

@akshay-krishnan akshay-krishnan left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ultimately we are using the translationrecovery class here as well.

It would be cleaner to re-use the existing averaging_1dsfm code as much as possible. feel free to refactor that class to support this "global positioner" variant if needed.

Comment thread gtsfm/multi_view_optimizer.py
Comment thread gtsfm/global_positioner/global_positioner.py Outdated
Comment thread gtsfm/global_positioner/global_positioner.py Outdated
@akshay-krishnan
Copy link
Copy Markdown
Collaborator

akshay-krishnan commented Apr 6, 2026

visualization is very cool! based on what Im seeing it should be fine to stop iterating sooner, not much happens after the first ~10 iterations. There is also a global rotation error guage freedom, we probably need to strengther the prior, likely inside gtsam code.

@akshay-krishnan
Copy link
Copy Markdown
Collaborator

CI seems to be failing due to some formatting errors.

@akshay-krishnan akshay-krishnan marked this pull request as ready for review April 6, 2026 14:33
kathirgounder and others added 3 commits April 25, 2026 12:02
Refactors the Global Positioner to use gtsam.GlobalPositioner
(merged into gtsam-develop after the original v2 PR was opened)
instead of TranslationRecovery + use_bilinear_translation_factor.
The new gtsam.GlobalPositioner exposes the BATA bipartite camera +
landmark estimator directly, handling graph construction, gauge
fixing, initialization, and Levenberg-Marquardt in one call.

GTSFM-side public class API is preserved; .run() additionally
takes an optional output_root kwarg for namespacing the convergence
trace pickle. multi_view_optimizer threads it through.

Also in this PR refresh:
- Bump gtsam-develop pin to 4.3a1.dev202604240153 in environment_*
  and pyproject.toml (newest wheel containing gtsam.GlobalPositioner).
- Drop CI-matrix proof-of-concept changes (.github/workflows/ci.yml
  and execute_single_benchmark.sh additions). These existed only to
  demo the v2 pipeline to the team and aren't needed in the merged
  PR.
- Add gtsfm/configs/megaloc_sift_gp_single_pt.yaml — production
  config we're using on phototourism datasets (MegaLoc retrieval,
  ColmapSIFT @ 8192, PoseLib verifier, GP). Outer-BA-loop params
  from the experimental gp-glomap-parity branch are deliberately
  stripped to keep this PR scoped to the GP-API migration.

Akshay's review comment (replace MVO's GP-vs-trans_avg if/else
with a common base class) is deferred to a follow-up.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
Addresses Akshay's review comment about duplicated code in
global_positioner.py:
- compute_world_directions: same per-measurement logic as
  averaging_1dsfm._get_landmark_directions (calibrate → unit ray →
  rotate to world frame). Now lives in gtsfm.utils.tracks and is
  shared by both global positioner and 1DSfM translation averaging.
- filter_tracks_by_measurements: track filter (keep tracks with
  enough valid-camera measurements, longest first, optional cap).
  Lifted to gtsfm.utils.tracks for reuse.

1DSfM's _get_landmark_directions is now a thin adapter that calls
the shared util and re-shapes the List[Tuple] output into the
existing Dict[(track, cam), Unit3] format. Behavior is identical;
the asserts on None wRi/intrinsics relax to silent skips, which is
strictly safer (the upstream caller guarantees validity, the asserts
just panic on edge cases).

Also in this commit:
- Replace sift_global_positioner.yaml with the production MegaLoc-
  based config so the team can run experiments without juggling
  two near-identical config files.
- Regenerate uv.lock for the gtsam-develop pin bump from the prior
  commit (CI was failing because --locked saw drift).
Resolves CI lint failures:
- gtsfm/global_positioner/global_positioner.py E127: switched the
  3-line "done in" log to hanging indent.
- gtsfm/utils/tracks.py F401: removed Unit3 import (the util returns
  np.ndarray, not Unit3 — 1DSfM does the wrap on its end).
@nantonzhang nantonzhang self-requested a review April 25, 2026 20:25
@kathirgounder kathirgounder merged commit bff2105 into borglab:master Apr 25, 2026
18 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants