3 Transcription of SelfCalibrationExample.cpp
7 from gtsam
import Cal3_S2
11 from gtsam
import GeneralSFMFactor2Cal3_S2
12 from gtsam
import PinholeCameraCal3_S2
15 from gtsam
import Point2
16 from gtsam
import Point3, Pose3, Rot3
19 from gtsam
import NonlinearFactorGraph, DoglegOptimizer, Values
27 Create the set of ground-truth landmarks
32 Point3(-10.0, -10.0, 10.0),
35 Point3(-10.0, 10.0, -10.0),
36 Point3(-10.0, -10.0, -10.0),
37 Point3(10.0, -10.0, -10.0),
42 init: Pose3 =
Pose3(Rot3.Ypr(math.pi / 2, 0, -math.pi / 2),
Point3(30, 0, 0)),
44 Rot3.Ypr(0, -math.pi / 4, 0),
45 Point3(math.sin(math.pi / 4) * 30, 0, 30 * (1 - math.sin(math.pi / 4))),
50 Create the set of ground-truth poses
51 Default values give a circular trajectory,
52 radius 30 at pi/4 intervals, always facing the circle center
54 poses: list[Pose3] = []
56 for i
in range(1, steps):
57 poses.append(poses[i - 1].
compose(delta))
71 poseNoise = Diagonal.Sigmas([0.1, 0.1, 0.1, 0.3, 0.3, 0.3])
72 graph.addPriorPose3(
X(0), poses[0], poseNoise)
75 Kcal =
Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)
76 measurementNoise = Isotropic.Sigma(2, 1.0)
77 for i, pose
in enumerate(poses):
78 for j, point
in enumerate(points):
80 measurement: Point2 = camera.project(point)
95 pointNoise = Isotropic.Sigma(3, 0.1)
96 graph.addPriorPoint3(
L(0), points[0], pointNoise)
99 calNoise = Diagonal.Sigmas([500, 500, 0.1, 100, 100])
100 graph.addPriorCal3_S2(
K(0), Kcal, calNoise)
104 initialEstimate =
Values()
105 initialEstimate.insert(
K(0),
Cal3_S2(60.0, 60.0, 0.0, 45.0, 45.0))
106 for i, pose
in enumerate(poses):
107 initialEstimate.insert(
110 Pose3(Rot3.Rodrigues(-0.1, 0.2, 0.25),
Point3(0.05, -0.10, 0.20))
113 for j, point
in enumerate(points):
114 initialEstimate.insert(
L(j), point +
Point3(-0.25, 0.20, 0.15))
118 result.print(
"Final results:\n")
121 if __name__ ==
"__main__":