00001
00002
00003 import time
00004 from random import *
00005
00006 import roslib
00007 roslib.load_manifest('cob_script_server')
00008 import rospy
00009
00010 import tf
00011 from tf.transformations import euler_from_quaternion
00012
00013 import cv
00014 from sensor_msgs.msg import Image
00015 from cv_bridge import CvBridge, CvBridgeError
00016 from math import *
00017
00018
00019 from simple_script_server import script
00020
00021 class CalibCam(script):
00022
00023 def Initialize(self):
00024 self.bridge = CvBridge()
00025 self.image_sub = rospy.Subscriber("/stereo/right/image_color",Image,self.callback)
00026 self.cv_image = cv.CreateImage((1,1), 1 , 3)
00027 self.sss.init("head")
00028 self.sss.init("torso")
00029 self.sss.init("sdh")
00030
00031 def Run(self):
00032 print "start"
00033 seed()
00034 maxVal = 0.04
00035 file_path = "./"
00036 listener = tf.TransformListener()
00037 nr_images = 14
00038
00039
00040 self.sss.move("head","back")
00041 self.sss.move("arm","calib")
00042 self.sss.move("torso","home")
00043 self.sss.move("sdh","home")
00044
00045 self.sss.wait_for_input()
00046 self.sss.move("sdh","calib")
00047 self.sss.wait_for_input()
00048
00049
00050 for i in range(1,nr_images):
00051 if i==1:
00052 r1 = maxVal
00053 r2 = maxVal
00054 elif i==2:
00055 r1 = -maxVal
00056 r2 = maxVal
00057 elif i==3:
00058 r1 = maxVal
00059 r2 = -maxVal
00060 elif i==4:
00061 r1 = -maxVal
00062 r2 = -maxVal
00063 else:
00064 r1 = (random()-0.5)*2*maxVal;
00065 r2 = (random()-0.5)*2*maxVal;
00066 self.sss.move("torso",[[r1,r2,r1,r2]])
00067 self.sss.sleep(1)
00068 try:
00069 (trans,rot) = listener.lookupTransform('/base_link', '/head_color_camera_r_link', rospy.Time(0))
00070 rpy = euler_from_quaternion(rot)
00071 cyaw = cos(rpy[2])
00072 syaw = sin(rpy[2])
00073 cpitch = cos(rpy[1])
00074 spitch = sin(rpy[1])
00075 croll = cos(rpy[0])
00076 sroll = sin(rpy[0])
00077 R11 = cyaw*cpitch
00078 R12 = cyaw*spitch*sroll-syaw*croll
00079 R13 = cyaw*spitch*croll+syaw*sroll
00080 R21 = syaw*cpitch
00081 R22 = syaw*spitch*sroll+cyaw*croll
00082 R23 = syaw*spitch*croll-cyaw*sroll
00083 R31 = -spitch
00084 R32 = cpitch*sroll
00085 R33 = cpitch*croll
00086 fout = open(file_path+'calpic'+str(i)+'.coords','w')
00087 fout.write(str(R11)+' '+str(R12)+' '+str(R13)+' '+str(trans[0]*1000)+'\n'+str(R21)+' '+str(R22)+' '+str(R23)+' '+str(trans[1]*1000)+'\n'+str(R31)+' '+str(R32)+' '+str(R33)+' '+str(trans[2]*1000))
00088 fout.close()
00089 except (tf.LookupException, tf.ConnectivityException):
00090 print "tf exception"
00091
00092 self.sss.sleep(1)
00093 cv.SaveImage(file_path+'calpic'+str(i)+'.png',self.cv_image)
00094 self.sss.sleep(1)
00095 self.sss.move("torso","home")
00096 print "finished"
00097
00098 def callback(self,data):
00099 try:
00100 self.cv_image = self.bridge.imgmsg_to_cv(data, "bgr8")
00101 except CvBridgeError, e:
00102 print e
00103
00104 if __name__ == "__main__":
00105 SCRIPT = CalibCam()
00106 SCRIPT.Start()