life_frame.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #       
00003 # License: BSD
00004 #   https://raw.github.com/yujinrobot/kobuki_desktop/master/kobuki_qtestsuite/LICENSE 
00005 #
00006 ##############################################################################
00007 # Imports
00008 ##############################################################################
00009 
00010 import os
00011 import numpy
00012 import operator
00013 #import python_qt_binding.QtCore
00014 from python_qt_binding.QtCore import QObject, SIGNAL, SLOT, Signal, Slot, pyqtSlot, QTimer
00015 from python_qt_binding.QtGui import QFrame, QVBoxLayout
00016 import math
00017 
00018 import roslib
00019 roslib.load_manifest('kobuki_qtestsuite')
00020 import rospy
00021 from qt_gui_py_common.worker_thread import WorkerThread
00022 from kobuki_testsuite import Rotate
00023 
00024 # Local resource imports
00025 import detail.common_rc
00026 import detail.text_rc
00027 from detail.life_frame_ui import Ui_life_frame
00028 
00029 ##############################################################################
00030 # Classes
00031 ##############################################################################
00032 
00033 class LifeFrame(QFrame):
00034     STATE_STOPPED = "stopped"
00035     STATE_RUN = "running"
00036     STATE_IDLE = "idle"
00037     
00038     def __init__(self, parent=None):
00039         super(LifeFrame, self).__init__(parent)
00040         self._ui = Ui_life_frame()
00041         self._motion = Rotate('/mobile_base/commands/velocity')
00042         self._motion_thread = None
00043         self._timer = QTimer()
00044         #self._timer.setInterval(60000) #60s
00045         self._timer.setInterval(250) #60s
00046         QObject.connect(self._timer, SIGNAL('timeout()'), self, SLOT('update_progress_callback()'))
00047         self._state = LifeFrame.STATE_STOPPED
00048         self._is_alive = False # Used to indicate whether the frame is alive or not (see hibernate/restore methods)
00049 
00050     def setupUi(self):
00051         self._ui.setupUi(self)
00052         self._ui.start_button.setEnabled(True)
00053         self._ui.stop_button.setEnabled(False)
00054         self._motion.init(self._ui.angular_speed_spinbox.value())
00055 
00056     def shutdown(self):
00057         '''
00058           Used to terminate the plugin
00059         '''
00060         rospy.loginfo("Kobuki TestSuite: life frame shutdown")
00061         self._motion.shutdown()
00062 
00063     ##########################################################################
00064     # Widget Management
00065     ##########################################################################
00066         
00067     def hibernate(self):
00068         '''
00069           This gets called when the frame goes out of focus (tab switch). 
00070           Disable everything to avoid running N tabs in parallel when in
00071           reality we are only running one.
00072         '''
00073         pass
00074     
00075     def restore(self):
00076         '''
00077           Restore the frame after a hibernate.
00078         '''
00079         pass
00080 
00081 
00082     ##########################################################################
00083     # Motion Callbacks
00084     ##########################################################################
00085 
00086     def start(self):
00087         self._state = LifeFrame.STATE_RUN
00088         self._ui.run_progress.reset()
00089         self._ui.idle_progress.reset()
00090         self._motion_thread = WorkerThread(self._motion.execute, None)
00091         self._motion_thread.start()
00092 
00093     def stop(self):
00094         self._state = LifeFrame.STATE_STOPPED
00095         self._motion.stop()
00096         if self._motion_thread:
00097             self._motion_thread.wait()
00098         
00099     ##########################################################################
00100     # Qt Callbacks
00101     ##########################################################################
00102     @Slot()
00103     def on_start_button_clicked(self):
00104         self._ui.start_button.setEnabled(False)
00105         self._ui.stop_button.setEnabled(True)
00106         self._timer.start()
00107         self.start()
00108         
00109     @Slot()
00110     def on_stop_button_clicked(self):
00111         self.stop()
00112         self._timer.stop()
00113         self._ui.start_button.setEnabled(True)
00114         self._ui.stop_button.setEnabled(False)
00115         
00116     @pyqtSlot(float)
00117     def on_angular_speed_spinbox_valueChanged(self, value):
00118         self._motion.init(self._ui.angular_speed_spinbox.value())
00119 
00120     ##########################################################################
00121     # Timer Callbacks
00122     ##########################################################################
00123 
00124     @Slot()
00125     def update_progress_callback(self):
00126         if self._state == LifeFrame.STATE_RUN:
00127             new_value = self._ui.run_progress.value()+1
00128             if new_value == self._ui.run_progress.maximum():
00129                 print("  Switching to idle")
00130                 self._motion.stop()
00131                 self._state = LifeFrame.STATE_IDLE
00132             else:
00133                 self._ui.run_progress.setValue(new_value)
00134         if self._state == LifeFrame.STATE_IDLE:
00135             new_value = self._ui.idle_progress.value()+1
00136             if new_value == self._ui.idle_progress.maximum():
00137                 print("  Switching to run")
00138                 self.start()
00139             else:
00140                 self._ui.idle_progress.setValue(new_value)
00141 
00142 
00143 #


kobuki_qtestsuite
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 19:42:56