38 from roslaunch
import node_args, nodeprocess
50 rospy.logdebug(
'Proc={} Died? {}'.format(self.
_parent.get_proc_name(),
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(
83 rospy.logdebug(
'Proc={} started={}, stopped={}, is_alive={}'.format(
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
115 except Exception
as e:
117 rospy.logdebug(
'Proxy stop_process exception={}'.format(e.message))