motor_resetter.py
Go to the documentation of this file.
00001 # Copyright 2011 Shadow Robot Company Ltd.
00002 #
00003 # This program is free software: you can redistribute it and/or modify it
00004 # under the terms of the GNU General Public License as published by the Free
00005 # Software Foundation, either version 2 of the License, or (at your option)
00006 # any later version.
00007 #
00008 # This program is distributed in the hope that it will be useful, but WITHOUT
00009 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00010 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00011 # more details.
00012 #
00013 # You should have received a copy of the GNU General Public License along
00014 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00015 
00016 import os
00017 import roslib
00018 roslib.load_manifest('sr_gui_motor_resetter')
00019 import rospy
00020 
00021 from qt_gui.plugin import Plugin
00022 from python_qt_binding import loadUi
00023 
00024 from QtCore import QEvent, QObject, Qt, QTimer, Slot, QThread, SIGNAL, QPoint
00025 from QtGui import QWidget, QShortcut, QMessageBox, QFrame, QHBoxLayout, QCheckBox, QLabel, QCursor, QColor, QMessageBox
00026 
00027 from std_srvs.srv import Empty
00028 from diagnostic_msgs.msg import DiagnosticArray
00029 
00030 class MotorFlasher(QThread):
00031     def __init__(self, parent, nb_motors_to_program):
00032         QThread.__init__(self, None)
00033         self.parent = parent
00034         self.nb_motors_to_program = nb_motors_to_program
00035 
00036     def run(self):
00037         programmed_motors = 0
00038         for motor in self.parent.motors:
00039             if motor.checkbox.checkState() == Qt.Checked:
00040                 try:
00041                     print("resetting: /realtime_loop/reset_motor_"+motor.motor_name)
00042                     self.flasher_service = rospy.ServiceProxy('/realtime_loop/reset_motor_'+motor.motor_name, Empty)
00043                     self.flasher_service()
00044                 except rospy.ServiceException, e:
00045                     self.emit( SIGNAL("failed(QString)"),
00046                                "Service did not process request: %s"%str(e) )
00047                     return
00048 
00049                 programmed_motors += 1
00050                 self.emit( SIGNAL("motor_finished(QPoint)"), QPoint( programmed_motors, 0.0 ) )
00051 
00052 class Motor(QFrame):
00053     def __init__(self, parent, motor_name, motor_index):
00054         QFrame.__init__(self, parent)
00055 
00056         self.motor_name = motor_name
00057         self.motor_index = motor_index
00058 
00059         self.layout = QHBoxLayout()
00060 
00061         self.checkbox = QCheckBox(motor_name + " [" + str(motor_index) +"]", self)
00062         self.layout.addWidget(self.checkbox)
00063 
00064         self.revision_label = QLabel( "" )
00065         self.revision_label.setToolTip("Svn Revision")
00066         self.layout.addWidget(self.revision_label)
00067 
00068         self.setLayout(self.layout)
00069 
00070 
00071 class SrGuiMotorResetter(Plugin):
00072 
00073     def __init__(self, context):
00074         super(SrGuiMotorResetter, self).__init__(context)
00075         self.setObjectName('SrGuiMotorResetter')
00076 
00077         self._publisher = None
00078         self._widget = QWidget()
00079 
00080         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../uis/SrGuiMotorResetter.ui')
00081         loadUi(ui_file, self._widget)
00082         self._widget.setObjectName('SrMotorResetterUi')
00083         context.add_widget(self._widget)
00084 
00085         # motors_frame is defined in the ui file with a grid layout
00086         self.motors = []
00087         self.motors_frame = self._widget.motors_frame
00088         self.populate_motors()
00089         self.progress_bar = self._widget.motors_progress_bar
00090         self.progress_bar.hide()
00091 
00092         self.server_revision = 0
00093         self.diag_sub = rospy.Subscriber("/diagnostics", DiagnosticArray, self.diagnostics_callback)
00094 
00095         # Bind button clicks
00096         self._widget.btn_select_all.pressed.connect(self.on_select_all_pressed)
00097         self._widget.btn_select_none.pressed.connect(self.on_select_none_pressed)
00098         self._widget.btn_reset_motors.pressed.connect(self.on_reset_motors_pressed)
00099 
00100 
00101     def populate_motors(self):
00102         if rospy.has_param("joint_to_motor_mapping"):
00103             joint_to_motor_mapping = rospy.get_param("joint_to_motor_mapping")
00104         else:
00105             QMessageBox.warning(self.motors_frame, "Warning", "Couldn't fint the joint_to_motor_mapping parameter. Make sure the etherCAT Hand node is running")
00106             self.close_plugin()
00107             return
00108 
00109         joint_names = [
00110                 ["FFJ0", "FFJ1", "FFJ2", "FFJ3", "FFJ4"],
00111                 ["MFJ0", "MFJ1", "MFJ2", "MFJ3", "MFJ4"],
00112                 ["RFJ0", "RFJ1", "RFJ2", "RFJ3", "RFJ4"],
00113                 ["LFJ0", "LFJ1", "LFJ2", "LFJ3", "LFJ4", "LFJ5"],
00114                 ["THJ1", "THJ2", "THJ3", "THJ4","THJ5"],
00115                 ["WRJ1", "WRJ2"]
00116             ]
00117 
00118         row = 0
00119         col = 0
00120         index_jtm_mapping = 0
00121         for finger in joint_names:
00122             col = 0
00123             for joint_name in finger:
00124                 motor_index = joint_to_motor_mapping[index_jtm_mapping]
00125                 if motor_index != -1:
00126                     motor = Motor(self.motors_frame, joint_name, motor_index)
00127                     self.motors_frame.layout().addWidget(motor, row, col)
00128                     self.motors.append( motor )
00129                     col += 1
00130                 index_jtm_mapping += 1
00131             row += 1
00132 
00133     def diagnostics_callback(self, msg):
00134         for status in msg.status:
00135             for motor in self.motors:
00136                 if motor.motor_name in status.name:
00137                     for key_values in status.values:
00138                         if "Firmware svn revision" in key_values.key:
00139                             server_current_modified = key_values.value.split(" / ")
00140 
00141                             if server_current_modified[0] > self.server_revision:
00142                                 self.server_revision = int( server_current_modified[0].strip() )
00143 
00144                             palette = motor.revision_label.palette();
00145                             palette.setColor(motor.revision_label.foregroundRole(), Qt.green)
00146                             if server_current_modified[0].strip() != server_current_modified[1].strip():
00147                                 palette.setColor(motor.revision_label.foregroundRole(), QColor(255, 170, 23) )
00148                                 motor.revision_label.setPalette(palette);
00149 
00150                             if "True" in server_current_modified[2]:
00151                                 palette.setColor(motor.revision_label.foregroundRole(), Qt.red)
00152                                 motor.revision_label.setText( "svn: "+ server_current_modified[1] + " [M]" )
00153                                 motor.revision_label.setPalette(palette);
00154                             else:
00155                                 motor.revision_label.setText( " svn: " + server_current_modified[1] )
00156                                 motor.revision_label.setPalette(palette);
00157 
00158     def on_select_all_pressed(self):
00159         for motor in self.motors:
00160             motor.checkbox.setCheckState( Qt.Checked )
00161 
00162     def on_select_none_pressed(self):
00163         for motor in self.motors:
00164             motor.checkbox.setCheckState( Qt.Unchecked )
00165 
00166     def on_reset_motors_pressed(self):
00167         print("Reset motors pressed");
00168         self.progress_bar.reset()
00169         nb_motors_to_program = 0
00170         for motor in self.motors:
00171             if motor.checkbox.checkState() == Qt.Checked:
00172                 nb_motors_to_program += 1
00173         if nb_motors_to_program == 0:
00174             QMessageBox.warning(self._widget, "Warning", "No motors selected for resetting.")
00175             return
00176         self.progress_bar.setMaximum(nb_motors_to_program)
00177 
00178         self.motor_flasher = MotorFlasher(self, nb_motors_to_program)
00179         self._widget.connect(self.motor_flasher, SIGNAL("finished()"), self.finished_programming_motors)
00180         self._widget.connect(self.motor_flasher, SIGNAL("motor_finished(QPoint)"), self.one_motor_finished)
00181         self._widget.connect(self.motor_flasher, SIGNAL("failed(QString)"), self.failed_programming_motors)
00182 
00183         self._widget.setCursor(Qt.WaitCursor)
00184         self.motors_frame.setEnabled(False)
00185         self._widget.btn_select_all.setEnabled(False)
00186         self._widget.btn_select_none.setEnabled(False)
00187         self.progress_bar.show()
00188         self._widget.btn_reset_motors.hide()
00189 
00190         self.motor_flasher.start()
00191 
00192     def one_motor_finished(self, point):
00193         self.progress_bar.setValue( int(point.x()) )
00194 
00195     def finished_programming_motors(self):
00196         self.motors_frame.setEnabled(True)
00197         self._widget.btn_select_all.setEnabled(True)
00198         self._widget.btn_select_none.setEnabled(True)
00199         self._widget.setCursor(Qt.ArrowCursor)
00200         self.progress_bar.hide()
00201         self._widget.btn_reset_motors.show()
00202 
00203     def failed_programming_motors(self, message):
00204         QMessageBox.warning(self.motors_frame, "Warning", message)
00205 
00206     def _unregisterPublisher(self):
00207         if self._publisher is not None:
00208             self._publisher.unregister()
00209             self._publisher = None
00210 
00211     def shutdown_plugin(self):
00212         self._unregisterPublisher()
00213 
00214     def save_settings(self, global_settings, perspective_settings):
00215         pass
00216 
00217     def restore_settings(self, global_settings, perspective_settings):
00218         pass
00219 


sr_gui_motor_resetter
Author(s): Mark Pitchless
autogenerated on Fri Jan 3 2014 12:03:33