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 QGridLayout, 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 def __init__(self, updater, config):
00076 """
00077 :param config: defined in dynamic_reconfigure.client.Client
00078 """
00079
00080 super(GroupWidget, self).__init__()
00081 self.state = config['state']
00082 self.name = config['name']
00083
00084 self.tab_bar = None
00085 self.tab_bar_shown = False
00086
00087 self.grid = QGridLayout()
00088
00089 self.updater = updater
00090
00091 self.editor_widgets = []
00092 self.add_widgets(config)
00093
00094
00095 self.grid.setColumnStretch(1,1)
00096 self.setLayout(self.grid)
00097
00098 def add_widgets(self, descr):
00099 i_debug = 0
00100 for param in descr['parameters']:
00101 if param['edit_method']:
00102 widget = EnumEditor(self.updater, param)
00103 elif param['type'] in EDITOR_TYPES:
00104 widget = eval(EDITOR_TYPES[param['type']])(self.updater, param)
00105
00106 self.editor_widgets.append(widget)
00107 rospy.logdebug('groups.add_widgets i=%d', i_debug)
00108 i_debug += 1
00109
00110 g_debug = 0
00111 for name, group in descr['groups'].items():
00112 if group['type'] == 'tab':
00113 widget = TabGroup(self, self.updater, group)
00114 elif group['type'] in _GROUP_TYPES.keys():
00115 widget = eval(_GROUP_TYPES[group['type']])(self.updater, group)
00116
00117 self.editor_widgets.append(widget)
00118 rospy.logdebug('groups.add_widgets g=%d', g_debug)
00119 g_debug += 1
00120
00121 for i, ed in enumerate(self.editor_widgets):
00122 ed.display(self.grid, i)
00123
00124 def display(self, grid, row):
00125
00126 grid.addWidget(self, row, 0, 1, -1)
00127
00128 def update_group(self, config):
00129 self.state = config['state']
00130
00131
00132 names = [name for name, v in config.items()]
00133
00134 for widget in self.editor_widgets:
00135 if isinstance(widget, EditorWidget):
00136 if widget.name in names:
00137 widget.update_value(config[widget.name])
00138 elif isinstance(widget, GroupWidget):
00139 cfg = find_cfg(config, widget.name)
00140 widget.update_group(cfg)
00141
00142 def close(self):
00143 for w in self.editor_widgets:
00144 w.close()
00145
00146 class BoxGroup(GroupWidget):
00147 def __init__(self, updater, config):
00148 super(BoxGroup, self).__init__(updater, config)
00149
00150 self.box = QGroupBox(self.name)
00151 self.box.setLayout(self.grid)
00152
00153 def display(self, grid, row):
00154 grid.addWidget(self.box, row, 0, 1, -1)
00155
00156 class CollapseGroup(BoxGroup):
00157 def __init__(self, updater, config):
00158 super(CollapseGroup, self).__init__(updater, config)
00159 self.box.setCheckable(True)
00160
00161 class HideGroup(BoxGroup):
00162 def update_group(self, config):
00163 super(HideGroup, self).update_group(config)
00164 self.box.setVisible(self.state)
00165
00166 class TabGroup(GroupWidget):
00167 def __init__(self, parent, updater, config):
00168 super(TabGroup, self).__init__(updater, config)
00169 self.parent = parent
00170
00171 if self.parent.tab_bar is None:
00172 self.parent.tab_bar = QTabWidget()
00173
00174 parent.tab_bar.addTab(self, self.name)
00175
00176 def display(self, grid, row):
00177 if not self.parent.tab_bar_shown:
00178 grid.addWidget(self.parent.tab_bar, row, 0, 1, -1)
00179 self.parent.tab_bar_shown = True
00180
00181 def close(self):
00182 super(TabGroup, self).close()
00183 self.parent.tab_bar = None
00184 self.parent.tab_bar_shown = False
00185
00186 class ApplyGroup(BoxGroup):
00187 class ApplyUpdater:
00188 def __init__(self, updater):
00189 self.updater = updater
00190 self._pending_config = {}
00191
00192 def update(self, config):
00193 for name, value in config.items():
00194 self._pending_config[name] = value
00195
00196 def apply_update(self):
00197 self.updater.update(self._pending_config)
00198 self._pending_config = {}
00199
00200 def __init__(self, updater, config):
00201 self.updater = ApplyGroup.ApplyUpdater(updater)
00202 super(ApplyGroup, self).__init__(self.updater, config)
00203
00204 self.button = QPushButton("Apply %s" % self.name)
00205 self.button.clicked.connect(self.updater.apply_update)
00206
00207 rows = self.grid.rowCount()
00208 self.grid.addWidget(self.button, rows+1, 1, Qt.AlignRight)