test_vision_node.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import roslib
00004 roslib.load_manifest('pi_head_tracking_tutorial')
00005 import sys
00006 import rospy
00007 import cv
00008 from std_msgs.msg import String
00009 from sensor_msgs.msg import Image
00010 from cv_bridge import CvBridge, CvBridgeError
00011 
00012 class test_vision_node:
00013 
00014     def __init__(self):
00015         rospy.init_node('test_vision_node')
00016 
00017         """ Give the OpenCV display window a name. """
00018         self.cv_window_name = "OpenCV Image"
00019 
00020         """ Create the window and make it re-sizeable (second parameter = 0) """
00021         cv.NamedWindow(self.cv_window_name, 0)
00022 
00023         """ Create the cv_bridge object """
00024         self.bridge = CvBridge()
00025 
00026         """ Subscribe to the raw camera image topic """
00027         self.image_sub = rospy.Subscriber("/camera/image_raw", Image, self.callback)
00028 
00029     def callback(self, data):
00030         try:
00031             """ Convert the raw image to OpenCV format """
00032             cv_image = self.bridge.imgmsg_to_cv(data, "bgr8")
00033         except CvBridgeError, e:
00034           print e
00035   
00036         
00037         """ Get the width and height of the image """
00038         (width, height) = cv.GetSize(cv_image)
00039 
00040         """ Overlay some text onto the image display """
00041         text_font = cv.InitFont(cv.CV_FONT_HERSHEY_DUPLEX, 2, 2)
00042         cv.PutText(cv_image, "OpenCV Image", (50, height / 2), text_font, cv.RGB(255, 255, 0))
00043   
00044         """ Refresh the image on the screen """
00045         cv.ShowImage(self.cv_window_name, cv_image)
00046         cv.WaitKey(3)
00047 
00048 def main(args):
00049       vn = test_vision_node()
00050       try:
00051         rospy.spin()
00052       except KeyboardInterrupt:
00053         print "Shutting down vison node."
00054         cv.DestroyAllWindows()
00055 
00056 if __name__ == '__main__':
00057     main(sys.argv)
00058     


pi_head_tracking_tutorial
Author(s): Patrick Goebel
autogenerated on Mon Oct 6 2014 03:27:15