Skip to content

Improve tracking performance#56

Open
aaptho wants to merge 8 commits intomasterfrom
aaptho/improve-tracking
Open

Improve tracking performance#56
aaptho wants to merge 8 commits intomasterfrom
aaptho/improve-tracking

Conversation

@aaptho
Copy link
Copy Markdown
Collaborator

@aaptho aaptho commented May 6, 2026

Uses a variety of fixes to improve tracking stability and performance

Also fixes some build warnings and unit tests

aaptho and others added 8 commits April 26, 2026 22:03
The old test compared squaredError/meanSquaredError against a threshold, which rejected
every correspondence above the mean — typically 40-55% of points, regardless of whether
they were real outliers. That biased ICP toward re-fitting already-matched areas.

Replace with mean + k·σ on the distance distribution.
Expose the k constant knob via the icp_outlier_deviations_threshold user default.
The linear Jacobian uses the skew-symmetric/axis-angle parameterization, so the consistent retraction is
R = exp([ω]×). The previous Euler-XYZ retraction agreed only to first order and diverged whenever a single
iteration stepped more than a few degrees, which is the regime ICP hits when catching up from a poor seed.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
Dividing by `rmsError` produces Inf/NaN when the fit becomes nearly perfect,
which then exits the iteration loop on the wrong condition.
Clamp the denominator with a 1e-6 floor.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
Pre-transform the incoming frame by (lastAcceptedDelta * prevPose) instead of just prevPose,
so ICP starts where the camera is predicted to be rather than where it was.
The cached delta is updated only on accepted frames; rejected frames leave it untouched so a
single bad frame doesn't poison the next prediction. Damping keeps a noisy delta from running away.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
Add per-iteration ICP diagnostic logs to PBFModel.
Track dropped input frames in SCReconstructionManager statistics and tighten log formatting.
@aaptho
Copy link
Copy Markdown
Collaborator Author

aaptho commented May 6, 2026

@rreusser this may interest you! Would also appreciate your more intuitive explanation of what Claude discovered.

@rreusser
Copy link
Copy Markdown
Contributor

rreusser commented May 6, 2026

👋 Whoa! Long time no see. Hope you're well.

I think, overwhelmingly, in hindsight, that the key missing piece was always RGB camera input and and a numerical optimization method which combined RGB and depth. That is, you really should be able to track camera motion if the camera is just pointed at a flat image painted on a wall. It looks like this maybe switches to SE(3) or something? I think what's going on in this PR is that it's switching a representation to SE(3) instead of just 3D transformation matrices. While that's good and the right choice in general, I'm not immediately convinced that it's a limiting factor here. Ideally, transforms are close to the identity if it's a frame-over-frame nudge, so that it's not particularly close to gimbal lock territory.

I'm not exactly certain what's best here. Some sort of ad hoc gradient minimization using ICP correspondences? Using ICP weighted together with RGB correspondences? Using SIFT/SURF points and trying to compute some sort of bundle adjustment? One thing for sure is that Claude is probably better poised to assemble some of these methods than we were. 🤖

These are just some verrry rough ideas. Love that this is getting dusted off.

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.

2 participants