Package rqt_joint_trajectory_controller :: Module double_editor
[frames] | no frames]

Source Code for Module rqt_joint_trajectory_controller.double_editor

  1  #!/usr/bin/env python 
  2   
  3  # Copyright (C) 2014, PAL Robotics S.L. 
  4  # 
  5  # Redistribution and use in source and binary forms, with or without 
  6  # modification, are permitted provided that the following conditions are met: 
  7  # * Redistributions of source code must retain the above copyright notice, 
  8  # this list of conditions and the following disclaimer. 
  9  # * Redistributions in binary form must reproduce the above copyright 
 10  # notice, this list of conditions and the following disclaimer in the 
 11  # documentation and/or other materials provided with the distribution. 
 12  # * Neither the name of PAL Robotics S.L. nor the names of its 
 13  # contributors may be used to endorse or promote products derived from 
 14  # this software without specific prior written permission. 
 15  # 
 16  # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
 17  # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
 18  # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 
 19  # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 
 20  # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 
 21  # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
 22  # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
 23  # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
 24  # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
 25  # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 
 26  # POSSIBILITY OF SUCH DAMAGE. 
 27   
 28  import os 
 29  import rospkg 
 30   
 31  from python_qt_binding import loadUi 
 32  from python_qt_binding.QtCore import Signal 
 33  from python_qt_binding.QtWidgets import QWidget 
 34   
 35   
36 -class DoubleEditor(QWidget):
37 # TODO: 38 # - Actually make bounds optional 39 # 40 # - Support wrapping mode 41 # 42 # - Support unspecified (+-Inf) lower and upper bounds (both, or one) 43 # 44 # - Allow to specify the step and page increment sizes 45 # (right-click context menu?) 46 # 47 # - Use alternative widget to slider for values that wrap, or are 48 # unbounded. 49 # QwtWheel could be a good choice, dials are not so good because they 50 # use lots of vertical (premium) screen space, and are fine for wrapping 51 # values, but not so much for unbounded ones 52 # 53 # - Merge with existing similar code such as rqt_reconfigure's 54 # DoubleEditor? 55 """ 56 Widget that allows to edit the value of a floating-point value, optionally 57 subject to lower and upper bounds. 58 """ 59 valueChanged = Signal(float) 60
61 - def __init__(self, min_val, max_val):
62 super(DoubleEditor, self).__init__() 63 64 # Preconditions 65 assert min_val < max_val 66 67 # Cache values 68 self._min_val = min_val 69 self._max_val = max_val 70 71 # Load editor UI 72 rp = rospkg.RosPack() 73 ui_file = os.path.join(rp.get_path('rqt_joint_trajectory_controller'), 74 'resource', 'double_editor.ui') 75 loadUi(ui_file, self) 76 77 # Setup widget ranges and slider scale factor 78 self.slider.setRange(0, 100) 79 self.slider.setSingleStep(1) 80 self._scale = (max_val - min_val) / \ 81 (self.slider.maximum() - self.slider.minimum()) 82 self.spin_box.setRange(min_val, max_val) 83 self.spin_box.setSingleStep(self._scale) 84 85 # Couple slider and spin box together 86 self.slider.valueChanged.connect(self._on_slider_changed) 87 self.spin_box.valueChanged.connect(self._on_spinbox_changed) 88 89 # Ensure initial sync of slider and spin box 90 self._on_spinbox_changed()
91
92 - def _slider_to_val(self, sval):
93 return self._min_val + self._scale * (sval - self.slider.minimum())
94
95 - def _val_to_slider(self, val):
96 return round(self.slider.minimum() + (val - self._min_val) / 97 self._scale)
98
99 - def _on_slider_changed(self):
100 val = self._slider_to_val(self.slider.value()) 101 self.spin_box.blockSignals(True) # Prevents updating the command twice 102 self.spin_box.setValue(val) 103 self.spin_box.blockSignals(False) 104 self.valueChanged.emit(val)
105
106 - def _on_spinbox_changed(self):
107 val = self.spin_box.value() 108 self.slider.blockSignals(True) # Prevents updating the command twice 109 self.slider.setValue(self._val_to_slider(val)) 110 self.slider.blockSignals(False) 111 self.valueChanged.emit(val)
112
113 - def setValue(self, val):
114 if val != self.spin_box.value(): 115 self.spin_box.blockSignals(True) 116 self.spin_box.setValue(val) # Update spin box first 117 self._on_spinbox_changed() # Sync slider with spin box 118 self.spin_box.blockSignals(False)
119
120 - def value(self):
121 return self.spin_box.value()
122