cliff_sensor_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 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 TravelForward
00022 
00023 # Local resource imports
00024 import detail.common_rc
00025 import detail.text_rc
00026 from detail.cliff_sensor_frame_ui import Ui_cliff_sensor_frame
00027 
00028 ##############################################################################
00029 # Classes
00030 ##############################################################################
00031 
00032 class CliffSensorFrame(QFrame):
00033     STATE_FORWARD = "forward"
00034     STATE_BACKWARD = "backward"
00035     STATE_STOPPED = "stopped"
00036         
00037     def __init__(self, parent=None):
00038         super(CliffSensorFrame, self).__init__(parent)
00039         self._ui = Ui_cliff_sensor_frame()
00040         self._motion = TravelForward('/mobile_base/commands/velocity','/odom', '/mobile_base/events/cliff')
00041         self._motion_thread = None
00042         self._distance = 1.2
00043         self._state = CliffSensorFrame.STATE_FORWARD
00044         self._is_alive = False # Used to indicate whether the frame is alive or not (see hibernate/restore methods)
00045         
00046 
00047     def setupUi(self):
00048         self._ui.setupUi(self)
00049         self._ui.start_button.setEnabled(True)
00050         self._ui.stop_button.setEnabled(False)
00051         self._motion.init(self._ui.speed_spinbox.value(), self._distance)
00052 
00053     def shutdown(self):
00054         '''
00055           Used to terminate the plugin
00056         '''
00057         rospy.loginfo("Kobuki TestSuite: cliff sensor shutdown")
00058         self._motion.shutdown()
00059 
00060     ##########################################################################
00061     # Widget Management
00062     ##########################################################################
00063         
00064     def hibernate(self):
00065         '''
00066           This gets called when the frame goes out of focus (tab switch). 
00067           Disable everything to avoid running N tabs in parallel when in
00068           reality we are only running one.
00069         '''
00070         pass
00071     
00072     def restore(self):
00073         '''
00074           Restore the frame after a hibernate.
00075         '''
00076         pass
00077 
00078 
00079     ##########################################################################
00080     # Motion Callbacks
00081     ##########################################################################
00082 
00083     def _run_finished(self):
00084         if self._state == CliffSensorFrame.STATE_STOPPED:
00085             return
00086         elif self._state == CliffSensorFrame.STATE_FORWARD:
00087             self._state = CliffSensorFrame.STATE_BACKWARD
00088             self._motion.init(-self._motion.speed, 0.2)
00089             self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
00090             self._motion_thread.start()
00091         else:
00092             self._state = CliffSensorFrame.STATE_FORWARD
00093             self._motion.init(-self._motion.speed, self._distance)
00094             self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
00095             self._motion_thread.start()
00096         
00097     ##########################################################################
00098     # Qt Callbacks
00099     ##########################################################################
00100     @Slot()
00101     def on_start_button_clicked(self):
00102         self._ui.start_button.setEnabled(False)
00103         self._ui.stop_button.setEnabled(True)
00104         self._state = CliffSensorFrame.STATE_FORWARD
00105         self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
00106         self._motion_thread.start()
00107 
00108     @Slot()
00109     def on_stop_button_clicked(self):
00110         self._state = CliffSensorFrame.STATE_STOPPED
00111         self.stop()
00112         
00113     def stop(self):
00114         self._motion.stop()
00115         if self._motion_thread:
00116             self._motion_thread.wait()
00117         self._ui.start_button.setEnabled(True)
00118         self._ui.stop_button.setEnabled(False)
00119         
00120     @pyqtSlot(float)
00121     def on_speed_spinbox_valueChanged(self, value):
00122         self._motion.init(self._ui.speed_spinbox.value(), self._distance)
00123 
00124     ##########################################################################
00125     # Ros Callbacks
00126     ##########################################################################
00127 
00128     #def robot_state_callback(self, data):
00129     #    if data.state == RobotStateEvent.OFFLINE:
00130     #        self.stop()
00131 
00132 #


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