NeoGeographyToolkit / StereoPipeline

The NASA Ames Stereo Pipeline is a suite of automated geodesy & stereogrammetry tools designed for processing planetary imagery captured from orbiting and landed robotic explorers on other planets.
Apache License 2.0
478 stars 168 forks source link

`bundle_adjust` Error: Too few points remain after filtering! #398

Closed iamtekson closed 1 year ago

iamtekson commented 1 year ago

I am trying to process the KH-9 imagery by following the official documentation. I succeed to follow the cam_gen command. In the next step, I am trying to run the bundle_adjust command as below,

bundle_adjust for_small.tif aft_small.tif for_small.tsai aft_small.tsai -t opticalbar  \
--inline-adjustments  --camera-weight 0 --ip-detect-method 1 -o bundle_for_small/out --max-iterations 30 

Since I don't have any gcp, I removed the gcp related argument. I have increased the max-iterations to 1000 but still no luck.

Also, I have tried to follow the KH4B processing method as below,

bundle_adjust for_small.tif aft_small.tif for_small.tsai aft_small.tsai -t opticalbar --max-iterations 100   \
  --camera-weight 0                       \
  --tri-weight 0.1                        \
  --tri-robust-threshold 0.1              \
  --disable-tri-ip-filter                 \
  --skip-rough-homography                 \
  --inline-adjustments                    \
  --ip-detect-method 1                    \
  --datum WGS84                           \
  -o ba_small/run

In both case, it is generating the following error,

Termination: No_CONVERGENCE (Maximum number of interation reached. Number of iterations: 10000.)
Found a valid solution, but did not reach the actual minimum.
Error: Too few points remain after filtering!

Could anyone please suggest me how to run the bundle adjustment correctly? Thank you very much in advance!

oleg-alexandrov commented 1 year ago

That the max number of iterations is reached is not a problem. That too few points are left after filtering is a problem. I will suggest you examine your two images and see if they are similar. Then I wonder what other messages you get before that, such as how many interest point features are detected, how many are matched, how many are removed as outliers.

iamtekson commented 1 year ago

Yes, I manually checked, visualized with stereo_gui. The image are similar with each other (My imagery is attached below). Just wondering, do I need to manually crop the intersection area of both imagery or software is able to crop it?

image

I am sorry but I didn't find any interest point features, matched point in my log file. Could you please help me with what will be the best way to solve this issue? My full log of bundle_adjust is as below,

ASP 3.2.0
Build ID: 479ace01
Build date: 2023-01-01

/home/tek/Downloads/ASP/libexec/bundle_adjust for_small.tif aft_small.tif for_small.tsai aft_small.tsai -t opticalbar --max-iteration 1000 --camera-weight 0 --inline-adjustments --ip-detect-method 1 -o ba_small_v2/run 

uname -a
Linux vm2 5.19.0-41-generic #42~22.04.1-Ubuntu SMP PREEMPT_DYNAMIC Tue Apr 18 17:40:00 UTC 2 x86_64 x86_64 x86_64 GNU/Linux

cat /proc/meminfo 2>/dev/null | grep MemTotal
MemTotal:       16383036 kB

cat /proc/cpuinfo 2>/dev/null | tail -n 25
cpu family  : 6
model       : 154
model name  : 12th Gen Intel(R) Core(TM) i7-12800H
stepping    : 3
microcode   : 0xffffffff
cpu MHz     : 2803.200
cache size  : 24576 KB
physical id : 0
siblings    : 12
core id     : 11
cpu cores   : 12
apicid      : 11
initial apicid  : 11
fpu     : yes
fpu_exception   : yes
cpuid level : 22
wp      : yes
flags       : fpu vme de pse tsc msr pae mce cx8 apic sep mtrr pge mca cmov pat pse36 clflush mmx fxsr sse sse2 ht syscall nx rdtscp lm constant_tsc rep_good nopl xtopology nonstop_tsc cpuid tsc_known_freq pni pclmulqdq ssse3 cx16 pcid sse4_1 sse4_2 movbe popcnt aes rdrand hypervisor lahf_lm abm 3dnowprefetch invpcid_single ibrs_enhanced fsgsbase bmi1 bmi2 invpcid rdseed clflushopt md_clear flush_l1d arch_capabilities
bugs        : spectre_v1 spectre_v2 spec_store_bypass swapgs retbleed eibrs_pbrsb
bogomips    : 5606.40
clflush size    : 64
cache_alignment : 64
address sizes   : 46 bits physical, 48 bits virtual
power management:

