Skip to content

Commit

Permalink
remove OpenCV 1 API
Browse files Browse the repository at this point in the history
  • Loading branch information
vrabaud committed Feb 15, 2014
1 parent 5305f91 commit aca0824
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 19 deletions.
2 changes: 1 addition & 1 deletion image_geometry/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,6 @@ install(TARGETS ${PROJECT_NAME}
)

# add tests
if(CAKTIN_ENABLE_TESTING)
if(CATKIN_ENABLE_TESTING)
add_subdirectory(test)
endif()
33 changes: 16 additions & 17 deletions image_geometry/src/image_geometry/cameramodels.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,14 @@
import array

import cv
import cv2
import sensor_msgs.msg
import math
import copy
import numpy

def mkmat(rows, cols, L):
mat = cv.CreateMat(rows, cols, cv.CV_64FC1)
cv.SetData(mat, array.array('d', L), 8 * cols)
mat = numpy.matrix(L, dtype='float64')
mat.resize((rows,cols))
return mat

class PinholeCameraModel:
Expand Down Expand Up @@ -80,10 +81,12 @@ def rectifyImage(self, raw, rectified):
Applies the rectification specified by camera parameters :math:`K` and and :math:`D` to image `raw` and writes the resulting image `rectified`.
"""

self.mapx = cv.CreateImage((self.width, self.height), cv.IPL_DEPTH_32F, 1)
self.mapy = cv.CreateImage((self.width, self.height), cv.IPL_DEPTH_32F, 1)
cv.InitUndistortRectifyMap(self.K, self.D, self.R, self.P, self.mapx, self.mapy)
cv.Remap(raw, rectified, self.mapx, self.mapy)
self.mapx = np.ndarray(shape=(self.height, self.width, 1),
dtype='float32')
self.mapy = np.ndarray(shape=(self.height, self.width, 1),
dtype='float32')
cv2.initUndistortRectifyMap(self.K, self.D, self.R, self.P, self.mapx, self.mapy)
cv2.remap(raw, rectified, self.mapx, self.mapy)

def rectifyPoint(self, uv_raw):
"""
Expand All @@ -96,9 +99,9 @@ def rectifyPoint(self, uv_raw):
"""

src = mkmat(1, 2, list(uv_raw))
src = cv.Reshape(src, 2)
dst = cv.CloneMat(src)
cv.UndistortPoints(src, dst, self.K, self.D, self.R, self.P)
src.resize((2, 1))
dst = src.copy()
cv2.undistortPoints(src, dst, self.K, self.D, self.R, self.P)
return dst[0,0]

def project3dToPixel(self, point):
Expand All @@ -111,8 +114,7 @@ def project3dToPixel(self, point):
This is the inverse of :meth:`projectPixelTo3dRay`.
"""
src = mkmat(4, 1, [point[0], point[1], point[2], 1.0])
dst = cv.CreateMat(3, 1, cv.CV_64FC1)
cv.MatMul(self.P, src, dst)
dst = self.P * src
x = dst[0,0]
y = dst[1,0]
w = dst[2,0]
Expand Down Expand Up @@ -276,8 +278,7 @@ def fromCameraInfo(self, left_msg, right_msg):
# [ 0, 0, 0, Fx ]
# [ 0, 0, 1 / Tx, (Crx-Clx)/Tx ]

self.Q = cv.CreateMat(4, 4, cv.CV_64FC1)
cv.SetZero(self.Q)
self.Q = numpy.zeros((4, 4), dtype='float64')
self.Q[0, 0] = 1.0
self.Q[0, 3] = -cx
self.Q[1, 1] = 1.0
Expand Down Expand Up @@ -321,9 +322,7 @@ def projectPixelTo3d(self, left_uv, disparity):
Note that a disparity of zero implies that the 3D point is at infinity.
"""
src = mkmat(4, 1, [left_uv[0], left_uv[1], disparity, 1.0])
dst = cv.CreateMat(4, 1, cv.CV_64FC1)
cv.SetZero(dst)
cv.MatMul(self.Q, src, dst)
dst = self.Q * src
x = dst[0, 0]
y = dst[1, 0]
z = dst[2, 0]
Expand Down
1 change: 0 additions & 1 deletion image_geometry/test/directed.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
roslib.load_manifest(PKG)
import rostest
import rospy
import cv
import unittest
import sensor_msgs.msg

Expand Down

0 comments on commit aca0824

Please sign in to comment.