2 Compare several methods for optimizing the view-graph.
3 We measure the distance from the ground truth in terms of the norm of
4 local coordinates (geodesic distance) on the F-manifold.
5 We also plot the final error of the optimization.
7 Author: Frank Dellaert (with heavy assist from ChatGPT)
13 import matplotlib.pyplot
as plt
23 LevenbergMarquardtOptimizer,
24 LevenbergMarquardtParams,
27 SimpleFundamentalMatrix,
32 K = gtsam.symbol_shorthand.K
35 methods = [
"SimpleF",
"Fundamental",
"Essential+Ks",
"Essential+K",
"Calibrated",
"Binary+Ks",
"Binary+K"]
41 if sym.chr() == ord(
"k"):
42 return f
"k{sym.index()}"
45 return f
"({edge.i()},{edge.j()})"
49 """simulate geometry (points and poses)"""
51 cal =
Cal3f(50.0, 50.0, 50.0)
54 points = SFMdata.createPoints()
57 extra_points = rng.uniform(-10, 10, (num_random_points, 3))
61 poses = SFMdata.posesOnCircle(num_cameras, 30)
63 return points, poses, cal
67 """Simulate measurements from each camera pose"""
68 measurements = [[
None for _
in points]
for _
in poses]
69 for i, pose
in enumerate(poses):
70 camera = PinholeCameraCal3f(pose, cal)
71 for j, point
in enumerate(points):
72 projection = camera.project(point)
73 noise = rng.normal(0, noise_std, size=2)
74 measurements[i][j] = projection + noise
80 """Function to compute ground truth edge variables."""
81 E1 = EssentialMatrix.FromPose3(poses[0].
between(poses[1]))
82 E2 = EssentialMatrix.FromPose3(poses[0].
between(poses[2]))
85 if method ==
"Fundamental":
87 elif method ==
"SimpleF":
89 c = cal.principalPoint()
98 """build the factor graph"""
102 if method ==
"Fundamental":
103 FactorClass = gtsam.TransferFactorFundamentalMatrix
104 elif method ==
"SimpleF":
105 FactorClass = gtsam.TransferFactorSimpleFundamentalMatrix
106 elif method
in [
"Essential+Ks",
"Essential+K"]:
107 FactorClass = gtsam.EssentialTransferFactorKCal3f
108 elif method ==
"Binary+K":
109 FactorClass = gtsam.EssentialMatrixFactor4Cal3f
110 elif method ==
"Binary+Ks":
111 FactorClass = gtsam.EssentialMatrixFactor5Cal3f
112 elif method ==
"Calibrated":
113 FactorClass = gtsam.EssentialTransferFactorCal3f
115 raise ValueError(f
"Unknown method {method}")
118 if method
in [
"Essential+Ks",
"Binary+Ks"]:
119 for i
in range(num_cameras):
121 graph.addPriorCal3f(
K(i), cal, model)
122 elif method
in [
"Essential+K",
"Binary+K"]:
124 graph.addPriorCal3f(
K(0), cal, model)
128 for a
in range(num_cameras):
129 b = (a + 1) % num_cameras
130 c = (a + 2) % num_cameras
131 if method
in [
"Binary+Ks",
"Binary+K"]:
134 for j
in range(
len(measurements[0])):
135 if method ==
"Binary+Ks":
136 graph.add(FactorClass(ab,
K(a),
K(b), z[a][j], z[b][j]))
137 graph.add(FactorClass(ac,
K(a),
K(c), z[a][j], z[c][j]))
139 graph.add(FactorClass(ab,
K(0), z[a][j], z[b][j]))
140 graph.add(FactorClass(ac,
K(0), z[a][j], z[c][j]))
149 for j
in range(
len(measurements[0])):
150 tuples1.append((z[a][j], z[b][j], z[c][j]))
151 tuples2.append((z[a][j], z[c][j], z[b][j]))
152 tuples3.append((z[c][j], z[b][j], z[a][j]))
155 if method
in [
"Calibrated"]:
156 graph.add(FactorClass(
EdgeKey(a, c),
EdgeKey(b, c), tuples1, cal))
157 graph.add(FactorClass(
EdgeKey(a, b),
EdgeKey(b, c), tuples2, cal))
158 graph.add(FactorClass(
EdgeKey(a, c),
EdgeKey(a, b), tuples3, cal))
159 elif method ==
"Essential+K":
172 """get initial estimate for method"""
173 initialEstimate =
Values()
176 if method
in [
"Fundamental",
"SimpleF"]:
177 F1, F2 = ground_truth
178 for a
in range(num_cameras):
179 b = (a + 1) % num_cameras
180 c = (a + 2) % num_cameras
181 initialEstimate.insert(
EdgeKey(a, b).
key(), F1)
182 initialEstimate.insert(
EdgeKey(a, c).
key(), F2)
183 total_dimension += F1.dim() + F2.dim()
184 elif method
in [
"Essential+Ks",
"Essential+K",
"Binary+Ks",
"Binary+K",
"Calibrated"]:
185 E1, E2 = ground_truth
186 for a
in range(num_cameras):
187 b = (a + 1) % num_cameras
188 c = (a + 2) % num_cameras
191 initialEstimate.insert(
EdgeKey(a, b).
key(), E1)
192 initialEstimate.insert(
EdgeKey(a, c).
key(), E2)
193 total_dimension += E1.dim() + E2.dim()
196 if method
in [
"Essential+Ks",
"Binary+Ks"]:
197 for i
in range(num_cameras):
198 initialEstimate.insert(
K(i), cal)
199 total_dimension += cal.dim()
200 elif method
in [
"Essential+K",
"Binary+K"]:
201 initialEstimate.insert(
K(0), cal)
202 total_dimension += cal.dim()
204 print(f
"Total dimension of the problem: {total_dimension}")
205 return initialEstimate
209 """optimize the graph"""
211 if method
not in [
"Calibrated",
"Binary+K",
"Binary+Ks"]:
212 params.setlambdaInitial(1e10)
213 params.setlambdaUpperBound(1e10)
215 params.setVerbosityLM(
"SUMMARY")
217 result = optimizer.optimize()
218 iterations = optimizer.iterations()
219 return result, iterations
223 """Compute geodesic distances from ground truth"""
226 F1, F2 = ground_truth[
"Fundamental"]
228 for a
in range(num_cameras):
229 b = (a + 1) % num_cameras
230 c = (a + 2) % num_cameras
234 if method
in [
"Essential+Ks",
"Essential+K",
"Binary+Ks",
"Binary+K",
"Calibrated"]:
235 E_est_ab = result.atEssentialMatrix(key_ab)
236 E_est_ac = result.atEssentialMatrix(key_ac)
239 if method ==
"Fundamental":
240 F_est_ab = result.atFundamentalMatrix(key_ab)
241 F_est_ac = result.atFundamentalMatrix(key_ac)
242 elif method ==
"SimpleF":
243 SF_est_ab = result.atSimpleFundamentalMatrix(key_ab).
matrix()
244 SF_est_ac = result.atSimpleFundamentalMatrix(key_ac).
matrix()
247 elif method
in [
"Essential+Ks",
"Binary+Ks"]:
249 cal_a = result.atCal3f(
K(a))
250 cal_b = result.atCal3f(
K(b))
251 cal_c = result.atCal3f(
K(c))
254 elif method
in [
"Essential+K",
"Binary+K"]:
256 cal_shared = result.atCal3f(
K(0))
259 elif method ==
"Calibrated":
264 raise ValueError(f
"Unknown method {method}")
267 dist_ab = np.linalg.norm(F1.localCoordinates(F_est_ab))
268 dist_ac = np.linalg.norm(F2.localCoordinates(F_est_ac))
269 distances.append(dist_ab)
270 distances.append(dist_ac)
277 methods =
list(results.keys())
278 final_errors = [results[method][
"final_error"]
for method
in methods]
279 distances = [results[method][
"distances"]
for method
in methods]
280 iterations = [results[method][
"iterations"]
for method
in methods]
282 fig, ax1 = plt.subplots()
285 ax1.set_xlabel(
"Method")
286 ax1.set_ylabel(
"Median Error (log scale)", color=color)
287 ax1.set_yscale(
"log")
288 ax1.bar(methods, final_errors, color=color, alpha=0.6)
289 ax1.tick_params(axis=
"y", labelcolor=color)
293 ax2.set_ylabel(
"Median Geodesic Distance", color=color)
294 ax2.plot(methods, distances, color=color, marker=
"o", linestyle=
"-")
295 ax2.tick_params(axis=
"y", labelcolor=color)
298 for i, method
in enumerate(methods):
300 f
"{iterations[i]:.1f}",
302 textcoords=
"offset points",
308 plt.title(
"Comparison of Methods (Labels show avg iterations)")
316 parser = argparse.ArgumentParser(description=
"Compare Fundamental and Essential Matrix Methods")
317 parser.add_argument(
"--num_cameras", type=int, default=4, help=
"Number of cameras (default: 4)")
318 parser.add_argument(
"--num_extra_points", type=int, default=12, help=
"Number of extra random points (default: 12)")
319 parser.add_argument(
"--num_trials", type=int, default=5, help=
"Number of trials (default: 5)")
320 parser.add_argument(
"--seed", type=int, default=42, help=
"Random seed (default: 42)")
321 parser.add_argument(
"--noise_std", type=float, default=0.5, help=
"Standard deviation of noise (default: 0.5)")
322 args = parser.parse_args()
325 rng = np.random.default_rng(seed=args.seed)
328 results = {method: {
"distances": [],
"final_error": [],
"iterations": []}
for method
in methods}
331 points, poses, cal =
simulate_geometry(args.num_cameras, rng, args.num_extra_points)
337 initial_estimate: dict[Values] = {
338 method:
get_initial_estimate(method, args.num_cameras, ground_truth[method], cal)
for method
in methods
340 simple_f_result: Values =
Values()
342 for trial
in range(args.num_trials):
343 print(f
"\nTrial {trial + 1}/{args.num_trials}")
346 measurements =
simulate_data(points, poses, cal, rng, args.noise_std)
348 for method
in methods:
349 print(f
"\nRunning method: {method}")
355 if method ==
"Fundamental":
356 initial_estimate[method] = simple_f_result
359 result, iterations =
optimize(graph, initial_estimate[method], method)
362 if method ==
"SimpleF":
363 simple_f_result =
Values()
364 for a
in range(args.num_cameras):
365 b = (a + 1) % args.num_cameras
366 c = (a + 2) % args.num_cameras
369 F1 = result.atSimpleFundamentalMatrix(key_ab).
matrix()
370 F2 = result.atSimpleFundamentalMatrix(key_ac).
matrix()
375 distances =
compute_distances(method, result, ground_truth, args.num_cameras, cal)
378 final_error = graph.error(result)
379 if method
in [
"Binary+K",
"Binary+Ks"]:
380 final_error *= cal.f() * cal.f()
383 results[method][
"distances"].extend(distances)
384 results[method][
"final_error"].append(final_error)
385 results[method][
"iterations"].append(iterations)
387 print(f
"Method: {method}")
388 print(f
"Final Error: {final_error:.3f}")
389 print(f
"Mean Geodesic Distance: {np.mean(distances):.3f}")
390 print(f
"Number of Iterations: {iterations}\n")
393 for method
in methods:
394 results[method][
"final_error"] = np.median(results[method][
"final_error"])
395 results[method][
"distances"] = np.median(results[method][
"distances"])
396 results[method][
"iterations"] = np.median(results[method][
"iterations"])
402 if __name__ ==
"__main__":