sysctl -a hw 2>/dev/null | grep -E "ncpu|byteorder|memsize|cpufamily|cachesize|mmx|sse|machine|model" | grep -v ipv6

Vision Workbench log started at 2023-05-10 11:40:42.

2023-05-10 11:40:42 {0} [ console ] : Using session: opticalbar
2023-05-10 11:40:42 {0} [ console ] : Loading camera model: for_small.tif for_small.tsai
2023-05-10 11:40:42 {0} [ console ] : Using session: opticalbar
2023-05-10 11:40:42 {0} [ console ] : Loading camera model: aft_small.tif aft_small.tsai
2023-05-10 11:40:42 {0} [ console ] : Computing statistics for for_small.tif
2023-05-10 11:40:42 {0} [ console ] :   --> Reading statistics from file ba_small_v2/run-for_small-stats.tif
2023-05-10 11:40:42 {0} [ console ] :       for_small.tif: [ lo: 1 hi: 255 mean: 123.543 std_dev: 98.6429 ]
2023-05-10 11:40:42 {0} [ console ] : Computing statistics for aft_small.tif
2023-05-10 11:40:42 {0} [ console ] :   --> Reading statistics from file ba_small_v2/run-aft_small-stats.tif
2023-05-10 11:40:42 {0} [ console ] :       aft_small.tif: [ lo: 3 hi: 255 mean: 145.711 std_dev: 79.3695 ]
2023-05-10 11:40:42 {0} [ console ] :   --> Using cached match file: ba_small_v2/run-for_small__aft_small.match
2023-05-10 11:40:42 {0} [ console ] : Match file ba_small_v2/run-for_small__aft_small.match has 107 matches.
2023-05-10 11:40:42 {0} [ console ] : Loaded 107 matches.
2023-05-10 11:40:42 {0} [ console ] : Loading GCP files...
2023-05-10 11:40:42 {0} [ console ] : Loading input model: 
------------------------ Optical Bar Model -----------------------

 Image size:             Vector2(68531,35284)
 Center loc (pixels):    Vector2(34265.5,17642)
 Pixel size (m):         7e-06
 Focal length (m):       0.61
 Scan time (s):          0.5
 Scan rate (rad/s):      1.57282
 Forward tilt (rad):     -0.261799
 Initial position:       Vector3(3.42054e+06,3.09874e+06,4.52365e+06)
 Initial pose:           Vector3(1.41101,2.5822,0.328483)
 Speed:                  7700
 Mean earth radius:      6.371e+06
 Mean surface elevation: 4000
 Motion comp factor:     1
 Left to right scan:     0

------------------------------------------------------------------------

2023-05-10 11:40:42 {0} [ console ] : Loading input model: 
------------------------ Optical Bar Model -----------------------

 Image size:             Vector2(71159,35601)
 Center loc (pixels):    Vector2(35579.5,17800.5)
 Pixel size (m):         7e-06
 Focal length (m):       0.61
 Scan time (s):          0.5
 Scan rate (rad/s):      1.63313
 Forward tilt (rad):     -0.261799
 Initial position:       Vector3(3.36956e+06,3.07258e+06,4.57086e+06)
 Initial pose:           Vector3(1.40296,2.57292,0.355848)
 Speed:                  7700
 Mean earth radius:      6.371e+06
 Mean surface elevation: 4000
 Motion comp factor:     1
 Left to right scan:     0

------------------------------------------------------------------------

