EssentialViewGraphExample.py
Go to the documentation of this file.
1 """
2  GTSAM Copyright 2010, Georgia Tech Research Corporation,
3  Atlanta, Georgia 30332-0415
4  All Rights Reserved
5  Authors: Frank Dellaert, et al. (see THANKS for the full author list)
6 
7  See LICENSE for the license information
8 """
9 
10 """
11 Python version of EssentialViewGraphExample.cpp
12 View-graph calibration with essential matrices.
13 Author: Frank Dellaert
14 Date: October 2024
15 """
16 
17 import numpy as np
18 from gtsam.examples import SFMdata
19 
20 import gtsam
21 from gtsam import Cal3f, EdgeKey, EssentialMatrix
22 from gtsam import EssentialTransferFactorCal3f as Factor
23 from gtsam import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
24  NonlinearFactorGraph, PinholeCameraCal3f, Values)
25 
26 # For symbol shorthand (e.g., X(0), L(1))
27 K = gtsam.symbol_shorthand.K
28 
29 
30 # Formatter function for printing keys
31 def formatter(key):
32  sym = gtsam.Symbol(key)
33  if sym.chr() == ord("k"):
34  return f"k{sym.index()}"
35  else:
36  edge = EdgeKey(key)
37  return f"({edge.i()},{edge.j()})"
38 
39 
40 def main():
41  # Define the camera calibration parameters
42  cal = Cal3f(50.0, 50.0, 50.0)
43 
44  # Create the set of 8 ground-truth landmarks
45  points = SFMdata.createPoints()
46 
47  # Create the set of 4 ground-truth poses
48  poses = SFMdata.posesOnCircle(4, 30)
49 
50  # Calculate ground truth essential matrices, 1 and 2 poses apart
51  E1 = EssentialMatrix.FromPose3(poses[0].between(poses[1]))
52  E2 = EssentialMatrix.FromPose3(poses[0].between(poses[2]))
53 
54  # Simulate measurements from each camera pose
55  p = [[None for _ in range(8)] for _ in range(4)]
56  for i in range(4):
57  camera = PinholeCameraCal3f(poses[i], cal)
58  for j in range(8):
59  p[i][j] = camera.project(points[j])
60 
61  # Create the factor graph
62  graph = NonlinearFactorGraph()
63 
64  for a in range(4):
65  b = (a + 1) % 4 # Next camera
66  c = (a + 2) % 4 # Camera after next
67 
68  # Collect data for the three factors
69  tuples1 = []
70  tuples2 = []
71  tuples3 = []
72 
73  for j in range(8):
74  tuples1.append((p[a][j], p[b][j], p[c][j]))
75  tuples2.append((p[a][j], p[c][j], p[b][j]))
76  tuples3.append((p[c][j], p[b][j], p[a][j]))
77 
78  # Add transfer factors between views a, b, and c.
79  graph.add(Factor(EdgeKey(a, c), EdgeKey(b, c), tuples1))
80  graph.add(Factor(EdgeKey(a, b), EdgeKey(b, c), tuples2))
81  graph.add(Factor(EdgeKey(a, c), EdgeKey(a, b), tuples3))
82 
83  graph.print("graph", formatter)
84 
85  # Create a delta vector to perturb the ground truth (small perturbation)
86  delta = np.ones(5) * 1e-2
87 
88  # Create the initial estimate for essential matrices
89  initialEstimate = Values()
90  for a in range(4):
91  b = (a + 1) % 4 # Next camera
92  c = (a + 2) % 4 # Camera after next
93  initialEstimate.insert(EdgeKey(a, b).key(), E1.retract(delta))
94  initialEstimate.insert(EdgeKey(a, c).key(), E2.retract(delta))
95 
96  # Insert initial calibrations
97  for i in range(4):
98  initialEstimate.insert(K(i), cal)
99 
100  # Optimize the graph and print results
101  params = LevenbergMarquardtParams()
102  params.setlambdaInitial(1000.0) # Initialize lambda to a high value
103  params.setVerbosityLM("SUMMARY")
104  optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate, params)
105  result = optimizer.optimize()
106 
107  print("Initial error = ", graph.error(initialEstimate))
108  print("Final error = ", graph.error(result))
109 
110  # Print final results
111  print("Final Results:")
112  result.print("", formatter)
113 
114  # Print ground truth essential matrices
115  print("Ground Truth E1:\n", E1)
116  print("Ground Truth E2:\n", E2)
117 
118 
119 if __name__ == "__main__":
120  main()
gtsam.examples.EssentialViewGraphExample.formatter
def formatter(key)
Definition: EssentialViewGraphExample.py:31
gtsam::between
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:17
gtsam.examples.EssentialViewGraphExample.K
K
Definition: EssentialViewGraphExample.py:27
gtsam::Cal3f
Calibration model with a single focal length and zero skew.
Definition: Cal3f.h:35
gtsam.examples
Definition: python/gtsam/examples/__init__.py:1
gtsam::Factor
Definition: Factor.h:70
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:155
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
key
const gtsam::Symbol key('X', 0)
gtsam::EdgeKey
Definition: EdgeKey.h:25
gtsam::Values
Definition: Values.h:65
gtsam.examples.EssentialViewGraphExample.main
def main()
Definition: EssentialViewGraphExample.py:40
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:16