00001 
00002 import roslib
00003 roslib.load_manifest('smach_ros')
00004 roslib.load_manifest('actionlib')
00005 roslib.load_manifest('rfid_datacapture')
00006 roslib.load_manifest('rfid_demos')
00007 roslib.load_manifest('rfid_behaviors')
00008 roslib.load_manifest('hrl_lib')
00009 roslib.load_manifest('tf')
00010 roslib.load_manifest('sensor_msgs')
00011 roslib.load_manifest('visualization_msgs')
00012 import rospy
00013 
00014 import cPickle as pkl
00015 import hrl_lib.rutils as ru
00016 import hrl_lib.viz as viz
00017 import sensor_msgs.msg as sm
00018 import numpy as np, math
00019 import sm_aware_home_explore as ahe
00020 import visualization_msgs.msg as vm
00021 import glob
00022 import json
00023 import yaml
00024 import time
00025 import os
00026 
00027 
00028 def publish_readings( trial, obj, pub_time = 30e3, screen_cap = False ):
00029     loc = ( trial + obj ) % 9
00030 
00031     fname = 'search_aware_home/woot_150_'+str(trial)+'_reads.pkl'
00032     
00033     f = open( fname, 'r' )
00034     r = pkl.load(f)
00035     f.close()
00036 
00037     rospy.init_node( 'starter_woot' )
00038 
00039     vsm = viz.single_marker
00040 
00041 
00042     
00043     pos = [ vsm( np.matrix([ p.ps_ant_map.pose.position.x,
00044                              p.ps_ant_map.pose.position.y,
00045                              p.ps_ant_map.pose.position.z ]).T,
00046                  np.matrix([ p.ps_ant_map.pose.orientation.x,
00047                              p.ps_ant_map.pose.orientation.y,
00048                              p.ps_ant_map.pose.orientation.z,
00049                              p.ps_ant_map.pose.orientation.w ]).T,
00050                  'arrow', '/map',
00051                  color = [1.0, 0.0, 0.0, 0.8], 
00052                  duration = 10.0,
00053                  m_id = i )
00054             for i,p in enumerate( r )
00055             if p.read.rssi != -1 and p.read.tagID == ahe.tdb[obj][0] ]
00056 
00057     neg = [ vsm( np.matrix([ p.ps_ant_map.pose.position.x,
00058                              p.ps_ant_map.pose.position.y,
00059                              p.ps_ant_map.pose.position.z ]).T,
00060                  np.matrix([ p.ps_ant_map.pose.orientation.x,
00061                              p.ps_ant_map.pose.orientation.y,
00062                              p.ps_ant_map.pose.orientation.z,
00063                              p.ps_ant_map.pose.orientation.w ]).T,
00064                  'arrow', '/map',
00065                  color = [0.2, 0.2, 0.2, 0.2], 
00066                  duration = 10.0,
00067                  m_id = i + len(r) )
00068             for i,p in enumerate( r )
00069             if p.read.tagID != ahe.tdb[obj] ] 
00070 
00071     print 'Pos: ', len(pos), '\nNeg: ', len(neg)
00072 
00073 
00074     
00075     tm = [ vsm( np.matrix([ ahe.pts[loc][1][0],
00076                             ahe.pts[loc][1][1],
00077                             ahe.pts[loc][1][2] ]).T,
00078                 np.matrix([ [0.0], [0.0], [0.0], [1.0] ]),
00079                 'sphere', '/map',
00080                 color = [0.0, 1.0, 0.0, 1.0], 
00081                 duration = 10.0,
00082                 m_id = 2*len(r) + 1 )]
00083 
00084     xyz = np.array([ [p.ps_base_map.pose.position.x,
00085                       p.ps_base_map.pose.position.y,
00086                       p.ps_base_map.pose.position.z ] for p in r ]).T
00087     pts = ru.np_to_pointcloud( xyz, '/map' )
00088 
00089     pub_pts = rospy.Publisher( '/robot_traj', sm.PointCloud )
00090     pub_mark = rospy.Publisher( '/tag_poses', vm.Marker )
00091 
00092 
00093     
00094 
00095     obj_name = ahe.tdb[obj][0]  
00096     tname = obj_name.replace( ' ', '' )
00097 
00098 
00099     
00100     search_fname = 'search_aware_home/woot_150_' + str(trial) + '_tag_' + tname + '.yaml'
00101     try:
00102         f = open( search_fname )
00103     except:
00104         return
00105     
00106     y = yaml.load( f )
00107     f.close()
00108 
00109     search = [ vsm( np.matrix([ y['pose']['position']['x'],
00110                                 y['pose']['position']['y'],
00111                                 y['pose']['position']['z'] ]).T,
00112                     np.matrix([ y['pose']['orientation']['x'],
00113                                 y['pose']['orientation']['y'],
00114                                 y['pose']['orientation']['z'],
00115                                 y['pose']['orientation']['w'] ]).T,
00116                    'arrow', '/map',
00117                    scale = [0.5, 1.0, 1.0],
00118                    color = [255./255, 123./255, 1./255, 1.0], 
00119                    duration = 10.0,
00120                    m_id = 2 * len(r) + 2 )]
00121 
00122 
00123     
00124     servo_fname = 'search_aware_home/woot_150_' + str(trial) + '_tag_' + tname + '_end.txt'
00125 
00126     try:
00127         f = open( servo_fname )
00128     except:
00129         return
00130     y = f.readlines()
00131     f.close()
00132     
00133     
00134     
00135     
00136     
00137     
00138     
00139     
00140 
00141     quat = y[-2].find('Quaternion')+10
00142     quat_list = json.loads( y[-2][quat:] )
00143 
00144     sloc = y[-3].find('tion:')+5
00145     sloc_list = json.loads( y[-3][sloc:] )
00146 
00147 
00148     servo = [ vsm( np.matrix([ sloc_list ]).T,
00149                    np.matrix([ quat_list ]).T,
00150                    'arrow', '/map',
00151                    scale = [0.5, 1.0, 1.0],
00152                    color = [0./255, 205./255, 255./255, 1.0], 
00153                    duration = 10.0,
00154                    m_id = 2 * len(r) + 3 )]
00155 
00156 
00157     marks = neg + pos + tm + search + servo
00158     
00159     t0 = time.time()
00160     while time.time() - t0 < pub_time and not rospy.is_shutdown():
00161         pts.header.stamp = rospy.Time.now()
00162         pub_pts.publish( pts )
00163         
00164         [ pub_mark.publish( x ) for x in marks ]
00165         rospy.sleep( 1.0 )
00166 
00167     if screen_cap:
00168         os.system( 'scrot -d 2 -u Obj%d_Trial%d.png' % ( obj, trial ))
00169         
00170 
00171     print 'Closing down... letting markers expire'
00172     rospy.sleep( 15 )
00173 
00174         
00175 
00176 if __name__ == '__main__':
00177     import optparse
00178     p = optparse.OptionParser()
00179     
00180     
00181     p.add_option('--trial', action='store', type='int', dest='trial',
00182                  help='trial number (0-8)')
00183     p.add_option('--obj', action='store', type='int', dest='obj',
00184                  help='object number (0-8)')
00185     
00186     
00187 
00188     opt, args = p.parse_args()
00189 
00190     if opt.trial < 9:
00191         publish_readings( opt.trial, opt.obj )
00192     else:
00193         print 'Click on RVIZ!'
00194         time.sleep( 3 )
00195         
00196         for trial in [1]:
00197             
00198             for obj in [6]:
00199                 print 'Change screen to RVIZ. Starting %d, %d' % (trial, obj)
00200                 publish_readings( trial, obj, 15, screen_cap = True )
00201     
00202