2023-05-10 11:40:42 {0} [ console ] : --> Bundle adjust pass: 0
2023-05-10 11:40:42 {0} [ console ] : Writing initial condition files.
2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_stats.txt
2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_raw_pixels.txt
2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_raw_gcp.txt
2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_raw_cameras.txt
2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_pointmap.csv
2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_points.kml
2023-05-10 11:40:42 {0} [ console ] : Starting the Ceres optimizer.
2023-05-10 11:41:51 {0} [ console ] : 
Solver Summary (v 1.14.0-eigen-(3.4.0)-lapack-suitesparse-(5.10.1)-cxsparse-(3.2.0)-eigensparse-openmp-no_tbb)

                                     Original                  Reduced
Parameter blocks                           99                       96
Parameters                                300                      294
Residual blocks                           188                      188
Residuals                                 376                      376

Minimizer                        TRUST_REGION

Dense linear algebra library            EIGEN
Trust region strategy     LEVENBERG_MARQUARDT

                                        Given                     Used
Linear solver                     DENSE_SCHUR              DENSE_SCHUR
Threads                                     4                        4
Linear solver ordering              AUTOMATIC                     94,2
Schur structure                         2,3,6                    2,3,6

Cost:
Initial                          2.163675e+02
Final                            1.043402e+02
Change                           1.120273e+02

Minimizer iterations                     1001
Successful steps                          826
Unsuccessful steps                        175

Time (in seconds):
Preprocessor                         0.000181

  Residual only evaluation           3.471152 (989)
  Jacobian & residual evaluation    60.945499 (826)
  Linear solver                      3.244038 (1000)
Minimizer                           68.589823

Postprocessor                        0.000020
Total                               68.590024

Termination:                   NO_CONVERGENCE (Maximum number of iterations reached. Number of iterations: 1000.)

2023-05-10 11:41:51 {0} [ console ] : Found a valid solution, but did not reach the actual minimum.
2023-05-10 11:41:51 {0} [ console ] : Writing final condition log files.
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_stats.txt
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_raw_pixels.txt
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_raw_gcp.txt
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_raw_cameras.txt
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_pointmap.csv
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_points.kml
2023-05-10 11:41:51 {0} [ console ] : Removing pixel outliers in preparation for another solver attempt.
2023-05-10 11:41:51 {0} [ console ] : Outlier statistics: b = -90.1605, e = 144.511.
2023-05-10 11:41:51 {0} [ console ] : Removing as outliers points with mean reprojection error > 3.
2023-05-10 11:41:51 {0} [ console ] : Removed 79 outliers out of 188 by reprojection error. Ratio: 0.420213.
2023-05-10 11:41:51 {0} [ console ] : Removed 0 outlier(s) based on spatial distribution of triangulated points.
2023-05-10 11:41:51 {0} [ console ] : IP coverage fraction after cleaning = 0
2023-05-10 11:41:51 {0} [ console ] : Saving 15 filtered interest points.
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-for_small__aft_small-clean.match
2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-convergence_angles.txt
2023-05-10 11:41:51 {0} [ console ] : Error: Too few points remain after filtering!.
oleg-alexandrov commented 1 year ago

This is a repeated run, and it does not show how matches were created. That you have so few of them, just 107, given that the image size is 71159 x 35601 pixels, shows that matching did not work so well.

You may want to completely delete the output directory, ba_small_v2, restart, and see what it says about the number of detected and matched interest points. Then you can use stereo_gui to plot the ba_small_v2, restart/run-for_small__aft_small.match match file, which will have matches after the filtering.

There's no need to do any cropping. The tool should be able to handle the data as it is.

You can also try a separate run with --ip-per-image 200000 and see if there's anything different.

On Wed, May 10, 2023 at 11:55 AM Tek Kshetri @.***> wrote:

Yes, I manually checked, visualized with stereo_gui. The image are similar with each other (My imagery is attached below). Just wondering, do I need to manually crop the intersection area of both imagery or software is able to crop it?

[image: image] https://user-images.githubusercontent.com/39838116/237487618-6d0db182-9a32-46a2-a746-6105e75f2fcd.png

