38 from python_qt_binding.QtCore
import pyqtSlot
39 from python_qt_binding.QtCore
import Qt
40 from python_qt_binding.QtCore
import Signal
41 from python_qt_binding.QtGui
import QFont
42 from python_qt_binding.QtWidgets
import QApplication
43 from python_qt_binding.QtWidgets
import QHBoxLayout
44 from python_qt_binding.QtWidgets
import QLabel
45 from python_qt_binding.QtWidgets
import QLineEdit
46 from python_qt_binding.QtWidgets
import QPushButton
47 from python_qt_binding.QtWidgets
import QSlider
48 from python_qt_binding.QtWidgets
import QVBoxLayout
49 from python_qt_binding.QtWidgets
import QGridLayout
50 from python_qt_binding.QtWidgets
import QScrollArea
51 from python_qt_binding.QtWidgets
import QSpinBox
52 from python_qt_binding.QtWidgets
import QWidget
58 sliderUpdateTrigger = Signal()
61 super(JointStatePublisherGui, self).
__init__()
68 self.scroll.setWidgetResizable(
True)
72 font = QFont(
"Helvetica", 9, QFont.Bold)
76 for name
in self.jsp.joint_list:
77 if name
not in self.jsp.free_joints:
79 joint = self.jsp.free_joints[name]
81 if joint[
'min'] == joint[
'max']:
84 joint_layout = QVBoxLayout()
85 row_layout = QHBoxLayout()
89 row_layout.addWidget(label)
90 display = QLineEdit(
"0.00")
91 display.setAlignment(Qt.AlignRight)
93 display.setReadOnly(
True)
94 row_layout.addWidget(display)
96 joint_layout.addLayout(row_layout)
98 slider = QSlider(Qt.Horizontal)
101 slider.setRange(0, RANGE)
102 slider.setValue(RANGE/2)
104 joint_layout.addWidget(slider)
106 self.
joint_map[name] = {
'slidervalue': 0,
'display': display,
107 'slider': slider,
'joint': joint}
109 slider.valueChanged.connect(
lambda event,name=name: self.
onValueChangedOne(name))
111 sliders.append(joint_layout)
120 for item, pos
in zip(sliders, self.
positions):
121 self.gridlayout.addLayout(item, *pos)
134 self.vlayout.addWidget(self.
scroll)
145 self.maxrowsupdown.setMinimum(1)
146 self.maxrowsupdown.setMaximum(len(sliders))
147 self.maxrowsupdown.setValue(self.
num_rows)
153 self.sliderUpdateTrigger.emit()
158 joint_info[
'slidervalue'] = joint_info[
'slider'].value()
159 joint = joint_info[
'joint']
160 joint[
'position'] = self.
sliderToValue(joint_info[
'slidervalue'], joint)
161 joint_info[
'display'].setText(
"%.2f" % joint[
'position'])
168 for name, joint_info
in self.joint_map.items():
169 joint = joint_info[
'joint']
170 joint_info[
'slidervalue'] = self.
valueToSlider(joint[
'position'],
172 joint_info[
'slider'].setValue(joint_info[
'slidervalue'])
178 rospy.loginfo(
"Centering")
179 for name, joint_info
in self.joint_map.items():
180 joint = joint_info[
'joint']
181 joint_info[
'slider'].setValue(self.
valueToSlider(joint[
'zero'], joint))
192 item = self.gridlayout.itemAtPosition(*pos)
194 self.gridlayout.removeItem(item)
198 for item, pos
in zip(items, self.
positions):
199 self.gridlayout.addLayout(item, *pos)
204 positions = [(y, x)
for x
in range(int((math.ceil(float(num_items) / num_rows))))
for y
in range(num_rows)]
205 positions = positions[:num_items]
212 rospy.loginfo(
"Randomizing")
213 for name, joint_info
in self.joint_map.items():
214 joint = joint_info[
'joint']
215 joint_info[
'slider'].setValue(
216 self.
valueToSlider(random.uniform(joint[
'min'], joint[
'max']), joint))
219 for name, joint_info
in self.joint_map.items():
220 joint_info[
'slidervalue'] = joint_info[
'slider'].value()
224 return (value - joint[
'min']) * float(RANGE) / (joint[
'max'] - joint[
'min'])
227 pctvalue = slider / float(RANGE)
228 return joint[
'min'] + (joint[
'max']-joint[
'min']) * pctvalue
def onValueChangedOne(self, name)
def center_event(self, event)
def generate_grid_positions(self, num_items, num_rows)
def reorggrid_event(self, event)
def reorganize_grid(self, number_of_rows)
def sliderToValue(self, slider, joint)
num_rows
Generate sliders ###.
def valueToSlider(self, value, joint)
def sliderUpdate(self, event)
def randomize_event(self, event)
def source_update_cb(self)
def __init__(self, title, jsp, num_rows=0)