SelfCalibrationExample.py
Go to the documentation of this file.
1 # pylint: disable=unused-import,consider-using-from-import,invalid-name,no-name-in-module,no-member,missing-function-docstring,too-many-locals
2 """
3 Transcription of SelfCalibrationExample.cpp
4 """
5 import math
6 
7 from gtsam import Cal3_S2
8 from gtsam.noiseModel import Diagonal, Isotropic
9 
10 # SFM-specific factors
11 from gtsam import GeneralSFMFactor2Cal3_S2 # does calibration !
12 from gtsam import PinholeCameraCal3_S2
13 
14 # Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
15 from gtsam import Point2
16 from gtsam import Point3, Pose3, Rot3
17 
18 # Inference and optimization
19 from gtsam import NonlinearFactorGraph, DoglegOptimizer, Values
20 from gtsam.symbol_shorthand import K, L, X
21 
22 
23 # this is a direct translation of examples/SFMData.h
24 # which is slightly different from python/gtsam/examples/SFMdata.py.
25 def createPoints() -> list[Point3]:
26  """
27  Create the set of ground-truth landmarks
28  """
29  return [
30  Point3(10.0, 10.0, 10.0),
31  Point3(-10.0, 10.0, 10.0),
32  Point3(-10.0, -10.0, 10.0),
33  Point3(10.0, -10.0, 10.0),
34  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),
38  ]
39 
40 
42  init: Pose3 = Pose3(Rot3.Ypr(math.pi / 2, 0, -math.pi / 2), Point3(30, 0, 0)),
43  delta: Pose3 = Pose3(
44  Rot3.Ypr(0, -math.pi / 4, 0),
45  Point3(math.sin(math.pi / 4) * 30, 0, 30 * (1 - math.sin(math.pi / 4))),
46  ),
47  steps: int = 8,
48 ) -> list[Pose3]:
49  """
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
53  """
54  poses: list[Pose3] = []
55  poses.append(init)
56  for i in range(1, steps):
57  poses.append(poses[i - 1].compose(delta))
58  return poses
59 
60 
61 def main() -> None:
62  # Create the set of ground-truth
63  points: list[Point3] = createPoints()
64  poses: list[Pose3] = createPoses()
65 
66  # Create the factor graph
67  graph = NonlinearFactorGraph()
68 
69  # Add a prior on pose x1.
70  # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
71  poseNoise = Diagonal.Sigmas([0.1, 0.1, 0.1, 0.3, 0.3, 0.3])
72  graph.addPriorPose3(X(0), poses[0], poseNoise)
73 
74  # Simulated measurements from each camera pose, adding them to the factor graph
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):
79  camera = PinholeCameraCal3_S2(pose, Kcal)
80  measurement: Point2 = camera.project(point)
81  # The only real difference with the Visual SLAM example is that here we
82  # use a different factor type, that also calculates the Jacobian with
83  # respect to calibration
84  graph.add(
86  measurement,
87  measurementNoise,
88  X(i),
89  L(j),
90  K(0),
91  )
92  )
93 
94  # Add a prior on the position of the first landmark.
95  pointNoise = Isotropic.Sigma(3, 0.1)
96  graph.addPriorPoint3(L(0), points[0], pointNoise) # add directly to graph
97 
98  # Add a prior on the calibration.
99  calNoise = Diagonal.Sigmas([500, 500, 0.1, 100, 100])
100  graph.addPriorCal3_S2(K(0), Kcal, calNoise)
101 
102  # Create the initial estimate to the solution
103  # now including an estimate on the camera calibration parameters
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(
108  X(i),
109  pose.compose(
110  Pose3(Rot3.Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))
111  ),
112  )
113  for j, point in enumerate(points):
114  initialEstimate.insert(L(j), point + Point3(-0.25, 0.20, 0.15))
115 
116  # Optimize the graph and print results
117  result: Values = DoglegOptimizer(graph, initialEstimate).optimize()
118  result.print("Final results:\n")
119 
120 
121 if __name__ == "__main__":
122  main()
gtsam.examples.SelfCalibrationExample.main
None main()
Definition: SelfCalibrationExample.py:61
gtsam::optimize
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Definition: triangulation.cpp:177
gtsam::symbol_shorthand
Definition: inference/Symbol.h:147
X
#define X
Definition: icosphere.cpp:20
gtsam::compose
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:23
gtsam::DoglegOptimizer
Definition: DoglegOptimizer.h:68
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
gtsam.examples.SelfCalibrationExample.createPoses
list[Pose3] createPoses(Pose3 init=Pose3(Rot3.Ypr(math.pi/2, 0, -math.pi/2), Point3(30, 0, 0)), Pose3 delta=Pose3(Rot3.Ypr(0, -math.pi/4, 0), Point3(math.sin(math.pi/4) *30, 0, 30 *(1 - math.sin(math.pi/4))),), int steps=8)
Definition: SelfCalibrationExample.py:41
gtsam::Pose3
Definition: Pose3.h:37
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
GeneralSFMFactor2Cal3_S2
gtsam::GeneralSFMFactor2< gtsam::Cal3_S2 > GeneralSFMFactor2Cal3_S2
Definition: serialization.cpp:83
L
MatrixXd L
Definition: LLT_example.cpp:6
gtsam.examples.SelfCalibrationExample.createPoints
list[Point3] createPoints()
Definition: SelfCalibrationExample.py:25
K
#define K
Definition: igam.h:8
gtsam::Values
Definition: Values.h:65
gtsam::noiseModel
All noise models live in the noiseModel namespace.
Definition: LossFunctions.cpp:28
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38


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