I am sorry but I didn't find any interest point features, matched point in my log file. Could you please help me with what will be the best way to solve this issue? My full log of bundle_adjust is as below,

ASP 3.2.0 Build ID: 479ace01 Build date: 2023-01-01

/home/tek/Downloads/ASP/libexec/bundle_adjust for_small.tif aft_small.tif for_small.tsai aft_small.tsai -t opticalbar --max-iteration 1000 --camera-weight 0 --inline-adjustments --ip-detect-method 1 -o ba_small_v2/run

uname -a Linux vm2 5.19.0-41-generic #42~22.04.1-Ubuntu SMP PREEMPT_DYNAMIC Tue Apr 18 17:40:00 UTC 2 x86_64 x86_64 x86_64 GNU/Linux

cat /proc/meminfo 2>/dev/null | grep MemTotal MemTotal: 16383036 kB

cat /proc/cpuinfo 2>/dev/null | tail -n 25 cpu family : 6 model : 154 model name : 12th Gen Intel(R) Core(TM) i7-12800H stepping : 3 microcode : 0xffffffff cpu MHz : 2803.200 cache size : 24576 KB physical id : 0 siblings : 12 core id : 11 cpu cores : 12 apicid : 11 initial apicid : 11 fpu : yes fpu_exception : yes cpuid level : 22 wp : yes flags : fpu vme de pse tsc msr pae mce cx8 apic sep mtrr pge mca cmov pat pse36 clflush mmx fxsr sse sse2 ht syscall nx rdtscp lm constant_tsc rep_good nopl xtopology nonstop_tsc cpuid tsc_known_freq pni pclmulqdq ssse3 cx16 pcid sse4_1 sse4_2 movbe popcnt aes rdrand hypervisor lahf_lm abm 3dnowprefetch invpcid_single ibrs_enhanced fsgsbase bmi1 bmi2 invpcid rdseed clflushopt md_clear flush_l1d arch_capabilities bugs : spectre_v1 spectre_v2 spec_store_bypass swapgs retbleed eibrs_pbrsb bogomips : 5606.40 clflush size : 64 cache_alignment : 64 address sizes : 46 bits physical, 48 bits virtual power management:

sysctl -a hw 2>/dev/null | grep -E "ncpu|byteorder|memsize|cpufamily|cachesize|mmx|sse|machine|model" | grep -v ipv6

Vision Workbench log started at 2023-05-10 11:40:42.

2023-05-10 11:40:42 {0} [ console ] : Using session: opticalbar 2023-05-10 11:40:42 {0} [ console ] : Loading camera model: for_small.tif for_small.tsai 2023-05-10 11:40:42 {0} [ console ] : Using session: opticalbar 2023-05-10 11:40:42 {0} [ console ] : Loading camera model: aft_small.tif aft_small.tsai 2023-05-10 11:40:42 {0} [ console ] : Computing statistics for for_small.tif 2023-05-10 11:40:42 {0} [ console ] : --> Reading statistics from file ba_small_v2/run-for_small-stats.tif 2023-05-10 11:40:42 {0} [ console ] : for_small.tif: [ lo: 1 hi: 255 mean: 123.543 std_dev: 98.6429 ] 2023-05-10 11:40:42 {0} [ console ] : Computing statistics for aft_small.tif 2023-05-10 11:40:42 {0} [ console ] : --> Reading statistics from file ba_small_v2/run-aft_small-stats.tif 2023-05-10 11:40:42 {0} [ console ] : aft_small.tif: [ lo: 3 hi: 255 mean: 145.711 std_dev: 79.3695 ] 2023-05-10 11:40:42 {0} [ console ] : --> Using cached match file: ba_small_v2/run-for_smallaft_small.match 2023-05-10 11:40:42 {0} [ console ] : Match file ba_small_v2/run-for_smallaft_small.match has 107 matches. 2023-05-10 11:40:42 {0} [ console ] : Loaded 107 matches. 2023-05-10 11:40:42 {0} [ console ] : Loading GCP files... 2023-05-10 11:40:42 {0} [ console ] : Loading input model: ------------------------ Optical Bar Model -----------------------

