2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
6 See LICENSE for the license information
8 Cal3Fisheye unit tests.
9 Author: Frank Dellaert & Duy Nguyen Ta (Python)
10 Refactored: Roderick Koehle
21 def ulp(ftype=np.float64):
23 Unit in the last place of floating point datatypes
26 return f.tiny / ftype(1 << f.nmant)
34 Equidistant fisheye projection
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.
40 x, y, z = 1.0, 0.0, 1.0
41 u, v = np.arctan2(x, z), 0.0
45 p1 = [-1.0, 0.0, -1.0]
46 p2 = [ 1.0, 0.0, -1.0]
53 cls.
origin = np.array([0.0, 0.0, 0.0])
60 self.assertEqual(K.fx(), 1.)
61 self.assertEqual(K.fy(), 1.)
64 """Fisheye distortion and rectification"""
67 distorted_pt = equidistant.uncalibrate(perspective_pt)
68 rectified_pt = equidistant.calibrate(distorted_pt)
73 """Spatial equidistant camera projection"""
78 obj1 = camera.backproject(self.
img_point, z)
84 self.assertEqual(r1, r)
87 """Evaluate residual using pose and point as state variables"""
92 pose_key, point_key =
P(0),
L(0)
95 state.insert_point3(point_key, self.
obj_point)
96 factor = gtsam.GenericProjectionFactorCal3Fisheye(measured, noise_model, pose_key, point_key, k)
98 score = graph.error(state)
99 self.assertAlmostEqual(score, 0)
102 """Evaluate residual with camera, pose and point as state variables"""
107 camera_key, pose_key, landmark_key =
K(0),
P(0),
L(0)
109 state.insert_cal3fisheye(camera_key, k)
112 factor = gtsam.GeneralSFMFactor2Cal3Fisheye(measured, noise_model, pose_key, landmark_key, camera_key)
114 score = graph.error(state)
115 self.assertAlmostEqual(score, 0)
118 """Check of jacobian at optical axis"""
119 obj_point_on_axis = np.array([0, 0, 1])
120 img_point = np.array([0, 0])
122 self.assertAlmostEqual(f, 0)
127 """Test stability of jacobian close to optical axis"""
129 obj_point_close_to_axis = np.array([t, 0, 1])
130 img_point = np.array([np.sqrt(t), 0])
132 self.assertAlmostEqual(f, 0)
138 obj_point_close_to_axis = np.array([np.sqrt(t), 0, 1])
139 img_point = np.array([np.sqrt(t), 0])
141 self.assertAlmostEqual(f, 0)
146 """Check convergence of atan2(r, z)/r ~ 1/z for small r"""
149 self.assertEqual(s, 1.0)
152 self.assertEqual(s, 1.0/z)
155 self.assertEqual(s, 1.0/z)
157 self.assertEqual(s, 1.0/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
166 """Evaluate jacobian at given object point"""
170 pose_key, landmark_key =
P(0),
L(0)
171 state.insert_point3(landmark_key, obj_point)
172 state.insert_pose3(pose_key, pose)
175 factor = gtsam.GenericProjectionFactorCal3Fisheye(img_point, noise_model, pose_key, landmark_key, camera)
178 gaussian_factor_graph = g.linearize(state)
179 H, z = gaussian_factor_graph.jacobian()
182 @unittest.skip(
"triangulatePoint3 currently seems to require perspective projections.")
184 """Estimate spatial point from image measurements"""
189 """Estimate spatial point from image measurements using rectification"""
190 rectified = [k.calibration().calibrate(pt)
for k, pt
in zip(self.
cameras, self.
measurements)]
197 1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10)
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)
203 np.testing.assert_allclose(d, k.localCoordinates(actual))
206 if __name__ ==
"__main__":