42 roslib.load_manifest(PKG)
43 roslib.load_manifest(
'rostest')
44 roslib.load_manifest(
'actionlib')
45 roslib.load_manifest(
'pr2_controllers_msgs')
48 import os, os.path, threading, time
49 import rospy, rostest, string
51 from sensor_msgs.msg
import Image
as image_msg
52 from sensor_msgs.msg
import CameraInfo
as camerainfo_msg
53 from PIL
import Image
as pili
54 from PIL
import ImageChops
as pilic
55 from geometry_msgs.msg
import PointStamped, Point, Vector3
56 from pr2_controllers_msgs.msg
import PointHeadGoal, PointHeadAction
60 FRAME_TARGET =
"test_camera.valid.ppm"
61 FRAME_DIR =
"test_camera_frames"
67 super(PollCameraThread, self).
__init__()
74 if (os.path.isdir(self.
dir)):
75 ls = os.listdir(self.
dir)
78 if (file == FRAME_TARGET):
79 self.
target.onTargetFrame()
84 super(TestCameras, self).
__init__(*args)
92 ps =
"diff -q " + FRAME_DIR +
"/" + FRAME_TARGET +
" test/test_camera.valid.ppm"
94 result = os.system(ps)
101 rospy.signal_shutdown(
'test done')
104 print(
"comparing images... ")
111 i0.thumbnail(size,pili.ANTIALIAS)
112 i1.thumbnail(size,pili.ANTIALIAS)
113 ic = pilic.difference(i0,i1)
123 if len(i0d) != len(i1d):
124 print(
"lengths not equal ",len(i0d), len(i1d))
126 print(
"thumbnail lengths ",len(i0d), len(i1d))
129 for i
in range(len(i0d)):
132 if abs(p0-p1) > pixel_tol:
133 error_count = error_count + 1
134 error_total = error_total + abs(p0-p1)
135 error_avg = float(error_total)/float(len(i0d))
136 print(
"total error count:",error_count)
137 print(
"average error: ",error_avg)
138 if error_avg > TOTAL_ERROR_TOL:
147 print(
" got cam info (",camerainfo.width,
"X",camerainfo.height,
")")
152 print(
" got image and camerainfo from ROS, begin comparing images.")
154 print(
" got image but no camerainfo.")
157 print(
" - load validation image from file test_camera.valid.ppm ")
158 fname = roslib.packages.get_pkg_dir(
'pr2_gazebo') +
'/test/sensors/test_camera.valid.ppm'
159 if os.path.isfile(fname):
160 im0 = pili.open(fname)
162 print(
"cannot find validation file: test_camera.valid.ppm")
166 print(
" - load image from ROS ")
168 im1 = pili.new(
"L",size)
169 if os.environ[
'ROS_DISTRO'] ==
'noetic':
170 im1 = pili.frombuffer(
"L",size,image.data,
"raw",
"L", 0, 1);
172 im1 = pili.frombuffer(
"L",size,str(image.data));
173 im1 = im1.transpose(pili.FLIP_LEFT_RIGHT).rotate(180);
174 imc = pilic.difference(im0,im1)
177 print(
" - comparing images ")
178 im1.save(
"test_1.ppm")
179 im0.save(
"test_0.ppm")
180 imc.save(
"test_d.ppm")
185 print(
"test comparison ", comp_result)
188 if (comp_result ==
True):
189 print(
" - images are the Same ")
192 print(
" - images differ ")
197 rospy.init_node(NAME, anonymous=
True)
199 def send_head_goal(g):
200 g.target.header.stamp = rospy.get_rostime()
201 return head_action_client.send_goal(g)
202 head_goal = PointHeadGoal()
203 head_goal.target.header.frame_id =
'base_link'
204 head_goal.target.point = Point(10,0,0.55)
206 projector_pub = rospy.Publisher(
"/projector_wg6802418_controller/projector", Int32, latch=
True);
207 projector_pub.publish(Int32(0));
209 print(
" subscribe stereo left image from ROS ")
210 rospy.Subscriber(
"/narrow_stereo/left/image_raw", image_msg, self.
imageInput)
211 rospy.Subscriber(
"/narrow_stereo/left/camera_info", camerainfo_msg, self.
camerainfoInput)
212 timeout_t = time.time() + TEST_DURATION
213 while not rospy.is_shutdown()
and not self.
success and time.time() < timeout_t:
214 head_goal_status = send_head_goal(head_goal)
221 if __name__ ==
'__main__':
226 print(
" starting test ")
227 rostest.run(PKG, sys.argv[0], TestCameras, sys.argv)