Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 import os
00011 import numpy
00012 import operator
00013 from python_qt_binding.QtCore import Signal, Slot, pyqtSlot
00014 from python_qt_binding.QtGui import QFrame, QVBoxLayout
00015 import math
00016 
00017 import roslib
00018 roslib.load_manifest('kobuki_qtestsuite')
00019 import rospy
00020 from qt_gui_py_common.worker_thread import WorkerThread
00021 from kobuki_testsuite import Square
00022 
00023 
00024 import detail.common_rc
00025 import detail.text_rc
00026 from detail.payload_frame_ui import Ui_payload_frame
00027 
00028 
00029 
00030 
00031 
00032 class PayloadFrame(QFrame):
00033     def __init__(self, parent=None):
00034         super(PayloadFrame, self).__init__(parent)
00035         self._gyro_topic_name = '/mobile_base/sensors/imu_data'
00036         self._ui = Ui_payload_frame()
00037         self._motion = None
00038         self._motion_thread = None
00039 
00040     def setupUi(self):
00041         self._ui.setupUi(self)
00042         self._ui.start_button.setEnabled(True)
00043         self._ui.stop_button.setEnabled(False)
00044 
00045     def shutdown(self):
00046         '''
00047           Used to terminate the plugin
00048         '''
00049         rospy.loginfo("Kobuki TestSuite: payload frame shutdown")
00050         self._stop()
00051 
00052     
00053     
00054     
00055         
00056     def hibernate(self):
00057         '''
00058           This gets called when the frame goes out of focus (tab switch). 
00059           Disable everything to avoid running N tabs in parallel when in
00060           reality we are only running one.
00061         '''
00062         self._stop()
00063     
00064     def restore(self):
00065         '''
00066           Restore the frame after a hibernate.
00067         '''
00068         pass
00069 
00070     
00071     
00072     
00073 
00074     def _run_finished(self):
00075         self._motion_thread = None
00076         self._motion = None
00077         self._ui.start_button.setEnabled(True)
00078         self._ui.stop_button.setEnabled(False)
00079         
00080     
00081     
00082     
00083     @Slot()
00084     def on_start_button_clicked(self):
00085         self._ui.start_button.setEnabled(False)
00086         self._ui.stop_button.setEnabled(True)
00087         self._motion = Square('/mobile_base/commands/velocity', '/odom', self._gyro_topic_name)
00088         self._motion.init(self._ui.speed_spinbox.value(), self._ui.distance_spinbox.value())
00089         self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
00090         self._motion_thread.start()
00091 
00092     @Slot()
00093     def on_stop_button_clicked(self):
00094         self._stop()
00095         
00096     def _stop(self):
00097         if self._motion:
00098             self._motion.stop()
00099         if self._motion_thread:
00100             self._motion_thread.wait()
00101             self._motion_thread = None
00102         if self._motion:
00103             self._motion = None
00104         self._ui.start_button.setEnabled(True)
00105         self._ui.stop_button.setEnabled(False)
00106         
00107     @pyqtSlot(float)
00108     def on_speed_spinbox_valueChanged(self, value):
00109         if self._motion:
00110             self._motion.init(self._ui.speed_spinbox.value(), self._ui.distance_spinbox.value())
00111 
00112     @pyqtSlot(float)
00113     def on_distance_spinbox_valueChanged(self, value):
00114         if self._motion:
00115             self._motion.init(self._ui.speed_spinbox.value(), self._ui.distance_spinbox.value())
00116 
00117     
00118     
00119     
00120 
00121     
00122     
00123     
00124 
00125