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


patrolling_sim
Author(s):
autogenerated on Thu Jun 6 2019 20:27:09