start_experiment.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 
00004 import Tkinter as tk
00005 import tkMessageBox
00006 import ConfigParser
00007 import thread
00008 from Tkinter import *
00009 from ttk import *
00010 import Image, tkFileDialog
00011 import numpy as np
00012 import sys, time, os, glob, shutil
00013 from math import atan2, degrees, radians
00014 import datetime
00015 import rospkg
00016 
00017 import os
00018 dirname = rospkg.RosPack().get_path('patrolling_sim')
00019 
00020 Alg_names = [ 
00021         [ 'RAND', 'Random' ],
00022         [ 'CR',   'Conscientious_Reactive' ],
00023         [ 'HCR',  'Heuristic_Conscientious_Reactive' ],
00024         [ 'HPCC', 'Conscientious_Cognitive' ],
00025         [ 'CGG',  'Cyclic' ],
00026         [ 'MSP',  'MSP' ],
00027         [ 'GBS',  'GBS' ],
00028         [ 'SEBS', 'SEBS' ],
00029         [ 'CBLS', 'CBLS' ],
00030         [ 'DTAG', 'DTAGreedy' ],
00031         [ 'DTAP', 'DTASSIPart' ]
00032      ]
00033 
00034 Map_names = ['cumberland','example','grid','1r5','broughton','DIAG_labs','DIAG_floor1']   
00035 
00036 NRobots_list = ['1','2','4','6','8','10','12']
00037 
00038 LocalizationMode_list = ['AMCL','fake_localization']
00039 
00040 NavigationMode_list = ['ros','thin_navigation']
00041 
00042 GWait_list = ['0','3','10']
00043 
00044 CommDelay_list = ['0','0.2','1','2']
00045 
00046 LostMsgRate_list = ['0','0.1','0.2','0.3']
00047 
00048 Terminal_list = ['gnome-terminal','xterm']
00049 
00050 initPoses = {}
00051 
00052 COMMDELAY_DEFAULT = 0.0
00053 
00054 NAVMODULE_DEFAULT = "ros" # "thin_navigation" or "ros"
00055 
00056 INITPOS_DEFAULT = "default"
00057 
00058 # return long name of the algorithm
00059 def findAlgName(alg):
00060     r = 'None'
00061     for i in range(0,len(Alg_names)):
00062         if (Alg_names[i][0]==alg):
00063             r = Alg_names[i][1]
00064     return r
00065 
00066 # load initial poses from configuration file
00067 def loadInitPoses():
00068   try:
00069     ConfigIP = ConfigParser.ConfigParser()
00070     ConfigIP.read(dirname+"/params/initial_poses.txt")
00071     for option in ConfigIP.options("InitialPoses"):
00072         #print option
00073         initPoses[option] = ConfigIP.get("InitialPoses", option)
00074   except:
00075     print "Could not load initial poses file"
00076 
00077 
00078 # get ROS time from /clock topic
00079 def getROStime():
00080     os.system("rostopic echo -n 1 /clock > rostime.txt")
00081     f = open(dirname+"/rostime.txt",'r')
00082     t = 0
00083     for line in f:
00084         if (line[2:6]=='secs'):
00085             t = int(line[8:])
00086     f.close()
00087     return t
00088 
00089 # get running simulation flag from /simulation_running param
00090 def getSimulationRunning():
00091     os.system("rosparam get /simulation_running > simrun.txt")
00092     f = open(dirname+"/simrun.txt",'r')
00093     t = True
00094     line = f.readline();
00095     if (line[0:5]=='false'):
00096         t = False
00097     f.close()
00098     return t
00099 
00100 # Run the experiment with the given arguments
00101 # Terminates if simulation is stopped (/simulation_running param is false)
00102 # or if timeout is reached (if this is >0)
00103 # CUSTOM_STAGE: use of extended API for stage (requires custom stage and stage_ros).
00104 def run_experiment(MAP, NROBOTS, INITPOS, ALG_SHORT, LOC_MODE, NAV_MODULE, GWAIT, COMMDELAY, TERM, TIMEOUT, CUSTOM_STAGE, SPEEDUP):
00105 
00106     ALG = findAlgName(ALG_SHORT)
00107     print 'Run the experiment'
00108     print 'Loading map ',MAP
00109     print 'Initial pos ',INITPOS
00110     print 'N. robot ',NROBOTS
00111     print 'Algorithm ',ALG,'  ',ALG_SHORT
00112     print 'Localization Mode ',LOC_MODE
00113     print 'Navigation module ', NAV_MODULE
00114     print 'Goal wait time ', GWAIT
00115     print 'Communication delay ',COMMDELAY
00116     print 'Terminal ',TERM
00117     print 'Timeout ',TIMEOUT
00118     print 'Custom Stage ',CUSTOM_STAGE
00119     print 'Simulator speed-up ',SPEEDUP    
00120 
00121     if (TIMEOUT>0):
00122         TIMEOUT = TIMEOUT + 10 # Let's give more time to complete actions and logging
00123 
00124     loadInitPoses()
00125     
00126     scenario = MAP+"_"+NROBOTS
00127 
00128     if (INITPOS!='default'):
00129         scenario = scenario+"_"+INITPOS
00130 
00131     iposes = initPoses[scenario.lower()]
00132     print scenario,'   ',iposes
00133     
00134     if (TERM == 'xterm'):
00135         roscore_cmd = 'xterm -e roscore &'
00136     else:
00137         roscore_cmd = 'gnome-terminal -e "bash -c \'roscore\'" &'
00138     print roscore_cmd
00139 
00140     os.system(roscore_cmd)
00141     os.system('sleep 3')
00142     os.system('rosparam set /use_sim_time true')
00143     os.system("rosparam set /goal_reached_wait "+GWAIT)
00144     os.system("rosparam set /communication_delay "+str(COMMDELAY))
00145 #    os.system("rosparam set /lost_message_rate "+LOSTMSGRATE)
00146     os.system("rosparam set /navigation_module "+NAV_MODULE)
00147     os.system("rosparam set /initial_positions "+INITPOS)
00148 
00149     cmd = './setinitposes.py '+MAP+' "'+iposes+'"'
00150     os.system(cmd)
00151     print cmd    
00152     os.system('sleep 1')
00153 
00154     cmd_monitor = 'rosrun patrolling_sim monitor '+MAP+' '+ALG_SHORT+' '+NROBOTS  
00155     custom_stage = ''
00156     if (CUSTOM_STAGE=="true"):
00157       custom_stage = ' custom_stage:=true'
00158     cmd_stage = 'roslaunch patrolling_sim map.launch map:='+MAP+custom_stage
00159     if (os.getenv('ROS_DISTRO')=='groovy'):
00160       cmd_stage = cmd_stage + " stage_pkg:=stage"
00161     print cmd_monitor
00162     print cmd_stage
00163     if (TERM == 'xterm'):
00164         os.system('xterm -e  "'+cmd_monitor+'" &') 
00165         os.system('xterm -e  "'+cmd_stage+'" &')
00166     else: 
00167         os.system('gnome-terminal --tab -e  "bash -c \''+cmd_monitor+'\'" --tab -e "bash -c \''+cmd_stage+'\'" &')
00168     
00169     os.system('sleep 3')
00170     
00171     # Start robots
00172     if (LOC_MODE == 'AMCL'):
00173         robot_launch = 'robot.launch'
00174     else:
00175         robot_launch = 'robot_fake_loc.launch'
00176     
00177     gcmd = 'gnome-terminal '
00178     for i in range(0,int(NROBOTS)):
00179         print 'Run robot ',i
00180         cmd = 'bash -c \'roslaunch patrolling_sim '+robot_launch+' robotname:=robot_'+str(i)+' mapname:='+MAP+' '
00181         
00182         # Set navigation modules
00183         if (NAV_MODULE=="ros_navigation"):
00184            cmd = cmd + ' use_amcl:=true use_move_base:=true use_thin_localizer:=false use_thin_planner:=false '
00185         elif (NAV_MODULE=="thin_navigation"):
00186            cmd = cmd + ' use_amcl:=false use_move_base:=false  use_thin_localizer:=true use_thin_planner:=true '
00187         elif (NAV_MODULE=="thin_localizer_only"):
00188            cmd = cmd + ' use_amcl:=false use_move_base:=true  use_thin_localizer:=true use_thin_planner:=false '
00189            
00190         cmd = cmd + "'"
00191         print cmd
00192         if (TERM == 'xterm'):
00193           os.system('xterm -e  "'+cmd+'" &')
00194           os.system('sleep 1')
00195         gcmd = gcmd + ' --tab -e "'+cmd+'" '
00196     gcmd = gcmd + '&'
00197     if (TERM == 'gnome-terminal'):
00198         #print gcmd
00199         os.system(gcmd)
00200     os.system('sleep 5')    
00201         
00202     # Start patrol behaviors
00203     gcmd = 'gnome-terminal '
00204     for i in range(0,int(NROBOTS)):
00205         print 'Run patrol robot ',i
00206         if (ALG_SHORT=='MSP'):
00207             cmd = 'bash -c \'rosrun patrolling_sim '+ALG+' __name:=patrol_robot'+str(i)+' '+MAP+' '+str(i)+' MSP/'+MAP+'/'+MAP+'_'+str(NROBOTS)+'_'+str(i)+' '+'\''
00208         elif (ALG_SHORT=='GBS' or ALG_SHORT=='SEBS' or ALG_SHORT=='CBLS'):
00209             cmd = 'bash -c \'rosrun patrolling_sim '+ALG+' __name:=patrol_robot'+str(i)+' '+MAP+' '+str(i)+' '+str(NROBOTS)+'\''
00210         else:
00211             now = datetime.datetime.now()
00212             dateString = now.strftime("%Y-%m-%d-%H:%M")
00213             #cmd = 'bash -c \'rosrun patrolling_sim '+ALG+' __name:=patrol_robot'+str(i)+' '+MAP+' '+str(i)+' > logs/'+ALG+'-'+dateString+'-robot'+str(i)+'.log \''
00214             cmd = 'bash -c \'rosrun patrolling_sim '+ALG+' __name:=patrol_robot'+str(i)+' '+MAP+' '+str(i)+'\''
00215         print cmd
00216         if (TERM == 'xterm'):
00217           os.system('xterm -e  "'+cmd+'" &')
00218           os.system('sleep 1')
00219         gcmd = gcmd + ' --tab -e "'+cmd+'" '
00220     gcmd = gcmd + '&'
00221     if (TERM == 'gnome-terminal'):
00222       #print gcmd
00223       os.system(gcmd)
00224     os.system('sleep '+NROBOTS)
00225 
00226     print 'Stage simulator footprints and speedup'
00227     os.system('rostopic pub /stageGUIRequest std_msgs/String "data: \'footprints\'"  --once')
00228     os.system('rostopic pub /stageGUIRequest std_msgs/String "data: \'speedup_%.1f\'"  --once' %(SPEEDUP))
00229     #os.system('rm ~/.ros/stage-000003.png')
00230 
00231     now = datetime.datetime.now()
00232     strinittime = now.strftime("%Y%m%d_%H%M%S")
00233 
00234     print 'Experiment started at ',strinittime
00235     # wait for termination
00236     run = True
00237     while (run):
00238         t = getROStime()
00239         #print "Elapsed time: ",t," sec Timeout = ",TIMEOUT
00240         if ((TIMEOUT>0 and t>TIMEOUT) or (not getSimulationRunning())):        
00241             run = False;
00242         os.system('sleep 1')
00243 
00244     #print "Taking a screenshot..."
00245     #os.system('rostopic pub /stageGUIRequest std_msgs/String "data: \'screenshot\'"  --once')
00246     #os.system('sleep 5')
00247     #cmd = 'mv ~/.ros/stage-000005.png results/screenshots/stage-%s.png' %(strinittime)
00248     #os.system(cmd)
00249 
00250     print "Terminating Experiment"
00251     os.system("./stop_experiment.sh")
00252 
00253 
00254 class DIP(tk.Frame):
00255     def __init__(self, parent):
00256         tk.Frame.__init__(self, parent) 
00257         self.parent = parent        
00258         self.initUI()
00259         
00260     def initUI(self):
00261         self.loadOldConfig()
00262         
00263         
00264         self.parent.title("MRP Experiment Launcher")
00265         self.style = Style()
00266         self.style.theme_use("alt")
00267         self.parent.resizable(width=FALSE, height=FALSE)
00268         self.pack(fill=BOTH, expand=1)
00269         
00270         #self.columnconfigure(1, weight=1)
00271         #self.columnconfigure(3, pad=7)
00272         #self.rowconfigure(3, weight=1)
00273         #self.rowconfigure(7, pad=7)
00274 
00275         _row = 0
00276         
00277         lbl = Label(self, text="Map")
00278         lbl.grid(sticky=W, row = _row, column= 0, pady=4, padx=5)
00279                 
00280         self.map_name_list = Map_names
00281         self.map_ddm = StringVar(self)
00282         try:
00283             lastmap=self.oldConfigs["map"]
00284         except:
00285             lastmap=self.map_name_list[0]
00286         self.map_ddm.set(lastmap)
00287         tk.OptionMenu(self, self.map_ddm, *self.map_name_list).grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00288 
00289         _row = _row + 1
00290 
00291         lbl = Label(self, text="N. Robots")
00292         lbl.grid(sticky=W, row=_row, column=0, pady=4, padx=5)
00293 
00294         self.robots_n_list = NRobots_list
00295         self.robots_ddm = StringVar(self)
00296         try:
00297             lastnrobots=self.oldConfigs["nrobots"]
00298         except:
00299             lastnrobots=self.robots_n_list[0]
00300         self.robots_ddm.set(lastnrobots)
00301         tk.OptionMenu(self, self.robots_ddm, *self.robots_n_list).grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00302 
00303         _row = _row + 1
00304 
00305         lbl = Label(self, text="Algorithm")
00306         lbl.grid(sticky=W, row = _row, column= 0, pady=4, padx=5)
00307 
00308         self.algorithm_list = []
00309         for i in range(0,len(Alg_names)):
00310             self.algorithm_list += [Alg_names[i][0]]
00311 
00312         self.alg_ddm = StringVar(self)
00313         try:
00314             lastalg=self.oldConfigs["algorithm"]
00315         except:
00316             lastalg=self.algorithm_list[0]
00317         self.alg_ddm.set(lastalg)
00318         tk.OptionMenu(self, self.alg_ddm, *self.algorithm_list).grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00319         
00320         _row = _row + 1
00321 
00322         lbl = Label(self, text="Localization Mode")
00323         lbl.grid(sticky=W, row = _row, column= 0, pady=4, padx=5)
00324 
00325         self.locmode_list = LocalizationMode_list
00326         self.locmode_ddm = StringVar(self)
00327         try:
00328             lastlocmode=self.oldConfigs["locMode"]
00329         except:
00330             lastlocmode=self.locmode_list[0]
00331         self.locmode_ddm.set(lastlocmode)
00332         tk.OptionMenu(self, self.locmode_ddm, *self.locmode_list).grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00333 
00334         _row = _row + 1
00335 
00336         lbl = Label(self, text="Navigation Mode")
00337         lbl.grid(sticky=W, row = _row, column= 0, pady=4, padx=5)
00338 
00339         self.navmode_list = NavigationMode_list
00340         self.navmode_ddm = StringVar(self)
00341         try:
00342             lastnavmode=self.oldConfigs["navMode"]
00343         except:
00344             lastnavmode=self.navmode_list[0]
00345         self.navmode_ddm.set(lastnavmode)
00346         tk.OptionMenu(self, self.navmode_ddm, *self.navmode_list).grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00347 
00348         _row = _row + 1
00349 
00350         lbl = Label(self, text="Goal wait time")
00351         lbl.grid(sticky=W, row = _row, column= 0, pady=4, padx=5)
00352 
00353         self.gwait_list = GWait_list
00354         self.gwait_ddm = StringVar(self)
00355         try:
00356             lastgwait=self.oldConfigs["gwait"]
00357         except:
00358             lastgwait=self.gwait_list[0]
00359         self.gwait_ddm.set(lastgwait)
00360         tk.OptionMenu(self, self.gwait_ddm, *self.gwait_list).grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00361 
00362         _row = _row + 1
00363 
00364         lbl = Label(self, text="Terminal")
00365         lbl.grid(sticky=W, row = _row, column= 0, pady=4, padx=5)
00366 
00367         self.term_list = Terminal_list
00368         self.term_ddm = StringVar(self)
00369         try:
00370             lastterm=self.oldConfigs["term"]
00371         except:
00372             lastterm=self.term_list[0]
00373         self.term_ddm.set(lastterm)
00374         tk.OptionMenu(self, self.term_ddm, *self.term_list).grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00375   
00376         _row = _row + 1
00377 
00378         launchButton = Button(self, text="Start Experiment",command=self.launch_script)
00379         launchButton.grid(sticky=W, row=_row, column=0, pady=4, padx=5)
00380         
00381         launchButton = Button(self, text="Stop Experiment",command=self.kill_demo)
00382         launchButton.grid(sticky=W, row=_row, column=1, pady=4, padx=5)
00383         
00384     
00385     def launch_script(self):
00386         self.saveConfigFile();
00387         thread.start_new_thread( run_experiment, (self.map_ddm.get(), self.robots_ddm.get(), INITPOS_DEFAULT, self.alg_ddm.get(),self.locmode_ddm.get(), NAVMODULE_DEFAULT, self.gwait_ddm.get(), COMMDELAY_DEFAULT, self.term_ddm.get(),0,"false",1.0) )
00388 
00389     
00390     def quit(self):
00391       self.parent.destroy()
00392       
00393     def kill_demo(self):
00394       os.system("rosparam set /simulation_running false")
00395       
00396       
00397     def saveConfigFile(self):
00398       f = open(dirname+"/lastConfigUsed", 'w')
00399       f.write("[Config]\n")
00400       f.write("map: %s\n"%self.map_ddm.get())
00401       f.write("nrobots: %s\n"%self.robots_ddm.get())
00402       f.write("algorithm: %s\n"%self.alg_ddm.get())
00403       f.write("locmode: %s\n"%self.locmode_ddm.get())
00404       f.write("navmode: %s\n"%self.navmode_ddm.get())
00405       f.write("gwait: %s\n"%self.gwait_ddm.get())
00406       f.write("term: %s\n"%self.term_ddm.get())
00407       f.close()
00408 
00409 
00410     def loadOldConfig(self):
00411       try:
00412         self.oldConfigs = {}
00413         self.Config = ConfigParser.ConfigParser()
00414         self.Config.read(dirname+"/lastConfigUsed")
00415         for option in self.Config.options("Config"):
00416           self.oldConfigs[option] = self.Config.get("Config", option)
00417       except:
00418         print "Could not load config file"
00419 
00420 
00421     
00422 
00423 
00424 def main():
00425 
00426   if (len(sys.argv)==1):
00427     root = tk.Tk()
00428     DIP(root)
00429     root.geometry("300x320+0+0")
00430     root.mainloop()  
00431 
00432   elif (len(sys.argv)<10):
00433     print "Use: ",sys.argv[0]
00434     print " or  ",sys.argv[0],' <map> <n.robots> <init_pos> <alg_short> <loc_mode> <nav_module> <goal_wait_time> <communication_delay> <terminal> <timeout> [<custom_stage_flag>|def:false] [<sim_speedup>|def:1.0]'
00435 
00436   else:
00437     MAP = sys.argv[1]
00438     NROBOTS = sys.argv[2]
00439     INITPOS = sys.argv[3]
00440     ALG_SHORT = sys.argv[4]
00441     LOC_MODE = sys.argv[5]
00442     NAV_MODULE = sys.argv[6]
00443     GWAIT = sys.argv[7]
00444     COMMDELAY = sys.argv[8]
00445     TERM = sys.argv[9]
00446     TIMEOUT = int(sys.argv[10])
00447     CUSTOM_STAGE = False
00448     SPEEDUP = 1.0
00449     if (len(sys.argv)>=12):
00450       CUSTOM_STAGE = sys.argv[11]
00451     if (len(sys.argv)>=13):
00452       SPEEDUP = float(sys.argv[12])
00453     
00454     run_experiment(MAP, NROBOTS, INITPOS, ALG_SHORT, LOC_MODE, NAV_MODULE, GWAIT, COMMDELAY, TERM, TIMEOUT, CUSTOM_STAGE,SPEEDUP)
00455 
00456  
00457 
00458 
00459 if __name__ == '__main__':
00460     os.chdir(dirname)
00461     main()
00462 


patrolling_sim
Author(s):
autogenerated on Mon Oct 2 2017 03:13:50