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