3_random.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
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 from random import choice
00010 
00011 from point_tests import sameObject, closestPoint
00012 
00013 load('rosh_robot', globals())
00014 
00015 xmin = -0.79651666
00016 xmax =  0.06501853
00017 ymin =  0.03261997
00018 ymax =  0.50817382
00019 
00020 # xs = np.linspace(xmin,xmax,4)
00021 ys = np.linspace(ymin,ymax,3)
00022 xs = np.arange(xmin+0.05, xmax, ys[1] - ys[0])
00023 xx, yy = np.meshgrid(xs, ys)
00024 points = np.array([(x,y,0) for x,y in zip(xx.ravel(), yy.ravel())])
00025 points_msg = xyz_array_to_pointcloud2(points, now(), '/table')
00026 topics.object_cloud(points_msg)
00027 services.set_selection_method(0)
00028     
00029 targets = []
00030 stds = []
00031 times = []
00032 cursor_history = []
00033 history_size = 0
00034 
00035 start_time = now()
00036 for idx in range(len(points)*2):
00037     point = choice(points)
00038     targets.append(point)
00039     print 'hilighting ', point
00040     services.clear_hilights()
00041     
00042     pt = PointStamped()
00043     pt.header.frame_id = '/table'
00044     pt.header.stamp = now()
00045     pt.point.x, pt.point.y, pt.point.z = point
00046     
00047     t1 = now()
00048     services.hilight_object(pt, ColorRGBA(255,0,0,0))
00049     click_pts_msg = services.get_cursor_stats()
00050     click_pt = [
00051         click_pts_msg.click_pos.point.x,
00052         click_pts_msg.click_pos.point.y,
00053         click_pts_msg.click_pos.point.z
00054     ]
00055     r = Rate(10)
00056     while not sameObject(click_pt, point):
00057         click_pts_msg = services.get_cursor_stats()
00058         click_pt = [
00059             click_pts_msg.click_pos.point.x,
00060             click_pts_msg.click_pos.point.y,
00061             click_pts_msg.click_pos.point.z
00062         ]
00063         r.sleep()
00064     click_pts = pointcloud2_to_xyz_array(click_pts_msg.points)
00065     t2 = now()
00066     times.append((t2-t1).to_sec())
00067     history_size = click_pts.shape[0]
00068     cursor_history.extend(click_pts)
00069     stds.append(click_pts.std(0))
00070     print 'std = ', stds[-1]
00071     sleep(3)
00072         
00073 services.clear_hilights()
00074 path = '/home/robotics/lazewatskyd/ros-pkgs/wu-ros-pkg/3d_interaction/projector_interface/study/data/3_random_%s.mat'
00075 timestr = datetime.datetime.today().strftime('%d-%m-%y-%H.%M.%f')
00076 scipy.io.savemat(path % timestr,    dict(targets=targets,
00077                                          stds=stds,
00078                                          times=times,
00079                                          cursor_history=cursor_history,
00080                                          history_size=history_size,
00081                                          total_time=(now()-start_time).to_sec()))
00082 print 'Saved %s' % (path % timestr)


projector_interface
Author(s): Daniel Lazewatsky
autogenerated on Mon Oct 6 2014 10:12:36