button_general.py
Go to the documentation of this file.
00001 from distutils.version import LooseVersion
00002 import math
00003 import os
00004 import sys
00005 
00006 import python_qt_binding
00007 import python_qt_binding.QtCore as QtCore
00008 from python_qt_binding.QtCore import QEvent
00009 from python_qt_binding.QtCore import QSize
00010 from python_qt_binding.QtCore import Qt
00011 from python_qt_binding.QtCore import QTimer
00012 from python_qt_binding.QtCore import qWarning
00013 from python_qt_binding.QtCore import Slot
00014 import python_qt_binding.QtGui as QtGui
00015 from python_qt_binding.QtGui import QBrush
00016 from python_qt_binding.QtGui import QColor
00017 from python_qt_binding.QtGui import QFont
00018 from python_qt_binding.QtGui import QIcon
00019 from python_qt_binding.QtGui import QPainter
00020 from python_qt_binding.QtGui import QPen
00021 import yaml
00022 
00023 from resource_retriever import get_filename
00024 import rospy
00025 from rqt_gui_py.plugin import Plugin
00026 from std_msgs.msg import Bool
00027 from std_msgs.msg import Time
00028 from std_srvs.srv import Empty
00029 
00030 if LooseVersion(python_qt_binding.QT_BINDING_VERSION).version[0] >= 5:
00031     from python_qt_binding.QtWidgets import QAction
00032     from python_qt_binding.QtWidgets import QComboBox
00033     from python_qt_binding.QtWidgets import QCompleter
00034     from python_qt_binding.QtWidgets import QDialog
00035     from python_qt_binding.QtWidgets import QGroupBox
00036     from python_qt_binding.QtWidgets import QHBoxLayout
00037     from python_qt_binding.QtWidgets import QLineEdit
00038     from python_qt_binding.QtWidgets import QMenu
00039     from python_qt_binding.QtWidgets import QMessageBox
00040     from python_qt_binding.QtWidgets import QPushButton
00041     from python_qt_binding.QtWidgets import QRadioButton
00042     from python_qt_binding.QtWidgets import QSizePolicy
00043     from python_qt_binding.QtWidgets import QToolButton
00044     from python_qt_binding.QtWidgets import QVBoxLayout
00045     from python_qt_binding.QtWidgets import QWidget
00046 
00047 else:
00048     from python_qt_binding.QtGui import QAction
00049     from python_qt_binding.QtGui import QComboBox
00050     from python_qt_binding.QtGui import QCompleter
00051     from python_qt_binding.QtGui import QDialog
00052     from python_qt_binding.QtGui import QGroupBox
00053     from python_qt_binding.QtGui import QHBoxLayout
00054     from python_qt_binding.QtGui import QLineEdit
00055     from python_qt_binding.QtGui import QMenu
00056     from python_qt_binding.QtGui import QMessageBox
00057     from python_qt_binding.QtGui import QPushButton
00058     from python_qt_binding.QtGui import QRadioButton
00059     from python_qt_binding.QtGui import QSizePolicy
00060     from python_qt_binding.QtGui import QToolButton
00061     from python_qt_binding.QtGui import QVBoxLayout
00062     from python_qt_binding.QtGui import QWidget
00063 
00064 
00065 class LineEditDialog(QDialog):
00066     def __init__(self, parent=None):
00067         super(LineEditDialog, self).__init__()
00068         self.value = None
00069         vbox = QVBoxLayout(self)
00070         # combo box
00071         model = QtGui.QStandardItemModel(self)
00072         for elm in rospy.get_param_names():
00073             model.setItem(model.rowCount(), 0, QtGui.QStandardItem(elm))
00074         self.combo_box = QComboBox(self)
00075         self.line_edit = QLineEdit()
00076         self.combo_box.setLineEdit(self.line_edit)
00077         self.combo_box.setCompleter(QCompleter())
00078         self.combo_box.setModel(model)
00079         self.combo_box.completer().setModel(model)
00080         self.combo_box.lineEdit().setText('')
00081         vbox.addWidget(self.combo_box)
00082         # button
00083         button = QPushButton()
00084         button.setText("Done")
00085         button.clicked.connect(self.buttonCallback)
00086         vbox.addWidget(button)
00087         self.setLayout(vbox)
00088 
00089     def buttonCallback(self, event):
00090         self.value = self.line_edit.text()
00091         self.close()
00092 
00093 
00094 class ServiceButtonGeneralWidget(QWidget):
00095     """
00096     Qt widget to visualize multiple buttons
00097     """
00098     def __init__(self, button_type="push"):
00099         super(ServiceButtonGeneralWidget, self).__init__()
00100         self.button_type = button_type
00101         self._layout_param = None
00102         self._dialog = LineEditDialog()
00103         self.show()
00104 
00105     def showError(self, message):
00106         QMessageBox.about(self, "ERROR", message)
00107 
00108     def loadLayoutYaml(self, layout_param):
00109         # Initialize layout of the buttons from yaml file
00110         # The yaml file can be specified by rosparam
00111         layout_yaml_file = rospy.get_param(
00112             layout_param,
00113             "package://jsk_rqt_plugins/resource/service_button_layout.yaml")
00114         resolved_layout_yaml_file = get_filename(
00115             layout_yaml_file)[len("file://"):]
00116         # check file exists
00117         if not os.path.exists(resolved_layout_yaml_file):
00118             self.showError("Cannot find %s (%s)" % (
00119                            layout_yaml_file, resolved_layout_yaml_file))
00120             sys.exit(1)
00121         self.setupButtons(resolved_layout_yaml_file)
00122         self.show()
00123 
00124     def setupButtons(self, yaml_file):
00125         """
00126         Parse yaml file and setup Buttons. Format of the yaml file should be:
00127         - name: 'button name' (required)
00128           image: 'path to image for icon' (optional)
00129           image_size: 'width and height of icon' (optional)
00130           service: 'service' (required)
00131           column: 'column index' (optional, defaults to 0)
00132         """
00133         self.buttons = []
00134         with open(yaml_file) as f:
00135             yaml_data = yaml.load(f)
00136             # lookup colum direction
00137             direction = 'vertical'
00138             for d in yaml_data:
00139                 if d.has_key('direction'):
00140                     if d['direction'] == 'horizontal':
00141                         direction = 'horizontal'
00142                     else: # d['direction'] == 'vertical':
00143                         direction = 'vertical'
00144                     yaml_data.remove(d)
00145                     break
00146             # lookup column num
00147             column_indices = [d['column'] for d in yaml_data]
00148             max_column_index = max(*column_indices)
00149             if direction == 'vertical':
00150                 self.layout = QHBoxLayout()
00151                 self.layout_boxes = [QVBoxLayout()
00152                                      for i in range(max_column_index + 1)]
00153             else:  # direction == 'horizontal'
00154                 self.layout = QVBoxLayout()
00155                 self.layout_boxes = [QHBoxLayout()
00156                                      for i in range(max_column_index + 1)]
00157             self.button_groups = [QGroupBox()
00158                                   for i in range(max_column_index + 1)]
00159             for button_data in yaml_data:
00160                 # check if all the field is available
00161                 if not button_data.has_key("name"):
00162                     self.showError("name field is missed in yaml")
00163                     raise Exception("name field is missed in yaml")
00164                 if not button_data.has_key("service"):
00165                     self.showError("service field is missed in yaml")
00166                     raise Exception("service field is missed in yaml")
00167                 if self.button_type == "push":
00168                     button = QToolButton()
00169                 else:  # self.button_type == "Radio":
00170                     button = QRadioButton()
00171                 button.setSizePolicy(
00172                     QSizePolicy(QSizePolicy.Preferred, QSizePolicy.Preferred))
00173                 if button_data.has_key("image"):
00174                     image_file = get_filename(
00175                         button_data["image"])[len("file://"):]
00176                     if os.path.exists(image_file):
00177                         icon = QtGui.QIcon(image_file)
00178                         button.setIcon(icon)
00179                         if button_data.has_key("image_size"):
00180                             button.setIconSize(QSize(
00181                                 button_data["image_size"][0],
00182                                 button_data["image_size"][1]))
00183                         else:
00184                             button.setIconSize(QSize(100, 100))
00185                 if button_data.has_key("name"):
00186                     name = button_data['name']
00187                     button.setText(name)
00188                 button.clicked.connect(
00189                     self.buttonCallback(button_data['service']))
00190                 if self.button_type == "push":
00191                     button.setToolButtonStyle(
00192                         QtCore.Qt.ToolButtonTextUnderIcon)
00193                 else:  # self.button_type == "Radio":
00194                     if button_data.has_key("default_value") and \
00195                        button_data['default_value']:
00196                         button.setChecked(True)
00197                 self.layout_boxes[button_data['column']].addWidget(button)
00198                 self.buttons.append(button)
00199             for i in range(len(self.button_groups)):
00200                 self.button_groups[i].setLayout(self.layout_boxes[i])
00201             for group in self.button_groups:
00202                 self.layout.addWidget(group)
00203             self.setLayout(self.layout)
00204 
00205     def buttonCallback(self, service_name):
00206         """
00207         return function as callback
00208         """
00209         return lambda x: self.buttonCallbackImpl(service_name)
00210 
00211     def buttonCallbackImpl(self, service_name):
00212         srv = rospy.ServiceProxy(service_name, Empty)
00213         try:
00214             srv()
00215         except rospy.ServiceException, e:
00216             self.showError("Failed to call %s" % service_name)
00217 
00218     def save_settings(self, plugin_settings, instance_settings):
00219         if self._layout_param:
00220             instance_settings.set_value("layout_param", self._layout_param)
00221             rospy.loginfo("save setting is called. %s" % self._layout_param)
00222 
00223     def restore_settings(self, plugin_settings, instance_settings):
00224         if instance_settings.value("layout_param"):
00225             self._layout_param = instance_settings.value("layout_param")
00226             self.loadLayoutYaml(self._layout_param)
00227             rospy.loginfo("restore setting is called. %s" % self._layout_param)
00228 
00229     def trigger_configuration(self):
00230         self._dialog.exec_()
00231         self._layout_param = self._dialog.value
00232         self.loadLayoutYaml(self._layout_param)
00233         rospy.loginfo(
00234             "trigger configuration is called. %s" % self._dialog.value)


jsk_rqt_plugins
Author(s):
autogenerated on Wed May 1 2019 02:40:16