state_saver.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Disabling E1002 check since it complains about super for no reason -
00004 # inheriting from QObject
00005 #
00006 
00007 # Copyright 2016 Shadow Robot Company Ltd.
00008 #
00009 # This program is free software: you can redistribute it and/or modify it
00010 # under the terms of the GNU General Public License as published by the Free
00011 # Software Foundation, either version 2 of the License, or (at your option)
00012 # any later version.
00013 #
00014 # This program is distributed in the hope that it will be useful, but WITHOUT
00015 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00016 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00017 # more details.
00018 #
00019 # You should have received a copy of the GNU General Public License along
00020 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00021 
00022 import os
00023 import rospkg
00024 import rospy
00025 
00026 from qt_gui.plugin import Plugin
00027 from python_qt_binding import loadUi
00028 
00029 from QtCore import Qt, QThread, SIGNAL, QPoint
00030 import QtCore
00031 from QtGui import QWidget, QMessageBox, QFrame, \
00032     QHBoxLayout, QCheckBox, QLabel, QColor
00033 
00034 from std_srvs.srv import Empty
00035 from diagnostic_msgs.msg import DiagnosticArray
00036 from sr_utilities.hand_finder import HandFinder
00037 from sr_robot_commander.sr_robot_state_saver import SrStateSaverUnsafe
00038 
00039 
00040 class SrGuiStateSaver(Plugin):
00041 
00042     """
00043     A gui plugin for resetting motors on the shadow hand.
00044     """
00045 
00046     def __init__(self, context):
00047         super(SrGuiStateSaver, self).__init__(context)
00048         self.setObjectName('SrGuiStateSaver')
00049 
00050         self._publisher = None
00051         self._widget = QWidget()
00052 
00053         ui_file = os.path.join(
00054             rospkg.RosPack().get_path('sr_gui_state_saver'), 'uis',
00055             'SrGuiStateSaver.ui')
00056         loadUi(ui_file, self._widget)
00057         self._widget.setObjectName('SrStateSaverUi')
00058         context.add_widget(self._widget)
00059 
00060         QtCore.QObject.connect(self._widget.button_save, QtCore.SIGNAL("clicked()"), self._button_pressed)
00061 
00062     def _button_pressed(self):
00063         name = self._widget.edit_name.text()
00064 
00065         if name == "":
00066             QMessageBox.warning(self._widget, "No name entered!", "You must enter a name to save the state.")
00067             return
00068 
00069         which = ""
00070         if self._widget.radio_hand.isChecked():
00071             which = "hand"
00072         elif self._widget.radio_arm.isChecked():
00073             which = "arm"
00074         elif self._widget.radio_both.isChecked():
00075             which = "both"
00076         else:
00077             QMessageBox.warning(self._widget, "Choose what to save!",
00078                                 "You must choose which part of the robot you are saving for.")
00079             return
00080 
00081         SrStateSaverUnsafe(name, which)


sr_gui_state_saver
Author(s): Dan Greenwald
autogenerated on Thu Jun 6 2019 21:14:01