param_editors.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, 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: Isaac Saito, Ze'ev Klapow
00034 
00035 import math
00036 import os
00037 
00038 from dynamic_reconfigure.msg import Config as ConfigMsg
00039 from python_qt_binding import loadUi
00040 from python_qt_binding.QtCore import Qt, Signal
00041 from python_qt_binding.QtGui import QCheckBox, QComboBox, QDoubleValidator, QIntValidator, QHBoxLayout, QLabel, QLineEdit, QPainter, QSlider, QWidget 
00042 import rospy
00043 
00044 from .param_updater import ParamUpdater
00045 
00046 EDITOR_TYPES = {
00047     'bool': 'BooleanEditor',
00048     'str': 'StringEditor',
00049     'int': 'IntegerEditor',
00050     'double': 'DoubleEditor',
00051 }
00052 
00053 class EditorWidget(QWidget):
00054 
00055     def __init__(self, updater, config):
00056         """
00057         :param updater: 
00058         :type updater: rqt_param.ParamUpdater
00059         """
00060         
00061         super(EditorWidget, self).__init__()
00062         
00063         self.updater = updater
00064         self.name = config['name']
00065 
00066         self.old_value = None
00067 
00068     def _update(self, value):
00069         if value != self.old_value:
00070             self.update_configuration(value)
00071             self.old_value = value
00072 
00073     def update_value(self, value):
00074         pass
00075 
00076     def update_configuration(self, value):
00077         self.updater.update({self.name : value})
00078 
00079     def display(self, grid, row):
00080         """
00081         Should be overridden in subclass.
00082     
00083         :type grid: ???
00084         :type row: ???
00085         """  
00086         pass
00087 
00088     def close(self):
00089         """
00090         Should be overridden in subclass.
00091         """
00092         pass
00093 
00094 class BooleanEditor(EditorWidget):
00095     def __init__(self, updater, config): 
00096         super(BooleanEditor, self).__init__(updater, config)
00097 
00098         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)),
00099                                'ui/editor_bool.ui')                
00100         loadUi(ui_file, self)  
00101         
00102         self.update_value(config['default'])
00103         self._checkbox.clicked.connect(self._update)
00104 
00105     def update_value(self, value):
00106         self._checkbox.setChecked(value)
00107 
00108     def display(self, grid, row):
00109 #        grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00110 #        grid.addWidget(self, row, 1)
00111         grid.addRow(QLabel(self.name, self))
00112 
00113 class StringEditor(EditorWidget):
00114     def __init__(self, updater, config):
00115         super(StringEditor, self).__init__(updater, config)
00116         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)),
00117                                'ui/editor_string.ui')    
00118         loadUi(ui_file, self) 
00119                 
00120         self._paramval_lineedit.editingFinished.connect(self.edit_finished)
00121 
00122     def update_value(self, value):
00123         self._paramval_lineedit.setText(value)
00124 
00125     def edit_finished(self):
00126         self._update(self._paramval_lineedit.text())
00127     
00128     def display(self, grid, row):
00129 #        grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00130 #        grid.addWidget(self, row, 1)
00131         grid.addRow(QLabel(self.name), self)
00132 
00133 class IntegerEditor(EditorWidget):
00134     def __init__(self, updater, config):
00135         super(IntegerEditor, self).__init__(updater, config)
00136         
00137         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)),
00138                                'ui/editor_number.ui')
00139         loadUi(ui_file, self) 
00140 
00141         self.min = int(config['min'])
00142         self.max = int(config['max'])
00143         self._min_val_label.setText(str(self.min))
00144         self._max_val_label.setText(str(self.max))
00145 
00146         self._slider_horizontal.setRange(self.min, self.max)
00147         self._slider_horizontal.sliderReleased.connect(self.slider_released)
00148         self._slider_horizontal.sliderMoved.connect(self.update_text)
00149         
00150         #TODO(Isaac) Fix that the naming of _paramval_lineEdit instance is not 
00151         #            consistent among Editor's subclasses. 
00152         self._paramval_lineEdit.setValidator(QIntValidator(self.min,
00153                                                            self.max, self))
00154         self._paramval_lineEdit.editingFinished.connect(self.editing_finished)
00155 
00156         # TODO: This should not always get set to the default it should be the current value
00157         self._paramval_lineEdit.setText(str(config['default']))
00158         self._slider_horizontal.setSliderPosition(int(config['default']))
00159 
00160     def slider_released(self):
00161         self.update_text(self._slider_horizontal.value())
00162         self._update(self._slider_horizontal.value())
00163 
00164     def update_text(self, val):
00165         rospy.logdebug(' IntegerEditor.update_text val=%s', str(val))
00166         self._paramval_lineEdit.setText(str(val))
00167 
00168     def editing_finished(self):
00169         self._slider_horizontal.setSliderPosition(
00170                                          int(self._paramval_lineEdit.text()))
00171         self._update(int(self._paramval_lineEdit.text()))
00172 
00173     def update_value(self, val):
00174         self._slider_horizontal.setSliderPosition(int(val))
00175         self._paramval_lineEdit.setText(str(val))
00176 
00177     def display(self, grid, row):
00178 #        grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00179 #        grid.addWidget(self, row, 1)
00180         grid.addRow(QLabel(self.name), self)
00181 
00182 class DoubleEditor(EditorWidget):
00183     def __init__(self, updater, config):
00184         super(DoubleEditor, self).__init__(updater, config)
00185         
00186         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)),
00187                                'ui/editor_number.ui')                
00188         loadUi(ui_file, self) 
00189 
00190         # Handle unbounded doubles nicely
00191         if config['min'] != -float('inf'):
00192             self.min = float(config['min'])
00193             self._min_val_label.setText(str(self.min))
00194             self.func = lambda x: x
00195             self.ifunc = self.func
00196         else:
00197             self.min = -1e10000 
00198             self._min_val_label.setText('-inf')
00199             self.func = lambda x: math.atan(x)
00200             self.ifunc = lambda x: math.tan(x)
00201 
00202         if config['max'] != float('inf'):
00203             self.max = float(config['max'])
00204             self._max_val_label.setText(str(self.max))
00205             self.func = lambda x: x
00206             self.ifunc = self.func
00207         else:
00208             self.max = 1e10000
00209             self.max_val_label.setText('inf')
00210             self.func = lambda x: math.atan(x)
00211             self.ifunc = lambda x: math.tan(x)
00212 
00213         self.scale = (self.func(self.max) - self.func(self.min)) / 100
00214         self.offset = self.func(self.min)
00215 
00216         self._slider_horizontal.setRange(self.slider_value(self.min),
00217                                          self.slider_value(self.max))
00218         self._slider_horizontal.sliderReleased.connect(self.slider_released)
00219         self._slider_horizontal.sliderMoved.connect(self.update_text)
00220 
00221         self._paramval_lineEdit.setValidator(QDoubleValidator(
00222                                                     self.min, self.max,
00223                                                     4, self))
00224         self._paramval_lineEdit.editingFinished.connect(self.editing_finished)
00225 
00226         self._paramval_lineEdit.setText(str(config['default']))
00227         self._slider_horizontal.setSliderPosition(
00228                                      self.slider_value(config['default']))
00229 
00230     def get_value(self):
00231         return self.ifunc(self._slider_horizontal.value() * self.scale)
00232 
00233     def slider_value(self, value):
00234         return int(round((self.func(value)) / self.scale))
00235 
00236     def slider_released(self):
00237         self.update_text(self.get_value())
00238         self._update(self.get_value())
00239 
00240     def update_text(self, value):
00241         self._paramval_lineEdit.setText(str(self.get_value()))
00242 
00243     def editing_finished(self):
00244         self._slider_horizontal.setSliderPosition(
00245                                self.slider_value(float(self._paramval_lineEdit.text())))
00246         self._update(float(self._paramval_lineEdit.text()))
00247 
00248     def update_value(self, val):
00249         self._slider_horizontal.setSliderPosition(
00250                                   self.slider_value(float(val)))
00251         self._paramval_lineEdit.setText(str(val))
00252 
00253     def display(self, grid, row):
00254         #grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00255         grid.addRow(QLabel(self.name), self)
00256 
00257 class EnumEditor(EditorWidget):
00258     def __init__(self, updater, config):
00259         super(EnumEditor, self).__init__(updater, config)
00260 
00261         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)),
00262                                'ui/editor_enum.ui')                
00263         loadUi(ui_file, self) 
00264         
00265         try:
00266             enum = eval(config['edit_method'])['enum']
00267         except:
00268             print("Malformed enum")
00269             return
00270 
00271         self.names = [item['name'] for item in enum]
00272         self.values = [item['value'] for item in enum]
00273 
00274         items = ["%s (%s)" % (self.names[i], self.values[i]) 
00275                  for i in range(0, len(self.names))]
00276 
00277         self._combobox.addItems(items)
00278         self._combobox.currentIndexChanged['int'].connect(self.selected)
00279 
00280     def selected(self, index):
00281         self._update(self.values[index])
00282 
00283     def update_value(self, val):
00284         self._combobox.setCurrentIndex(self.values.index(val))
00285 
00286     def display(self, grid, row):
00287 #        grid.addWidget(QLabel(self.name), row, 0, Qt.AlignRight)
00288 #        grid.addWidget(self, row, 1)
00289         grid.addRow(QLabel(self.name), self)
00290         
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rqt_param
Author(s): Isaac Saito, Ze'ev Klapow
autogenerated on Wed Dec 19 2012 23:57:05