00001
00002 import roslib; roslib.load_manifest('projector_interface')
00003 from std_msgs.msg import ColorRGBA
00004 from pr2_python.pointclouds import pointcloud2_to_xyz_array, xyz_array_to_pointcloud2
00005 import datetime
00006 import scipy.io
00007 import numpy as np
00008 from itertools import chain
00009
00010 from point_tests import sameObject, closestPoint
00011
00012 load('rosh_robot', globals())
00013
00014 xmin = -0.79651666
00015 xmax = 0.06501853
00016 ymin = 0.03261997
00017 ymax = 0.50817382
00018
00019
00020 ys = np.linspace(ymin,ymax,3)
00021 xs = np.arange(xmin+0.05, xmax, ys[1] - ys[0])
00022 xx, yy = np.meshgrid(xs, ys)
00023 points = np.array([(x,y,0) for x,y in zip(xx.ravel(), yy.ravel())])
00024 points_msg = xyz_array_to_pointcloud2(points, now(), '/table')
00025 topics.object_cloud(points_msg)
00026 services.set_selection_method(0)
00027
00028 order = [
00029 [0, 2, 1, 3],
00030 [7, 5, 6, 4],
00031 [8, 10, 9, 11],
00032 [0, 4, 8 ],
00033 [1, 5, 9 ],
00034 [2, 6, 10],
00035 [3, 7, 11]
00036 ]
00037
00038 targets = []
00039 stds = []
00040 times = []
00041 cursor_history = []
00042 history_size = 0
00043
00044 start_time = now()
00045 for idx in reversed(list(chain(*order))):
00046 point = points[idx]
00047 targets.append(point)
00048 print 'hilighting ', point
00049 services.clear_hilights()
00050
00051 pt = PointStamped()
00052 pt.header.frame_id = '/table'
00053 pt.header.stamp = now()
00054 pt.point.x, pt.point.y, pt.point.z = point
00055
00056 t1 = now()
00057 services.hilight_object(pt, ColorRGBA(255,0,0,0))
00058 click_pts_msg = services.get_cursor_stats()
00059 click_pt = [
00060 click_pts_msg.click_pos.point.x,
00061 click_pts_msg.click_pos.point.y,
00062 click_pts_msg.click_pos.point.z
00063 ]
00064 r = Rate(10)
00065 while not sameObject(click_pt, point):
00066 click_pts_msg = services.get_cursor_stats()
00067 click_pt = [
00068 click_pts_msg.click_pos.point.x,
00069 click_pts_msg.click_pos.point.y,
00070 click_pts_msg.click_pos.point.z
00071 ]
00072 r.sleep()
00073 click_pts = pointcloud2_to_xyz_array(click_pts_msg.points)
00074 t2 = now()
00075 times.append((t2-t1).to_sec())
00076 history_size = click_pts.shape[0]
00077 cursor_history.extend(click_pts)
00078 stds.append(click_pts.std(0))
00079 print 'std = ', stds[-1]
00080 sleep(3)
00081
00082 services.clear_hilights()
00083 path = '/home/robotics/lazewatskyd/ros-pkgs/wu-ros-pkg/3d_interaction/projector_interface/study/data/4_object_designation_%s.mat'
00084 timestr = datetime.datetime.today().strftime('%d-%m-%y-%H.%M.%f')
00085 scipy.io.savemat(path % timestr, dict(targets=targets,
00086 stds=stds,
00087 times=times,
00088 cursor_history=cursor_history,
00089 history_size=history_size,
00090 total_time=(now()-start_time).to_sec()))
00091 print 'Saved %s' % (path % timestr)