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 ViewGraphExample.cpp
12 View-graph calibration on a simulated dataset, a la Sweeney 2015
13 Author: Frank Dellaert
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
30 return f
"({edge.i()},{edge.j()})"
35 cal =
Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)
38 points = SFMdata.createPoints()
41 poses = SFMdata.posesOnCircle(4, 30)
48 p = [[
None for _
in range(8)]
for _
in range(4)]
52 p[i][j] = camera.project(points[j])
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]))
78 graph.print(
"Factor Graph:\n", formatter)
81 delta = np.array([1, 2, 3, 4, 5, 6, 7]) * 1e-5
88 initialEstimate.insert(
EdgeKey(a, b).
key(), F1.retract(delta))
89 initialEstimate.insert(
EdgeKey(a, c).
key(), F2.retract(delta))
91 initialEstimate.print(
"Initial Estimates:\n", formatter)
92 graph.printErrors(initialEstimate,
"Initial Errors:\n", formatter)
96 params.setlambdaInitial(1000.0)
97 params.setVerbosityLM(
"SUMMARY")
99 result = optimizer.optimize()
101 print(f
"Initial error = {graph.error(initialEstimate)}")
102 print(f
"Final error = {graph.error(result)}")
104 result.print(
"Final Results:\n", formatter)
106 print(
"Ground Truth F1:\n", F1.matrix())
107 print(
"Ground Truth F2:\n", F2.matrix())
110 if __name__ ==
"__main__":