ros_py_plugin_provider.py
Go to the documentation of this file.
1 # Copyright (c) 2011, Dirk Thomas, TU Darmstadt
2 # All rights reserved.
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions
6 # are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above
11 # copyright notice, this list of conditions and the following
12 # disclaimer in the documentation and/or other materials provided
13 # with the distribution.
14 # * Neither the name of the TU Darmstadt nor the names of its
15 # contributors may be used to endorse or promote products derived
16 # from this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 # POSSIBILITY OF SUCH DAMAGE.
30 
31 import os
32 import threading
33 import time
34 
35 import rospy
36 
37 from python_qt_binding.QtCore import qDebug, Qt, Signal
38 from python_qt_binding.QtWidgets import QMessageBox
39 
40 from qt_gui.composite_plugin_provider import CompositePluginProvider
41 from qt_gui.errors import PluginLoadError
42 
43 from rqt_gui.rospkg_plugin_provider import RospkgPluginProvider
44 
45 
47 
48  _master_found_signal = Signal(int)
49 
50  def __init__(self):
51  super(RosPyPluginProvider, self).__init__(
52  [RospkgPluginProvider('rqt_gui', 'rqt_gui_py::Plugin')])
53  self.setObjectName('RosPyPluginProvider')
54  self._node_initialized = False
57 
58  def load(self, plugin_id, plugin_context):
59  self._check_for_master()
60  self._init_node()
61  return super(RosPyPluginProvider, self).load(plugin_id, plugin_context)
62 
63  def _check_for_master(self):
64  # check if master is available
65  try:
66  rospy.get_master().getSystemState()
67  return
68  except Exception:
69  pass
70  # spawn thread to detect when master becomes available
71  self._wait_for_master_thread = threading.Thread(target=self._wait_for_master)
72  self._wait_for_master_thread.start()
73  self._wait_for_master_dialog = QMessageBox(
74  QMessageBox.Question,
75  self.tr('Waiting for ROS master'),
76  self.tr(
77  "Could not find ROS master. Either start a 'roscore' or abort loading the plugin."),
78  QMessageBox.Abort)
79 
80  self._master_found_signal.connect(self._wait_for_master_dialog.done, Qt.QueuedConnection)
81  button = self._wait_for_master_dialog.exec_()
82  # check if master existence was not detected by background thread
83  no_master = button != QMessageBox.Ok
84  self._wait_for_master_dialog.deleteLater()
85  self._wait_for_master_dialog = None
86  if no_master:
87  raise PluginLoadError('RosPyPluginProvider._init_node() could not find ROS master')
88 
89  def _wait_for_master(self):
90  while True:
91  time.sleep(0.1)
92  if not self._wait_for_master_dialog:
93  break
94  try:
95  rospy.get_master().getSystemState()
96  except Exception:
97  continue
98  self._master_found_signal.emit(QMessageBox.Ok)
99  break
100 
101  def _init_node(self):
102  # initialize node once
103  if not self._node_initialized:
104  name = 'rqt_gui_py_node_%d' % os.getpid()
105  qDebug('RosPyPluginProvider._init_node() initialize ROS node "%s"' % name)
106  rospy.init_node(name, disable_signals=True)
107  self._node_initialized = True


rqt_gui_py
Author(s): Dirk Thomas
autogenerated on Sat Mar 16 2019 02:54:15