Image size: Vector2(68531,35284) Center loc (pixels): Vector2(34265.5,17642) Pixel size (m): 7e-06 Focal length (m): 0.61 Scan time (s): 0.5 Scan rate (rad/s): 1.57282 Forward tilt (rad): -0.261799 Initial position: Vector3(3.42054e+06,3.09874e+06,4.52365e+06) Initial pose: Vector3(1.41101,2.5822,0.328483) Speed: 7700 Mean earth radius: 6.371e+06 Mean surface elevation: 4000 Motion comp factor: 1 Left to right scan: 0


2023-05-10 11:40:42 {0} [ console ] : Loading input model: ------------------------ Optical Bar Model -----------------------

Image size: Vector2(71159,35601) Center loc (pixels): Vector2(35579.5,17800.5) Pixel size (m): 7e-06 Focal length (m): 0.61 Scan time (s): 0.5 Scan rate (rad/s): 1.63313 Forward tilt (rad): -0.261799 Initial position: Vector3(3.36956e+06,3.07258e+06,4.57086e+06) Initial pose: Vector3(1.40296,2.57292,0.355848) Speed: 7700 Mean earth radius: 6.371e+06 Mean surface elevation: 4000 Motion comp factor: 1 Left to right scan: 0


2023-05-10 11:40:42 {0} [ console ] : --> Bundle adjust pass: 0 2023-05-10 11:40:42 {0} [ console ] : Writing initial condition files. 2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_stats.txt 2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_raw_pixels.txt 2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_raw_gcp.txt 2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_raw_cameras.txt 2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_residuals_pointmap.csv 2023-05-10 11:40:42 {0} [ console ] : Writing: ba_small_v2/run-initial_points.kml 2023-05-10 11:40:42 {0} [ console ] : Starting the Ceres optimizer. 2023-05-10 11:41:51 {0} [ console ] : Solver Summary (v 1.14.0-eigen-(3.4.0)-lapack-suitesparse-(5.10.1)-cxsparse-(3.2.0)-eigensparse-openmp-no_tbb)

                                 Original                  Reduced

Parameter blocks 99 96 Parameters 300 294 Residual blocks 188 188 Residuals 376 376

Minimizer TRUST_REGION

Dense linear algebra library EIGEN Trust region strategy LEVENBERG_MARQUARDT

                                    Given                     Used

Linear solver DENSE_SCHUR DENSE_SCHUR Threads 4 4 Linear solver ordering AUTOMATIC 94,2 Schur structure 2,3,6 2,3,6

Cost: Initial 2.163675e+02 Final 1.043402e+02 Change 1.120273e+02

Minimizer iterations 1001 Successful steps 826 Unsuccessful steps 175

Time (in seconds): Preprocessor 0.000181

Residual only evaluation 3.471152 (989) Jacobian & residual evaluation 60.945499 (826) Linear solver 3.244038 (1000) Minimizer 68.589823

Postprocessor 0.000020 Total 68.590024

Termination: NO_CONVERGENCE (Maximum number of iterations reached. Number of iterations: 1000.)

2023-05-10 11:41:51 {0} [ console ] : Found a valid solution, but did not reach the actual minimum. 2023-05-10 11:41:51 {0} [ console ] : Writing final condition log files. 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_stats.txt 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_raw_pixels.txt 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_raw_gcp.txt 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_raw_cameras.txt 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_residuals_pointmap.csv 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-final_points.kml 2023-05-10 11:41:51 {0} [ console ] : Removing pixel outliers in preparation for another solver attempt. 2023-05-10 11:41:51 {0} [ console ] : Outlier statistics: b = -90.1605, e = 144.511. 2023-05-10 11:41:51 {0} [ console ] : Removing as outliers points with mean reprojection error > 3. 2023-05-10 11:41:51 {0} [ console ] : Removed 79 outliers out of 188 by reprojection error. Ratio: 0.420213. 2023-05-10 11:41:51 {0} [ console ] : Removed 0 outlier(s) based on spatial distribution of triangulated points. 2023-05-10 11:41:51 {0} [ console ] : IP coverage fraction after cleaning = 0 2023-05-10 11:41:51 {0} [ console ] : Saving 15 filtered interest points. 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-for_small__aft_small-clean.match 2023-05-10 11:41:51 {0} [ console ] : Writing: ba_small_v2/run-convergence_angles.txt 2023-05-10 11:41:51 {0} [ console ] : Error: Too few points remain after filtering!.

