diff --git a/image_geometry/image_geometry/cameramodels.py b/image_geometry/image_geometry/cameramodels.py index a6cf27f0..86a5be24 100644 --- a/image_geometry/image_geometry/cameramodels.py +++ b/image_geometry/image_geometry/cameramodels.py @@ -3,8 +3,6 @@ import copy import numpy import numpy as np -import warnings -from deprecated.sphinx import deprecated def _mkmat(rows, cols, L) -> numpy.ndarray: mat = np.array(L,dtype='float64') @@ -334,418 +332,6 @@ def get_tf_frame(self)->str: """ return self._tf_frame - # Deprecated members planned for removal in K-turtle - # -------------------------------------------------- - @property - @deprecated(version="J-turtle", reason="The binning_x property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.") - def binning_x(self): - """ - .. warning:: - The binning_x property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._binning_x - - @property - @deprecated(version="J-turtle", reason="The binning_y property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.") - def binning_y(self): - """ - .. warning:: - The binning_y property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._binning_y - - @property - @deprecated(version="J-turtle", reason="The D->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the distortion_coeffs()->numpy.ndarray method instead.") - def D(self)->numpy.matrix: - """ - .. warning:: - The D property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return numpy.matrix(self._d, dtype="float64") - - @property - @deprecated(version="J-turtle", reason="The full_K->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_intrinsic_matrix()->numpy.ndarray method instead.") - def full_K(self)->numpy.matrix: - """ - .. warning:: - The full_K property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return numpy.matrix(self._full_k, dtype="float64") - - @property - @deprecated(version="J-turtle", reason="The full_P->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_projection_matrix()->numpy.ndarray method instead.") - def full_P(self)->numpy.matrix: - """ - .. warning:: - The full_P property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return numpy.matrix(self._full_p, dtype="float64") - - @property - @deprecated(version="J-turtle", reason="The height property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.") - def height(self): - """ - .. warning:: - The height property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._height - - @property - @deprecated(version="J-turtle", reason="The K->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the intrinsic_matrix()->numpy.ndarray method instead.") - def K(self)->numpy.matrix: - """ - .. warning:: - The K property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return numpy.matrix(self._k, dtype="float64") - - @property - @deprecated(version="J-turtle", reason="The P->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the projection_matrix()->numpy.ndarray method instead.") - def P(self)->numpy.matrix: - """ - .. warning:: - The P property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return numpy.matrix(self._p, dtype="float64") - - @property - @deprecated(version="J-turtle", reason="The R->numpy.matrix property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rotation_matrix()->numpy.ndarray method instead.") - def R(self)->numpy.matrix: - """ - .. warning:: - The R property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return numpy.matrix(self._r) - - @property - @deprecated(version="J-turtle", reason="The binning_y property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.") - def raw_roi(self): - """ - .. warning:: - The raw_roi property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._raw_roi - - @property - @deprecated(version="J-turtle", reason="The stamp property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.") - def stamp(self): - """ - .. warning:: - The stamp property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._stamp - - @property - @deprecated(version="J-turtle", reason="The tf_frame property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_tf_frame() method.") - def tf_frame(self): - """ - .. warning:: - The tf_frame property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._tf_frame - - @property - @deprecated(version="J-turtle", reason="The width property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.") - def width(self): - """ - .. warning:: - The width property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._width - - @deprecated(version="J-turtle", reason="The distortionCoeffs()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the distortion_coeffs()->numpy.ndarray method instead.") - def distortionCoeffs(self)->numpy.matrix: - """ - .. warning:: - The distortionCoeffs()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the distortion_coeffs()->numpy.ndarray method instead." - - :rtype: numpy.matrix - - Returns :math:`D` - """ - return numpy.matrix(self.distortion_coeffs(), dtype="float64") - - @deprecated(version="J-turtle", reason="The fovX() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the fov_x() method instead.") - def fovX(self)->float: - """ - .. warning:: - The fovX() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the fov_x() method instead. - - :rtype: float - - Returns the horizontal field of view in radians. - Horizontal FoV = 2 * arctan((width) / (2 * Horizontal Focal Length) ) - """ - return self.fov_x() - - @deprecated(version="J-turtle", reason="The fovY() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the fov_y() method instead.") - def fovY(self)->float: - """ - .. warning:: - The fovY() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the fov_y() method instead. - - :rtype: float - - Returns the vertical field of view in radians. - Vertical FoV = 2 * arctan((height) / (2 * Vertical Focal Length) ) - """ - return self.fov_y() - - @deprecated(version="J-turtle", reason="The fromCameraInfo() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the from_camera_info() method instead.") - def fromCameraInfo(self,msg)->None: - """ - .. warning:: - The fromCameraInfo() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the from_camera_info() method instead. - - :param msg: camera parameters - :type msg: sensor_msgs.msg.CameraInfo - - Set the camera parameters from the :class:`sensor_msgs.msg.CameraInfo` message. - """ - self.from_camera_info(msg) - - @deprecated(version="J-turtle", reason="The fullIntrinsicMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_intrinsic_matrix()->numpy.ndarray method instead.") - def fullIntrinsicMatrix(self) -> numpy.matrix: - """ - .. warning:: - The fullIntrinsicMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_intrinsic_matrix()->numpy.ndarray method instead. - - :rtype: numpy.matrix - - Return the original camera matrix for full resolution - """ - return numpy.matrix(self.full_intrinsic_matrix(), dtype='float64') - - @deprecated(version="J-turtle", reason="The fullProjectionMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_projection_matrix()->numpy.ndarray method instead.") - def fullProjectionMatrix(self)->numpy.matrix: - """ - .. warning:: - The fullProjectionMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_projection_matrix()->numpy.ndarray method instead. - - :rtype: numpy.matrix - - Return the projection matrix for full resolution """ - return numpy.matrix(self.full_projection_matrix(), dtype='float64') - - @deprecated(version="J-turtle", reason="The fullResolution() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_resolution() method instead.") - def fullResolution(self)->tuple[int, int]: - """ - .. warning:: - The fullResolution() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the full_resolution() method instead. - - :rtype: tuple[int, int] - - Returns the full resolution of the camera as a tuple in the format (width, height) - """ - return self.full_resolution() - - @deprecated(version="J-turtle", reason="The getDeltaU() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_u() method instead.") - def getDeltaU(self, deltaX, Z)->float: - """ - .. warning:: - The getDeltaU() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_u() method instead. - - :param deltaX: delta X, in cartesian space - :type deltaX: float - :param Z: Z, in cartesian space - :type Z: float - :rtype: float - - Compute delta u, given Z and delta X in Cartesian space. - For given Z, this is the inverse of :math:`get_delta_x`. - """ - return self.get_delta_u(deltaX, Z) - - @deprecated(version="J-turtle", reason="The getDeltaV() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_v() method instead.") - def getDeltaV(self, deltaY, Z)->float: - """ - .. warning:: - he getDeltaV() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_v() method instead. - - :param deltaY: delta Y, in cartesian space - :type deltaY: float - :param Z: Z, in cartesian space - :type Z: float - :rtype: float - - Compute delta v, given Z and delta Y in Cartesian space. - For given Z, this is the inverse of :math:`get_delta_y`. - - """ - return(self.get_delta_v(deltaY,Z)) - - @deprecated(version="J-turtle", reason="The getDeltaX() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_x() method instead.") - def getDeltaX(self, deltaU, Z)->float: - """ - .. warning:: - The getDeltaX() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_x() method instead. - - :param deltaU: delta u in pixels - :type deltaU: float - :param Z: Z, in cartesian space - :type Z: float - :rtype: float - - Compute delta X, given Z in cartesian space and delta u in pixels. - For given Z, this is the inverse of :math:`get_delta_u`. - """ - return self.get_delta_x(deltaU,Z) - - @deprecated(version="J-turtle", reason="The getDeltaY() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_y() method instead.") - def getDeltaY(self, deltaV, Z)->float: - """ - .. warning:: - The getDeltaY() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_delta_y() method instead. - - :param deltaV: delta v in pixels - :type deltaV: float - :param Z: Z, in cartesian space - :type Z: float - :rtype: float - - Compute delta Y, given Z in cartesian space and delta v in pixels. - For given Z, this is the inverse of :math:`get_delta_v`. - """ - return self.get_delta_y(deltaV,Z) - - @deprecated(version="J-turtle", reason="The intrinsicMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the intrinsic_matrix()->numpy.ndarray method instead.") - def intrinsicMatrix(self)->numpy.matrix: - """ - .. warning:: - The intrinsicMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the intrinsic_matrix()->numpy.ndarray method instead. - - :rtype: numpy.matrix - - Returns :math:`K`, also called camera_matrix in cv docs - """ - return numpy.matrix(self.intrinsic_matrix(), dtype="float64") - - @deprecated(version="J-turtle", reason="The project3dToPixel() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_3d_to_pixel() method instead.") - def project3dToPixel(self, point)->tuple[float,float]: - """ - .. warning:: - The project3dToPixel() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_3d_to_pixel() method instead. - - :param point: 3D point - :type point: (x, y, z) - :rtype: tuple[float,float] - - Returns the rectified pixel coordinates (u, v) of the 3D point, - using the camera :math:`P` matrix. - This is the inverse of :math:`projectPixelTo3dRay`. - """ - return self.project_3d_to_pixel(point) - - @deprecated(version="J-turtle", reason="The projectionMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the projection_matrix()->numpy.ndarray method instead.") - def projectionMatrix(self) -> numpy.matrix: - """ - .. warning:: - The projectionMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the projection_matrix()->numpy.ndarray method instead. - - :rtype: numpy.matrix - - Returns :math:`P` - """ - return np.matrix(self.projection_matrix(), dtype='float64') - - @deprecated(version="J-turtle", reason="The projectPixelTo3dRay() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_pixel_to_3d_ray() method instead.") - def projectPixelTo3dRay(self, uv)->tuple[float,float,float]: - """ - .. warning:: - The projectPixelTo3dRay() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_pixel_to_3d_ray() method instead. - - :param uv: rectified pixel coordinates - :type uv: (u, v) - :rtype: tuple[float,float,float] - - Returns the unit vector which passes from the camera center to through rectified pixel (u, v), - using the camera :math:`P` matrix. - This is the inverse of :math:`project_3d_to_pixel`. - """ - return self.project_pixel_to_3d_ray(uv) - - @deprecated(version="J-turtle", reason="The rectifyImage() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rectify_image() method instead.") - def rectifyImage(self, raw, rectified): - """ - .. warning:: - The rectifyImage() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rectify_image() method instead. - - :param raw: input image - :type raw: :class:`CvMat` or :class:`IplImage` - :param rectified: rectified output image - :type rectified: :class:`CvMat` or :class:`IplImage` - - Applies the rectification specified by camera parameters :math:`K` and and :math:`D` to image `raw` and writes the resulting image `rectified`. - """ - self.rectify_image(raw, rectified) - - @deprecated(version="J-turtle", reason="The rectifyPoint() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rectify_point() method instead.") - def rectifyPoint(self, uv_raw)->numpy.ndarray: - """ - .. warning:: - The rectifyPoint() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rectify_point() method instead. - - :param uv_raw: pixel coordinates - :type uv_raw: (u, v) - :rtype: numpy.ndarray - - Applies the rectification specified by camera parameters - :math:`K` and and :math:`D` to point (u, v) and returns the - pixel coordinates of the rectified point. - """ - return self.rectify_point(uv_raw) - - @deprecated(version="J-turtle", reason="The rotationMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rotation_matrix()->numpy.ndarray method instead.") - def rotationMatrix(self)->numpy.matrix: - """ - .. warning:: - The rotationMatrix()->numpy.matrix method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the rotation_matrix()->numpy.ndarray method instead. - - :rtype: numpy.matrix - - Returns :math:`R` - """ - return np.matrix(self.rotation_matrix(), dtype='float64') - - @deprecated(version="J-turtle", reason="The tfFrame() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_tf_frame() method instead.") - def tfFrame(self)->str: - """ - .. warning:: - The tfFrame() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_tf_frame() method instead. - - :rtype: str - - Returns the tf frame name - a string - of the camera. - This is the frame of the :class:`sensor_msgs.msg.CameraInfo` message. - """ - return self.get_tf_frame() - - @deprecated(version="J-turtle", reason="The Tx() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the tx() method instead.") - def Tx(self)->float: - """ - .. warning:: - The Tx() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the tx() method instead. - - :rtype: float - - Return the x-translation term of the projection matrix - """ - return self.tx() - - @deprecated(version="J-turtle", reason="The Ty() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the ty() method instead.") - def Ty(self)->float: - """ - .. warning:: - The Ty() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the ty() method instead. - - :rtype: float - - Return the y-translation term of the projection matrix - """ - return self.ty() - - - class StereoCameraModel: """ @@ -885,130 +471,3 @@ def get_right_camera(self)->PinholeCameraModel: Returns the PinholeCameraModel object of the right camera """ return self._right - - # Deprecated members planned for removal in K-turtle - # -------------------------------------------------- - @property - @deprecated(version="J-turtle", reason="The left property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_left_camera() method.") - def left(self): - """ - .. warning:: - The left property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._left - - @property - @deprecated(version="J-turtle", reason="The right property is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_right_camera() method.") - def right(self): - """ - .. warning:: - The right property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._right - - @property - @deprecated(version="J-turtle", reason="The Q property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member.") - def Q(self): - """ - .. warning:: - The Q property is deprecated as of J-turtle, and will be removed in K-turtle. It is not meant to be an exposed member. - """ - return self._q - - @deprecated(version="J-turtle", reason="The fromCameraInfo() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the from_camera_info() method instead.") - def fromCameraInfo(self, left_msg, right_msg): - """ - .. warning:: - The fromCameraInfo() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the from_camera_info() method instead. - - :param left_msg: left camera parameters - :type left_msg: sensor_msgs.msg.CameraInfo - :param right_msg: right camera parameters - :type right_msg: sensor_msgs.msg.CameraInfo - - Set the camera parameters from the :class:`sensor_msgs.msg.CameraInfo` messages. - """ - - self.from_camera_info(left_msg,right_msg) - - @deprecated(version="J-turtle", reason="The getDisparity() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_disparity() method instead.") - def getDisparity(self, Z)->float: - """ - .. warning:: - The getDisparity() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_disparity() method instead. - - :param Z: Z (depth), in cartesian space - :type Z: float - :rtype: float - - Returns the disparity observed for a point at depth Z. - This is the inverse of :math:`getZ`. - """ - return self.get_disparity(Z) - - @deprecated(version="J-turtle", reason="The getZ() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_z() method instead.") - def getZ(self, disparity)->float: - """ - .. warning:: - The getZ() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_z() method instead. - - :param disparity: disparity, in pixels - :type disparity: float - :rtype: float - - Returns the depth at which a point is observed with a given disparity. - This is the inverse of :math:`getDisparity`. - - Note that a disparity of zero implies Z is infinite. - """ - return self.get_z(disparity) - - @deprecated(version="J-turtle", reason="The project3dToPixel() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_3d_to_pixel() method instead.") - def project3dToPixel(self, point)->tuple[tuple[float,float],tuple[float,float]]: - """ - .. warning:: - The project3dToPixel() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_3d_to_pixel() method instead. - - :param point: 3D point - :type point: (x, y, z) - :rtype: tuple[tuple[float,float],tuple[float,float]] - - Returns the rectified pixel coordinates (u, v) of the 3D point, for each camera, as ((u_left, v_left), (u_right, v_right)) - using the cameras' :math:`P` matrices. - This is the inverse of :math:`projectPixelTo3d`. - """ - return self.project_3d_to_pixel(point) - - @deprecated(version="J-turtle", reason="The projectPixelTo3d() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_pixel_to_3d() method instead.") - def projectPixelTo3d(self, left_uv, disparity)->tuple[float,float,float]: - """ - .. warning:: - The projectPixelTo3d() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the project_pixel_to_3d() method instead. - - :param left_uv: rectified pixel coordinates - :type left_uv: (u, v) - :param disparity: disparity, in pixels - :type disparity: float - :rtype: tuple[float,float,float] - - Returns the 3D point (x, y, z) for the given pixel position, - using the cameras' :math:`P` matrices. - This is the inverse of :math:`project3dToPixel`. - - Note that a disparity of zero implies that the 3D point is at infinity. - """ - return self.project_pixel_to_3d(left_uv,disparity) - - @deprecated(version="J-turtle", reason="The tfFrame() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the tf_frame() method instead.") - def tfFrame(self)->str: - """ - .. warning:: - The tfFrame() method is deprecated as of J-turtle, and will be removed in K-turtle. Please use the get_tf_frame() method instead. - - :rtype: str - - Returns the tf frame name - a string - of the camera. - This is the frame of the :class:`sensor_msgs.msg.CameraInfo` message. - """ - return self.get_tf_frame() - diff --git a/image_geometry/package.xml b/image_geometry/package.xml index 652c9c24..2cd8b53a 100644 --- a/image_geometry/package.xml +++ b/image_geometry/package.xml @@ -21,7 +21,6 @@ libopencv-dev sensor_msgs - python3-deprecated ament_cmake_gtest ament_cmake_pytest diff --git a/image_geometry/test/directed.py b/image_geometry/test/directed.py index a7f43395..baaa458f 100644 --- a/image_geometry/test/directed.py +++ b/image_geometry/test/directed.py @@ -84,9 +84,6 @@ def test_rectify_image(self): self.cam.get_left_camera().rectify_image(raw, rectified) assert_almost_equal(expected, rectified[56,47]) - with self.assertWarns(DeprecationWarning): - self.cam.get_left_camera().rectifyImage(raw,rectified) - assert_almost_equal(expected, rectified[56,47]) def test_rectify_point(self): @@ -94,27 +91,18 @@ def test_rectify_point(self): expected = [48.16447369,45.49210841] actual = self.cam.get_left_camera().rectify_point(uv_raw) assert_almost_equal(expected,actual,3) - with self.assertWarns(DeprecationWarning): - deprecated = self.cam.get_left_camera().rectifyPoint(uv_raw) - assert_almost_equal(expected, deprecated, 3) def test_project_3d_to_pixel(self): point = (1.0, 2.0, 3.0) expected = [384.069,420.319] actual = self.cam.get_left_camera().project_3d_to_pixel(point) assert_almost_equal(expected,actual,3) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().project3dToPixel(point) - assert_almost_equal(expected,actual,3) def test_project_pixel_to_3d_ray(self): uv = (1.0, 2.0) expected = [-0.61,-0.475,0.634] actual = self.cam.get_left_camera().project_pixel_to_3d_ray(uv) assert_almost_equal(expected,actual,3) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().projectPixelTo3dRay(uv) - assert_almost_equal(expected,actual,3) def test_get_delta_u(self): delta_x = 1.0 @@ -122,9 +110,6 @@ def test_get_delta_u(self): expected = 147.767 actual = self.cam.get_left_camera().get_delta_u(delta_x,z) assert_almost_equal(expected,actual,3) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().getDeltaU(delta_x,z) - assert_almost_equal(expected,actual,3) def test_get_delta_v(self): delta_y = 1.0 @@ -132,9 +117,6 @@ def test_get_delta_v(self): expected = 147.767 actual = self.cam.get_left_camera().get_delta_v(delta_y,z) assert_almost_equal(expected,actual,3) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().getDeltaV(delta_y,z) - assert_almost_equal(expected,actual,3) def test_get_delta_x(self): delta_u = 1.0 @@ -142,9 +124,6 @@ def test_get_delta_x(self): expected = 0.00676741 actual = self.cam.get_left_camera().get_delta_x(delta_u,z) assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().getDeltaX(delta_u,z) - assert_almost_equal(expected,actual,6) def test_get_delta_y(self): delta_v = 1.0 @@ -152,17 +131,11 @@ def test_get_delta_y(self): expected = 0.00676741 actual = self.cam.get_left_camera().get_delta_y(delta_v,z) assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().getDeltaY(delta_v,z) - assert_almost_equal(expected,actual,6) def test_full_resolution(self): expected = (640,480) actual = self.cam.get_left_camera().full_resolution() self.assertTupleEqual(expected,actual) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().fullResolution() - self.assertTupleEqual(expected,actual) def test_intrinsic_matrix(self): expected = [[430.15433 , 0. , 311.713398], @@ -170,9 +143,6 @@ def test_intrinsic_matrix(self): [ 0. , 0. , 1. ]] actual = self.cam.get_left_camera().intrinsic_matrix() assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().intrinsicMatrix() - assert_almost_equal(expected,actual,6) def test_distortion_coeffs(self): expected = [[-3.63528858e-01], @@ -182,9 +152,6 @@ def test_distortion_coeffs(self): [ 0.00000000e+00]] actual = self.cam.get_left_camera().distortion_coeffs() assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().distortionCoeffs() - assert_almost_equal(expected,actual,6) def test_rotation_matrix(self): expected = [[ 0.998066, 0.006856, 0.06179 ], @@ -192,9 +159,6 @@ def test_rotation_matrix(self): [-0.061802, 0.00147 , 0.998087]] actual = self.cam.get_left_camera().rotation_matrix() assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().rotationMatrix() - assert_almost_equal(expected,actual,6) def test_projection_matrix(self): expected = [[295.534021, 0. , 285.557608, 0. ], @@ -202,9 +166,6 @@ def test_projection_matrix(self): [ 0. , 0. , 1. , 0. ]] actual = self.cam.get_left_camera().projection_matrix() assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().projectionMatrix() - assert_almost_equal(expected,actual,6) def test_full_intrinsic_matrix(self): expected = [[430.15433 , 0. , 311.713398], @@ -212,9 +173,6 @@ def test_full_intrinsic_matrix(self): [ 0. , 0. , 1. ]] actual = self.cam.get_left_camera().full_intrinsic_matrix() assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().fullIntrinsicMatrix() - assert_almost_equal(expected,actual,6) def test_full_projection_matrix(self): expected = [[295.534021, 0. , 285.557608, 0. ], @@ -222,9 +180,6 @@ def test_full_projection_matrix(self): [ 0. , 0. , 1. , 0. ]] actual = self.cam.get_left_camera().full_projection_matrix() assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().fullProjectionMatrix() - assert_almost_equal(expected,actual,6) def test_cx(self): expected = 285.557607 @@ -249,47 +204,29 @@ def test_fy(self): def test_tx(self): expected = 0.0 actual = self.cam.get_left_camera().tx() - assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().Tx() - assert_almost_equal(expected,actual,6) + assert_almost_equal(expected,actual,6) def test_ty(self): expected = 0.0 actual = self.cam.get_left_camera().ty() assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().Ty() - assert_almost_equal(expected,actual,6) def test_fov_x(self): expected = 1.6502496354 actual = self.cam.get_left_camera().fov_x() - assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().fovX() - assert_almost_equal(expected,actual,6) + assert_almost_equal(expected,actual,6) def test_fov_y(self): expected = 1.364138172 actual = self.cam.get_left_camera().fov_y() - assert_almost_equal(expected,actual,6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().fovY() - assert_almost_equal(expected,actual,6) + assert_almost_equal(expected,actual,6) def test_get_tf_frame(self): expected = "left_camera" actual = self.cam.get_left_camera().get_tf_frame() - self.assertEqual(expected,actual) - with self.assertWarns(DeprecationWarning): - actual = self.cam.get_left_camera().tfFrame() - self.assertEqual(expected,actual) + self.assertEqual(expected,actual) actual = self.cam.get_tf_frame() self.assertEqual(expected,actual) - with self.assertWarns(DeprecationWarning): - actual = self.cam.tfFrame() - self.assertEqual(expected,actual) def test_stereo_project_3d_to_pixel(self): @@ -297,9 +234,6 @@ def test_stereo_project_3d_to_pixel(self): expected = (self.cam.get_left_camera().project_3d_to_pixel(point), self.cam.get_right_camera().project_3d_to_pixel(point)) actual = self.cam.project_3d_to_pixel(point) assert_almost_equal(expected, actual, 6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.project3dToPixel(point) - assert_almost_equal(expected, actual, 6) def test_stereo_project_pixel_to_3d(self): left_uv = (1.0,2.0) @@ -307,66 +241,18 @@ def test_stereo_project_pixel_to_3d(self): expected = [-22.71975 , -17.668808, 23.596132] actual = self.cam.project_pixel_to_3d(left_uv, disparity) assert_almost_equal(expected, actual, 6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.projectPixelTo3d(left_uv, disparity) - assert_almost_equal(expected, actual, 6) def test_stereo_get_z(self): disparity = 1.1234 expected = 23.59613246 actual = self.cam.get_z(disparity) assert_almost_equal(expected, actual, 6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.getZ(disparity) - assert_almost_equal(expected, actual, 6) def test_stereo_get_disparity(self): z = 23.59613246 expected = 1.1234 actual = self.cam.get_disparity(z) assert_almost_equal(expected, actual, 6) - with self.assertWarns(DeprecationWarning): - actual = self.cam.getDisparity(z) - assert_almost_equal(expected, actual, 6) - - def test_deprecation(self): - pinholeCam = self.cam.get_left_camera() - with self.assertWarns(DeprecationWarning): - self.cam.get_left_camera().fromCameraInfo(self.lmsg) - with self.assertWarns(DeprecationWarning): - self.cam.fromCameraInfo(self.lmsg, self.rmsg) - with self.assertWarns(DeprecationWarning): - assert_almost_equal(pinholeCam.K, pinholeCam._k) - with self.assertWarns(DeprecationWarning): - assert_almost_equal(pinholeCam.D, pinholeCam._d) - with self.assertWarns(DeprecationWarning): - assert_almost_equal(pinholeCam.R, pinholeCam._r) - with self.assertWarns(DeprecationWarning): - assert_almost_equal(pinholeCam.P, pinholeCam._p) - with self.assertWarns(DeprecationWarning): - assert_almost_equal(pinholeCam.full_K, pinholeCam._full_k) - with self.assertWarns(DeprecationWarning): - assert_almost_equal(pinholeCam.full_P, pinholeCam._full_p) - with self.assertWarns(DeprecationWarning): - self.assertEqual(pinholeCam.width, pinholeCam._width) - with self.assertWarns(DeprecationWarning): - self.assertEqual(pinholeCam.height, pinholeCam._height) - with self.assertWarns(DeprecationWarning): - self.assertEqual(pinholeCam.binning_x, pinholeCam._binning_x) - with self.assertWarns(DeprecationWarning): - self.assertEqual(pinholeCam.binning_y, pinholeCam._binning_y) - with self.assertWarns(DeprecationWarning): - self.assertEqual(pinholeCam.raw_roi, pinholeCam._raw_roi) - with self.assertWarns(DeprecationWarning): - self.assertEqual(pinholeCam.tf_frame, pinholeCam._tf_frame) - with self.assertWarns(DeprecationWarning): - self.assertEqual(pinholeCam.stamp, pinholeCam._stamp) - with self.assertWarns(DeprecationWarning): - self.assertIs(self.cam.left, self.cam.get_left_camera()) - with self.assertWarns(DeprecationWarning): - self.assertEqual(self.cam.right, self.cam.get_right_camera()) - with self.assertWarns(DeprecationWarning): - assert_almost_equal(self.cam.Q, self.cam._q)