editors.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2009, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 
00033 # Author: Ze'ev Klapow
00034 
00035 from QtCore import Qt
00036 import QtGui
00037 from QtGui import QWidget, QLabel, QCheckBox, QLineEdit, QSlider, QComboBox, QHBoxLayout
00038 
00039 import sys
00040 import math
00041 
00042 editor_types = {
00043     'bool': 'BooleanEditor',
00044     'str': 'StringEditor',
00045     'int': 'IntegerEditor',
00046     'double': 'DoubleEditor',
00047 }
00048 
00049 class Editor(QWidget):
00050     def __init__(self, updater, config):
00051         super(Editor, self).__init__()
00052         
00053         self.updater = updater
00054         self.name = config['name']
00055 
00056         self.old_value = None
00057 
00058     def _update(self, value):
00059         if value != self.old_value:
00060             self.update_configuration(value)
00061             self.old_value = value
00062 
00063     def update_value(self, value):
00064         pass
00065 
00066     def update_configuration(self, value):
00067         self.updater.update({ self.name : value })
00068 
00069     def display(self, grid, row):
00070         pass
00071 
00072     def close(self):
00073         pass
00074 
00075 class BooleanEditor(Editor):
00076     def __init__(self, updater, config): 
00077         super(BooleanEditor, self).__init__(updater, config)
00078 
00079         hbox = QHBoxLayout()
00080         self.cb = QCheckBox('', self)
00081 
00082         hbox.addWidget(self.cb)
00083         self.setLayout(hbox)
00084 
00085         self.update_value(config['default'])
00086 
00087         self.cb.clicked.connect(self._update)
00088 
00089     def update_value(self, value):
00090         self.cb.setChecked(value)
00091 
00092     def display(self, grid, row):
00093         grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00094 
00095         grid.addWidget(self, row, 1)
00096 
00097 class StringEditor(Editor):
00098     def __init__(self, updater, config):
00099         super(StringEditor, self).__init__(updater, config)
00100 
00101         hbox = QHBoxLayout()
00102         self.tb = QLineEdit(config['default'])
00103 
00104         hbox.addWidget(self.tb)
00105         self.setLayout(hbox)
00106 
00107         self.tb.editingFinished.connect(self.edit_finished)
00108 
00109     def update_value(self, value):
00110         self.tb.setText(value)
00111 
00112     def edit_finished(self):
00113         self._update(self.tb.text())
00114 
00115     def display(self, grid, row):
00116         grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00117 
00118         grid.addWidget(self, row, 1)
00119 
00120 
00121 class IntegerEditor(Editor):
00122     def __init__(self, updater, config):
00123         super(IntegerEditor, self).__init__(updater, config)
00124          
00125         hbox = QHBoxLayout()
00126 
00127         self.min = int(config['min'])
00128         self.max = int(config['max'])
00129 
00130         self.min_label = QLabel(str(self.min))
00131         self.max_label = QLabel(str(self.max))
00132 
00133         self.slider = QSlider(Qt.Horizontal)
00134         self.slider.setRange(self.min, self.max)
00135         self.slider.sliderReleased.connect(self.slider_released)
00136         self.slider.sliderMoved.connect(self.update_text)
00137 
00138         self.tb = QLineEdit()   
00139         self.tb.setValidator(QtGui.QIntValidator(self.min, self.max, self))
00140         self.tb.editingFinished.connect(self.editing_finished)
00141 
00142         hbox.addWidget(self.min_label, 0)
00143         hbox.addWidget(self.slider, 1)
00144         hbox.addWidget(self.max_label, 0)
00145         hbox.addWidget(self.tb, 0)
00146 
00147         self.setLayout(hbox)
00148 
00149         # TODO: This should not always get set to the default it should be the current value
00150         self.tb.setText(str(config['default']))
00151         self.slider.setSliderPosition(int(config['default']))
00152 
00153     def slider_released(self):
00154         self.update_text(self.slider.value())
00155         self._update(self.slider.value())
00156 
00157     def update_text(self, val):
00158         self.tb.setText(str(val))
00159 
00160     def editing_finished(self):
00161         self.slider.setSliderPosition(int(self.tb.text()))
00162         self._update(int(self.tb.text()))
00163 
00164     def update_value(self, val):
00165         self.slider.setSliderPosition(int(val))
00166         self.tb.setText(str(val))
00167 
00168     def display(self, grid, row):
00169         grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00170         grid.addWidget(self, row, 1)
00171 
00172 class DoubleEditor(Editor):
00173     def __init__(self, updater, config):
00174         super(DoubleEditor, self).__init__(updater,config)
00175 
00176         # Handle unbounded doubles nicely
00177         if config['min'] != -float('inf'):
00178             self.min = float(config['min'])
00179             self.min_label = QLabel(str(self.min))
00180 
00181             self.func = lambda x: x
00182             self.ifunc = self.func
00183         else:
00184             self.min = -1e10000 
00185             self.min_label = QLabel('-inf')
00186 
00187             self.func = lambda x: math.atan(x)
00188             self.ifunc = lambda x: math.tan(x)
00189 
00190         if config['max'] != float('inf'):
00191             self.max = float(config['max'])
00192             self.max_label = QLabel(str(self.max))
00193 
00194             self.func = lambda x: x
00195             self.ifunc = self.func
00196         else:
00197             self.max = 1e10000
00198             self.max_label = QLabel('inf')
00199 
00200             self.func = lambda x: math.atan(x)
00201             self.ifunc = lambda x: math.tan(x)
00202 
00203         self.scale = (self.func(self.max) - self.func(self.min))/100
00204         self.offset = self.func(self.min)
00205 
00206         hbox = QHBoxLayout()
00207 
00208         self.slider = QSlider(Qt.Horizontal)
00209         self.slider.setRange(self.slider_value(self.min), self.slider_value(self.max))
00210         self.slider.sliderReleased.connect(self.slider_released)
00211         self.slider.sliderMoved.connect(self.update_text)
00212 
00213         self.tb = QLineEdit()
00214         self.tb.setValidator(QtGui.QDoubleValidator(self.min, self.max, 4, self))
00215         self.tb.editingFinished.connect(self.editing_finished)
00216 
00217         hbox.addWidget(self.min_label, 0)
00218         hbox.addWidget(self.slider, 1)
00219         hbox.addWidget(self.max_label, 0)
00220         hbox.addWidget(self.tb, 0)
00221 
00222         self.setLayout(hbox)
00223 
00224         self.tb.setText(str(config['default']))
00225         self.slider.setSliderPosition(self.slider_value(config['default']))
00226 
00227     def get_value(self):
00228         return self.ifunc(self.slider.value() * self.scale)
00229 
00230     def slider_value(self, value):
00231         return int(round((self.func(value))/self.scale))
00232 
00233     def slider_released(self):
00234         self.update_text(self.get_value())
00235         self._update(self.get_value())
00236 
00237     def update_text(self, value):
00238         self.tb.setText(str(self.get_value()))
00239 
00240     def editing_finished(self):
00241         self.slider.setSliderPosition(self.slider_value(float(self.tb.text())))
00242         self._update(float(self.tb.text()))
00243 
00244     def update_value(self, val):
00245         self.slider.setSliderPosition(self.slider_value(float(val)))
00246         self.tb.setText(str(val))
00247 
00248     def display(self, grid, row):
00249         grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00250         grid.addWidget(self, row, 1)
00251 
00252 class EnumEditor(Editor):
00253     def __init__(self, updater, config):
00254         super(EnumEditor, self).__init__(updater, config)
00255 
00256         try:
00257             enum = eval(config['edit_method'])['enum']
00258         except:
00259             print("Malformed enum")
00260             return
00261 
00262         self.names = [item['name'] for item in enum]
00263         self.values = [item['value'] for item in enum]
00264 
00265         items = ["%s (%s)"%(self.names[i], self.values[i]) for i in range(0, len(self.names))]
00266 
00267         self.combo = QComboBox()
00268         self.combo.addItems(items)
00269         self.combo.currentIndexChanged['int'].connect(self.selected)
00270 
00271         hbox = QHBoxLayout()
00272         hbox.addWidget(self.combo)
00273 
00274         self.setLayout(hbox)
00275 
00276     def selected(self, index):
00277         self._update(self.values[index])
00278 
00279     def update_value(self, val):
00280         self.combo.setCurrentIndex(self.values.index(val))
00281 
00282     def display(self, grid, row):
00283         grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00284         grid.addWidget(self, row, 1)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


reconfigure_gui
Author(s): Ze'ev Klapow
autogenerated on Mon Aug 19 2013 11:00:48