— Reply to this email directly, view it on GitHub https://github.com/NeoGeographyToolkit/StereoPipeline/issues/398#issuecomment-1542658418, or unsubscribe https://github.com/notifications/unsubscribe-auth/AAKDU3HWASKDMA4ECF2JHRTXFPQA3ANCNFSM6AAAAAAX5BXHQU . You are receiving this because you commented.Message ID: @.***>

iamtekson commented 1 year ago

Thank you very much. The --ip-per-image 200000 run successfully. But still, I am getting the wrong image match, all points within the small region as below,

stereo_gui image matching

iamtekson commented 1 year ago

I just noticed that, I loaded the different imagery for the match point. I will give a update after correcting the issue from myside.

oleg-alexandrov commented 1 year ago

This is weird. Are you showing the .match file or the clean.match file? The clean one has only inliers, and if the cameras are really messed up, the wrong points will ber shown as inliers and outliers. So, one should check the original .match file first.

You can also try to use bundle_adjust with the --no-datum option (after wiping the existing directory, or doing things with a new output prefix). This option makes the interest point matching not dependent on input cameras, which may not be correct here. Then you can again examine the .match file.

iamtekson commented 1 year ago

I just noticed that, I loaded the different imagery for the match point. I will give a update after correcting the issue from myside.

The points are all over the image but they are not matching with each other as below,

stereo image match points

You can also try to use bundle_adjust with the --no-datum option (after wiping the existing directory, or doing things with a new output prefix). This option makes the interest point matching not dependent on input cameras, which may not be correct here. Then you can again examine the .match file.

--no-datum works perfectly. It is perfectly matching the left image with right one as below. Do you suggest any possible way to process the imagery without datum and create the DEM?

stereo match without datum

oleg-alexandrov commented 1 year ago

The reason --no-datum was likely necessary is because the cameras were messed up. You can use this option in parallel_stereo too, after bundle adjustment, and it will work just fine. The datum is only an auxiliary helper, and things work just fine without it.

In bundle adjustment I suggest you use --camera-weight 0 --tri-weight 0.1 to ensure that the cameras don't move too much during optimization.

After you do bundle adjustment, you may want to examine the clean match file too, to see if a lot of data is thrown out.

Then, in stereo you can use --clean-match-file prefix to reuse the already made clean match file if it looks nice (and as before, --no-datum).

This will likely result in some kind of DEM. You can also overlay L.tif and R.tif in the output directory to see if they are aligned well.

There's a chance the DEM will have gross distortions at end points, and maybe even funny orientation, but that's because, as before, the camera parameters are not known well.

adehecq commented 1 year ago

Hi Tek, Looking at your very first message, I see that you used the option "-t opticalbar". The data that you show is from the KH-9 MC camera, which is a frame camera. You should use the option "-t nadirpinhole" instead. I think that's the reason bundle_adjust was unable to find appropriate matches, because it iteratively reject matches that have large reprojections errors. Since your camera model is probably very wrong, your matches get all filtered.

As Oleg suggested, a good check is to run ipfind and ipmatch separately, outside of bundle_adjust. The last results you show are very reasonable. If you pass those to bundle_adjust, it should be able to handle the few outliers you have during the iteration. What you need to do is check the clean match file as mentioned by Oleg.

iamtekson commented 1 year ago

Hi @adehecq, Thank you very much for your response. It would be really nice if we could manage to add at least the one pair of stereo pair processing in the documentation. I will be really happy to contribute if you guide me a bit.