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