projector_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import roslib; roslib.load_manifest('projector_calibration')
00003 import rospy
00004 import cv2
00005 from sensor_msgs.msg import RegionOfInterest, Image
00006 from cv_bridge import CvBridge, CvBridgeError
00007 import numpy as np
00008 bridge = CvBridge()
00009 roi_pub = None
00010 def img_cb(msg):
00011     cv2.imshow('win', np.asarray(bridge.imgmsg_to_cv(msg)))
00012     cv2.waitKey(10)
00013 
00014 def click(s, x, y, click, u):
00015         if click:
00016                 roi = RegionOfInterest()
00017                 #r = 10
00018                 roi.x_offset = x#max(x-r,0)
00019                 roi.y_offset = y#max(y-r,0)
00020                 #roi.width = 2*r
00021                 #roi.height= 2*r
00022                 roi_pub.publish(roi)
00023                 print roi.x_offset, roi.y_offset
00024 
00025 if __name__ == '__main__':
00026         cv2.namedWindow('win')
00027         cv2.setMouseCallback('win', click)
00028         rospy.init_node('projector_test')
00029         rospy.Subscriber('image', Image, img_cb)
00030         roi_pub = rospy.Publisher('roi', RegionOfInterest)
00031         rospy.spin()
00032         cv2.destroyAllWindows()


projector_calibration
Author(s): Daniel Lazewatsky
autogenerated on Mon Oct 6 2014 10:10:01