00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 PKG = 'test_pr2_sensors_gazebo'
00038 NAME = 'test_camera'
00039
00040 import math
00041 import roslib
00042 roslib.load_manifest(PKG)
00043 roslib.load_manifest('rostest')
00044 roslib.load_manifest('actionlib')
00045 roslib.load_manifest('pr2_controllers_msgs')
00046
00047 import sys, unittest
00048 import os, os.path, threading, time
00049 import rospy, rostest, string
00050 from sensor_msgs.msg import Image as image_msg
00051 from sensor_msgs.msg import CameraInfo as camerainfo_msg
00052 from PIL import Image as pili
00053 from PIL import ImageChops as pilic
00054 from geometry_msgs.msg import PointStamped, Point, Vector3
00055 from pr2_controllers_msgs.msg import PointHeadGoal, PointHeadAction
00056 import actionlib.action_client
00057
00058 FRAME_TARGET = "cam_sen-0050.ppm"
00059 FRAME_DIR = "test_camera_frames"
00060 TOTAL_ERROR_TOL = 5
00061 TEST_DURATION = 70
00062
00063 class PollCameraThread(threading.Thread):
00064 def __init__(self, target, dir):
00065 super(PollCameraThread, self).__init__()
00066 self.target = target
00067 self.dir = dir
00068
00069 def run(self):
00070 while 1:
00071 time.sleep(0.01)
00072 if (os.path.isdir(self.dir)):
00073 ls = os.listdir(self.dir)
00074
00075 for file in ls:
00076 if (file == FRAME_TARGET):
00077 self.target.onTargetFrame()
00078 return
00079
00080 class TestCameras(unittest.TestCase):
00081 def __init__(self, *args):
00082 super(TestCameras, self).__init__(*args)
00083 self.success = False
00084 self.got_camerainfo = False
00085 self.camerainfo_height = 0
00086 self.camerainfo_width = 0
00087
00088 def onTargetFrame(self):
00089 time.sleep(0.5)
00090 ps = "diff -q " + FRAME_DIR + "/" + FRAME_TARGET + " test/test_camera.valid.ppm"
00091
00092 result = os.system(ps)
00093 if (result == 0):
00094 self.success = True
00095
00096 else:
00097 self.success = False
00098
00099 rospy.signal_shutdown('test done')
00100
00101 def images_are_the_same(self,i0,i1):
00102 print "comparing images... "
00103 error_count = 0
00104 error_total = 0
00105 pixel_tol = 0
00106
00107
00108 size = 100,100
00109 i0.thumbnail(size,pili.ANTIALIAS)
00110 i1.thumbnail(size,pili.ANTIALIAS)
00111 ic = pilic.difference(i0,i1)
00112 i0.save("t_0.ppm")
00113 i1.save("t_1.ppm")
00114 ic.save("t_d.ppm")
00115
00116
00117 i0d = i0.getdata()
00118 i1d = i1.getdata()
00119
00120
00121 if len(i0d) != len(i1d):
00122 print "lengths not equal ",len(i0d), len(i1d)
00123 return False
00124 print "thumbnail lengths ",len(i0d), len(i1d)
00125
00126
00127 for i in range(len(i0d)):
00128 (p0) = i0d[i]
00129 (p1) = i1d[i]
00130 if abs(p0-p1) > pixel_tol:
00131 error_count = error_count + 1
00132 error_total = error_total + abs(p0-p1)
00133 error_avg = float(error_total)/float(len(i0d))
00134 print "total error count:",error_count
00135 print "average error: ",error_avg
00136 if error_avg > TOTAL_ERROR_TOL:
00137 return False
00138 else:
00139 return True
00140
00141 def camerainfoInput(self,camerainfo):
00142 self.got_camerainfo = True
00143 self.camerainfo_width = camerainfo.width
00144 self.camerainfo_height = camerainfo.height
00145 print " got cam info (",camerainfo.width,"X",camerainfo.height,")"
00146
00147 def imageInput(self,image):
00148
00149 if (self.got_camerainfo):
00150 print " got image and camerainfo from ROS, begin comparing images."
00151 else:
00152 print " got image but no camerainfo."
00153 return
00154
00155 print " - load validation image from file test_camera.valid.ppm "
00156 fname = roslib.packages.get_pkg_dir('test_pr2_sensors_gazebo') + '/test_camera.valid.ppm'
00157 if os.path.isfile(fname):
00158 im0 = pili.open(fname)
00159 else:
00160 print "cannot find validation file: test_camera.valid.ppm"
00161 self.success = False
00162 return
00163
00164 print " - load image from ROS "
00165 size = self.camerainfo_width,self.camerainfo_height
00166 im1 = pili.new("L",size)
00167 im1 = pili.frombuffer("L",size,str(image.data));
00168 im1 = im1.transpose(pili.FLIP_LEFT_RIGHT).rotate(180);
00169 imc = pilic.difference(im0,im1)
00170
00171
00172 print " - comparing images "
00173 im1.save("test_1.ppm")
00174 im0.save("test_0.ppm")
00175 imc.save("test_d.ppm")
00176
00177
00178
00179 comp_result = self.images_are_the_same(im0,im1)
00180 print "test comparison ", comp_result
00181
00182 if (self.success == False):
00183 if (comp_result == True):
00184 print " - images are the Same "
00185 self.success = True
00186 else:
00187 print " - images differ "
00188 self.success = False
00189
00190
00191 def test_camera(self):
00192 rospy.init_node(NAME, anonymous=True)
00193 head_action_client = actionlib.action_client.ActionClient('/head_traj_controller/point_head_action',PointHeadAction)
00194 def send_head_goal(g):
00195 g.target.header.stamp = rospy.get_rostime()
00196 return head_action_client.send_goal(g)
00197 head_goal = PointHeadGoal()
00198 head_goal.target.header.frame_id = 'base_link'
00199 head_goal.target.point = Point(10,0,0.6)
00200
00201 print " subscribe stereo left image from ROS "
00202 rospy.Subscriber("/narrow_stereo/left/image_raw", image_msg, self.imageInput)
00203 rospy.Subscriber("/narrow_stereo/left/camera_info", camerainfo_msg, self.camerainfoInput)
00204 timeout_t = time.time() + TEST_DURATION
00205 while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
00206 head_goal_status = send_head_goal(head_goal)
00207 time.sleep(1.0)
00208 self.assert_(self.success)
00209
00210
00211
00212
00213 if __name__ == '__main__':
00214
00215
00216
00217
00218 print " starting test "
00219 rostest.run(PKG, sys.argv[0], TestCameras, sys.argv)
00220
00221