-
-
Notifications
You must be signed in to change notification settings - Fork 850
Bootstrap with injected depths from Depthmaps #1994
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
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change | ||||||||
|---|---|---|---|---|---|---|---|---|---|---|
|
|
@@ -8,6 +8,9 @@ | |||||||||
| #include <aliceVision/sfm/pipeline/bootstrapping/EstimateAngle.hpp> | ||||||||||
| #include <aliceVision/sfm/pipeline/expanding/ExpansionPolicyLegacy.hpp> | ||||||||||
| #include <aliceVision/multiview/triangulation/triangulationDLT.hpp> | ||||||||||
| #include <aliceVision/sfm/pipeline/bootstrapping/TracksDepths.hpp> | ||||||||||
| #include <aliceVision/sfm/pipeline/expanding/SfmResection.hpp> | ||||||||||
| #include <aliceVision/sfm/pipeline/expanding/LocalizationValidationPolicyLegacy.hpp> | ||||||||||
|
|
||||||||||
| namespace aliceVision { | ||||||||||
| namespace sfm { | ||||||||||
|
|
@@ -116,5 +119,110 @@ IndexT findBestPair(const sfmData::SfMData & sfmData, | |||||||||
| return bestPair; | ||||||||||
| } | ||||||||||
|
|
||||||||||
| sfm::ReconstructedPair findBestPairFromTrackDepths(const sfmData::SfMData & sfmData, | ||||||||||
| const std::vector<sfm::ReconstructedPair> & pairs, | ||||||||||
| const track::TracksMap& tracksMap, | ||||||||||
| const track::TracksPerView & tracksPerView, | ||||||||||
| std::mt19937 & randomNumberGenerator) | ||||||||||
| { | ||||||||||
| //Create set of unique view ids | ||||||||||
| std::set<IndexT> views; | ||||||||||
| for (IndexT pairId = 0; pairId < pairs.size(); pairId++) | ||||||||||
| { | ||||||||||
| views.insert(pairs[pairId].reference); | ||||||||||
| views.insert(pairs[pairId].next); | ||||||||||
| } | ||||||||||
|
|
||||||||||
| sfm::ReconstructedPair bestPair; | ||||||||||
| bestPair.reference = UndefinedIndexT; | ||||||||||
| size_t bestCount = 0; | ||||||||||
|
|
||||||||||
| sfm::LocalizationValidationPolicy::uptr resectionValidationPolicy = std::make_unique<sfm::LocalizationValidationPolicyLegacy>(); | ||||||||||
|
|
||||||||||
| sfm::SfmResection resection; | ||||||||||
| resection.setMaxIterations(1024); | ||||||||||
| resection.setResectionMaxError(std::numeric_limits<double>::infinity()); | ||||||||||
|
||||||||||
| resection.setResectionMaxError(std::numeric_limits<double>::infinity()); | |
| // Use a reasonable finite reprojection error threshold (in pixels) instead of infinity. | |
| // Consider making this value configurable if needed. | |
| resection.setResectionMaxError(4.0); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
no, it's a problem with acransac, infinite value has some algotihmic meaning
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,82 @@ | ||
| // This file is part of the AliceVision project. | ||
| // Copyright (c) 2025 AliceVision contributors. | ||
| // This Source Code Form is subject to the terms of the Mozilla Public License, | ||
| // v. 2.0. If a copy of the MPL was not distributed with this file, | ||
| // You can obtain one at https://mozilla.org/MPL/2.0/. | ||
|
|
||
| #include <aliceVision/sfm/pipeline/bootstrapping/TracksDepths.hpp> | ||
|
|
||
| namespace aliceVision { | ||
| namespace sfm { | ||
|
|
||
| bool buildSfmDataFromDepthMap(sfmData::SfMData & output, | ||
| const sfmData::SfMData & sfmData, | ||
| const track::TracksMap& tracksMap, | ||
| const track::TracksPerView & tracksPerView, | ||
| IndexT viewId) | ||
| { | ||
| output.clear(); | ||
|
|
||
| const sfmData::View & view = sfmData.getView(viewId); | ||
| const camera::IntrinsicBase & intrinsic = sfmData.getIntrinsic(view.getIntrinsicId()); | ||
|
|
||
| if (tracksPerView.find(viewId) == tracksPerView.end()) | ||
| { | ||
| return false; | ||
| } | ||
|
|
||
| sfmData::Landmarks & landmarks = output.getLandmarks(); | ||
|
|
||
| //Copy all intrinsics, because it's light. | ||
| for (const auto & [intrinsicId, intrinsic] : sfmData.getIntrinsics()) | ||
| { | ||
| output.getIntrinsics().insert( | ||
| std::make_pair(intrinsicId, | ||
| camera::IntrinsicBase::sptr(intrinsic->clone())) | ||
| ); | ||
| } | ||
|
|
||
| std::set<IndexT> usedViewIds; | ||
| const auto & trackIds = tracksPerView.at(viewId); | ||
| for (const auto & trackId : trackIds) | ||
| { | ||
| const auto & track = tracksMap.at(trackId); | ||
| const auto & feat = track.featPerView.at(viewId); | ||
| const double & Z = feat.depth; | ||
|
|
||
| if (Z <= 0.0) | ||
| { | ||
| continue; | ||
| } | ||
|
|
||
| const Vec2 meters = intrinsic.removeDistortion(intrinsic.ima2cam(feat.coords.cast<double>())); | ||
|
|
||
| sfmData::Landmark & landmark = landmarks[trackId]; | ||
| landmark.X.x() = meters.x() * Z; | ||
| landmark.X.y() = meters.y() * Z; | ||
| landmark.X.z() = Z; | ||
|
|
||
| landmark.descType = track.descType; | ||
|
|
||
| for (const auto & [otherViewId, otherFeat] : track.featPerView) | ||
| { | ||
| usedViewIds.insert(otherViewId); | ||
| } | ||
| } | ||
|
|
||
| // Copy only used views | ||
| for (const auto & usedViewId : usedViewIds) | ||
| { | ||
| const auto & iview = sfmData.getViewSharedPtr(usedViewId); | ||
|
|
||
| output.getViews().insert( | ||
| std::make_pair(usedViewId, | ||
| sfmData::View::sptr(iview->clone())) | ||
| ); | ||
| } | ||
|
|
||
| return true; | ||
| } | ||
|
|
||
| } | ||
| } |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Using infinity for max error and 50000 iterations are magic numbers that should be defined as named constants or made configurable parameters for better maintainability.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
will do in another PR