diff --git a/2024_04_16_15_23_29_545171_aggregated_results_table.tsv b/2024_04_16_15_23_29_545171_aggregated_results_table.tsv deleted file mode 100644 index 9df39bbea..000000000 --- a/2024_04_16_15_23_29_545171_aggregated_results_table.tsv +++ /dev/null @@ -1,14 +0,0 @@ -method_name retriever_num input images retriever_num retrieved image pairs retriever_retriever duration sec isp_rot3 angular errors deg isp_trans angular errors deg isp_pose errors deg isp_total correspondence generation duration sec isp_total two view estimation duration sec vg_num input measurements vg_num inlier measurements vg_num outlier measurements vg_inlier R angular errors deg vg_inlier U angular errors deg ra_rotation angle error deg ra_total duration sec ta_relative translation angle error deg ta_translation angle error deg ta_total duration sec ta_outlier rejection duration sec ta_optimization duration sec da_triangulation runtime sec da_gtsfm data creation runtime da_total duration sec ba_number cameras ba_number tracks filtered ba_3d track lengths filtered ba_reprojection errors filtered px ba_rotation angle error deg ba_relative translation angle error deg ba_translation angle error deg ba_pose auc @1 deg ba_pose auc @2.5 deg ba_pose auc @5 deg ba_pose auc @10 deg ba_pose auc @20 deg ba_step 0 run duration sec ba_step 1 run duration sec ba_step 2 run duration sec ba_total run duration sec total_total runtime sec -20240416_004547__courtyard__results__num_matched5__maxframelookahead10__760p__unified_roma 38 345 9.44866 0.2 / 31.0 0.6 / 39.3 0.6 / 48.0 493.75 163.411 298 226 72 0.1 / 13.2 0.2 / 22.4 15.2 / 12.9 0.0252783 0.6 / 25.4 19.0 / 20.8 5.05006 3.86895 0.0685906 140.763 44.3316 185.094 37 6900 3.0 / 3.0 0.1 / 0.1 14.6 / 11.9 27.0 / 43.1 18.3 / 19.3 41.0557 43.2644 44.0006 44.3687 45.9586 2.67318 2.63082 2.63482 7.93893 899.102 -20240416_004547__delivery_area__results__num_matched5__maxframelookahead10__760p__unified_roma 44 403 10.2997 0.0 / 11.0 0.1 / 19.6 0.1 / 22.5 494.36 160.752 240 227 13 0.0 / 0.3 0.0 / 4.3 0.0 / 0.0 0.0196939 0.1 / 3.8 0.3 / 19.6 5.3495 3.89795 0.233811 165.776 52.6731 218.449 23 8485 3.0 / 3.0 0.1 / 0.1 0.0 / 0.0 0.0 / 0.1 0.0 / 0.0 51.0069 51.7664 52.0196 52.1461 52.2094 2.19856 2.1621 2.16313 6.5239 932.65 -20240416_004547__electro__results__num_matched5__maxframelookahead10__760p__unified_roma 45 455 10.0224 0.3 / 36.0 0.7 / 39.5 0.7 / 53.2 511.963 158.641 222 206 16 0.1 / 12.6 0.1 / 20.0 0.1 / 0.3 0.0307453 1.9 / 22.3 6.3 / 25.5 6.62227 5.49328 0.0503752 142.055 46.3129 188.367 44 5649 3.0 / 3.0 0.2 / 0.3 0.4 / 2.3 10.0 / 29.9 0.7 / 15.8 37.4668 46.9867 51.1734 55.1233 60.2327 1.37807 1.34478 1.34654 4.0695 915.303 -20240416_004547__facade__results__num_matched5__maxframelookahead10__760p__unified_roma 76 773 17.5648 0.1 / 17.0 0.1 / 18.5 0.1 / 25.0 1722.26 471.251 666 625 41 0.1 / 8.4 0.1 / 9.4 0.1 / 0.2 0.493123 0.2 / 14.8 1.4 / 23.2 33.4941 29.8558 0.179274 429.65 135.909 565.558 65 49028 3.0 / 3.0 0.1 / 0.1 0.0 / 0.0 0.1 / 0.1 0.0 / 0.1 80.8406 83.652 84.5892 85.0577 85.292 16.1126 16.0062 16.0489 48.1678 2964.72 -20240416_004547__kicker__results__num_matched5__maxframelookahead10__760p__unified_roma 31 279 8.55726 0.1 / 18.8 0.2 / 19.2 0.2 / 24.5 321.093 100.671 197 180 17 0.1 / 0.4 0.1 / 1.4 0.1 / 0.1 0.0139537 0.1 / 0.4 0.1 / 0.4 3.93062 2.97383 0.064934 101.531 30.9511 132.482 30 13196 3.0 / 3.0 0.1 / 0.2 0.0 / 0.0 0.1 / 0.1 0.1 / 0.1 91.1637 94.53 95.6521 96.2131 96.4937 4.2303 4.21019 4.20041 12.641 614.053 -20240416_004547__meadow__results__num_matched5__maxframelookahead10__760p__unified_roma 15 97 5.20897 0.6 / 8.1 0.6 / 38.6 0.9 / 40.8 78.3462 26.3383 79 74 5 0.2 / 0.9 0.3 / 28.9 0.2 / 0.2 0.00432038 2.5 / 49.4 0.1 / 47.0 1.15836 0.840095 0.0494051 23.2848 6.69554 29.9803 15 962 3.0 / 3.0 0.1 / 0.2 0.2 / 1.1 15.1 / 60.6 0.2 / 48.1 53.5546 57.4218 58.7109 59.3555 59.6777 0.190173 0.194745 0.189607 0.574641 155.577 -20240416_004547__office__results__num_matched5__maxframelookahead10__760p__unified_roma 26 215 6.61806 0.2 / 35.6 1.1 / 28.2 1.1 / 42.8 197.151 60.0505 128 104 24 0.1 / 3.9 0.2 / 5.9 0.3 / 0.7 0.0223935 0.3 / 2.8 0.2 / 0.8 2.52123 1.95309 0.04357 57.6012 18.1926 75.7938 23 8644 3.0 / 3.0 0.2 / 0.2 0.0 / 0.1 0.3 / 1.1 0.1 / 0.2 74.3359 82.3489 85.4052 86.9334 87.6975 1.70421 1.74814 1.72095 5.17341 372.094 -20240416_004547__pipes__results__num_matched5__maxframelookahead10__760p__unified_roma 14 85 4.42346 0.1 / 9.1 0.2 / 9.7 0.2 / 11.6 92.1008 33.9374 60 60 0 0.1 / 0.5 0.1 / 1.2 0.1 / 0.2 0.00335836 0.4 / 0.8 0.5 / 0.6 1.01958 0.683143 0.0102017 40.6181 12.696 53.3141 14 3992 3.0 / 3.0 0.2 / 0.2 0.0 / 0.0 0.1 / 0.2 0.1 / 0.1 90.2901 96.1161 98.058 99.029 99.5145 0.988264 0.988888 0.98982 2.96707 202.585 -20240416_004547__playground__results__num_matched5__maxframelookahead10__760p__unified_roma 38 373 9.73473 0.2 / 42.5 0.4 / 44.5 0.4 / 54.6 349.129 110.4 134 127 7 0.1 / 7.0 0.1 / 5.9 0.7 / 0.7 0.0130603 0.2 / 4.4 4.2 / 10.9 3.72444 3.04102 0.0341258 71.1993 22.6006 93.7998 36 3725 3.0 / 3.0 0.1 / 0.2 0.1 / 0.3 0.5 / 2.4 0.4 / 1.2 47.6056 54.9145 72.6307 83.6838 89.2103 2.78801 2.77861 2.76931 8.33603 605.099 -20240416_004547__relief_2__results__num_matched5__maxframelookahead10__760p__unified_roma 31 259 7.75481 0.0 / 21.4 0.1 / 18.5 0.1 / 26.4 346.515 118.075 193 176 17 0.0 / 0.7 0.0 / 0.6 0.0 / 0.0 0.0136645 0.1 / 0.1 0.1 / 0.3 3.07725 2.25982 0.0468502 135.938 43.2887 179.226 31 10484 3.0 / 3.0 0.1 / 0.1 0.0 / 0.0 0.0 / 0.1 0.0 / 0.0 97.2168 98.8867 99.4434 99.7217 99.8608 1.55964 1.54169 1.51918 4.62062 691.094 -20240416_004547__relief__results__num_matched5__maxframelookahead10__760p__unified_roma 31 257 7.61716 0.0 / 16.6 0.1 / 12.6 0.1 / 18.6 437.565 136.912 221 204 17 0.0 / 0.6 0.0 / 0.3 0.0 / 0.1 0.0141704 0.1 / 0.1 0.1 / 0.2 3.35229 2.22128 0.0959258 160.809 51.1086 211.918 31 15490 3.0 / 3.0 0.1 / 0.2 0.0 / 0.0 0.0 / 0.1 0.0 / 0.0 95.8998 98.3599 99.18 99.59 99.795 4.49505 4.46932 4.48687 13.4514 846.669 -20240416_004547__terrace__results__num_matched5__maxframelookahead10__760p__unified_roma 23 184 6.06359 0.1 / 7.9 0.1 / 8.8 0.1 / 11.3 283.782 96.0394 150 150 0 0.1 / 0.4 0.1 / 3.3 0.0 / 0.0 0.0146356 0.3 / 2.9 0.4 / 1.7 2.07133 1.27944 0.0190086 116.176 36.2103 152.387 23 8520 3.0 / 3.0 0.1 / 0.1 0.0 / 0.1 0.1 / 0.1 0.0 / 0.0 94.7723 97.9089 98.9545 99.4772 99.7386 1.55409 1.54158 1.58617 4.68193 570.515 -20240416_004547__terrains__results__num_matched5__maxframelookahead10__760p__unified_roma 42 380 9.61873 0.1 / 16.9 0.1 / 13.7 0.2 / 19.9 475.688 156.934 264 263 1 0.1 / 1.7 0.1 / 1.4 0.1 / 0.1 0.0242808 0.1 / 1.2 0.3 / 30.7 5.87948 4.64931 0.0240877 174.321 55.1503 229.472 30 19874 3.0 / 3.0 0.1 / 0.2 0.0 / 0.0 0.1 / 0.1 0.1 / 0.1 66.0743 69.2869 70.3577 70.8931 71.1609 4.6866 4.79851 4.58799 14.0732 935.745 \ No newline at end of file diff --git a/2024_04_18_18_10_46_790577_aggregated_results_table.tsv b/2024_04_18_18_10_46_790577_aggregated_results_table.tsv deleted file mode 100644 index 1a75c2184..000000000 --- a/2024_04_18_18_10_46_790577_aggregated_results_table.tsv +++ /dev/null @@ -1,14 +0,0 @@ -method_name retriever_num input images retriever_num retrieved image pairs retriever_retriever duration sec isp_rot3 angular errors deg isp_trans angular errors deg isp_pose errors deg isp_total correspondence generation duration sec isp_total two view estimation duration sec vg_num input measurements vg_num inlier measurements vg_num outlier measurements vg_inlier R angular errors deg vg_inlier U angular errors deg ra_rotation angle error deg ra_total duration sec ta_relative translation angle error deg ta_translation angle error deg ta_total duration sec ta_outlier rejection duration sec ta_optimization duration sec da_triangulation runtime sec da_gtsfm data creation runtime da_total duration sec ba_number cameras ba_number tracks filtered ba_3d track lengths filtered ba_reprojection errors filtered px ba_rotation angle error deg ba_relative translation angle error deg ba_translation angle error deg ba_pose auc @1 deg ba_pose auc @2.5 deg ba_pose auc @5 deg ba_pose auc @10 deg ba_pose auc @20 deg ba_step 0 run duration sec ba_step 1 run duration sec ba_step 2 run duration sec ba_total run duration sec total_total runtime sec -20240416_103326__courtyard__results__num_matched5__maxframelookahead10__760p__unified_roma 38 345 9.20293 0.2 / 32.4 0.6 / 41.7 0.6 / 50.8 486.481 162.026 301 222 79 0.1 / 14.8 0.2 / 24.3 18.0 / 14.0 0.0275073 0.6 / 32.0 66.9 / 64.9 4.93689 3.6123 0.153725 132.026 40.8668 172.893 35 18124 3.0 / 3.1 0.1 / 0.2 6.6 / 13.4 47.0 / 54.0 22.3 / 60.5 40.4507 43.0224 43.8796 44.3082 44.5225 35.4314 35.2939 35.3373 106.063 983.363 -20240416_103326__delivery_area__results__num_matched5__maxframelookahead10__760p__unified_roma 44 403 10.0701 0.0 / 11.7 0.1 / 19.0 0.1 / 22.6 488.682 159.72 238 227 11 0.0 / 0.2 0.0 / 2.9 0.0 / 0.0 0.020071 0.1 / 0.5 0.2 / 3.8 5.38677 4.04836 0.0462282 165.964 51.3521 217.317 40 38543 3.0 / 3.1 0.1 / 0.2 0.0 / 0.0 0.2 / 5.2 0.0 / 3.3 54.539 58.2242 62.8556 69.7916 77.2567 14.5634 14.543 14.7327 43.8391 984.273 -20240416_103326__electro__results__num_matched5__maxframelookahead10__760p__unified_roma 45 455 10.4498 0.2 / 38.1 0.6 / 39.6 0.7 / 53.4 514.838 161.194 217 200 17 0.1 / 8.5 0.1 / 18.2 0.1 / 0.2 0.0199475 2.0 / 19.8 7.3 / 24.1 6.30028 5.01225 0.0304451 133.057 42.1093 175.166 38 9891 3.0 / 3.0 0.2 / 0.3 1.0 / 0.8 3.1 / 18.8 2.0 / 13.6 31.984 37.8228 42.8348 47.6747 52.216 6.50224 6.57126 6.59284 19.6664 925.725 -20240416_103326__facade__results__num_matched5__maxframelookahead10__760p__unified_roma 76 773 18.1791 0.1 / 16.7 0.1 / 18.5 0.1 / 25.0 1688.87 458.14 664 624 40 0.1 / 8.1 0.1 / 10.0 0.1 / 0.1 0.251827 0.2 / 17.5 0.9 / 25.5 33.4839 29.4754 0.141789 421.243 128.562 549.805 72 127841 3.0 / 3.2 0.1 / 0.2 0.0 / 1.4 0.1 / 31.0 0.1 / 18.7 76.8899 81.1804 82.6954 83.453 83.8318 122.19 121.763 122.573 366.526 3292.26 -20240416_103326__kicker__results__num_matched5__maxframelookahead10__760p__unified_roma 31 279 8.3917 0.1 / 17.8 0.2 / 20.0 0.2 / 24.3 316.232 98.5586 200 180 20 0.1 / 0.4 0.1 / 1.0 0.1 / 0.1 0.0137243 0.1 / 0.2 0.1 / 0.1 3.44338 2.5123 0.0159268 99.1452 30.069 129.214 31 32147 3.0 / 3.2 0.2 / 0.3 0.0 / 0.0 0.0 / 0.1 0.0 / 0.0 95.7028 98.2811 99.1406 99.5703 99.7851 14.7541 14.8502 14.6749 44.2793 647.542 -20240416_103326__meadow__results__num_matched5__maxframelookahead10__760p__unified_roma 15 97 5.1929 0.5 / 6.9 0.7 / 37.4 0.8 / 39.4 77.2786 26.8852 80 75 5 0.3 / 0.9 0.3 / 32.6 0.2 / 0.3 0.0049777 1.9 / 39.2 0.4 / 29.7 1.12925 0.845879 0.0246818 21.5873 5.97621 27.5635 15 2762 3.0 / 3.1 0.2 / 0.3 0.0 / 5.6 37.3 / 50.8 0.0 / 31.2 64.1703 65.6681 66.1674 66.417 66.5418 0.983979 0.978882 0.979037 2.94199 156.154 -20240416_103326__office__results__num_matched5__maxframelookahead10__760p__unified_roma 26 215 6.48896 0.2 / 37.3 1.1 / 28.7 1.1 / 44.8 193.798 58.1945 124 103 21 0.1 / 3.8 0.3 / 5.5 0.1 / 0.2 0.0121009 0.5 / 1.5 0.2 / 0.5 2.15212 1.49374 0.0981746 55.3205 16.7843 72.1049 23 18089 3.0 / 3.2 0.2 / 0.3 0.0 / 0.1 0.3 / 0.9 0.0 / 0.1 77.0209 83.8853 86.1734 87.3175 87.8895 5.36109 5.38842 5.35582 16.1055 379.864 -20240416_103326__pipes__results__num_matched5__maxframelookahead10__760p__unified_roma 14 85 4.64939 0.1 / 7.4 0.2 / 7.3 0.2 / 9.6 91.2199 32.9956 61 61 0 0.1 / 0.5 0.1 / 1.7 0.1 / 0.1 0.00340295 0.3 / 0.4 0.4 / 0.3 1.13503 0.783081 0.00643539 38.5851 11.3952 49.9803 14 8798 3.0 / 3.1 0.2 / 0.3 0.0 / 0.0 0.1 / 0.1 0.1 / 0.1 91.282 96.5128 98.2564 99.1282 99.5641 2.39397 2.37497 2.37218 7.14122 204.284 -20240416_103326__playground__results__num_matched5__maxframelookahead10__760p__unified_roma 38 373 9.3676 0.3 / 46.8 0.6 / 46.9 0.6 / 59.2 344.451 108.921 134 124 10 0.1 / 8.5 0.1 / 8.5 36.1 / 35.2 0.0290785 0.2 / 7.1 39.8 / 46.7 3.9318 3.26451 0.0569804 69.9189 20.8763 90.7951 19 3269 3.0 / 3.0 0.2 / 0.3 0.2 / 5.9 0.2 / 8.5 0.1 / 1.7 39.4063 44.1836 45.776 46.5722 46.9703 0.634949 0.613172 0.598575 1.8468 587.978 -20240416_103326__relief_2__results__num_matched5__maxframelookahead10__760p__unified_roma 31 259 7.32952 0.0 / 21.4 0.1 / 16.9 0.1 / 25.9 343.992 116.065 198 177 21 0.0 / 1.2 0.0 / 1.9 0.0 / 0.0 0.0136471 0.1 / 1.3 0.1 / 1.1 2.87286 2.016 0.0303712 133.829 41.4431 175.272 31 24556 3.0 / 3.1 0.1 / 0.2 0.0 / 0.0 0.1 / 0.1 0.0 / 0.0 96.6896 98.6758 99.3379 99.669 99.8345 6.36438 6.46475 6.39264 19.2219 706.269 -20240416_103326__relief__results__num_matched5__maxframelookahead10__760p__unified_roma 31 257 7.48133 0.0 / 15.2 0.1 / 10.5 0.1 / 16.8 434.459 136.423 216 206 10 0.0 / 0.2 0.0 / 0.3 0.0 / 0.1 0.01529 0.1 / 0.1 0.1 / 0.1 3.45202 2.03958 0.0147092 164.548 50.025 214.573 31 40746 3.0 / 3.1 0.2 / 0.2 0.0 / 0.0 0.0 / 0.1 0.0 / 0.0 96.31 98.524 99.262 99.631 99.8155 16.5018 16.4082 16.4108 49.3209 898.71 -20240416_103326__terrace__results__num_matched5__maxframelookahead10__760p__unified_roma 23 184 5.99508 0.1 / 5.6 0.1 / 8.0 0.1 / 9.7 280.533 95.7331 149 149 0 0.1 / 0.4 0.1 / 2.0 0.0 / 0.0 0.0144472 0.2 / 1.6 0.2 / 0.6 2.11164 1.27706 0.0243375 116.181 35.8172 151.998 23 24743 3.0 / 3.1 0.1 / 0.2 0.0 / 0.0 0.1 / 0.1 0.0 / 0.0 95.0869 98.0347 99.0174 99.5087 99.7543 7.58312 7.59135 7.5611 22.7357 594.536 -20240416_103326__terrains__results__num_matched5__maxframelookahead10__760p__unified_roma 42 380 9.48263 0.1 / 13.5 0.1 / 14.3 0.2 / 18.0 469.405 154.74 258 257 1 0.1 / 1.6 0.1 / 1.1 53.5 / 76.4 0.118336 0.1 / 1.0 0.4 / 27.5 5.33886 3.88956 0.140503 178.533 54.1644 232.697 30 44614 3.0 / 3.2 0.2 / 0.2 0.0 / 0.0 0.1 / 0.1 0.1 / 0.1 66.2533 69.3585 70.3935 70.911 71.1698 21.582 21.5111 21.6222 64.7154 998.6 \ No newline at end of file diff --git a/2024_04_20_15_47_13_477451_aggregated_results_table.tsv b/2024_04_20_15_47_13_477451_aggregated_results_table.tsv deleted file mode 100644 index 031f10000..000000000 --- a/2024_04_20_15_47_13_477451_aggregated_results_table.tsv +++ /dev/null @@ -1,14 +0,0 @@ -method_name retriever_num input images retriever_num retrieved image pairs retriever_retriever duration sec isp_rot3 angular errors deg isp_trans angular errors deg isp_pose errors deg isp_total correspondence generation duration sec isp_total two view estimation duration sec vg_num input measurements vg_num inlier measurements vg_num outlier measurements vg_inlier R angular errors deg vg_inlier U angular errors deg ra_rotation angle error deg ra_total duration sec ta_relative translation angle error deg ta_translation angle error deg ta_total duration sec ta_outlier rejection duration sec ta_optimization duration sec da_triangulation runtime sec da_gtsfm data creation runtime da_total duration sec ba_number cameras ba_number tracks filtered ba_3d track lengths filtered ba_reprojection errors filtered px ba_rotation angle error deg ba_relative translation angle error deg ba_translation angle error deg ba_pose auc @1 deg ba_pose auc @2.5 deg ba_pose auc @5 deg ba_pose auc @10 deg ba_pose auc @20 deg ba_step 0 run duration sec ba_step 1 run duration sec ba_step 2 run duration sec ba_total run duration sec total_total runtime sec -20240419_153409__courtyard__results__num_matched5__maxframelookahead10__760p__unified_roma 38 345 9.50227 0.2 / 33.6 0.7 / 44.2 0.7 / 52.5 871.19 237.737 314 205 109 0.1 / 15.5 0.2 / 24.1 23.5 / 16.9 0.280381 0.7 / 29.2 40.0 / 41.0 4.83216 3.63406 0.0866964 170.722 54.9152 225.637 35 6228 3.0 / 3.0 0.1 / 0.1 4.7 / 17.8 3.6 / 39.2 4.0 / 19.4 36.762 38.389 40.8626 54.2641 61.3426 11.2635 11.266 11.2575 33.787 1417.96 -20240419_153409__delivery_area__results__num_matched5__maxframelookahead10__760p__unified_roma 44 403 10.1694 0.1 / 40.3 0.2 / 43.7 0.2 / 57.5 736.834 224.123 253 223 30 0.0 / 0.3 0.0 / 5.0 0.0 / 0.0 0.0178623 0.1 / 2.8 0.3 / 26.3 5.8816 4.35137 0.0477619 198.225 62.913 261.138 23 11660 3.0 / 3.0 0.1 / 0.1 0.0 / 0.3 0.0 / 1.3 0.0 / 0.3 49.0316 49.6126 49.8063 51.294 51.7834 2.8317 2.77862 2.77884 8.38926 1286.49 -20240419_153409__electro__results__num_matched5__maxframelookahead10__760p__unified_roma 45 455 10.4627 5.2 / 52.2 20.6 / 52.2 49.0 / 70.4 799.061 229.65 241 205 36 0.1 / 14.4 0.1 / 23.7 16.1 / 25.8 1297.22 3.9 / 28.8 22.6 / 29.6 6.51289 5.27921 0.0448792 140.974 51.8414 192.815 37 1124 3.0 / 3.0 0.2 / 0.3 0.4 / 8.3 21.5 / 38.0 15.7 / 25.3 27.9162 31.1665 32.2499 34.5968 37.8086 1.71249 1.73161 1.72937 5.17357 2573.59 -20240419_153409__facade__results__num_matched5__maxframelookahead10__760p__unified_roma 76 773 18.1341 0.1 / 21.2 0.1 / 22.3 0.1 / 30.1 2695.21 634.958 685 612 73 0.1 / 9.4 0.1 / 11.1 10.6 / 21.5 405.542 0.4 / 19.3 3.5 / 23.4 34.1463 29.882 0.11198 551.879 177.49 729.369 61 54397 3.0 / 3.0 0.1 / 0.1 0.0 / 0.5 0.1 / 3.3 0.1 / 0.5 71.8806 75.3312 76.4814 77.0565 78.6452 45.379 45.4287 45.4695 136.277 4767.05 -20240419_153409__kicker__results__num_matched5__maxframelookahead10__760p__unified_roma 31 279 8.03017 0.2 / 27.9 0.2 / 25.5 0.3 / 33.7 554.18 149.755 211 177 34 0.1 / 1.0 0.1 / 1.2 0.1 / 0.1 0.0142729 0.1 / 0.2 0.1 / 0.1 3.82362 2.68059 0.0380123 138.14 43.1754 181.315 31 18227 3.0 / 3.0 0.2 / 0.3 0.0 / 0.0 0.0 / 0.1 0.0 / 0.0 95.4308 98.1723 99.0862 99.5431 99.7715 6.53843 6.60521 6.63445 19.7782 955.44 -20240419_153409__meadow__results__num_matched5__maxframelookahead10__760p__unified_roma 15 97 4.68225 0.3 / 8.5 0.4 / 39.5 0.7 / 42.0 149.219 48.4122 82 77 5 0.2 / 0.7 0.2 / 34.6 0.1 / 0.2 0.00478148 0.4 / 42.0 0.1 / 30.8 1.23997 0.821674 0.0256472 36.0498 10.6362 46.686 15 1665 3.0 / 3.0 0.2 / 0.3 0.1 / 2.2 15.7 / 51.7 0.0 / 30.0 63.8712 65.5485 66.1076 66.3871 66.5269 0.359486 0.352348 0.341015 1.05294 266.477 -20240419_153409__office__results__num_matched5__maxframelookahead10__760p__unified_roma 26 215 6.48619 0.8 / 52.4 6.1 / 40.4 9.3 / 61.3 303.696 92.5644 127 108 19 0.1 / 18.6 0.3 / 14.5 7.4 / 13.9 0.0226824 0.8 / 9.6 0.6 / 4.2 2.72386 2.00123 0.0745261 74.9513 23.5739 98.5253 22 10598 3.0 / 3.0 0.2 / 0.2 0.0 / 8.1 0.3 / 10.0 0.0 / 1.8 70.7827 76.7746 78.7719 79.7706 80.2699 2.83327 2.81844 2.86629 8.5181 539.509 -20240419_153409__pipes__results__num_matched5__maxframelookahead10__760p__unified_roma 14 85 4.2721 0.1 / 22.0 0.4 / 18.1 0.5 / 26.7 139.935 46.5909 65 63 2 0.1 / 0.7 0.1 / 1.1 0.1 / 0.2 0.00339031 0.3 / 0.6 0.5 / 0.7 1.19493 0.794644 0.00951147 54.7564 16.7711 71.5275 14 5755 3.0 / 3.0 0.2 / 0.2 0.0 / 0.0 0.1 / 0.2 0.1 / 0.1 90.1851 96.074 98.037 99.0185 99.5093 1.43367 1.45867 1.44911 4.34154 283.992 -20240419_153409__playground__results__num_matched5__maxframelookahead10__760p__unified_roma 38 373 9.45975 46.3 / 59.9 40.9 / 60.9 91.5 / 77.2 599.067 170.822 117 108 9 0.1 / 2.9 0.1 / 6.9 0.1 / 0.1 0.0107644 0.4 / 5.6 6.7 / 10.1 3.77917 3.02702 0.0479169 76.0196 23.7443 99.7639 35 2559 3.0 / 3.0 0.2 / 0.3 0.1 / 0.1 0.2 / 0.3 0.1 / 0.1 77.7749 86.3731 89.2392 90.6722 91.3887 1.01486 1.02004 1.01656 3.05156 914.793 -20240419_153409__relief_2__results__num_matched5__maxframelookahead10__760p__unified_roma 31 259 7.37256 0.0 / 25.3 0.1 / 15.8 0.1 / 27.9 606.372 175.889 197 181 16 0.0 / 0.1 0.0 / 0.7 0.0 / 0.0 0.0135844 0.1 / 0.2 0.1 / 0.2 3.20406 2.19761 0.0137043 190.409 60.6451 251.055 31 15996 3.0 / 3.0 0.1 / 0.1 0.0 / 0.0 0.0 / 0.1 0.0 / 0.0 97.171 98.8684 99.4342 99.7171 99.8586 4.15015 4.12562 4.11209 12.388 1093.65 -20240419_153409__relief__results__num_matched5__maxframelookahead10__760p__unified_roma 31 257 7.42472 0.0 / 17.4 0.1 / 12.9 0.1 / 19.7 746.544 193.36 218 210 8 0.0 / 0.5 0.1 / 1.5 0.0 / 0.0 0.0139396 0.1 / 0.2 0.0 / 0.2 3.70646 2.32572 0.0458643 216.512 67.4984 284.01 31 21787 3.0 / 3.0 0.1 / 0.2 0.0 / 0.0 0.1 / 0.1 0.0 / 0.0 95.4821 98.1928 99.0964 99.5482 99.7741 7.84393 7.87182 7.98793 23.7038 1300.41 -20240419_153409__terrace__results__num_matched5__maxframelookahead10__760p__unified_roma 23 184 5.91381 0.1 / 16.2 0.1 / 17.3 0.1 / 21.8 466.439 134.992 157 155 2 0.1 / 0.3 0.1 / 5.7 0.0 / 0.0 0.0126622 0.3 / 5.5 0.2 / 1.8 2.35429 1.31525 0.0397565 155.746 49.681 205.427 23 11992 3.0 / 3.0 0.1 / 0.1 0.0 / 0.0 0.1 / 0.1 0.0 / 0.0 94.7458 97.8983 98.9492 99.4746 99.7373 3.62963 3.63009 3.63901 10.8989 855.199 -20240419_153409__terrains__results__num_matched5__maxframelookahead10__760p__unified_roma 42 380 9.24043 0.1 / 28.3 0.2 / 25.0 0.2 / 34.9 819.303 229.546 281 266 15 0.1 / 1.8 0.1 / 1.3 60.0 / 85.7 0.052882 0.1 / 1.1 0.3 / 19.7 5.75011 3.93434 0.0966253 251.891 78.429 330.32 42 40915 3.0 / 3.0 0.1 / 0.2 0.0 / 42.7 0.2 / 36.9 0.1 / 23.4 66.1488 69.3167 70.3726 70.9006 71.1646 21.6149 21.7372 21.5544 64.9066 1522.55 \ No newline at end of file diff --git a/gtsfm/two_view_estimator.py b/gtsfm/two_view_estimator.py index 10b8da7a2..72ee06d89 100644 --- a/gtsfm/two_view_estimator.py +++ b/gtsfm/two_view_estimator.py @@ -9,6 +9,7 @@ from dask.distributed import Client import numpy as np +import gtsam from gtsam import PinholeCameraCal3Bundler, Pose3, Rot3, SfmTrack, Unit3 import gtsfm.common.types as gtsfm_types @@ -318,7 +319,17 @@ def run_2view( # Optionally, do two-view bundle adjustment if self._bundle_adjust_2view and len(pre_ba_v_corr_idxs) >= self.processor._min_num_inliers_est_model: - post_ba_i2Ri1, post_ba_i2Ui1, post_ba_v_corr_idxs = self.bundle_adjust( + # post_ba_i2Ri1, post_ba_i2Ui1, post_ba_v_corr_idxs = self.bundle_adjust( + # keypoints_i1, + # keypoints_i2, + # pre_ba_v_corr_idxs, + # camera_intrinsics_i1, + # camera_intrinsics_i2, + # pre_ba_i2Ri1, + # pre_ba_i2Ui1, + # i2Ti1_prior, + # ) + post_ba_i2Ri1, post_ba_i2Ui1 = optimize_essential_matrix( keypoints_i1, keypoints_i2, pre_ba_v_corr_idxs, @@ -326,8 +337,8 @@ def run_2view( camera_intrinsics_i2, pre_ba_i2Ri1, pre_ba_i2Ui1, - i2Ti1_prior, ) + post_ba_v_corr_idxs = np.copy(pre_ba_v_corr_idxs) post_ba_inlier_ratio_wrt_estimate = float(len(post_ba_v_corr_idxs)) / len(putative_corr_idxs) # TODO: Remove this hack once we can handle the lower post_ba_inlier_ratio_wrt_estimate downstream. @@ -360,6 +371,67 @@ def run_2view( return post_isp_i2Ri1, post_isp_i2Ui1, post_isp_v_corr_idxs, pre_ba_report, post_ba_report, post_isp_report +def optimize_essential_matrix( + keypoints_i1: Keypoints, + keypoints_i2: Keypoints, + corr_idxs_i1i2: np.ndarray, + camera_intrinsics_i1: gtsam.Cal3Bundler, + camera_intrinsics_i2: gtsam.Cal3Bundler, + i2Ri1: Rot3, + i2Ui1: Unit3, + use_robust_loss: bool = True, +) -> Tuple[Dict[Tuple[int, int], Rot3], Dict[Tuple[int, int], Unit3]]: + """Jointly optimize over all essential matrices for edges contained in triplets. + + Args: + triplets: List of triplets in view graph. + i2Ri1_dict: Dict from (i1, i2) to relative rotation of i1 with respect to i2. + i2Ui1_dict: Dict from (i1, i2) to relative translation direction of i1 with respect to i2. + calibrations: List of calibrations for each image. + corr_idxs_i1i2: Dict from (i1, i2) to indices of verified correspondences from i1 to i2. + keypoints: keypoints for each images. + use_robust_loss: whether to use Huber loss. + + Returns: + Optimized relative rotations and directions. + """ + # Create GTSAM objects. + graph = gtsam.NonlinearFactorGraph() + initial = gtsam.Values() + noise_model=gtsam.noiseModel.Isotropic.Sigma(1, 1e-2) + if use_robust_loss: + huber_loss = gtsam.noiseModel.mEstimator.Huber.Create(1.345) + noise_model = gtsam.noiseModel.Robust.Create(huber_loss, noise_model) + + # Add essential matrix factors. + mkps1 = keypoints_i1.coordinates[corr_idxs_i1i2[:, 0]] + mkps2 = keypoints_i2.coordinates[corr_idxs_i1i2[:, 1]] + initial.insert(0, gtsam.EssentialMatrix(i2Ri1, i2Ui1)) + for kp1, kp2 in zip(mkps1, mkps2): + graph.add( + gtsam.EssentialMatrixFactor( + 0, + camera_intrinsics_i2.calibrate(kp2), + camera_intrinsics_i1.calibrate(kp1), + noise_model, + ) + ) + + # Optimize! + params = gtsam.LevenbergMarquardtParams() + params.setVerbosity("ERROR") + params.setMaxIterations(10) + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) + result = optimizer.optimize() + + # Add optimized rotations and translations to the dictionary. + E_opt = result.atEssentialMatrix(0) + i2Ri1 = E_opt.rotation() + i2Ui1 = E_opt.direction() + + return i2Ri1, i2Ui1 + + def generate_two_view_report( inlier_ratio_est_model: float, v_corr_idxs: np.ndarray, diff --git a/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py b/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py index 2a00d7bd2..16ab5a597 100644 --- a/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py +++ b/gtsfm/view_graph_estimator/cycle_consistent_rotation_estimator.py @@ -110,10 +110,10 @@ def run( triplets: List[Tuple[int, int, int]] = graph_utils.extract_cyclic_triplets_from_edges(input_edges) logger.info("Number of triplets: %d" % len(triplets)) - # Optimize essential matrices. - i2Ri1_dict, i2Ui1_dict = self.optimize_essential_matrices( - triplets, i2Ri1_dict, i2Ui1_dict, calibrations, corr_idxs_i1i2, keypoints - ) + # # Optimize essential matrices. + # i2Ri1_dict, i2Ui1_dict = self.optimize_essential_matrices( + # triplets, i2Ri1_dict, i2Ui1_dict, calibrations, corr_idxs_i1i2, keypoints + # ) # Compute the cycle error for each triplet, and add it to its edges for aggregation. per_edge_errors = defaultdict(list) diff --git a/thirdparty/LightGlue b/thirdparty/LightGlue index 29f3e449e..fe7fb4fa0 160000 --- a/thirdparty/LightGlue +++ b/thirdparty/LightGlue @@ -1 +1 @@ -Subproject commit 29f3e449efa1994758b8a16299d2816028dca65b +Subproject commit fe7fb4fa0cffec65e33bf4c2f62a863d5b03433a