hand_calibration.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2011 Shadow Robot Company Ltd.
00004 #
00005 # This program is free software: you can redistribute it and/or modify it
00006 # under the terms of the GNU General Public License as published by the Free
00007 # Software Foundation, either version 2 of the License, or (at your option)
00008 # any later version.
00009 #
00010 # This program is distributed in the hope that it will be useful, but WITHOUT
00011 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00012 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00013 # more details.
00014 #
00015 # You should have received a copy of the GNU General Public License along
00016 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 #
00018 
00019 import os
00020 import rospy
00021 import rospkg
00022 
00023 from qt_gui.plugin import Plugin
00024 from python_qt_binding import loadUi
00025 
00026 from QtCore import QEvent, QObject, Qt, QTimer, Slot
00027 from QtGui import QWidget, QShortcut, QColor, QTreeWidgetItem, QFileDialog, QMessageBox
00028 from QtCore import QVariant
00029 from sr_gui_hand_calibration.sr_hand_calibration_model import HandCalibration
00030 
00031 
00032 class SrHandCalibration(Plugin):
00033 
00034     """
00035     A rosgui plugin for calibrating the Shadow EtherCAT Hand
00036     """
00037 
00038     def __init__(self, context):
00039         super(SrHandCalibration, self).__init__(context)
00040         self.setObjectName('SrHandCalibration')
00041 
00042         self._publisher = None
00043         self._widget = QWidget()
00044 
00045         ui_file = os.path.join(rospkg.RosPack().get_path(
00046             'sr_gui_hand_calibration'), 'uis', 'SrHandCalibration.ui')
00047         loadUi(ui_file, self._widget)
00048         self._widget.setObjectName('SrHandCalibrationUi')
00049         context.add_widget(self._widget)
00050 
00051         self._widget.tree_calibration.setColumnCount(4)
00052         self._widget.tree_calibration.setHeaderLabels(
00053             ["Finger", "Joint", "Raw Value", "Calibrated Value"])
00054 
00055         self.hand_model = None
00056 
00057         self._widget.btn_save.clicked.connect(self.btn_save_clicked_)
00058         self._widget.btn_load.clicked.connect(self.btn_load_clicked_)
00059         self._widget.btn_joint_0s.clicked.connect(self.btn_joint_0s_clicked_)
00060 
00061         self.populate_tree()
00062 
00063     def populate_tree(self):
00064         """
00065         Create tree with calibrations
00066         """
00067         self._widget.tree_calibration.clear()
00068 
00069         self.hand_model = HandCalibration(
00070             tree_widget=self._widget.tree_calibration, progress_bar=self._widget.progress)
00071         if not self.hand_model.is_active:
00072             self.close_plugin()
00073             return
00074 
00075         self._widget.tree_calibration.expandAll()
00076 
00077         for col in range(0, self._widget.tree_calibration.columnCount()):
00078             self._widget.tree_calibration.resizeColumnToContents(col)
00079 
00080     def btn_save_clicked_(self):
00081         """
00082         Save calibration to a yaml file.
00083         sr_ethercat_hand_config package must be installed
00084         """
00085         path_to_config = "~"
00086         # Reading the param that contains the config_dir suffix that we should
00087         # use for this hand (e.g. '' normally for a right hand  or 'lh' if this
00088         # is for a left hand)
00089         config_dir = rospy.get_param('config_dir', '')
00090         try:
00091             path_to_config = os.path.join(rospkg.RosPack().get_path(
00092                 'sr_ethercat_hand_config'), 'calibrations', config_dir)
00093         except:
00094             rospy.logwarn("couldnt find the sr_ethercat_hand_config package")
00095 
00096         filter_files = "*.yaml"
00097         filename, _ = QFileDialog.getOpenFileName(
00098             self._widget.tree_calibration, self._widget.tr('Save Calibration'),
00099             self._widget.tr(
00100                 path_to_config),
00101             self._widget.tr(filter_files))
00102 
00103         if filename == "":
00104             return
00105 
00106         if not self.hand_model.is_calibration_complete():
00107             btn_pressed = QMessageBox.warning(
00108                 self._widget.tree_calibration, "Warning", "Are you sure you want to save this incomplete calibration?"
00109                 " The uncalibrated values will be saved as a flat map (the calibrated value will always be 0)",
00110                 buttons=QMessageBox.Ok | QMessageBox.Cancel)
00111 
00112             if btn_pressed == QMessageBox.Cancel:
00113                 return
00114         self.hand_model.save(filename)
00115 
00116     def btn_load_clicked_(self):
00117         """
00118         Load calibration from a yaml file.
00119         sr_ethercat_hand_config package must be installed
00120         """
00121         path_to_config = "~"
00122         # Reading the param that contains the config_dir suffix that we should
00123         # use for this hand (e.g. '' normally for a right hand  or 'lh' if this
00124         # is for a left hand)
00125         config_dir = rospy.get_param('config_dir', '')
00126         try:
00127             path_to_config = os.path.join(rospkg.RosPack().get_path('sr_ethercat_hand_config'),
00128                                           'calibrations', config_dir)
00129         except:
00130             rospy.logwarn("couldn't find the sr_ethercat_hand_config package")
00131 
00132         filter_files = "*.yaml"
00133         filename, _ = QFileDialog.getOpenFileName(self._widget.tree_calibration,
00134                                                   self._widget.tr('Load Calibration'),
00135                                                   self._widget.tr(path_to_config),
00136                                                   self._widget.tr(filter_files))
00137 
00138         if filename == "":
00139             return
00140 
00141         self.hand_model.load(filename)
00142 
00143     def btn_joint_0s_clicked_(self):
00144         """
00145         calibrate the first joint of each finger
00146         """
00147         self.hand_model.calibrate_joint0s(self._widget.btn_joint_0s)
00148 
00149     def _unregisterPublisher(self):
00150         if self._publisher is not None:
00151             self._publisher.unregister()
00152             self._publisher = None
00153 
00154         self.hand_model.unregister()
00155 
00156     def shutdown_plugin(self):
00157         self._unregisterPublisher()
00158 
00159     def save_settings(self, global_settings, perspective_settings):
00160         pass
00161 
00162     def restore_settings(self, global_settings, perspective_settings):
00163         pass


sr_gui_hand_calibration
Author(s): Ugo Cupcic
autogenerated on Thu Jun 6 2019 21:13:44