1
1
"""
2
2
Compare the Fundamental Matrix and Essential Matrix methods for optimizing the view-graph.
3
3
It measures the distance from the ground truth matrices in terms of the norm of local coordinates (geodesic distance)
4
- on the respective manifolds . It also plots the final error of the optimization.
4
+ on the F-manifold . It also plots the final error of the optimization.
5
5
Author: Frank Dellaert (with heavy assist from ChatGPT)
6
6
Date: October 2024
7
7
"""
@@ -113,26 +113,26 @@ def build_factor_graph(method, num_cameras, measurements):
113
113
114
114
115
115
# Function to get initial estimates
116
- def get_initial_estimate (method , num_cameras , ground_truth_matrices , K_initial ):
116
+ def get_initial_estimate (method , num_cameras , ground_truth , K ):
117
117
initialEstimate = Values ()
118
118
119
119
if method == "FundamentalMatrix" :
120
- F1 , F2 = ground_truth_matrices
120
+ F1 , F2 = ground_truth
121
121
for a in range (num_cameras ):
122
122
b = (a + 1 ) % num_cameras # Next camera
123
123
c = (a + 2 ) % num_cameras # Camera after next
124
124
initialEstimate .insert (EdgeKey (a , b ).key (), F1 )
125
125
initialEstimate .insert (EdgeKey (a , c ).key (), F2 )
126
126
elif method == "EssentialMatrix" :
127
- E1 , E2 = ground_truth_matrices
127
+ E1 , E2 = ground_truth
128
128
for a in range (num_cameras ):
129
129
b = (a + 1 ) % num_cameras # Next camera
130
130
c = (a + 2 ) % num_cameras # Camera after next
131
131
initialEstimate .insert (EdgeKey (a , b ).key (), E1 )
132
132
initialEstimate .insert (EdgeKey (a , c ).key (), E2 )
133
133
# Insert initial calibrations
134
134
for i in range (num_cameras ):
135
- initialEstimate .insert (K_sym (i ), K_initial )
135
+ initialEstimate .insert (K_sym (i ), K )
136
136
else :
137
137
raise ValueError (f"Unknown method { method } " )
138
138
@@ -150,38 +150,43 @@ def optimize(graph, initialEstimate):
150
150
151
151
152
152
# Function to compute distances from ground truth
153
- def compute_distances (method , result , ground_truth_matrices , num_cameras ):
153
+ def compute_distances (method , result , ground_truth , num_cameras , K ):
154
154
distances = []
155
+
155
156
if method == "FundamentalMatrix" :
156
- F1 , F2 = ground_truth_matrices
157
- for a in range (num_cameras ):
158
- b = (a + 1 ) % num_cameras
159
- c = (a + 2 ) % num_cameras
160
- key_ab = EdgeKey (a , b ).key ()
161
- key_ac = EdgeKey (a , c ).key ()
157
+ F1 , F2 = ground_truth
158
+ elif method == "EssentialMatrix" :
159
+ E1 , E2 = ground_truth
160
+ # Convert ground truth EssentialMatrices to FundamentalMatrices using GTSAM method
161
+ F1 = gtsam .FundamentalMatrix (K , E1 , K )
162
+ F2 = gtsam .FundamentalMatrix (K , E2 , K )
163
+ else :
164
+ raise ValueError (f"Unknown method { method } " )
165
+
166
+ for a in range (num_cameras ):
167
+ b = (a + 1 ) % num_cameras
168
+ c = (a + 2 ) % num_cameras
169
+ key_ab = EdgeKey (a , b ).key ()
170
+ key_ac = EdgeKey (a , c ).key ()
171
+
172
+ if method == "FundamentalMatrix" :
162
173
F_est_ab = result .atFundamentalMatrix (key_ab )
163
174
F_est_ac = result .atFundamentalMatrix (key_ac )
164
- # Compute local coordinates
165
- dist_ab = np .linalg .norm (F1 .localCoordinates (F_est_ab ))
166
- dist_ac = np .linalg .norm (F2 .localCoordinates (F_est_ac ))
167
- distances .append (dist_ab )
168
- distances .append (dist_ac )
169
- elif method == "EssentialMatrix" :
170
- E1 , E2 = ground_truth_matrices
171
- for a in range (num_cameras ):
172
- b = (a + 1 ) % num_cameras
173
- c = (a + 2 ) % num_cameras
174
- key_ab = EdgeKey (a , b ).key ()
175
- key_ac = EdgeKey (a , c ).key ()
175
+ elif method == "EssentialMatrix" :
176
176
E_est_ab = result .atEssentialMatrix (key_ab )
177
177
E_est_ac = result .atEssentialMatrix (key_ac )
178
- # Compute local coordinates
179
- dist_ab = np .linalg .norm (E1 .localCoordinates (E_est_ab ))
180
- dist_ac = np .linalg .norm (E2 .localCoordinates (E_est_ac ))
181
- distances .append (dist_ab )
182
- distances .append (dist_ac )
183
- else :
184
- raise ValueError (f"Unknown method { method } " )
178
+ # Convert estimated EssentialMatrices to FundamentalMatrices using GTSAM method
179
+ F_est_ab = gtsam .FundamentalMatrix (K , E_est_ab , K )
180
+ F_est_ac = gtsam .FundamentalMatrix (K , E_est_ac , K )
181
+ else :
182
+ raise ValueError (f"Unknown method { method } " )
183
+
184
+ # Compute local coordinates (geodesic distance on the F-manifold)
185
+ dist_ab = np .linalg .norm (F1 .localCoordinates (F_est_ab ))
186
+ dist_ac = np .linalg .norm (F2 .localCoordinates (F_est_ac ))
187
+ distances .append (dist_ab )
188
+ distances .append (dist_ac )
189
+
185
190
return distances
186
191
187
192
@@ -224,22 +229,22 @@ def main():
224
229
print (f"Running method: { method } " )
225
230
226
231
# Simulate data
227
- points , poses , measurements , K_initial = simulate_data (args .num_cameras )
232
+ points , poses , measurements , K = simulate_data (args .num_cameras )
228
233
229
234
# Compute ground truth matrices
230
- ground_truth_matrices = compute_ground_truth_matrices (method , poses , K_initial )
235
+ ground_truth = compute_ground_truth_matrices (method , poses , K )
231
236
232
237
# Build the factor graph
233
238
graph = build_factor_graph (method , args .num_cameras , measurements )
234
239
235
240
# Get initial estimates
236
- initialEstimate = get_initial_estimate (method , args .num_cameras , ground_truth_matrices , K_initial )
241
+ initialEstimate = get_initial_estimate (method , args .num_cameras , ground_truth , K )
237
242
238
243
# Optimize the graph
239
244
result = optimize (graph , initialEstimate )
240
245
241
246
# Compute distances from ground truth
242
- distances = compute_distances (method , result , ground_truth_matrices , args .num_cameras )
247
+ distances = compute_distances (method , result , ground_truth , args .num_cameras , K )
243
248
244
249
# Compute final error
245
250
final_error = graph .error (result )
0 commit comments