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
00044 def __init__(self, parent):
00045 super(Polling, self).__init__()
00046 self._parent = parent
00047
00048 def run(self):
00049 while True:
00050 rospy.logdebug('Proc={} Died? {}'.format(self._parent.get_proc_name(),
00051 self._parent.has_died()))
00052 time.sleep(1.0)
00053
00054
00055 class NodeProxy(object):
00056
00057 '''
00058 Works as a proxy between ROS Node
00059 (more in particular, roslaunch.nodeprocess) & GUI.
00060 '''
00061
00062 __slots__ = ['_run_id', 'master_uri', 'config', '_process']
00063
00064 def __init__(self, run_id, master_uri, config):
00065 self._run_id = run_id
00066 self.master_uri = master_uri
00067 self.config = config
00068
00069
00070 self._process = self.recreate_process()
00071
00072
00073 def is_running(self):
00074 rospy.logdebug('BEFORE started={}, stopped={} alive={}'.format(
00075 self._process.started,
00076 self._process.stopped,
00077 self._process.is_alive()))
00078 return self._process.started and not self._process.stopped
00079
00080
00081
00082 def has_died(self):
00083 rospy.logdebug('Proc={} started={}, stopped={}, is_alive={}'.format(
00084 self.get_proc_name(), self._process.started, self._process.stopped,
00085 self._process.is_alive()))
00086
00087 return (self._process.started and not self._process.stopped
00088 and not self._process.is_alive())
00089
00090 def recreate_process(self):
00091 '''
00092 Create and set roslaunch.nodeprocess.LocalProcess to member variable.
00093 @rtype: roslaunch.nodeprocess.LocalProcess
00094 '''
00095 _local_process = nodeprocess.LocalProcess
00096 try:
00097 _local_process = nodeprocess.create_node_process(
00098 self._run_id, self.config, self.master_uri)
00099 except node_args.NodeParamsException as e:
00100 rospy.logerr('roslaunch failed to load the node. {}'.format(
00101 e.message))
00102
00103
00104 return _local_process
00105
00106 def start_process(self):
00107
00108 self._process.start()
00109
00110 def stop_process(self):
00111
00112
00113 try:
00114 self._process.stop()
00115 except Exception as e:
00116
00117 rospy.logdebug('Proxy stop_process exception={}'.format(e.message))
00118
00119 def get_spawn_count(self):
00120 return self._process.spawn_count
00121
00122 def get_proc_name(self):
00123 return self._process.name
00124
00125 def get_proc_exit_code(self):
00126 return self._process.exit_code