explore.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 import os
00003 import argparse
00004 import rospkg
00005 import time
00006 import ConfigParser
00007 import socket
00008 
00009 parser = argparse.ArgumentParser(description="Create and run multi-robot exploration.")
00010 
00011 parser.add_argument("-t", "--time", metavar="HH-MM-SS", default=[time.strftime("%H-%M-%S", time.localtime())],
00012                     dest="time", nargs=1, help="The name of the 'time'-directory for the log path.")
00013 parser.add_argument("-d", "--date", metavar="yy-mm-dd", default=[time.strftime("%y-%m-%d", time.localtime())],
00014                     dest="date", nargs=1, help="The name of the 'time'-directory for the log path.")
00015 parser.add_argument("-i", "--sim-id", default=[1], nargs=1, metavar="ID",
00016                     help="The ID of the execution run", dest="sim_id")
00017 parser.add_argument("--exp-strategy",dest="exploration_strategy",type=int,nargs="?",default=1,
00018                     help="The strategy to be used for exploration.",choices=range(0,7))
00019 parser.add_argument("--screen-output",dest="screen_output",default=False,help="Set ROS output to screen.",
00020                     action="store_true")
00021 
00022 args, unknown = parser.parse_known_args()
00023 
00024 
00025 
00026 if args.screen_output:
00027     output_type = "screen"
00028 else:
00029     output_type = "log"
00030 
00031 rospack = rospkg.RosPack()
00032 launch_file = "now.launch";
00033 sim_id = args.sim_id[0]
00034 
00035 package_path = rospack.get_path("explorer")
00036 launch_file = "launch_exploration.launch";
00037 launch_path = os.path.join(package_path, "launch", launch_file)
00038 
00039 t = time.localtime()
00040 log_path = os.path.join(rospack.get_path("multi_robot_analyzer"), "logs", args.date[0], args.time[0], str(sim_id))
00041 fh_launch_file = open(launch_path,"w")
00042 fh_launch_file.truncate()
00043 print ("Writing File headers")
00044 fh_launch_file.write("<?xml version=\"1.0\"?>\n")
00045 fh_launch_file.write("<launch>\n")
00046 
00047 
00048 fh_launch_file.write("\t<include file=\"$(find explorer)/launch/simple_navigation_prerequisites_hydro_$(env ROBOT_PLATFORM).launch\">\n")
00049 fh_launch_file.write("\t\t<arg name=\"log_path\" value=\"%s\" />\n" % log_path)
00050 fh_launch_file.write("\t</include>\n")
00051 
00052 fh_launch_file.write("\t<include file=\"$(find explorer)/launch/simple_navigation_$(env ROBOT_PLATFORM).launch\">\n")
00053 fh_launch_file.write("\t\t<arg name=\"frontier_selection\" value=\"%s\" />" %args.exploration_strategy)
00054 fh_launch_file.write("\t\t<arg name=\"log_path\" value=\"%s\" />\n" % log_path)
00055 fh_launch_file.write("\t</include>\n")
00056 
00057 fh_launch_file.write("\t\t<include file=\"$(find map_merger)/launch/map_merger.launch\">\n")
00058 fh_launch_file.write("\t\t\t<arg name=\"output\" value=\"%s\" />" %output_type)
00059 fh_launch_file.write("\t\t\t<arg name=\"log_path\" value=\"%s\" />\n" %log_path)
00060 fh_launch_file.write("\t\t\t<arg name=\"use_sim_time\" value=\"false\" />\n")
00061 fh_launch_file.write("\t\t</include>\n")
00062 
00063 
00064 fh_launch_file.write("</launch>\n")
00065 fh_launch_file.close()
00066 
00067 print("start_time_run_%s" %sim_id, "%s" %time.ctime())
00068 os.system("roslaunch explorer launch_exploration.launch")


explorer
Author(s): Daniel Neuhold , Torsten Andre
autogenerated on Thu Aug 27 2015 11:56:52