ViewGraphComparison.py
Go to the documentation of this file.
1 """
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.
6 
7  Author: Frank Dellaert (with heavy assist from ChatGPT)
8  Date: October 2024
9 """
10 
11 import argparse
12 
13 import matplotlib.pyplot as plt
14 import numpy as np
15 from gtsam.examples import SFMdata
16 
17 import gtsam
18 from gtsam import (
19  Cal3f,
20  EdgeKey,
21  EssentialMatrix,
22  FundamentalMatrix,
23  LevenbergMarquardtOptimizer,
24  LevenbergMarquardtParams,
25  NonlinearFactorGraph,
26  PinholeCameraCal3f,
27  SimpleFundamentalMatrix,
28  Values,
29 )
30 
31 # For symbol shorthand (e.g., K(0), K(1))
32 K = gtsam.symbol_shorthand.K
33 
34 # Methods to compare
35 methods = ["SimpleF", "Fundamental", "Essential+Ks", "Essential+K", "Calibrated", "Binary+Ks", "Binary+K"]
36 
37 
38 # Formatter function for printing keys
39 def formatter(key):
40  sym = gtsam.Symbol(key)
41  if sym.chr() == ord("k"):
42  return f"k{sym.index()}"
43  else:
44  edge = EdgeKey(key)
45  return f"({edge.i()},{edge.j()})"
46 
47 
48 def simulate_geometry(num_cameras, rng, num_random_points=12):
49  """simulate geometry (points and poses)"""
50  # Define the camera calibration parameters
51  cal = Cal3f(50.0, 50.0, 50.0)
52 
53  # Create the set of 8 ground-truth landmarks
54  points = SFMdata.createPoints()
55 
56  # Create extra random points in the -10,10 cube around the origin
57  extra_points = rng.uniform(-10, 10, (num_random_points, 3))
58  points.extend([gtsam.Point3(p) for p in extra_points])
59 
60  # Create the set of ground-truth poses
61  poses = SFMdata.posesOnCircle(num_cameras, 30)
62 
63  return points, poses, cal
64 
65 
66 def simulate_data(points, poses, cal, rng, noise_std):
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
75 
76  return measurements
77 
78 
79 def compute_ground_truth(method, poses, cal):
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]))
83  F1 = FundamentalMatrix(cal.K(), E1, cal.K())
84  F2 = FundamentalMatrix(cal.K(), E2, cal.K())
85  if method == "Fundamental":
86  return F1, F2
87  elif method == "SimpleF":
88  f = cal.fx()
89  c = cal.principalPoint()
90  SF1 = SimpleFundamentalMatrix(E1, f, f, c, c)
91  SF2 = SimpleFundamentalMatrix(E2, f, f, c, c)
92  return SF1, SF2
93  else:
94  return E1, E2
95 
96 
97 def build_factor_graph(method, num_cameras, measurements, cal):
98  """build the factor graph"""
99  graph = NonlinearFactorGraph()
100 
101  # Determine the FactorClass based on the method
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
114  else:
115  raise ValueError(f"Unknown method {method}")
116 
117  # Add priors on calibrations if necessary
118  if method in ["Essential+Ks", "Binary+Ks"]:
119  for i in range(num_cameras):
120  model = gtsam.noiseModel.Isotropic.Sigma(1, 1000.0)
121  graph.addPriorCal3f(K(i), cal, model)
122  elif method in ["Essential+K", "Binary+K"]:
123  model = gtsam.noiseModel.Isotropic.Sigma(1, 1000.0)
124  graph.addPriorCal3f(K(0), cal, model)
125 
126  z = measurements # shorthand
127 
128  for a in range(num_cameras):
129  b = (a + 1) % num_cameras # Next camera
130  c = (a + 2) % num_cameras # Camera after next
131  if method in ["Binary+Ks", "Binary+K"]:
132  # Add binary Essential Matrix factors
133  ab, ac = EdgeKey(a, b).key(), EdgeKey(a, c).key()
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]))
138  else: # Binary+K
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]))
141  else:
142  # Add transfer factors between views a, b, and c
143 
144  # Vectors to collect tuples for each factor
145  tuples1 = []
146  tuples2 = []
147  tuples3 = []
148 
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]))
153 
154  # Add transfer factors between views a, b, and c.
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":
160  graph.add(FactorClass(EdgeKey(a, c), EdgeKey(b, c), K(0), tuples1))
161  graph.add(FactorClass(EdgeKey(a, b), EdgeKey(b, c), K(0), tuples2))
162  graph.add(FactorClass(EdgeKey(a, c), EdgeKey(a, b), K(0), tuples3))
163  else:
164  graph.add(FactorClass(EdgeKey(a, c), EdgeKey(b, c), tuples1))
165  graph.add(FactorClass(EdgeKey(a, b), EdgeKey(b, c), tuples2))
166  graph.add(FactorClass(EdgeKey(a, c), EdgeKey(a, b), tuples3))
167 
168  return graph
169 
170 
171 def get_initial_estimate(method, num_cameras, ground_truth, cal):
172  """get initial estimate for method"""
173  initialEstimate = Values()
174  total_dimension = 0
175 
176  if method in ["Fundamental", "SimpleF"]:
177  F1, F2 = ground_truth
178  for a in range(num_cameras):
179  b = (a + 1) % num_cameras # Next camera
180  c = (a + 2) % num_cameras # Camera after next
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
189  # initialEstimate.insert(EdgeKey(a, b).key(), E1.retract(0.1 * np.ones((5, 1))))
190  # initialEstimate.insert(EdgeKey(a, c).key(), E2.retract(0.1 * np.ones((5, 1))))
191  initialEstimate.insert(EdgeKey(a, b).key(), E1)
192  initialEstimate.insert(EdgeKey(a, c).key(), E2)
193  total_dimension += E1.dim() + E2.dim()
194 
195  # Insert initial calibrations
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()
203 
204  print(f"Total dimension of the problem: {total_dimension}")
205  return initialEstimate
206 
207 
208 def optimize(graph, initialEstimate, method):
209  """optimize the graph"""
210  params = LevenbergMarquardtParams()
211  if method not in ["Calibrated", "Binary+K", "Binary+Ks"]:
212  params.setlambdaInitial(1e10) # Initialize lambda to a high value
213  params.setlambdaUpperBound(1e10)
214  # params.setAbsoluteErrorTol(0.1)
215  params.setVerbosityLM("SUMMARY")
216  optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate, params)
217  result = optimizer.optimize()
218  iterations = optimizer.iterations()
219  return result, iterations
220 
221 
222 def compute_distances(method, result, ground_truth, num_cameras, cal):
223  """Compute geodesic distances from ground truth"""
224  distances = []
225 
226  F1, F2 = ground_truth["Fundamental"]
227 
228  for a in range(num_cameras):
229  b = (a + 1) % num_cameras
230  c = (a + 2) % num_cameras
231  key_ab = EdgeKey(a, b).key()
232  key_ac = EdgeKey(a, c).key()
233 
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)
237 
238  # Compute estimated FundamentalMatrices
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()
245  F_est_ab = FundamentalMatrix(SF_est_ab)
246  F_est_ac = FundamentalMatrix(SF_est_ac)
247  elif method in ["Essential+Ks", "Binary+Ks"]:
248  # Retrieve calibrations from result for each camera
249  cal_a = result.atCal3f(K(a))
250  cal_b = result.atCal3f(K(b))
251  cal_c = result.atCal3f(K(c))
252  F_est_ab = FundamentalMatrix(cal_a.K(), E_est_ab, cal_b.K())
253  F_est_ac = FundamentalMatrix(cal_a.K(), E_est_ac, cal_c.K())
254  elif method in ["Essential+K", "Binary+K"]:
255  # Use single shared calibration
256  cal_shared = result.atCal3f(K(0))
257  F_est_ab = FundamentalMatrix(cal_shared.K(), E_est_ab, cal_shared.K())
258  F_est_ac = FundamentalMatrix(cal_shared.K(), E_est_ac, cal_shared.K())
259  elif method == "Calibrated":
260  # Use ground truth calibration
261  F_est_ab = FundamentalMatrix(cal.K(), E_est_ab, cal.K())
262  F_est_ac = FundamentalMatrix(cal.K(), E_est_ac, cal.K())
263  else:
264  raise ValueError(f"Unknown method {method}")
265 
266  # Compute local coordinates (geodesic distance on the F-manifold)
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)
271 
272  return distances
273 
274 
275 def plot_results(results):
276  """plot results"""
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]
281 
282  fig, ax1 = plt.subplots()
283 
284  color = "tab:red"
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)
290 
291  ax2 = ax1.twinx()
292  color = "tab:blue"
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)
296 
297  # Annotate the blue data points with the average number of iterations
298  for i, method in enumerate(methods):
299  ax2.annotate(
300  f"{iterations[i]:.1f}",
301  (i, distances[i]),
302  textcoords="offset points",
303  xytext=(0, 10),
304  ha="center",
305  color=color,
306  )
307 
308  plt.title("Comparison of Methods (Labels show avg iterations)")
309  fig.tight_layout()
310  plt.show()
311 
312 
313 # Main function
314 def main():
315  # Parse command line arguments
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()
323 
324  # Initialize the random number generator
325  rng = np.random.default_rng(seed=args.seed)
326 
327  # Initialize results dictionary
328  results = {method: {"distances": [], "final_error": [], "iterations": []} for method in methods}
329 
330  # Simulate geometry
331  points, poses, cal = simulate_geometry(args.num_cameras, rng, args.num_extra_points)
332 
333  # Compute ground truth matrices
334  ground_truth = {method: compute_ground_truth(method, poses, cal) for method in methods}
335 
336  # Get initial estimates
337  initial_estimate: dict[Values] = {
338  method: get_initial_estimate(method, args.num_cameras, ground_truth[method], cal) for method in methods
339  }
340  simple_f_result: Values = Values()
341 
342  for trial in range(args.num_trials):
343  print(f"\nTrial {trial + 1}/{args.num_trials}")
344 
345  # Simulate data
346  measurements = simulate_data(points, poses, cal, rng, args.noise_std)
347 
348  for method in methods:
349  print(f"\nRunning method: {method}")
350 
351  # Build the factor graph
352  graph = build_factor_graph(method, args.num_cameras, measurements, cal)
353 
354  # For F, initialize from SimpleF:
355  if method == "Fundamental":
356  initial_estimate[method] = simple_f_result
357 
358  # Optimize the graph
359  result, iterations = optimize(graph, initial_estimate[method], method)
360 
361  # Store SimpleF result as a set of FundamentalMatrices
362  if method == "SimpleF":
363  simple_f_result = Values()
364  for a in range(args.num_cameras):
365  b = (a + 1) % args.num_cameras # Next camera
366  c = (a + 2) % args.num_cameras # Camera after next
367  key_ab = EdgeKey(a, b).key()
368  key_ac = EdgeKey(a, c).key()
369  F1 = result.atSimpleFundamentalMatrix(key_ab).matrix()
370  F2 = result.atSimpleFundamentalMatrix(key_ac).matrix()
371  simple_f_result.insert(key_ab, FundamentalMatrix(F1))
372  simple_f_result.insert(key_ac, FundamentalMatrix(F2))
373 
374  # Compute distances from ground truth
375  distances = compute_distances(method, result, ground_truth, args.num_cameras, cal)
376 
377  # Compute final error
378  final_error = graph.error(result)
379  if method in ["Binary+K", "Binary+Ks"]:
380  final_error *= cal.f() * cal.f()
381 
382  # Store results
383  results[method]["distances"].extend(distances)
384  results[method]["final_error"].append(final_error)
385  results[method]["iterations"].append(iterations)
386 
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")
391 
392  # Average results over trials
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"])
397 
398  # Plot results
399  plot_results(results)
400 
401 
402 if __name__ == "__main__":
403  main()
gtsam.examples.ViewGraphComparison.compute_distances
def compute_distances(method, result, ground_truth, num_cameras, cal)
Definition: ViewGraphComparison.py:222
gtsam.examples.ViewGraphComparison.simulate_geometry
def simulate_geometry(num_cameras, rng, num_random_points=12)
Definition: ViewGraphComparison.py:48
gtsam.examples.ViewGraphComparison.optimize
def optimize(graph, initialEstimate, method)
Definition: ViewGraphComparison.py:208
gtsam::between
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:17
list
Definition: pytypes.h:2166
gtsam::Cal3f
Calibration model with a single focal length and zero skew.
Definition: Cal3f.h:35
gtsam.examples.ViewGraphComparison.build_factor_graph
def build_factor_graph(method, num_cameras, measurements, cal)
Definition: ViewGraphComparison.py:97
gtsam.examples
Definition: python/gtsam/examples/__init__.py:1
gtsam.examples.ViewGraphComparison.K
K
Definition: ViewGraphComparison.py:32
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam.examples.ViewGraphComparison.main
def main()
Definition: ViewGraphComparison.py:314
gtsam.examples.ViewGraphComparison.compute_ground_truth
def compute_ground_truth(method, poses, cal)
Definition: ViewGraphComparison.py:79
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam.examples.ViewGraphComparison.get_initial_estimate
def get_initial_estimate(method, num_cameras, ground_truth, cal)
Definition: ViewGraphComparison.py:171
gtsam.examples.ViewGraphComparison.plot_results
def plot_results(results)
Definition: ViewGraphComparison.py:275
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
key
const gtsam::Symbol key('X', 0)
gtsam::EdgeKey
Definition: EdgeKey.h:25
gtsam::SimpleFundamentalMatrix
Class for representing a simple fundamental matrix.
Definition: FundamentalMatrix.h:132
gtsam::Values
Definition: Values.h:65
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:625
len
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2446
gtsam.examples.ViewGraphComparison.formatter
def formatter(key)
Definition: ViewGraphComparison.py:39
gtsam::FundamentalMatrix
Represents a fundamental matrix in computer vision, which encodes the epipolar geometry between two v...
Definition: FundamentalMatrix.h:29
gtsam.examples.ViewGraphComparison.simulate_data
def simulate_data(points, poses, cal, rng, noise_std)
Definition: ViewGraphComparison.py:66
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:18:24