ViewGraphExample.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 ViewGraphExample.cpp
12 View-graph calibration on a simulated dataset, a la Sweeney 2015
13 Author: Frank Dellaert
14 Date: October 2024
15 """
16 
17 import numpy as np
18 from gtsam.examples import SFMdata
19 
20 from gtsam import (Cal3_S2, EdgeKey, FundamentalMatrix,
21  LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
22  NonlinearFactorGraph, PinholeCameraCal3_S2)
23 from gtsam import TransferFactorFundamentalMatrix as Factor
24 from gtsam import Values
25 
26 
27 # Formatter function for printing keys
28 def formatter(key):
29  edge = EdgeKey(key)
30  return f"({edge.i()},{edge.j()})"
31 
32 
33 def main():
34  # Define the camera calibration parameters
35  cal = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)
36 
37  # Create the set of 8 ground-truth landmarks
38  points = SFMdata.createPoints()
39 
40  # Create the set of 4 ground-truth poses
41  poses = SFMdata.posesOnCircle(4, 30)
42 
43  # Calculate ground truth fundamental matrices, 1 and 2 poses apart
44  F1 = FundamentalMatrix(cal.K(), poses[0].between(poses[1]), cal.K())
45  F2 = FundamentalMatrix(cal.K(), poses[0].between(poses[2]), cal.K())
46 
47  # Simulate measurements from each camera pose
48  p = [[None for _ in range(8)] for _ in range(4)]
49  for i in range(4):
50  camera = PinholeCameraCal3_S2(poses[i], cal)
51  for j in range(8):
52  p[i][j] = camera.project(points[j])
53 
54  # Create the factor graph
55  graph = NonlinearFactorGraph()
56 
57  for a in range(4):
58  b = (a + 1) % 4 # Next camera
59  c = (a + 2) % 4 # Camera after next
60 
61  # Vectors to collect tuples for each factor
62  tuples1 = []
63  tuples2 = []
64  tuples3 = []
65 
66  # Collect data for the three factors
67  for j in range(8):
68  tuples1.append((p[a][j], p[b][j], p[c][j]))
69  tuples2.append((p[a][j], p[c][j], p[b][j]))
70  tuples3.append((p[c][j], p[b][j], p[a][j]))
71 
72  # Add transfer factors between views a, b, and c.
73  graph.add(Factor(EdgeKey(a, c), EdgeKey(b, c), tuples1))
74  graph.add(Factor(EdgeKey(a, b), EdgeKey(b, c), tuples2))
75  graph.add(Factor(EdgeKey(a, c), EdgeKey(a, b), tuples3))
76 
77  # Print the factor graph
78  graph.print("Factor Graph:\n", formatter)
79 
80  # Create a delta vector to perturb the ground truth
81  delta = np.array([1, 2, 3, 4, 5, 6, 7]) * 1e-5
82 
83  # Create the data structure to hold the initial estimate to the solution
84  initialEstimate = Values()
85  for a in range(4):
86  b = (a + 1) % 4 # Next camera
87  c = (a + 2) % 4 # Camera after next
88  initialEstimate.insert(EdgeKey(a, b).key(), F1.retract(delta))
89  initialEstimate.insert(EdgeKey(a, c).key(), F2.retract(delta))
90 
91  initialEstimate.print("Initial Estimates:\n", formatter)
92  graph.printErrors(initialEstimate, "Initial Errors:\n", formatter)
93 
94  # Optimize the graph and print results
95  params = LevenbergMarquardtParams()
96  params.setlambdaInitial(1000.0) # Initialize lambda to a high value
97  params.setVerbosityLM("SUMMARY")
98  optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate, params)
99  result = optimizer.optimize()
100 
101  print(f"Initial error = {graph.error(initialEstimate)}")
102  print(f"Final error = {graph.error(result)}")
103 
104  result.print("Final Results:\n", formatter)
105 
106  print("Ground Truth F1:\n", F1.matrix())
107  print("Ground Truth F2:\n", F2.matrix())
108 
109 
110 if __name__ == "__main__":
111  main()
gtsam::between
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:17
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::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
key
const gtsam::Symbol key('X', 0)
gtsam.examples.ViewGraphExample.main
def main()
Definition: ViewGraphExample.py:33
gtsam::EdgeKey
Definition: EdgeKey.h:25
gtsam::Values
Definition: Values.h:65
gtsam.examples.ViewGraphExample.formatter
def formatter(key)
Definition: ViewGraphExample.py:28
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::FundamentalMatrix
Represents a fundamental matrix in computer vision, which encodes the epipolar geometry between two v...
Definition: FundamentalMatrix.h:28


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