test_Cal3Unified.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 
6 See LICENSE for the license information
7 
8 Cal3Unified unit tests.
9 Author: Frank Dellaert & Duy Nguyen Ta (Python)
10 """
11 import unittest
12 
13 import numpy as np
14 from gtsam.symbol_shorthand import K, L, P
15 from gtsam.utils.test_case import GtsamTestCase
16 
17 import gtsam
18 
19 
21 
22  @classmethod
23  def setUpClass(cls):
24  """
25  Stereographic fisheye projection
26 
27  An equidistant fisheye projection with focal length f is defined
28  as the relation r/f = 2*tan(theta/2), with r being the radius in the
29  image plane and theta the incident angle of the object point.
30  """
31  x, y, z = 1.0, 0.0, 1.0
32  r = np.linalg.norm([x, y, z])
33  u, v = 2*x/(z+r), 0.0
34  cls.obj_point = np.array([x, y, z])
35  cls.img_point = np.array([u, v])
36 
37  fx, fy, s, u0, v0 = 2, 2, 0, 0, 0
38  k1, k2, p1, p2 = 0, 0, 0, 0
39  xi = 1
40  cls.stereographic = gtsam.Cal3Unified(fx, fy, s, u0, v0, k1, k2, p1, p2, xi)
41 
42  p1 = [-1.0, 0.0, -1.0]
43  p2 = [ 1.0, 0.0, -1.0]
44  q1 = gtsam.Rot3(1.0, 0.0, 0.0, 0.0)
45  q2 = gtsam.Rot3(1.0, 0.0, 0.0, 0.0)
46  pose1 = gtsam.Pose3(q1, p1)
47  pose2 = gtsam.Pose3(q2, p2)
48  camera1 = gtsam.PinholeCameraCal3Unified(pose1, cls.stereographic)
49  camera2 = gtsam.PinholeCameraCal3Unified(pose2, cls.stereographic)
50  cls.origin = np.array([0.0, 0.0, 0.0])
51  cls.poses = [pose1, pose2]
52  cls.cameras = [camera1, camera2]
53  cls.measurements = [k.project(cls.origin) for k in cls.cameras]
54 
55  def test_Cal3Unified(self):
56  K = gtsam.Cal3Unified()
57  self.assertEqual(K.fx(), 1.)
58  self.assertEqual(K.fx(), 1.)
59 
60  def test_distortion(self):
61  """Stereographic fisheye model of focal length f, defined as r/f = 2*tan(theta/2)"""
62  x, y, z = self.obj_point
63  r = np.linalg.norm([x, y, z])
64  # Note: 2*tan(atan2(x, z)/2) = 2*x/(z+sqrt(x^2+z^2))
65  self.assertAlmostEqual(2*np.tan(np.arctan2(x, z)/2), 2*x/(z+r))
66  perspective_pt = self.obj_point[0:2]/self.obj_point[2]
67  distorted_pt = self.stereographic.uncalibrate(perspective_pt)
68  rectified_pt = self.stereographic.calibrate(distorted_pt)
69  self.gtsamAssertEquals(distorted_pt, self.img_point)
70  self.gtsamAssertEquals(rectified_pt, perspective_pt)
71 
72  def test_pinhole(self):
73  """Spatial stereographic camera projection"""
74  x, y, z = self.obj_point
75  u, v = self.img_point
76  r = np.linalg.norm(self.obj_point)
77  pose = gtsam.Pose3()
79  pt1 = camera.Project(self.obj_point)
80  self.gtsamAssertEquals(pt1, np.array([x/z, y/z]))
81  pt2 = camera.project(self.obj_point)
82  self.gtsamAssertEquals(pt2, self.img_point)
83  obj1 = camera.backproject(self.img_point, z)
84  self.gtsamAssertEquals(obj1, self.obj_point)
85  r1 = camera.range(self.obj_point)
86  self.assertEqual(r1, r)
87 
89  """Evaluate residual using pose and point as state variables"""
91  state = gtsam.Values()
92  measured = self.img_point
93  noise_model = gtsam.noiseModel.Isotropic.Sigma(2, 1)
94  pose_key, point_key = P(0), L(0)
95  k = self.stereographic
96  state.insert_pose3(pose_key, gtsam.Pose3())
97  state.insert_point3(point_key, self.obj_point)
98  factor = gtsam.GenericProjectionFactorCal3Unified(measured, noise_model, pose_key, point_key, k)
99  graph.add(factor)
100  score = graph.error(state)
101  self.assertAlmostEqual(score, 0)
102 
103  def test_sfm_factor2(self):
104  """Evaluate residual with camera, pose and point as state variables"""
105  r = np.linalg.norm(self.obj_point)
107  state = gtsam.Values()
108  measured = self.img_point
109  noise_model = gtsam.noiseModel.Isotropic.Sigma(2, 1)
110  camera_key, pose_key, landmark_key = K(0), P(0), L(0)
111  k = self.stereographic
112  state.insert_cal3unified(camera_key, k)
113  state.insert_pose3(pose_key, gtsam.Pose3())
114  state.insert_point3(landmark_key, self.obj_point)
115  factor = gtsam.GeneralSFMFactor2Cal3Unified(measured, noise_model, pose_key, landmark_key, camera_key)
116  graph.add(factor)
117  score = graph.error(state)
118  self.assertAlmostEqual(score, 0)
119 
120  def test_jacobian(self):
121  """Evaluate jacobian at optical axis"""
122  obj_point_on_axis = np.array([0, 0, 1])
123  img_point = np.array([0.0, 0.0])
124  pose = gtsam.Pose3()
125  camera = gtsam.Cal3Unified()
126  state = gtsam.Values()
127  camera_key, pose_key, landmark_key = K(0), P(0), L(0)
128  state.insert_cal3unified(camera_key, camera)
129  state.insert_point3(landmark_key, obj_point_on_axis)
130  state.insert_pose3(pose_key, pose)
132  noise_model = gtsam.noiseModel.Unit.Create(2)
133  factor = gtsam.GeneralSFMFactor2Cal3Unified(img_point, noise_model, pose_key, landmark_key, camera_key)
134  g.add(factor)
135  f = g.error(state)
136  gaussian_factor_graph = g.linearize(state)
137  H, z = gaussian_factor_graph.jacobian()
138  self.assertAlmostEqual(f, 0)
139  self.gtsamAssertEquals(z, np.zeros(2))
140  self.gtsamAssertEquals(H @ H.T, 4*np.eye(2))
141 
142  Dcal = np.zeros((2, 10), order='F')
143  Dp = np.zeros((2, 2), order='F')
144  camera.calibrate(img_point, Dcal, Dp)
145 
146  self.gtsamAssertEquals(Dcal, np.array(
147  [[ 0., 0., 0., -1., 0., 0., 0., 0., 0., 0.],
148  [ 0., 0., 0., 0., -1., 0., 0., 0., 0., 0.]]))
149  self.gtsamAssertEquals(Dp, np.array(
150  [[ 1., -0.],
151  [-0., 1.]]))
152 
153  @unittest.skip("triangulatePoint3 currently seems to require perspective projections.")
155  """Estimate spatial point from image measurements"""
156  triangulated = gtsam.triangulatePoint3(self.cameras, self.measurements, rank_tol=1e-9, optimize=True)
157  self.gtsamAssertEquals(triangulated, self.origin)
158 
160  """Estimate spatial point from image measurements using rectification"""
161  rectified = [k.calibration().calibrate(pt) for k, pt in zip(self.cameras, self.measurements)]
162  shared_cal = gtsam.Cal3_S2()
163  triangulated = gtsam.triangulatePoint3(self.poses, shared_cal, rectified, rank_tol=1e-9, optimize=False)
164  self.gtsamAssertEquals(triangulated, self.origin)
165 
166  def test_retract(self):
167  expected = gtsam.Cal3Unified(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6,
168  1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10, 0.1 + 1)
169  K = gtsam.Cal3Unified(100, 105, 0.0, 320, 240,
170  1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3, 0.1)
171  d = np.array([2, 3, 4, 5, 6, 7, 8, 9, 10, 1], order='F')
172  actual = K.retract(d)
173  self.gtsamAssertEquals(actual, expected)
174  np.testing.assert_allclose(d, K.localCoordinates(actual))
175 
176 
177 if __name__ == "__main__":
178  unittest.main()
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
MatrixXd L
Definition: LLT_example.cpp:6
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
Point3 triangulatePoint3(const CameraSet< PinholeCamera< CALIBRATION >> &cameras, const Point2Vector &measurements, double rank_tol=1e-9, bool optimize=false, const SharedNoiseModel &model=nullptr, const bool useLOST=false)
Pinhole-specific version.
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
Calibration of a omni-directional camera with mirror + lens radial distortion.
Definition: Cal3Unified.h:45
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:37:45