2 GTSAM Copyright 2010, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
5 Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 See LICENSE for the license information
11 Python version of EssentialViewGraphExample.cpp
12 View-graph calibration with essential matrices.
13 Author: Frank Dellaert
21 from gtsam
import Cal3f, EdgeKey, EssentialMatrix
22 from gtsam
import EssentialTransferFactorCal3f
as Factor
23 from gtsam
import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
24 NonlinearFactorGraph, PinholeCameraCal3f, Values)
27 K = gtsam.symbol_shorthand.K
33 if sym.chr() == ord(
"k"):
34 return f
"k{sym.index()}"
37 return f
"({edge.i()},{edge.j()})"
42 cal =
Cal3f(50.0, 50.0, 50.0)
45 points = SFMdata.createPoints()
48 poses = SFMdata.posesOnCircle(4, 30)
51 E1 = EssentialMatrix.FromPose3(poses[0].
between(poses[1]))
52 E2 = EssentialMatrix.FromPose3(poses[0].
between(poses[2]))
55 p = [[
None for _
in range(8)]
for _
in range(4)]
57 camera = PinholeCameraCal3f(poses[i], cal)
59 p[i][j] = camera.project(points[j])
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]))
83 graph.print(
"graph", formatter)
86 delta = np.ones(5) * 1e-2
93 initialEstimate.insert(
EdgeKey(a, b).
key(), E1.retract(delta))
94 initialEstimate.insert(
EdgeKey(a, c).
key(), E2.retract(delta))
98 initialEstimate.insert(
K(i), cal)
102 params.setlambdaInitial(1000.0)
103 params.setVerbosityLM(
"SUMMARY")
105 result = optimizer.optimize()
107 print(
"Initial error = ", graph.error(initialEstimate))
108 print(
"Final error = ", graph.error(result))
111 print(
"Final Results:")
112 result.print(
"", formatter)
115 print(
"Ground Truth E1:\n", E1)
116 print(
"Ground Truth E2:\n", E2)
119 if __name__ ==
"__main__":