Go to the documentation of this file.00001
00002
00003 PKG = 'launch_tools'
00004
00005 import roslib; roslib.load_manifest(PKG)
00006 import rospy
00007 import subprocess
00008 import signal
00009 import shlex
00010 import time
00011
00012 class Executer():
00013 """
00014 Simple class for executing a command in a subprocess.
00015 """
00016 def __init__(self, command, stdout, stderr):
00017 self.command = shlex.split(command)
00018 self.stdout = stdout
00019 self.stderr = stderr
00020 def execute(self):
00021 rospy.loginfo("Launching process: \"%s\"...", " ".join(self.command))
00022 rospy.loginfo("stdout/stderr: %s/%s", str(self.stdout), str(self.stderr))
00023 self.process = subprocess.Popen(self.command, stdout=self.stdout, stderr=self.stderr)
00024 rospy.loginfo("Process launched.")
00025 def interrupt(self):
00026 if self.process.poll() is None:
00027 rospy.loginfo("Terminating process...")
00028 self.process.terminate()
00029 waiting_seconds = 0
00030 while self.process.poll() is None and waiting_seconds < 5:
00031 rospy.loginfo("Waiting for process to finish...")
00032 time.sleep(1)
00033 waiting_seconds = waiting_seconds + 1
00034 if self.process.poll() is None:
00035 rospy.loginfo("Killing process...")
00036 self.process.kill()
00037 self.process.wait()
00038 rospy.loginfo("Process has stopped with return code %i", self.process.returncode)
00039
00040 if __name__ == "__main__":
00041 rospy.init_node('executer', anonymous=True)
00042 command = rospy.get_param("~command")
00043 stdout_file = rospy.get_param("~stdout_file", "")
00044 stderr_file = rospy.get_param("~stderr_file", "")
00045 stdout = None if len(stdout_file) == 0 else open(stdout_file, 'w')
00046 stderr = None if len(stderr_file) == 0 else open(stderr_file, 'w')
00047 executer = Executer(command, stdout, stderr)
00048 executer.execute()
00049 rospy.on_shutdown(executer.interrupt)
00050 while executer.process.poll() is None and not rospy.is_shutdown():
00051 time.sleep(0.1)
00052