node_proxy.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Author: Isaac Saito
34 
35 import time
36 import threading
37 
38 from roslaunch import node_args, nodeprocess
39 import rospy
40 
41 
42 class Polling(threading.Thread):
43 
44  def __init__(self, parent):
45  super(Polling, self).__init__()
46  self._parent = parent
47 
48  def run(self):
49  while True:
50  rospy.logdebug('Proc={} Died? {}'.format(self._parent.get_proc_name(),
51  self._parent.has_died()))
52  time.sleep(1.0)
53 
54 
55 class NodeProxy(object):
56 
57  '''
58  Works as a proxy between ROS Node
59  (more in particular, roslaunch.nodeprocess) & GUI.
60  '''
61 
62  __slots__ = ['_run_id', 'master_uri', 'config', '_process']
63 
64  def __init__(self, run_id, master_uri, config):
65  self._run_id = run_id
66  self.master_uri = master_uri
67  self.config = config
68 
69  # @type: roslaunch.nodeprocess.LocalProcess
70  self._process = self.recreate_process()
71 
72  # LocalProcess.is_alive() does not do what you would expect
73  def is_running(self):
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
79  # and self._process.is_alive()
80  # is_alive() returns False once nodeprocess was stopped.
81 
82  def has_died(self):
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()))
86 
87  return (self._process.started and not self._process.stopped
88  and not self._process.is_alive())
89 
90  def recreate_process(self):
91  '''
92  Create and set roslaunch.nodeprocess.LocalProcess to member variable.
93  @rtype: roslaunch.nodeprocess.LocalProcess
94  '''
95  _local_process = nodeprocess.LocalProcess
96  try:
97  _local_process = nodeprocess.create_node_process(
98  self._run_id, self.config, self.master_uri)
99  except node_args.NodeParamsException as e:
100  rospy.logerr('roslaunch failed to load the node. {}'.format(
101  e.message))
102  # TODO: Show msg on GUI that the node wasn't loaded.
103 
104  return _local_process
105 
106  def start_process(self):
107  # TODO: add null exception check for _process
108  self._process.start()
109 
110  def stop_process(self):
111  # TODO: add null exception check for _process
112 
113  try:
114  self._process.stop()
115  except Exception as e:
116  # TODO: Change roslaunch to raise exception
117  rospy.logdebug('Proxy stop_process exception={}'.format(e.message))
118 
119  def get_spawn_count(self):
120  return self._process.spawn_count
121 
122  def get_proc_name(self):
123  return self._process.name
124 
126  return self._process.exit_code
def __init__(self, parent)
Definition: node_proxy.py:44
def __init__(self, run_id, master_uri, config)
Definition: node_proxy.py:64


rqt_launch
Author(s): Isaac Saito, Stuart Glaser
autogenerated on Wed Jun 5 2019 21:35:22