00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 from python_qt_binding.QtCore import Qt
00036 from python_qt_binding.QtGui import QFormLayout, QGroupBox, QLabel, QPushButton, QTabWidget, QWidget
00037 import rospy
00038
00039 from .param_editors import BooleanEditor, DoubleEditor, EditorWidget, EDITOR_TYPES, EnumEditor, IntegerEditor, StringEditor
00040
00041 _GROUP_TYPES = {
00042 '': 'BoxGroup',
00043 'collapse': 'CollapseGroup',
00044 'tab': 'TabGroup',
00045 'hide': 'HideGroup',
00046 'apply': 'ApplyGroup',
00047 }
00048
00049 def find_cfg(config, name):
00050 """
00051 (Ze'ev) reaaaaallly cryptic function which returns the config object for
00052 specified group.
00053 """
00054 cfg = None
00055 for k, v in config.items():
00056 try:
00057 if k.lower() == name.lower():
00058 cfg = v
00059 return cfg
00060 else:
00061 try:
00062 cfg = find_cfg(v, name)
00063 if not cfg == None:
00064 return cfg
00065 except Exception as exc:
00066 raise exc
00067 except AttributeError:
00068 pass
00069 except Exception as exc:
00070 raise exc
00071 return cfg
00072
00073 class GroupWidget(QWidget):
00074 """
00075 (Isaac's guess as of 12/13/2012)
00076 This class bonds multiple Editor instances that are associated with
00077 a single node as a group.
00078 """
00079
00080 def __init__(self, updater, config):
00081 """
00082 :param config: defined in dynamic_reconfigure.client.Client
00083 :type config: Dictionary?
00084 """
00085
00086 super(GroupWidget, self).__init__()
00087 self.state = config['state']
00088 self.name = config['name']
00089
00090 self.tab_bar = None
00091 self.tab_bar_shown = False
00092
00093
00094 self.grid = QFormLayout()
00095
00096 self.updater = updater
00097
00098 self.editor_widgets = []
00099 self.add_widgets(config)
00100
00101
00102
00103 self.setLayout(self.grid)
00104
00105 def add_widgets(self, config):
00106 """
00107 :type config: Dict?
00108 """
00109 i_debug = 0
00110 for param in config['parameters']:
00111 if param['edit_method']:
00112 widget = EnumEditor(self.updater, param)
00113 elif param['type'] in EDITOR_TYPES:
00114 widget = eval(EDITOR_TYPES[param['type']])(self.updater, param)
00115
00116 self.editor_widgets.append(widget)
00117 rospy.logdebug('groups.add_widgets num editors=%d', i_debug)
00118 i_debug += 1
00119
00120 g_debug = 0
00121 for name, group in config['groups'].items():
00122 if group['type'] == 'tab':
00123 widget = TabGroup(self, self.updater, group)
00124 elif group['type'] in _GROUP_TYPES.keys():
00125 widget = eval(_GROUP_TYPES[group['type']])(self.updater, group)
00126
00127 self.editor_widgets.append(widget)
00128 rospy.logdebug('groups.add_widgets num groups=%d', g_debug)
00129 g_debug += 1
00130
00131 for i, ed in enumerate(self.editor_widgets):
00132 ed.display(self.grid, i)
00133
00134 rospy.logdebug('GroupWidget.add_widgets len(self.editor_widgets)=%d',
00135 len(self.editor_widgets))
00136
00137 def display(self, grid, row):
00138
00139 grid.addWidget(self, row, 0, 1, -1)
00140
00141 def update_group(self, config):
00142 self.state = config['state']
00143
00144
00145 names = [name for name, v in config.items()]
00146
00147 for widget in self.editor_widgets:
00148 if isinstance(widget, EditorWidget):
00149 if widget.name in names:
00150 widget.update_value(config[widget.name])
00151 elif isinstance(widget, GroupWidget):
00152 cfg = find_cfg(config, widget.name)
00153 widget.update_group(cfg)
00154
00155 def close(self):
00156 for w in self.editor_widgets:
00157 w.close()
00158
00159 class BoxGroup(GroupWidget):
00160 def __init__(self, updater, config):
00161 super(BoxGroup, self).__init__(updater, config)
00162
00163 self.box = QGroupBox(self.name)
00164 self.box.setLayout(self.grid)
00165
00166 def display(self, grid, row):
00167 grid.addWidget(self.box, row, 0, 1, -1)
00168
00169 class CollapseGroup(BoxGroup):
00170 def __init__(self, updater, config):
00171 super(CollapseGroup, self).__init__(updater, config)
00172 self.box.setCheckable(True)
00173
00174 class HideGroup(BoxGroup):
00175 def update_group(self, config):
00176 super(HideGroup, self).update_group(config)
00177 self.box.setVisible(self.state)
00178
00179 class TabGroup(GroupWidget):
00180 def __init__(self, parent, updater, config):
00181 super(TabGroup, self).__init__(updater, config)
00182 self.parent = parent
00183
00184 if self.parent.tab_bar is None:
00185 self.parent.tab_bar = QTabWidget()
00186
00187 parent.tab_bar.addTab(self, self.name)
00188
00189 def display(self, grid, row):
00190 if not self.parent.tab_bar_shown:
00191 grid.addWidget(self.parent.tab_bar, row, 0, 1, -1)
00192 self.parent.tab_bar_shown = True
00193
00194 def close(self):
00195 super(TabGroup, self).close()
00196 self.parent.tab_bar = None
00197 self.parent.tab_bar_shown = False
00198
00199 class ApplyGroup(BoxGroup):
00200 class ApplyUpdater:
00201 def __init__(self, updater):
00202 self.updater = updater
00203 self._pending_config = {}
00204
00205 def update(self, config):
00206 for name, value in config.items():
00207 self._pending_config[name] = value
00208
00209 def apply_update(self):
00210 self.updater.update(self._pending_config)
00211 self._pending_config = {}
00212
00213 def __init__(self, updater, config):
00214 self.updater = ApplyGroup.ApplyUpdater(updater)
00215 super(ApplyGroup, self).__init__(self.updater, config)
00216
00217 self.button = QPushButton("Apply %s" % self.name)
00218 self.button.clicked.connect(self.updater.apply_update)
00219
00220 rows = self.grid.rowCount()
00221 self.grid.addWidget(self.button, rows + 1, 1, Qt.AlignRight)