37 PKG =
'image_cb_detector'
38 NAME =
'image_cb_detector_node'
39 import roslib; roslib.load_manifest(PKG)
45 from sensor_msgs.msg
import Image
46 from image_cb_detector.msg
import ObjectInImage
48 from cv_bridge
import CvBridge, CvBridgeError
51 def __init__(self, corners_x, corners_y, spacing_x = None, spacing_y = None, width_scaling = 1, height_scaling = 1):
60 return (corners[0], corners[self.
corners_x - 1],
69 image_scaled = cv.CreateMat(scaled_height, scaled_width, cv.GetElemType(image))
70 cv.Resize(image, image_scaled, cv.CV_INTER_LINEAR)
73 found, corners = cv.FindChessboardCorners(image_scaled, (self.
corners_x, self.
corners_y), cv.CV_CALIB_CB_ADAPTIVE_THRESH)
76 rospy.logdebug(
"Found cb")
81 for i
in range(len(board_corners)):
83 xdiff = board_corners[i][0] - board_corners[next][0]
84 ydiff = board_corners[i][1] - board_corners[next][1]
85 perimeter += math.sqrt(xdiff * xdiff + ydiff * ydiff)
89 radius = int(square_size * 0.5 + 0.5)
91 corners = cv.FindCornerSubPix(image_scaled, corners, (radius, radius), (-1, -1), (cv.CV_TERMCRIT_EPS | cv.CV_TERMCRIT_ITER, 30, 0.1))
107 return (corners, object_points)
110 rospy.logdebug(
"Didn't find checkerboard")
115 corners_x = rospy.get_param(
'~corners_x', 6)
116 corners_y = rospy.get_param(
'~corners_y', 6)
117 spacing_x = rospy.get_param(
'~spacing_x',
None)
118 spacing_y = rospy.get_param(
'~spacing_y',
None)
119 width_scaling = rospy.get_param(
'~width_scaling', 1)
120 height_scaling = rospy.get_param(
'~height_scaling', 1)
123 spacing_y, width_scaling, height_scaling)
125 rospy.Subscriber(
"image_stream", Image, self.
callback)
126 self.
corner_pub = rospy.Publisher(
"corners_in_image", ObjectInImage)
132 image = self.
bridge.imgmsg_to_cv(ros_image,
"mono8")
133 except CvBridgeError, e:
134 rospy.logerror(
"Error importing image %s" % e)
140 obj_msg = ObjectInImage()
141 obj_msg.header = ros_image.header
144 obj_msg.set_image_points_size(len(corners))
145 for i
in range(len(corners)):
146 obj_msg.image_points[i].x = corners[i][0]
147 obj_msg.image_points[i].y = corners[i][1]
150 obj_msg.set_model_points_size(len(model))
151 for i
in range(len(corners)):
152 obj_msg.model_points[i].x = model[i][0]
153 obj_msg.model_points[i].y = model[i][1]
158 rospy.init_node(NAME, anonymous=
False)
162 if __name__ ==
'__main__':