Closed alexsmartens closed 7 years ago
I0617 19:11:18.600488 8882 reconstruction_builder.cc:360] Attempting to reconstruct 66 images from 0 two view matches.
That seems to be the problem -- for some reason there are zero two view matches to those 66 images? Can you verify that features were extracted and matched for those images?
I do not know, I though I was working with all the images at the same time. How can I check if the features were extracted and matched for those 66 images?
One way to check would be to go through all unestimated views and see if any tracks exist (estimated and unestimated) in the unestimated views. If tracks exist then this means that features were matched to these views.
Sorry for my question, but how can check the track existence in the unestimated views?
Assuming you have a reconstruction, it would be something like this. See the code and website for more documentation.
const auto& view_ids = my_reconstruction.ViewIds();
for (const theia::ViewId view_id : view_ids) {
const theia::View* view = my_reconstruction.View(view);
if (view != nullptr && !view->IsEstimated()) {
const auto& track_ids_in_view = view->TrackIds();
if (track_ids_in_view.size() > 0) {
LOG(INFO) << "Found " << track_ids_in_view.size() << " tracks in view " << view->Name();
}
}
}
Checked. There are no tracks exist in the unestimated views. What should be my next step?
Extract features (e.g., SIFT) from them and match them using theia's API. Another sanity check would be to create a fresh reconstruction from only those 66 images. So copy those images into a new directory and try to extract features, match, and build a reconstruction only from them. If it succeeds then you can be sure that the original model failed due to some bad parameters or input that you're providing.
I've done the overall reconstruction again. It resulted in 104 estimated views and 64 unestimated ones. Then, I run reconstruction on the 64 unestimated views, which gave me 48 estimated and 16 unestimated views. The resulting point cloud screenshot:
For reference, this is the initial point cloud screenshot:
My final reconstruction log:
I0620 19:31:01.707811 24578 trust_region_minimizer.cc:703] Terminating: Function tolerance reached. |cost_change|/cost: 9.980282e-07 <= 1.000000e-06
I0620 19:31:01.711112 24578 bundle_adjustment.cc:369]
Solver Summary (v 1.13.0-eigen-(3.3.3)-lapack-suitesparse-(4.4.6)-cxsparse-(3.1.4)-openmp)
Original Reduced
Parameter blocks 5788 5787
Parameters 23251 23244
Residual blocks 17845 17845
Residual 35690 35690
Minimizer TRUST_REGION
Dense linear algebra library EIGEN
Trust region strategy LEVENBERG_MARQUARDT
Given Used
Linear solver DENSE_SCHUR DENSE_SCHUR
Threads 3584 3584
Linear solver threads 3584 3584
Linear solver ordering 5739,1,48 5739,48
Schur structure 2,4,6 2,4,d
Use inner iterations True True
Inner iteration ordering 48,1,5739 48,5739
Cost:
Initial 1.263713e+05
Final 7.159127e+04
Change 5.478003e+04
Minimizer iterations 72
Successful steps 72
Unsuccessful steps 0
Steps with inner iterations 6
Time (in seconds):
Preprocessor 0.0558
Residual evaluation 0.9076
Jacobian evaluation 9.0950
Linear solver 2.5205
Inner iterations 0.7980
Minimizer 13.3867
Postprocessor 0.0007
Total 13.4432
Termination: CONVERGENCE (Function tolerance reached. |cost_change|/cost: 9.980282e-07 <= 1.000000e-06)
I0620 19:31:01.719916 24578 set_outlier_tracks_to_unestimated.cc:128] 474 points were removed because of bad reprojection errors. 409 points were removed because they had insufficient viewing angles and were poorly constrained.
I0620 19:31:01.720088 24578 global_reconstruction_estimator.cc:263] 883 outlier points were removed.
I0620 19:31:01.720667 24578 reconstruction_builder.cc:376]
Reconstruction estimation statistics:
Num estimated views = 48
Num input views = 64
Num estimated tracks = 4856
Num input tracks = 7831
Pose estimation time = 0.447588
Triangulation time = 0.279929
Bundle Adjustment time = 48.1864
Total time = 48.9259
Global Reconstruction Estimator timings:
Initial view graph filtering time = 4.4e-05
Camera intrinsic calibration time = 1e-05
Rotation estimation time = 0.297553
Rotation filtering time = 0.000451
Relative translation optimization time = 0.077738
Relative translation filtering time = 0.041033
Position estimation time = 0.030813
I0620 19:31:01.729934 24578 reconstruction_builder.cc:360] Attempting to reconstruct 16 images from 0 two view matches.
I0620 19:31:01.729950 24578 global_reconstruction_estimator.cc:152] Filtering the intial view graph.
I0620 19:31:01.729954 24578 global_reconstruction_estimator.cc:155] Insufficient view pairs to perform estimation.
I0620 19:31:01.732801 24578 build_reconstruction.cc:511] Writing reconstruction 0 to /home/alex/Downloads/libraries/TheiaSfM/test/theia-unestimated-views-1/images/1/reconstruction/-0
It seems to me, that the combination of these two point clouds is reasonable.
What do you think @sweeneychris ? What would you recommend to try next?
Looks reasonable to me. Maybe you just need to detect more features or loosen the matching criterion on the whole dataset when performing feature matching?
On Tue, Jun 20, 2017, 6:58 PM Alex Martens notifications@github.com wrote:
I've done the overall reconstruction again. It resulted in 104 estimated views and 64 unestimated ones. Then, I run reconstruction on the 64 unestimated views, which gave me 48 estimated and 16 unestimated views. The resulting point cloud screenshot:
[image: image] https://user-images.githubusercontent.com/26261714/27363200-4aedea80-55f0-11e7-85b9-0a1b205df368.png
For reference, this is the initial point cloud screenshot: [image: image] https://user-images.githubusercontent.com/26261714/27363488-22a3239a-55f2-11e7-9942-a9fbf15fae15.png
My final reconstruction log:
I0620 19:31:01.707811 24578 trust_region_minimizer.cc:703] Terminating: Function tolerance reached. |cost_change|/cost: 9.980282e-07 <= 1.000000e-06 I0620 19:31:01.711112 24578 bundle_adjustment.cc:369] Solver Summary (v 1.13.0-eigen-(3.3.3)-lapack-suitesparse-(4.4.6)-cxsparse-(3.1.4)-openmp)
Original Reduced
Parameter blocks 5788 5787 Parameters 23251 23244 Residual blocks 17845 17845 Residual 35690 35690
Minimizer TRUST_REGION
Dense linear algebra library EIGEN Trust region strategy LEVENBERG_MARQUARDT
Given Used
Linear solver DENSE_SCHUR DENSE_SCHUR Threads 3584 3584 Linear solver threads 3584 3584 Linear solver ordering 5739,1,48 5739,48 Schur structure 2,4,6 2,4,d Use inner iterations True True Inner iteration ordering 48,1,5739 48,5739
Cost: Initial 1.263713e+05 Final 7.159127e+04 Change 5.478003e+04
Minimizer iterations 72 Successful steps 72 Unsuccessful steps 0 Steps with inner iterations 6
Time (in seconds): Preprocessor 0.0558
Residual evaluation 0.9076 Jacobian evaluation 9.0950 Linear solver 2.5205 Inner iterations 0.7980 Minimizer 13.3867
Postprocessor 0.0007 Total 13.4432
Termination: CONVERGENCE (Function tolerance reached. |cost_change|/cost: 9.980282e-07 <= 1.000000e-06) I0620 19:31:01.719916 24578 set_outlier_tracks_to_unestimated.cc:128] 474 points were removed because of bad reprojection errors. 409 points were removed because they had insufficient viewing angles and were poorly constrained. I0620 19:31:01.720088 24578 global_reconstruction_estimator.cc:263] 883 outlier points were removed. I0620 19:31:01.720667 24578 reconstruction_builder.cc:376] Reconstruction estimation statistics: Num estimated views = 48 Num input views = 64 Num estimated tracks = 4856 Num input tracks = 7831 Pose estimation time = 0.447588 Triangulation time = 0.279929 Bundle Adjustment time = 48.1864 Total time = 48.9259
Global Reconstruction Estimator timings: Initial view graph filtering time = 4.4e-05 Camera intrinsic calibration time = 1e-05 Rotation estimation time = 0.297553 Rotation filtering time = 0.000451 Relative translation optimization time = 0.077738 Relative translation filtering time = 0.041033 Position estimation time = 0.030813 I0620 19:31:01.729934 24578 reconstruction_builder.cc:360] Attempting to reconstruct 16 images from 0 two view matches. I0620 19:31:01.729950 24578 global_reconstruction_estimator.cc:152] Filtering the intial view graph. I0620 19:31:01.729954 24578 global_reconstruction_estimator.cc:155] Insufficient view pairs to perform estimation. I0620 19:31:01.732801 24578 build_reconstruction.cc:511] Writing reconstruction 0 to /home/alex/Downloads/libraries/TheiaSfM/test/theia-unestimated-views-1/images/1/reconstruction/-0
It seems to me, that the combination of these two point clouds is reasonable.
What do you think @sweeneychris https://github.com/sweeneychris ?
— You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub https://github.com/sweeneychris/TheiaSfM/issues/159#issuecomment-309940672, or mute the thread https://github.com/notifications/unsubscribe-auth/AAwytsz8xM_UwMQDWLfO645ynobGJWCPks5sGHiwgaJpZM4N9YHB .
Do you mean increasing the feature density?
Changing feature_density
to DENSE
on the whole dataset resulted in 72 estimated views
Changing feature_density
to SPARSE
on the whole dataset resulted in 70 estimated views
What might be my next step?
So the normal setting reconstructs 102 views but the other settings only reconstruct 72-ish? That seems odd. More features should almost always give better results. Make sure you're not passing in a matches file as input or it will skip feature extraction and use the features present in the matches file
On Tue, Jun 20, 2017, 7:22 PM Alex Martens notifications@github.com wrote:
Do you mean increasing the features density?
Changing feature_density to DENSE resulted in 72 estimated views Changing feature_density to SPARSE resulted in 70 estimated views
What might be my next step?
— You are receiving this because you were mentioned.
Reply to this email directly, view it on GitHub https://github.com/sweeneychris/TheiaSfM/issues/159#issuecomment-309943996, or mute the thread https://github.com/notifications/unsubscribe-auth/AAwytsSNfkPdga9gZAoNyvNTQClH4LTdks5sGH5XgaJpZM4N9YHB .
I was not sure if I did clean reconstruction previous time, so I repeated the reconstructions with DENSE and SPARSE feature density.
Interestingly, DENSE reconstruction indicated 94 estimated views whereas SPARSE reconstruction employed 134 views.
The DENSE reconstruction looks pretty much the same as the initial image in this issue.
The SPARSE reconstruction is different, have a look at this image:
The overall camera poses coverage seems to be betters than previously, however there are two regions (highlighted in yellow) which are actually not relevant
This is usually an indication that it's having a hard time finding matches for those yellow areas, and so the geometric constraints are not very stable. Global SfM is typically a bit less robust than Incremental SfM for scenes like this, so I would try using the incremental pipeline. If you really want to stick with the global solver you can relax the BA filtering threshold.
It's still odd to me that the DENSE setting reconstructs fewer cameras. I'm not sure what to make of that... does your scene have repeating textures in it? I wonder if the matching quality somehow degrades when there are more features.
Increasing the BA filtering threshold to 10 did not help.
My scene does have similar structures, but they are not identical.
Did you try the incremental pipeline?
The incremental pipeline estimated 124 views. The views coverage is better than the one in the initial model. Here is a screenshot of the incremental reconstruction
@alexsmartens It may be that you're hitting to limit of the ability to reconstruct this scene then. My best advice to is to play around with the various thresholds and see if you can get it to fully connect. In the next 6 months or so I'll be adding a few new sfm pipelines to Theia so check back once those go up and maybe you'll have better success with them!
Hi Chris, I installed Theia and I am trying to work out a proper reconstruction. The "make test" successfully passed all the test. Then, I took your command line flags example build_reconstruction_flags.txt and run it with my data set.
Quick data set description: 168 1920x1080 photos around an object.
Soon after the visualisation of the results I realised that something went wrong with the reconstruction. It seems that some camera views were ignored, as the object is covered only form one side. The visualisation screenshot and my final reconstruction results are shown below
I am really curious why it happened and how I can improve the results. I am wondering if you have any suggestions for getting the full object coverage Should I change any reconstruction parameters? Anything else?