00001
00002
00003 PKG = 'cv_markers'
00004 import roslib; roslib.load_manifest(PKG)
00005
00006 import math
00007 from functools import partial
00008 import array
00009 import time
00010 import Queue
00011 import threading
00012
00013 import numpy
00014
00015 import rospy
00016 from cv_markers.refinecorners import refinecorners
00017 import cv
00018 import cv_bridge
00019 import sensor_msgs.msg
00020 import message_filters
00021 from cv_bridge import CvBridge, CvBridgeError
00022 import image_geometry
00023 import geometry_msgs.msg
00024 import tf_conversions.posemath as pm
00025 import PyKDL
00026 import tf.msg
00027
00028 class ConsumerThread(threading.Thread):
00029 def __init__(self, queue, function):
00030 threading.Thread.__init__(self)
00031 self.queue = queue
00032 self.function = function
00033
00034 def run(self):
00035 while True:
00036 while True:
00037 m = self.queue.get()
00038 if self.queue.empty():
00039 break
00040 self.function(m)
00041
00042 class DataMatrix:
00043 def __init__(self):
00044 self.i = 0
00045 def topic(lr, sub):
00046 return rospy.resolve_name("stereo") + "/%s/%s" % ({'l' : 'left', 'r' : 'right'}[lr], sub)
00047 self.tracking = {}
00048 if 0:
00049 self.cams = {}
00050 for lr in "lr":
00051 rospy.Subscriber(topic(lr, "camera_info"), sensor_msgs.msg.CameraInfo, partial(self.got_info, lr))
00052 rospy.Subscriber(topic("l", "image_rect_color"), sensor_msgs.msg.Image, self.gotimage)
00053 else:
00054 tosync_stereo = [
00055 (topic('l', "image_rect_color"), sensor_msgs.msg.Image),
00056 (topic('l', "camera_info"), sensor_msgs.msg.CameraInfo),
00057 (topic('r', "image_rect_color"), sensor_msgs.msg.Image),
00058 (topic('r', "camera_info"), sensor_msgs.msg.CameraInfo)
00059 ]
00060 tosync_mono = [
00061 ("image_stream", sensor_msgs.msg.Image),
00062 ("camera_info", sensor_msgs.msg.CameraInfo),
00063 ]
00064
00065 self.q_stereo = Queue.Queue()
00066 tss = message_filters.TimeSynchronizer([message_filters.Subscriber(topic, type) for (topic, type) in tosync_stereo], 10)
00067 tss.registerCallback(self.queue_stereo)
00068
00069 sth = ConsumerThread(self.q_stereo, self.handle_stereo)
00070 sth.setDaemon(True)
00071 sth.start()
00072
00073 self.q_mono = Queue.Queue()
00074 tss = message_filters.TimeSynchronizer([message_filters.Subscriber(topic, type) for (topic, type) in tosync_mono], 10)
00075 tss.registerCallback(self.queue_mono)
00076
00077 mth = ConsumerThread(self.q_mono, self.handle_mono)
00078 mth.setDaemon(True)
00079 mth.start()
00080
00081 self.pub_tf = rospy.Publisher("/tf", tf.msg.tfMessage)
00082 self.nf = 0
00083
00084
00085
00086 def getraw(self, rawimg):
00087 print "raw", rawimg.encoding
00088 rawimg.encoding = "mono8"
00089 img = CvBridge().imgmsg_to_cv(rawimg)
00090 cv.SaveImage("/tmp/raw.png", img)
00091
00092 def got_info(self, lr, cammsg):
00093 cam = image_geometry.PinholeCameraModel()
00094 cam.fromCameraInfo(cammsg)
00095 self.cams[lr] = cam
00096
00097 def track(self, img):
00098 self.tracking = {}
00099 allfound = cv.FindDataMatrix(img)
00100
00101 self.nf += 1
00102 for found in allfound:
00103 (code,perfect,_) = found
00104 corners = refinecorners(img, found)
00105 if corners:
00106 self.tracking[code] = corners
00107
00108
00109
00110
00111 def broadcast(self, header, code, posemsg):
00112 ts = geometry_msgs.msg.TransformStamped()
00113 ts.header.frame_id = header.frame_id
00114 ts.header.stamp = header.stamp
00115 ts.child_frame_id = code
00116 ts.transform.translation = posemsg.position
00117 ts.transform.rotation = posemsg.orientation
00118 tfm = tf.msg.tfMessage([ts])
00119 self.pub_tf.publish(tfm)
00120
00121 def gotimage(self, imgmsg):
00122 if imgmsg.encoding == "bayer_bggr8":
00123 imgmsg.encoding = "8UC1"
00124 img = CvBridge().imgmsg_to_cv(imgmsg)
00125
00126
00127
00128 self.track(img)
00129
00130
00131 print self.cams
00132 if 'l' in self.cams:
00133 for (code, corners) in self.tracking.items():
00134 model = cv.fromarray(numpy.array([[0,0,0], [.1, 0, 0], [.1, .1, 0], [0, .1, 0]], numpy.float32))
00135
00136 rot = cv.CreateMat(3, 1, cv.CV_32FC1)
00137 trans = cv.CreateMat(3, 1, cv.CV_32FC1)
00138 cv.FindExtrinsicCameraParams2(model,
00139 cv.fromarray(numpy.array(corners, numpy.float32)),
00140 self.cams['l'].intrinsicMatrix(),
00141 self.cams['l'].distortionCoeffs(),
00142 rot,
00143 trans)
00144
00145 ts = geometry_msgs.msg.TransformStamped()
00146 ts.header.frame_id = imgmsg.header.frame_id
00147 ts.header.stamp = imgmsg.header.stamp
00148 ts.child_frame_id = code
00149 posemsg = pm.toMsg(pm.fromCameraParams(cv, rot, trans))
00150 ts.transform.translation = posemsg.position
00151 ts.transform.rotation = posemsg.orientation
00152
00153 tfm = tf.msg.tfMessage([ts])
00154 self.pub_tf.publish(tfm)
00155
00156 def queue_mono(self, img, caminfo):
00157 qq = (img, caminfo)
00158 self.q_mono.put(qq)
00159
00160 def queue_stereo(self, lmsg, lcmsg, rmsg, rcmsg):
00161 qq = (lmsg, lcmsg, rmsg, rcmsg)
00162 self.q_stereo.put(qq)
00163
00164 def handle_mono(self, qq):
00165 (imgmsg, caminfo) = qq
00166 img = CvBridge().imgmsg_to_cv(imgmsg, "mono8")
00167 pcm = image_geometry.PinholeCameraModel()
00168 pcm.fromCameraInfo(caminfo)
00169
00170 self.track(img)
00171
00172 for (code, corners) in self.tracking.items():
00173
00174
00175
00176 if isinstance(self.dim, (float, int)):
00177 d = self.dim
00178 else:
00179 d = self.dim[code]
00180
00181
00182
00183 d = d * 14 / 10
00184 model = cv.fromarray(numpy.array([[0,0,0], [0, d, 0], [d, d, 0], [d, 0, 0]], numpy.float32))
00185
00186 rot = cv.CreateMat(3, 1, cv.CV_32FC1)
00187 trans = cv.CreateMat(3, 1, cv.CV_32FC1)
00188 cv.FindExtrinsicCameraParams2(model,
00189 cv.fromarray(numpy.array(corners, numpy.float32)),
00190 pcm.intrinsicMatrix(),
00191 pcm.distortionCoeffs(),
00192 rot,
00193 trans)
00194
00195 ts = geometry_msgs.msg.TransformStamped()
00196 ts.header.frame_id = imgmsg.header.frame_id
00197 ts.header.stamp = imgmsg.header.stamp
00198 ts.child_frame_id = code
00199 posemsg = pm.toMsg(pm.fromCameraParams(cv, rot, trans))
00200 ts.transform.translation = posemsg.position
00201 ts.transform.rotation = posemsg.orientation
00202
00203 tfm = tf.msg.tfMessage([ts])
00204 self.pub_tf.publish(tfm)
00205
00206 def handle_stereo(self, qq):
00207
00208 (lmsg, lcmsg, rmsg, rcmsg) = qq
00209 limg = CvBridge().imgmsg_to_cv(lmsg, "mono8")
00210 rimg = CvBridge().imgmsg_to_cv(rmsg, "mono8")
00211
00212 if 0:
00213 cv.SaveImage("/tmp/l%06d.png" % self.i, limg)
00214 cv.SaveImage("/tmp/r%06d.png" % self.i, rimg)
00215 self.i += 1
00216
00217 scm = image_geometry.StereoCameraModel()
00218 scm.fromCameraInfo(lcmsg, rcmsg)
00219
00220 bm = cv.CreateStereoBMState()
00221 if "wide" in rospy.resolve_name("stereo"):
00222 bm.numberOfDisparities = 160
00223 if 0:
00224 disparity = cv.CreateMat(limg.rows, limg.cols, cv.CV_16SC1)
00225 started = time.time()
00226 cv.FindStereoCorrespondenceBM(limg, rimg, disparity, bm)
00227 print time.time() - started
00228 ok = cv.CreateMat(limg.rows, limg.cols, cv.CV_8UC1)
00229 cv.CmpS(disparity, 0, ok, cv.CV_CMP_GT)
00230 cv.ShowImage("limg", limg)
00231 cv.ShowImage("disp", ok)
00232 cv.WaitKey(6)
00233 self.track(CvBridge().imgmsg_to_cv(lmsg, "rgb8"))
00234 if len(self.tracking) == 0:
00235 print "No markers found"
00236 for code, corners in self.tracking.items():
00237 corners3d = []
00238 for (x, y) in corners:
00239 limr = cv.GetSubRect(limg, (0, y - bm.SADWindowSize / 2, limg.cols, bm.SADWindowSize + 1))
00240 rimr = cv.GetSubRect(rimg, (0, y - bm.SADWindowSize / 2, rimg.cols, bm.SADWindowSize + 1))
00241 tiny_disparity = cv.CreateMat(limr.rows, limg.cols, cv.CV_16SC1)
00242 cv.FindStereoCorrespondenceBM(limr, rimr, tiny_disparity, bm)
00243 if tiny_disparity[7, x] < 0:
00244 return
00245 corners3d.append(scm.projectPixelTo3d((x, y), tiny_disparity[7, x] / 16.))
00246 if 0:
00247 cv.ShowImage("d", disparity)
00248 (a, b, c, d) = [numpy.array(pt) for pt in corners3d]
00249 def normal(s, t):
00250 return (t - s) / numpy.linalg.norm(t - s)
00251 x = PyKDL.Vector(*normal(a, b))
00252 y = PyKDL.Vector(*normal(a, d))
00253 f = PyKDL.Frame(PyKDL.Rotation(x, y, x * y), PyKDL.Vector(*a))
00254 msg = pm.toMsg(f)
00255
00256 print code, msg.position.x, msg.position.y, msg.position.z
00257 self.broadcast(lmsg.header, code, msg)
00258
00259 def main():
00260 rospy.init_node('datamatrix')
00261 node = DataMatrix()
00262 try:
00263 node.dim = rospy.get_param('~size')
00264 except KeyError:
00265 node.dim = 0.145
00266 rospy.spin()
00267
00268 if __name__ == "__main__":
00269 main()