rqt_editor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import os
00004 import math
00005 
00006 import rospy
00007 import rospkg
00008 import tf
00009 import actionlib
00010 
00011 from qt_gui.plugin import Plugin
00012 from qt_gui_py_common.worker_thread import WorkerThread
00013 
00014 from python_qt_binding import loadUi, QtGui, QtCore
00015 from python_qt_binding.QtGui import QWidget
00016 from python_qt_binding.QtCore import Signal, Slot
00017 
00018 from frame_editor.editor import Frame, FrameEditor
00019 from frame_editor.commands import *
00020 from frame_editor.constructors_geometry import *
00021 
00022 from project_plugin import ProjectPlugin
00023 
00024 from frame_editor.interface import Interface
00025 
00026 ## Views
00027 from frame_editor.interface_gui import FrameEditor_StyleWidget
00028 
00029 
00030 class FrameEditorGUI(ProjectPlugin, Interface):
00031 
00032     signal_update = QtCore.Signal(int)
00033 
00034     def __init__(self, context):
00035         super(FrameEditorGUI, self).__init__(context)
00036 
00037         self.setObjectName('FrameEditorGUI')
00038 
00039         self.file_type = "YAML files(*.yaml)"
00040 
00041 
00042         self.filename = ""
00043 
00044         filename = self.editor.parse_args(context.argv())
00045         if filename:
00046             self.set_current_file(filename)
00047 
00048 
00049         ## Update thread ##
00050         ##
00051         self._update_thread.start()
00052         self.update_all(3)
00053 
00054 
00055     def create_editor(self):
00056         editor = FrameEditor()
00057 
00058         editor.observers.append(self)
00059 
00060         self.signal_update.connect(self.update_all)
00061 
00062         self._update_thread = WorkerThread(self._update_thread_run, self._update_finished)
00063 
00064         self.old_frame_list = []
00065         self.old_selected = ""
00066 
00067         return editor
00068 
00069 
00070     def create_main_widget(self):
00071 
00072         ## Main widget
00073         widget = QWidget()
00074         ui_file = os.path.join(rospkg.RosPack().get_path('frame_editor'), 'src/frame_editor', 'FrameEditorGUI.ui')
00075         loadUi(ui_file, widget)
00076         widget.setObjectName('FrameEditorGUIUi')
00077 
00078         #if context.serial_number() > 1:
00079         #    widget.setWindowTitle(widget.windowTitle() + (' (%d)' % context.serial_number()))
00080 
00081 
00082         ## Undo View
00083         #widget.undo_frame.layout().addWidget(QtGui.QUndoView(self.editor.undo_stack))
00084 
00085 
00086         ## Views
00087         self.editor.init_views()
00088         self.interface_style = FrameEditor_StyleWidget(self.editor)
00089 
00090         widget.style_frame.layout().addWidget(self.interface_style.get_widget())
00091 
00092 
00093         ## Connections ##
00094         ##
00095         widget.btn_add.clicked.connect(self.btn_add_clicked)
00096         widget.btn_delete.clicked.connect(self.btn_delete_clicked)
00097         widget.list_frames.currentTextChanged.connect(self.selected_frame_changed)
00098         widget.btn_refresh.clicked.connect(self.update_tf_list)
00099 
00100         widget.btn_set_parent_rel.clicked.connect(self.btn_set_parent_rel_clicked)
00101         widget.btn_set_parent_abs.clicked.connect(self.btn_set_parent_abs_clicked)
00102         widget.btn_set_pose.clicked.connect(self.btn_set_pose_clicked)
00103         widget.btn_set_position.clicked.connect(self.btn_set_position_clicked)
00104         widget.btn_set_orientation.clicked.connect(self.btn_set_orientation_clicked)
00105         widget.btn_set_x.clicked.connect(self.btn_set_x_clicked)
00106         widget.btn_set_y.clicked.connect(self.btn_set_y_clicked)
00107         widget.btn_set_z.clicked.connect(self.btn_set_z_clicked)
00108         widget.btn_set_a.clicked.connect(self.btn_set_a_clicked)
00109         widget.btn_set_b.clicked.connect(self.btn_set_b_clicked)
00110         widget.btn_set_c.clicked.connect(self.btn_set_c_clicked)
00111 
00112         widget.btn_reset_position_rel.clicked.connect(self.btn_reset_position_rel_clicked)
00113         widget.btn_reset_position_abs.clicked.connect(self.btn_reset_position_abs_clicked)
00114         widget.btn_reset_orientation_rel.clicked.connect(self.btn_reset_orientation_rel_clicked)
00115         widget.btn_reset_orientation_abs.clicked.connect(self.btn_reset_orientation_abs_clicked)
00116 
00117         widget.txt_x.editingFinished.connect(self.x_valueChanged)
00118         widget.txt_y.editingFinished.connect(self.y_valueChanged)
00119         widget.txt_z.editingFinished.connect(self.z_valueChanged)
00120         widget.txt_a.editingFinished.connect(self.a_valueChanged)
00121         widget.txt_b.editingFinished.connect(self.b_valueChanged)
00122         widget.txt_c.editingFinished.connect(self.c_valueChanged)
00123 
00124         widget.btn_rad.toggled.connect(self.update_fields)
00125 
00126         widget.combo_style.currentIndexChanged.connect(self.frame_style_changed)
00127 
00128         return widget
00129 
00130 
00131     def _update_thread_run(self):
00132         self.editor.run()
00133 
00134     @Slot()
00135     def _update_finished(self):
00136         print "> Shutting down"
00137 
00138 
00139     def update(self, editor, level, elements):
00140         self.signal_update.emit(level)
00141 
00142 
00143     @Slot(int)
00144     def update_all(self, level):
00145         ## Update list widgets
00146         if level & 1:
00147             self.update_frame_list()
00148             self.update_tf_list()
00149 
00150         ## Update the currently selected frame
00151         if level & 2:
00152             self.update_active_frame()
00153 
00154         ## Update only text fields, spin boxes,...
00155         if level & 4:
00156             self.update_fields()
00157 
00158 
00159     @Slot()
00160     def update_tf_list(self):
00161         self.widget.list_tf.clear()
00162         self.widget.list_tf.addItems(
00163             sorted(self.editor.all_frame_ids(include_temp=False)))
00164 
00165     def update_frame_list(self):
00166         new_list = self.editor.frames.keys()
00167 
00168         ## Add missing
00169         items = []
00170         for item in new_list:
00171             if item not in self.old_frame_list:
00172                 items.append(item)
00173         self.widget.list_frames.addItems(items)
00174 
00175         ## Delete removed
00176         for item in self.old_frame_list:
00177             if item not in new_list:
00178                 if self.widget.list_frames.currentItem() and item == self.widget.list_frames.currentItem().text():
00179                     self.widget.list_frames.setCurrentItem(None)
00180                 found = self.widget.list_frames.findItems(item, QtCore.Qt.MatchExactly)
00181                 self.widget.list_frames.takeItem(self.widget.list_frames.row(found[0]))
00182 
00183         self.widget.list_frames.sortItems()
00184 
00185         self.old_frame_list = new_list
00186 
00187 
00188     def update_active_frame(self):
00189         if not self.editor.active_frame:
00190             self.old_selected = ""
00191             self.widget.list_frames.setCurrentItem(None)
00192             self.widget.box_edit.setEnabled(False)
00193             return # deselect and quit
00194 
00195         self.widget.box_edit.setEnabled(True)
00196 
00197         name = self.editor.active_frame.name
00198         if name == self.old_selected:
00199             return # no change
00200 
00201         ## Select item in list
00202         items = self.widget.list_frames.findItems(name, QtCore.Qt.MatchExactly)
00203         self.widget.list_frames.setCurrentItem(items[0])
00204 
00205         self.update_fields()
00206 
00207         self.old_selected = name
00208 
00209 
00210     @Slot()
00211     def update_fields(self):
00212 
00213         f = self.editor.active_frame
00214         if not f:
00215             return
00216 
00217         w = self.widget
00218 
00219         w.txt_name.setText(f.name)
00220         w.txt_parent.setText(f.parent)
00221 
00222         ## Relative
00223         w.txt_x.setValue(f.position[0])
00224         w.txt_y.setValue(f.position[1])
00225         w.txt_z.setValue(f.position[2])
00226 
00227         rot = tf.transformations.euler_from_quaternion(f.orientation)
00228         if self.widget.btn_deg.isChecked():
00229             rot = (180.0*rot[0]/math.pi, 180.0*rot[1]/math.pi, 180.0*rot[2]/math.pi)
00230 
00231         w.txt_a.setValue(rot[0])
00232         w.txt_b.setValue(rot[1])
00233         w.txt_c.setValue(rot[2])
00234 
00235         ## Absolute
00236         position, orientation = FromTransformStamped(
00237             f.tf_buffer.lookup_transform('world', f.name, rospy.Time(0)))
00238         ## TODO, tf is sometimes too slow! values may still be the old ones
00239 
00240         w.txt_abs_x.setValue(position[0])
00241         w.txt_abs_y.setValue(position[1])
00242         w.txt_abs_z.setValue(position[2])
00243 
00244         rot = tf.transformations.euler_from_quaternion(orientation)
00245         if self.widget.btn_deg.isChecked():
00246             rot = (180.0*rot[0]/math.pi, 180.0*rot[1]/math.pi, 180.0*rot[2]/math.pi)
00247         w.txt_abs_a.setValue(rot[0])
00248         w.txt_abs_b.setValue(rot[1])
00249         w.txt_abs_c.setValue(rot[2])
00250 
00251         ## Style
00252         self.widget.combo_style.setCurrentIndex(self.widget.combo_style.findText(f.style))
00253 
00254 
00255     @Slot(str)
00256     def selected_frame_changed(self, name):
00257         if name == "":
00258             return
00259 
00260         if not self.editor.active_frame or (self.editor.active_frame.name != name):
00261             self.editor.command(Command_SelectElement(self.editor, self.editor.frames[name]))
00262 
00263 
00264     ## BUTTONS ##
00265     ##
00266     def write_file(self, file_name):
00267         return self.editor.save_file(file_name)
00268 
00269 
00270     @Slot()
00271     def clear_all(self):
00272         self.editor.command(Command_ClearAll(self.editor))
00273 
00274     @Slot(bool)
00275     def btn_add_clicked(self, checked):
00276         # Get a unique frame name
00277         existing_frames = set(self.editor.all_frame_ids())
00278 
00279         name, ok = QtGui.QInputDialog.getText(self.widget, "Add New Frame", "Name:", QtGui.QLineEdit.Normal, "my_frame")
00280 
00281         while ok and name in existing_frames:
00282             name, ok = QtGui.QInputDialog.getText(self.widget, "Add New Frame", "Name (must be unique):", QtGui.QLineEdit.Normal, "my_frame")
00283         if not ok:
00284             return
00285 
00286         if not existing_frames:
00287             available_parents = ["world"]
00288         else:
00289             available_parents = self.editor.all_frame_ids(include_temp=False)
00290         parent, ok = QtGui.QInputDialog.getItem(self.widget, "Add New Frame", "Parent Name:", sorted(available_parents))
00291 
00292         if not ok or parent == "":
00293             return
00294 
00295         self.editor.command(Command_AddElement(self.editor, Frame(name, parent=parent)))
00296 
00297 
00298 
00299     @Slot(bool)
00300     def btn_delete_clicked(self, checked):
00301         item = self.widget.list_frames.currentItem()
00302         if not item:
00303             return
00304         self.editor.command(Command_RemoveElement(self.editor, self.editor.frames[item.text()]))
00305         
00306 
00307     ## PARENTING ##
00308     ##
00309     @Slot(bool)
00310     def btn_set_parent_rel_clicked(self, checked):
00311         self.set_parent(False)
00312 
00313     @Slot(bool)
00314     def btn_set_parent_abs_clicked(self, checked):
00315         self.set_parent(True)
00316 
00317     def set_parent(self, keep_absolute):
00318         parent = self.widget.list_tf.currentItem()
00319         if not parent:
00320             return # none selected
00321 
00322         if parent.text() == self.editor.active_frame.name:
00323             return # you can't be your own parent
00324 
00325         self.editor.command(Command_SetParent(self.editor, self.editor.active_frame, parent.text(), keep_absolute))
00326 
00327 
00328     ## SET BUTTONS ##
00329     ##
00330     @Slot(bool)
00331     def btn_set_pose_clicked(self, checked):
00332         self.set_pose(["x", "y", "z", "a", "b", "c"])
00333 
00334     @Slot(bool)
00335     def btn_set_position_clicked(self, checked):
00336         self.set_pose(["x", "y", "z"])
00337 
00338     @Slot(bool)
00339     def btn_set_orientation_clicked(self, checked):
00340         self.set_pose(["a", "b", "c"])
00341 
00342     @Slot(bool)
00343     def btn_set_x_clicked(self, checked):
00344         self.set_pose(["x"])
00345     @Slot(bool)
00346     def btn_set_y_clicked(self, checked):
00347         self.set_pose(["y"])
00348     @Slot(bool)
00349     def btn_set_z_clicked(self, checked):
00350         self.set_pose(["z"])
00351     @Slot(bool)
00352     def btn_set_a_clicked(self, checked):
00353         self.set_pose(["a"])
00354     @Slot(bool)
00355     def btn_set_b_clicked(self, checked):
00356         self.set_pose(["b"])
00357     @Slot(bool)
00358     def btn_set_c_clicked(self, checked):
00359         self.set_pose(["c"])
00360 
00361     def set_pose(self, mode):
00362         source = self.widget.list_tf.currentItem()
00363         if not source:
00364             return # none selected
00365 
00366         frame = self.editor.active_frame
00367         self.editor.command(Command_AlignElement(self.editor, frame, source.text(), mode))
00368 
00369 
00370     ## RESET BUTTONS ##
00371     ##
00372     @Slot(bool)
00373     def btn_reset_position_rel_clicked(self, checked):
00374         self.editor.command(Command_SetPosition(self.editor, self.editor.active_frame, (0, 0, 0)))
00375 
00376     @Slot(bool)
00377     def btn_reset_position_abs_clicked(self, checked):
00378         position, orientation = FromTransformStamped(
00379             self.editor.active_frame.tf_buffer.lookup_transform(
00380                 self.editor.active_frame.parent, "world", rospy.Time(0)))
00381         self.editor.command(Command_SetPosition(self.editor, self.editor.active_frame, position))
00382 
00383     @Slot(bool)
00384     def btn_reset_orientation_rel_clicked(self, checked):
00385         self.editor.command(Command_SetOrientation(self.editor, self.editor.active_frame, (0, 0, 0, 1)))
00386 
00387     @Slot(bool)
00388     def btn_reset_orientation_abs_clicked(self, checked):
00389         position, orientation = FromTransformStamped(
00390             self.editor.active_frame.listener.lookupTransform(
00391                 self.editor.active_frame.parent, "world", rospy.Time(0)))
00392         self.editor.command(Command_SetOrientation(self.editor, self.editor.active_frame, orientation))
00393 
00394 
00395     ## Spin Boxes ##
00396     ##
00397     def set_value(self, widget, symbol):
00398         frame = self.editor.active_frame
00399         value = widget.value()
00400 
00401         ## Deg to rad
00402         if self.widget.btn_deg.isChecked() and symbol in ['a', 'b', 'c']:
00403             value = value * math.pi / 180.0
00404 
00405         if frame.value(symbol) != value:
00406             self.editor.command(Command_SetValue(self.editor, self.editor.active_frame, symbol, value))
00407 
00408     @Slot()
00409     def x_valueChanged(self):
00410         self.set_value(self.widget.txt_x, 'x')
00411     @Slot()
00412     def y_valueChanged(self):
00413         self.set_value(self.widget.txt_y, 'y')
00414     @Slot()
00415     def z_valueChanged(self):
00416         self.set_value(self.widget.txt_z, 'z')
00417     @Slot()
00418     def a_valueChanged(self):
00419         self.set_value(self.widget.txt_a, 'a')
00420     @Slot()
00421     def b_valueChanged(self):
00422         self.set_value(self.widget.txt_b, 'b')
00423     @Slot()
00424     def c_valueChanged(self):
00425         self.set_value(self.widget.txt_c, 'c')
00426 
00427 
00428     ## FRAME STYLE ##
00429     ##
00430     @Slot(int)
00431     def frame_style_changed(self, id):
00432         style = self.widget.combo_style.currentText().lower()
00433         if self.editor.active_frame.style != style:
00434             self.editor.command(Command_SetStyle(self.editor, self.editor.active_frame, style))
00435 
00436 
00437     ## PLUGIN ##
00438     ##
00439     def shutdown_plugin(self):
00440         super(FrameEditorGUI, self).shutdown_plugin()
00441         self._update_thread.kill()
00442 
00443 # eof


frame_editor
Author(s): ipa-frn
autogenerated on Sat Jun 8 2019 20:21:35