Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import time
00036 import threading
00037
00038 from roslaunch import node_args, nodeprocess
00039 import rospy
00040
00041
00042 class Polling(threading.Thread):
00043 def __init__(self, parent):
00044 super(Polling, self).__init__()
00045 self._parent = parent
00046
00047 def run(self):
00048 while True:
00049 rospy.logdebug('Proc={} Died? {}'.format(
00050 self._parent.get_proc_name(),
00051 self._parent.has_died()))
00052 time.sleep(1.0)
00053
00054
00055 class NodeProxy(object):
00056 '''
00057 Works as a proxy between ROS Node
00058 (more in particular, roslaunch.nodeprocess) & GUI.
00059 '''
00060
00061 __slots__ = ['_run_id', 'master_uri', 'config', '_process']
00062
00063 def __init__(self, run_id, master_uri, config):
00064 self._run_id = run_id
00065 self.master_uri = master_uri
00066 self.config = config
00067
00068
00069 self._process = self.recreate_process()
00070
00071
00072 def is_running(self):
00073 rospy.logdebug('BEFORE started={}, stopped={} alive={}'.format(
00074 self._process.started,
00075 self._process.stopped,
00076 self._process.is_alive()))
00077 return self._process.started and not self._process.stopped
00078
00079
00080
00081 def has_died(self):
00082 rospy.logdebug('Proc={} started={}, stopped={}, is_alive={}'.format(
00083 self.get_proc_name(), self._process.started, self._process.stopped,
00084 self._process.is_alive()))
00085
00086 return (self._process.started and not self._process.stopped
00087 and not self._process.is_alive())
00088
00089 def recreate_process(self):
00090 '''
00091 Create and set roslaunch.nodeprocess.LocalProcess to member variable.
00092 @rtype: roslaunch.nodeprocess.LocalProcess
00093 '''
00094 _local_process = nodeprocess.LocalProcess
00095 try:
00096 _local_process = nodeprocess.create_node_process(
00097 self._run_id, self.config, self.master_uri)
00098 except node_args.NodeParamsException as e:
00099 rospy.logerr('roslaunch failed to load the node. {}'.format(
00100 e.message))
00101
00102
00103 return _local_process
00104
00105 def start_process(self):
00106
00107 self._process.start()
00108
00109 def stop_process(self):
00110
00111
00112 try:
00113 self._process.stop()
00114 except Exception as e:
00115
00116 rospy.logdebug('Proxy stop_process exception={}'.format(e.message))
00117
00118 def get_spawn_count(self):
00119 return self._process.spawn_count
00120
00121 def get_proc_name(self):
00122 return self._process.name
00123
00124 def get_proc_exit_code(self):
00125 return self._process.exit_code