00001
00002
00003 import time
00004
00005 import roslib
00006 roslib.load_manifest('cob_script_server')
00007 import rospy
00008
00009
00010 import cv
00011 from sensor_msgs.msg import Image
00012 from cv_bridge import CvBridge, CvBridgeError
00013 from math import *
00014
00015
00016 from simple_script_server import script
00017
00018 class CalibCam(script):
00019
00020 def Initialize(self):
00021 self.bridge = CvBridge()
00022 self.image_sub = rospy.Subscriber("/stereo/right/camera/image_raw",Image,self.callback)
00023 self.cv_image = cv.CreateImage((1,1), 1 , 3)
00024 self.bridge1 = CvBridge()
00025 self.image_sub1 = rospy.Subscriber("/stereo/left/camera/image_raw",Image,self.callback1)
00026 self.cv_image1 = cv.CreateImage((1,1), 1 , 3)
00027 self.bridge2 = CvBridge()
00028 self.image_sub2 = rospy.Subscriber("/swissranger/intensity/image_raw",Image,self.callback2)
00029 self.cv_image2 = cv.CreateImage((1,1), 1 , 3)
00030 cv.NamedWindow("right", 1)
00031 cv.NamedWindow("left", 1)
00032 cv.NamedWindow("sr", 1)
00033
00034 def Run(self):
00035 print "start"
00036 file_path = "./"
00037 nr_images = 14
00038
00039 self.sss.wait_for_input()
00040
00041
00042 if not self.sss.parse:
00043 for i in range(1,nr_images):
00044 cv.SaveImage(file_path+'right'+str(i)+'.png',self.cv_image)
00045 cv.SaveImage(file_path+'left'+str(i)+'.png',self.cv_image1)
00046 cv.SaveImage(file_path+'sr'+str(i)+'.png',self.cv_image2)
00047 self.sss.wait_for_input()
00048 print "next image"
00049 print "finished"
00050
00051 def callback(self,data):
00052 try:
00053 self.cv_image = self.bridge.imgmsg_to_cv(data, "bgr8")
00054 cv.ShowImage("right",self.cv_image)
00055 cv.WaitKey(3)
00056 except CvBridgeError, e:
00057 print e
00058
00059 def callback1(self,data):
00060 try:
00061 self.cv_image1 = self.bridge1.imgmsg_to_cv(data, "bgr8")
00062 cv.ShowImage("left",self.cv_image1)
00063
00064 except CvBridgeError, e:
00065 print e
00066
00067 def callback2(self,data):
00068 try:
00069 self.cv_image2 = self.bridge2.imgmsg_to_cv(data, "mono8")
00070 cv.ShowImage("sr",self.cv_image2)
00071
00072 except CvBridgeError, e:
00073 print e
00074
00075 if __name__ == "__main__":
00076 SCRIPT = CalibCam()
00077 SCRIPT.Start()