test_Cal3Fisheye.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 Cal3Fisheye unit tests.
9 Author: Frank Dellaert & Duy Nguyen Ta (Python)
10 Refactored: Roderick Koehle
11 """
12 import unittest
13 
14 import numpy as np
15 from gtsam.symbol_shorthand import K, L, P
16 from gtsam.utils.test_case import GtsamTestCase
17 
18 import gtsam
19 
20 
21 def ulp(ftype=np.float64):
22  """
23  Unit in the last place of floating point datatypes
24  """
25  f = np.finfo(ftype)
26  return f.tiny / ftype(1 << f.nmant)
27 
28 
30 
31  @classmethod
32  def setUpClass(cls):
33  """
34  Equidistant fisheye projection
35 
36  An equidistant fisheye projection with focal length f is defined
37  as the relation r/f = tan(theta), with r being the radius in the
38  image plane and theta the incident angle of the object point.
39  """
40  x, y, z = 1.0, 0.0, 1.0
41  u, v = np.arctan2(x, z), 0.0
42  cls.obj_point = np.array([x, y, z])
43  cls.img_point = np.array([u, v])
44 
45  p1 = [-1.0, 0.0, -1.0]
46  p2 = [ 1.0, 0.0, -1.0]
47  q1 = gtsam.Rot3(1.0, 0.0, 0.0, 0.0)
48  q2 = gtsam.Rot3(1.0, 0.0, 0.0, 0.0)
49  pose1 = gtsam.Pose3(q1, p1)
50  pose2 = gtsam.Pose3(q2, p2)
51  camera1 = gtsam.PinholeCameraCal3Fisheye(pose1)
52  camera2 = gtsam.PinholeCameraCal3Fisheye(pose2)
53  cls.origin = np.array([0.0, 0.0, 0.0])
54  cls.poses = [pose1, pose2]
55  cls.cameras = [camera1, camera2]
56  cls.measurements = [k.project(cls.origin) for k in cls.cameras]
57 
58  def test_Cal3Fisheye(self):
59  K = gtsam.Cal3Fisheye()
60  self.assertEqual(K.fx(), 1.)
61  self.assertEqual(K.fy(), 1.)
62 
63  def test_distortion(self):
64  """Fisheye distortion and rectification"""
65  equidistant = gtsam.Cal3Fisheye()
66  perspective_pt = self.obj_point[0:2] / self.obj_point[2]
67  distorted_pt = equidistant.uncalibrate(perspective_pt)
68  rectified_pt = equidistant.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 equidistant camera projection"""
75  pt1 = camera.Project(self.obj_point) # Perspective projection
76  pt2 = camera.project(self.obj_point) # Equidistant projection
77  x, y, z = self.obj_point
78  obj1 = camera.backproject(self.img_point, z)
79  r1 = camera.range(self.obj_point)
80  r = np.linalg.norm(self.obj_point)
81  self.gtsamAssertEquals(pt1, np.array([x/z, y/z]))
82  self.gtsamAssertEquals(pt2, self.img_point)
83  self.gtsamAssertEquals(obj1, self.obj_point)
84  self.assertEqual(r1, r)
85 
87  """Evaluate residual using pose and point as state variables"""
89  state = gtsam.Values()
90  measured = self.img_point
91  noise_model = gtsam.noiseModel.Isotropic.Sigma(2, 1)
92  pose_key, point_key = P(0), L(0)
93  k = gtsam.Cal3Fisheye()
94  state.insert_pose3(pose_key, gtsam.Pose3())
95  state.insert_point3(point_key, self.obj_point)
96  factor = gtsam.GenericProjectionFactorCal3Fisheye(measured, noise_model, pose_key, point_key, k)
97  graph.add(factor)
98  score = graph.error(state)
99  self.assertAlmostEqual(score, 0)
100 
101  def test_sfm_factor2(self):
102  """Evaluate residual with camera, pose and point as state variables"""
104  state = gtsam.Values()
105  measured = self.img_point
106  noise_model = gtsam.noiseModel.Isotropic.Sigma(2, 1)
107  camera_key, pose_key, landmark_key = K(0), P(0), L(0)
108  k = gtsam.Cal3Fisheye()
109  state.insert_cal3fisheye(camera_key, k)
110  state.insert_pose3(pose_key, gtsam.Pose3())
111  state.insert_point3(landmark_key, gtsam.Point3(self.obj_point))
112  factor = gtsam.GeneralSFMFactor2Cal3Fisheye(measured, noise_model, pose_key, landmark_key, camera_key)
113  graph.add(factor)
114  score = graph.error(state)
115  self.assertAlmostEqual(score, 0)
116 
118  """Check of jacobian at optical axis"""
119  obj_point_on_axis = np.array([0, 0, 1])
120  img_point = np.array([0, 0])
121  f, z, H = self.evaluate_jacobian(obj_point_on_axis, img_point)
122  self.assertAlmostEqual(f, 0)
123  self.gtsamAssertEquals(z, np.zeros(2))
124  self.gtsamAssertEquals(H @ H.T, 3*np.eye(2))
125 
127  """Test stability of jacobian close to optical axis"""
128  t = ulp(np.float64)
129  obj_point_close_to_axis = np.array([t, 0, 1])
130  img_point = np.array([np.sqrt(t), 0])
131  f, z, H = self.evaluate_jacobian(obj_point_close_to_axis, img_point)
132  self.assertAlmostEqual(f, 0)
133  self.gtsamAssertEquals(z, np.zeros(2))
134  self.gtsamAssertEquals(H @ H.T, 3*np.eye(2))
135 
136  # With a height of sqrt(ulp), this may cause an overflow
137  t = ulp(np.float64)
138  obj_point_close_to_axis = np.array([np.sqrt(t), 0, 1])
139  img_point = np.array([np.sqrt(t), 0])
140  f, z, H = self.evaluate_jacobian(obj_point_close_to_axis, img_point)
141  self.assertAlmostEqual(f, 0)
142  self.gtsamAssertEquals(z, np.zeros(2))
143  self.gtsamAssertEquals(H @ H.T, 3*np.eye(2))
144 
146  """Check convergence of atan2(r, z)/r ~ 1/z for small r"""
147  r = ulp(np.float64)
148  s = np.arctan(r) / r
149  self.assertEqual(s, 1.0)
150  z = 1
151  s = self.scaling_factor(r, z)
152  self.assertEqual(s, 1.0/z)
153  z = 2
154  s = self.scaling_factor(r, z)
155  self.assertEqual(s, 1.0/z)
156  s = self.scaling_factor(2*r, z)
157  self.assertEqual(s, 1.0/z)
158 
159  @staticmethod
160  def scaling_factor(r, z):
161  """Projection factor theta/r for equidistant fisheye lens model"""
162  return np.arctan2(r, z) / r if r/z != 0 else 1.0/z
163 
164  @staticmethod
165  def evaluate_jacobian(obj_point, img_point):
166  """Evaluate jacobian at given object point"""
167  pose = gtsam.Pose3()
168  camera = gtsam.Cal3Fisheye()
169  state = gtsam.Values()
170  pose_key, landmark_key = P(0), L(0)
171  state.insert_point3(landmark_key, obj_point)
172  state.insert_pose3(pose_key, pose)
174  noise_model = gtsam.noiseModel.Unit.Create(2)
175  factor = gtsam.GenericProjectionFactorCal3Fisheye(img_point, noise_model, pose_key, landmark_key, camera)
176  g.add(factor)
177  f = g.error(state)
178  gaussian_factor_graph = g.linearize(state)
179  H, z = gaussian_factor_graph.jacobian()
180  return f, z, H
181 
182  @unittest.skip("triangulatePoint3 currently seems to require perspective projections.")
184  """Estimate spatial point from image measurements"""
185  triangulated = gtsam.triangulatePoint3(self.cameras, self.measurements, rank_tol=1e-9, optimize=True)
186  self.gtsamAssertEquals(triangulated, self.origin)
187 
189  """Estimate spatial point from image measurements using rectification"""
190  rectified = [k.calibration().calibrate(pt) for k, pt in zip(self.cameras, self.measurements)]
191  shared_cal = gtsam.Cal3_S2()
192  triangulated = gtsam.triangulatePoint3(self.poses, shared_cal, rectified, rank_tol=1e-9, optimize=False)
193  self.gtsamAssertEquals(triangulated, self.origin)
194 
195  def test_retract(self):
196  expected = gtsam.Cal3Fisheye(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6,
197  1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10)
198  k = gtsam.Cal3Fisheye(100, 105, 0.0, 320, 240,
199  1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3)
200  d = np.array([2, 3, 4, 5, 6, 7, 8, 9, 10], order='F')
201  actual = k.retract(d)
202  self.gtsamAssertEquals(actual, expected)
203  np.testing.assert_allclose(d, k.localCoordinates(actual))
204 
205 
206 if __name__ == "__main__":
207  unittest.main()
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
def ulp(ftype=np.float64)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
MatrixXd L
Definition: LLT_example.cpp:6
def evaluate_jacobian(obj_point, img_point)
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
Vector3 Point3
Definition: Point3.h:38
Calibration of a fisheye camera.
Definition: Cal3Fisheye.h:51
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594


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