plugin_container_widget.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2013, Open Source Robotics Foundation 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 from __future__ import division
36 
37 import os
38 
39 from python_qt_binding import loadUi
40 from python_qt_binding.QtWidgets import QWidget
41 import rospkg
42 import rospy
43 
44 
45 class PluginContainerWidget(QWidget):
46 
47  """
48  This widget accommodates a plugin widget that needs an area to show system
49  message. A plugin widget is the pane that provides plugin's main
50  functionalities. PluginContainerWidget visually encapsulates a plugin
51  widget.
52 
53  In order to print msg in the msg pane provided by this class, plugin widget
54  MUST define and emit following signals:
55 
56  - sig_sysmsg
57  - sig_progress
58 
59  Having said that this architecture is based on signals, it is recommended
60  that exceptions raised in classes that are used in a plugin widget be
61  aggregated in it, so that only plugin widget is responsible for emitting
62  signals.
63  """
64 
65  def __init__(self, plugin_widget,
66  on_sys_msg=True, on_sysprogress_bar=True):
67  """
68  @param plugin_widget: The main widget of an rqt plugin.
69  @type plugin_widget: QWidget
70  @type on_sys_msg: bool
71  @param on_sys_msg: If True, a pane that accommodates str messages will
72  appear in the plugin's region.
73  @param on_sysprogress_bar: If True, a progress bar will appear in the
74  plugin's region.
75  """
76  super(PluginContainerWidget, self).__init__()
77 
78  ui_file = os.path.join(rospkg.RosPack().get_path('rqt_py_common'),
79  'resource', 'plugin_container.ui')
80  loadUi(ui_file, self)
81 
82  self._plugin_widget = plugin_widget
83  self._splitter.insertWidget(0, self._plugin_widget)
84  self.setWindowTitle(self._plugin_widget.windowTitle())
85 
86  # Default is on for these sys status widgets. Only if the flag for them
87  # are 'False', hide them.
88  if on_sys_msg:
89  self._plugin_widget.sig_sysmsg.connect(self.set_sysmsg)
90  else:
91  self._sysmsg_widget.hide()
92 
93  if on_sysprogress_bar:
94  self._plugin_widget.sig_sysprogress.connect(self.set_sysprogress)
95  else:
96  self._sysprogress_bar.hide()
97 
98  def set_sysprogress(self, sysprogress):
99  # TODO: Pass progress value
100  pass
101 
102  def set_sysmsg(self, sysmsg):
103  """
104  Set system msg that's supposed to be shown in sys msg pane.
105  @type sysmsg: str
106  """
107  rospy.loginfo('PluginContainerWidget; {}'.format(sysmsg))
108  # self._sysmsg_widget.setPlainText(sysmsg)
109  self._sysmsg_widget.append(sysmsg)
110 
111  def shutdown(self):
112 
113  # TODO: Is shutdown step necessary for PluginContainerWidget?
114 
115  self._plugin_widget.shutdown()
116 
117  def save_settings(self, plugin_settings, instance_settings):
118 
119  # Save setting of PluginContainerWidget.
120  instance_settings.set_value('_splitter', self._splitter.saveState())
121 
122  # Save setting of ContainED widget
123  self._plugin_widget.save_settings(plugin_settings, instance_settings)
124 
125  def restore_settings(self, plugin_settings, instance_settings):
126 
127  # Restore the setting of PluginContainerWidget, separate from
128  # ContainED widget.
129  if instance_settings.contains('_splitter'):
130  self._splitter.restoreState(instance_settings.value('_splitter'))
131  else:
132  self._splitter.setSizes([100, 100, 200])
133 
134  # Now restore the setting of ContainED widget
135  self._plugin_widget.restore_settings(plugin_settings,
136  instance_settings)
def __init__(self, plugin_widget, on_sys_msg=True, on_sysprogress_bar=True)
def save_settings(self, plugin_settings, instance_settings)
def restore_settings(self, plugin_settings, instance_settings)


rqt_py_common
Author(s): Dorian Scholz, Isaac Saito, Dirk Thomas
autogenerated on Mon Mar 22 2021 02:13:26