2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 8 Cal3Unified unit tests. 9 Author: Frank Dellaert & Duy Nguyen Ta (Python) 25 Stereographic fisheye projection 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. 31 x, y, z = 1.0, 0.0, 1.0
32 r = np.linalg.norm([x, y, z])
37 fx, fy, s, u0, v0 = 2, 2, 0, 0, 0
38 k1, k2, p1, p2 = 0, 0, 0, 0
42 p1 = [-1.0, 0.0, -1.0]
43 p2 = [ 1.0, 0.0, -1.0]
50 cls.
origin = np.array([0.0, 0.0, 0.0])
57 self.assertEqual(K.fx(), 1.)
58 self.assertEqual(K.fx(), 1.)
61 """Stereographic fisheye model of focal length f, defined as r/f = 2*tan(theta/2)""" 63 r = np.linalg.norm([x, y, z])
65 self.assertAlmostEqual(2*np.tan(np.arctan2(x, z)/2), 2*x/(z+r))
73 """Spatial stereographic camera projection""" 83 obj1 = camera.backproject(self.
img_point, z)
86 self.assertEqual(r1, r)
89 """Evaluate residual using pose and point as state variables""" 94 pose_key, point_key =
P(0),
L(0)
97 state.insert_point3(point_key, self.
obj_point)
98 factor = gtsam.GenericProjectionFactorCal3Unified(measured, noise_model, pose_key, point_key, k)
100 score = graph.error(state)
101 self.assertAlmostEqual(score, 0)
104 """Evaluate residual with camera, pose and point as state variables""" 110 camera_key, pose_key, landmark_key =
K(0),
P(0),
L(0)
112 state.insert_cal3unified(camera_key, k)
114 state.insert_point3(landmark_key, self.
obj_point)
115 factor = gtsam.GeneralSFMFactor2Cal3Unified(measured, noise_model, pose_key, landmark_key, camera_key)
117 score = graph.error(state)
118 self.assertAlmostEqual(score, 0)
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])
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)
133 factor = gtsam.GeneralSFMFactor2Cal3Unified(img_point, noise_model, pose_key, landmark_key, camera_key)
136 gaussian_factor_graph = g.linearize(state)
137 H, z = gaussian_factor_graph.jacobian()
138 self.assertAlmostEqual(f, 0)
142 Dcal = np.zeros((2, 10), order=
'F')
143 Dp = np.zeros((2, 2), order=
'F')
144 camera.calibrate(img_point, Dcal, Dp)
147 [[ 0., 0., 0., -1., 0., 0., 0., 0., 0., 0.],
148 [ 0., 0., 0., 0., -1., 0., 0., 0., 0., 0.]]))
153 @unittest.skip(
"triangulatePoint3 currently seems to require perspective projections.")
155 """Estimate spatial point from image measurements""" 160 """Estimate spatial point from image measurements using rectification""" 161 rectified = [k.calibration().calibrate(pt)
for k, pt
in zip(self.
cameras, self.
measurements)]
168 1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10, 0.1 + 1)
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)
174 np.testing.assert_allclose(d, K.localCoordinates(actual))
177 if __name__ ==
"__main__":
def test_generic_factor(self)
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
def test_distortion(self)
def test_triangulation(self)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static shared_ptr Create(size_t dim)
def test_sfm_factor2(self)
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.
Calibration of a omni-directional camera with mirror + lens radial distortion.
def test_triangulation_rectify(self)
def test_Cal3Unified(self)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)