training_gui.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import sys
00003 import os
00004 import random
00005 import csv
00006 import math
00007 import pygame
00008 
00009 import roslib; roslib.load_manifest('wouse')
00010 import rospy
00011 from geometry_msgs.msg import Vector3Stamped
00012 
00013 from PySide.QtCore import *
00014 from PySide.QtGui import *
00015 from PySide.QtUiTools import QUiLoader
00016 
00017 #DEGREES = ['WEAK', 'AVERAGE', 'STRONG']
00018 DEGREES = ['']
00019 ACTIONS = ['WINCE', 'NOD', 'SHAKE', 'JOY', 'SUPRISE', 'FEAR', 'ANGER', 
00020             'DISGUST', 'SADNESS']
00021 SYMBOLS = ["**"*25, "%%"*25, "^v"*25, '##'*25, '&&'*25, '$$'*25]
00022 
00023 class WouseSetupDialog(object):
00024     """A dialog box for setting session parameters for training the wouse."""
00025     def __init__(self):
00026         """ Load .ui file from QtDesigner, add callbacks as necessary"""
00027         ui_file = WOUSE_PKG+'/src/wouse/wouse_train_options.ui'
00028         self.dialog = QUiLoader().load(ui_file)
00029         self.dialog.rounds_spin.valueChanged.connect(self.update_time)
00030         self.dialog.recording_spin.valueChanged.connect(self.update_time)
00031         self.dialog.recovery_spin.valueChanged.connect(self.update_time)
00032         self.dialog.file_button.clicked.connect(self.file_button_cb) 
00033         self.dialog.file_field_edit.setText(WOUSE_PKG+'/data/')
00034         self.dialog.buttonBox.accepted.connect(self.ok_cb)
00035         self.dialog.buttonBox.rejected.connect(self.cancel_cb)
00036         self.update_time()
00037 
00038     def file_button_cb(self):
00039         """Use file dialog to get .csv file.  Check for csv, update Lineedit"""
00040         direc = self.dialog.file_field_edit.text()
00041         filename = QFileDialog.getOpenFileName(self.dialog,
00042                                     caption="File to stop wouse training data",
00043                                     dir=direc,
00044                                     filter="*.csv")
00045         if len(filename[0]) != 0:
00046             if filename[0][-4:] != '.csv':
00047                 QMessageBox.warning(self.dialog, "Warning: Invalid File",
00048                 "Warning: Selected File does not appear to be a CSV (.csv)\
00049                 data file.")
00050             self.dialog.file_field_edit.setText(filename[0])
00051          
00052     def calc_time(self):
00053         """Calculate the time (s) required for full run with current settings"""
00054         tot_time = (self.dialog.recording_spin.value()+
00055                     self.dialog.recovery_spin.value())
00056         return len(ACTIONS)*self.dialog.rounds_spin.value()*tot_time
00057 
00058     def update_time(self):
00059         """Parse time to minutes:seconds format, update interface"""
00060         time = self.calc_time()
00061         mins = str(int(time)/60)
00062         secs = str(int(round(time%60.)))
00063         if len(secs)==1:
00064             secs = "".join(['0',secs])
00065         self.dialog.duration.setText('%s:%s' %(mins,secs))
00066 
00067     def ok_cb(self):
00068         """Check for acceptable file. Warn if bad, if good, close, return 1"""
00069         if self.dialog.file_field_edit.text()[-4:] != '.csv':
00070             return QMessageBox.warning(self.dialog, "Warning: Invalid File",
00071             "Please choose a valid CSV (.csv) data file.")
00072         self.dialog.accept()
00073 
00074     def cancel_cb(self):
00075         """ Close dialog, return 0/Rejected"""
00076         self.dialog.reject()
00077 
00078 class WouseTrainer(object):
00079     """ A class for printing random facial expression commands,\\
00080         and saving data from a topic of wouse movement data."""
00081     def __init__(self):
00082         #QtDialog for setting parameters for session
00083         app = QApplication([])
00084         self.setup_gui = WouseSetupDialog()
00085         self.setup_gui.dialog.show()
00086         if self.setup_gui.dialog.exec_() == 0:
00087             sys.exit()
00088         self.rounds = self.setup_gui.dialog.rounds_spin.value()
00089         self.record_dur = self.setup_gui.dialog.recording_spin.value()
00090         self.recovery_dur = self.setup_gui.dialog.recovery_spin.value() 
00091         
00092         rospy.Subscriber('/wouse_movement', Vector3Stamped, self.movement_cb)
00093         #Open file for recoding data
00094         output_file = self.setup_gui.dialog.file_field_edit.text()
00095         self.csv_writer = csv.writer(open(output_file, 'ab'))
00096 
00097         #Init pygame, used for playing sounds
00098         pygame.init()
00099         self.sound_new = pygame.mixer.Sound(WOUSE_PKG+'/sounds/new_item.wav')
00100         self.sound_done = pygame.mixer.Sound(WOUSE_PKG+'/sounds/item_done.wav')
00101 
00102         self.degree='AVERAGE'
00103         self.recording = False
00104 
00105     def movement_cb(self, v3s):
00106         """Write a new line to the csv file for incoming data."""
00107         if self.recording:
00108             line = [self.degree, self.behavior, v3s.header.stamp.to_sec(),
00109                     v3s.vector.x, v3s.vector.y]
00110             self.csv_writer.writerow(line)
00111 
00112     def run(self, rounds, record_dur, recovery_dur):
00113         """Perform training given parameters and actions."""
00114         act_list = rounds*ACTIONS
00115         random.shuffle(act_list)
00116         count = 1
00117         print "Starting in: "
00118         countdown = range(1,10)
00119         countdown.reverse()
00120         for number in countdown:
00121             print "%s" %number
00122             rospy.sleep(1)
00123         while len(act_list) > 0 and not rospy.is_shutdown():
00124             self.behavior = act_list.pop()
00125             bar = random.choice(SYMBOLS)
00126             self.recording = True
00127             self.sound_new.play()
00128             print "\r\n"*15
00129             print bar
00130             print "%s:     %s" %(count, self.behavior)
00131             print bar
00132             print "\r\n"*15
00133             rospy.sleep(record_dur)
00134             self.recording = False
00135             self.sound_done.play()
00136             count += 1
00137             rospy.sleep(recovery_dur)
00138         if not act_list:
00139             print "Training Session Completed"
00140         else:
00141             print "Training Session Ended Early"
00142 
00143 if __name__=='__main__':
00144     rospy.init_node('wouse_trainer')
00145     WOUSE_PKG = roslib.packages.get_pkg_dir('wouse')
00146     wt = WouseTrainer()
00147     wt.run(wt.rounds, wt.record_dur, wt.recovery_dur)
00148 


wouse
Author(s): Phillip M. Grice, Advisor: Prof. Charlie Kemp, Lab: The Healthcare Robotoics Lab at Georgia Tech.
autogenerated on Wed Nov 27 2013 11:57:42