Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 import os
00020
00021 import roslib
00022 roslib.load_manifest('sr_gui_hand_calibration')
00023 import rospy
00024
00025 from qt_gui.plugin import Plugin
00026 from python_qt_binding import loadUi
00027
00028 from QtCore import QEvent, QObject, Qt, QTimer, Slot
00029 from QtGui import QWidget, QShortcut, QColor, QTreeWidgetItem, QFileDialog, QMessageBox
00030 from QtCore import QVariant
00031 from sr_gui_hand_calibration.sr_hand_calibration_model import HandCalibration
00032
00033 class SrHandCalibration(Plugin):
00034
00035 def __init__(self, context):
00036 super(SrHandCalibration, self).__init__(context)
00037 self.setObjectName('SrHandCalibration')
00038
00039 self._publisher = None
00040 self._widget = QWidget()
00041
00042 ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../uis/SrHandCalibration.ui')
00043 loadUi(ui_file, self._widget)
00044 self._widget.setObjectName('SrHandCalibrationUi')
00045 context.add_widget(self._widget)
00046
00047 self._widget.tree_calibration.setColumnCount(4)
00048 self._widget.tree_calibration.setHeaderLabels(["Finger", "Joint", "Raw Value", "Calibrated Value"])
00049
00050 self.hand_model = None
00051
00052 self._widget.btn_save.clicked.connect(self.btn_save_clicked_)
00053 self._widget.btn_load.clicked.connect(self.btn_load_clicked_)
00054 self._widget.btn_joint_0s.clicked.connect(self.btn_joint_0s_clicked_)
00055
00056 self.populate_tree()
00057
00058 def populate_tree(self):
00059 self._widget.tree_calibration.clear()
00060
00061 self.hand_model = HandCalibration( tree_widget = self._widget.tree_calibration, progress_bar = self._widget.progress )
00062 if not self.hand_model.is_active:
00063 self.close_plugin()
00064 return
00065
00066 self._widget.tree_calibration.expandAll()
00067
00068 for col in range(0, self._widget.tree_calibration.columnCount()):
00069 self._widget.tree_calibration.resizeColumnToContents(col)
00070
00071 def btn_save_clicked_(self):
00072 path_to_config = "~"
00073 try:
00074 path_to_config = roslib.packages.get_pkg_dir("sr_ethercat_hand_config") + "/calibrations"
00075 except:
00076 rospy.logwarn("couldnt find the sr_ethercat_hand_config package")
00077
00078 filter_files = "*.yaml"
00079 filename, _ = QFileDialog.getOpenFileName(self._widget.tree_calibration, self._widget.tr('Save Calibration'),
00080 self._widget.tr(path_to_config),
00081 self._widget.tr(filter_files))
00082
00083 if filename == "":
00084 return
00085
00086 if not self.hand_model.is_calibration_complete():
00087 btn_pressed = QMessageBox.warning(self._widget.tree_calibration, "Warning", "Are you sure you want to save this incomplete calibration? The uncalibrated values will be saved as a flat map (the calibrated value will always be 0)",
00088 buttons = QMessageBox.Ok | QMessageBox.Cancel)
00089
00090 if btn_pressed == QMessageBox.Cancel:
00091 return
00092 self.hand_model.save( filename )
00093
00094 def btn_load_clicked_(self):
00095 path_to_config = "~"
00096 try:
00097 path_to_config = roslib.packages.get_pkg_dir("sr_ethercat_hand_config") + "/calibrations"
00098 except:
00099 rospy.logwarn("couldnt find the sr_ethercat_hand_config package")
00100
00101 filter_files = "*.yaml"
00102 filename, _ = QFileDialog.getOpenFileName(self._widget.tree_calibration, self._widget.tr('Load Calibration'),
00103 self._widget.tr(path_to_config),
00104 self._widget.tr(filter_files))
00105
00106 if filename == "":
00107 return
00108
00109 self.hand_model.load( filename )
00110
00111 def btn_joint_0s_clicked_(self):
00112 self.hand_model.calibrate_joint0s( self._widget.btn_joint_0s )
00113
00114 def _unregisterPublisher(self):
00115 if self._publisher is not None:
00116 self._publisher.unregister()
00117 self._publisher = None
00118
00119 self.hand_model.unregister()
00120
00121 def shutdown_plugin(self):
00122 self._unregisterPublisher()
00123
00124 def save_settings(self, global_settings, perspective_settings):
00125 pass
00126
00127 def restore_settings(self, global_settings, perspective_settings):
00128 pass
00129