38 from roslaunch
import node_args, nodeprocess
50 rospy.logdebug(
'Proc={} Died? {}'.format(self._parent.get_proc_name(),
51 self._parent.has_died()))
58 Works as a proxy between ROS Node 59 (more in particular, roslaunch.nodeprocess) & GUI. 62 __slots__ = [
'_run_id',
'master_uri',
'config',
'_process']
64 def __init__(self, run_id, master_uri, config):
74 rospy.logdebug(
'BEFORE started={}, stopped={} alive={}'.format(
75 self._process.started,
76 self._process.stopped,
77 self._process.is_alive()))
78 return self._process.started
and not self._process.stopped
83 rospy.logdebug(
'Proc={} started={}, stopped={}, is_alive={}'.format(
84 self.
get_proc_name(), self._process.started, self._process.stopped,
85 self._process.is_alive()))
87 return (self._process.started
and not self._process.stopped
88 and not self._process.is_alive())
92 Create and set roslaunch.nodeprocess.LocalProcess to member variable. 93 @rtype: roslaunch.nodeprocess.LocalProcess 95 _local_process = nodeprocess.LocalProcess
97 _local_process = nodeprocess.create_node_process(
99 except node_args.NodeParamsException
as e:
100 rospy.logerr(
'roslaunch failed to load the node. {}'.format(
104 return _local_process
108 self._process.start()
115 except Exception
as e:
117 rospy.logdebug(
'Proxy stop_process exception={}'.format(e.message))
120 return self._process.spawn_count
123 return self._process.name
126 return self._process.exit_code
def __init__(self, parent)
def recreate_process(self)
def __init__(self, run_id, master_uri, config)
def get_spawn_count(self)
def get_proc_exit_code(self)