wandering_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 from python_qt_binding.QtCore import Signal, Slot, pyqtSlot
00012 from python_qt_binding.QtGui import QFrame
00013 import math
00014 
00015 import roslib
00016 roslib.load_manifest('kobuki_qtestsuite')
00017 import rospy
00018 from kobuki_testsuite import SafeWandering
00019 from kobuki_msgs.msg import BumperEvent
00020 
00021 # Local resource imports
00022 import detail.common_rc
00023 import detail.text_rc
00024 from detail.wandering_frame_ui import Ui_wandering_frame
00025 from qt_gui_py_common.worker_thread import WorkerThread
00026 
00027 ##############################################################################
00028 # Classes
00029 ##############################################################################
00030 
00031 class WanderingFrame(QFrame):
00032     def __init__(self, parent=None):
00033         super(WanderingFrame, self).__init__(parent)
00034         self._ui = Ui_wandering_frame()
00035         self.bump_subscriber = rospy.Subscriber('/mobile_base/events/bumper', BumperEvent, self.bumper_event_callback)
00036         self._motion = SafeWandering('/mobile_base/commands/velocity','/odom', '/mobile_base/events/bumper', '/mobile_base/events/cliff')
00037         self._motion_thread = None
00038         self._is_alive = False # Used to indicate whether the frame is alive or not (see hibernate/restore methods)
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         self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
00045 
00046     def shutdown(self):
00047         '''
00048           Used to terminate the plugin
00049         '''
00050         rospy.loginfo("Kobuki TestSuite: wandering test shutdown")
00051         self._motion.shutdown()
00052         self.bump_subscriber.unregister()
00053 
00054     ##########################################################################
00055     # Widget Management
00056     ##########################################################################
00057         
00058     def hibernate(self):
00059         '''
00060           This gets called when the frame goes out of focus (tab switch). 
00061           Disable everything to avoid running N tabs in parallel when in
00062           reality we are only running one.
00063         '''
00064         pass
00065     
00066     def restore(self):
00067         '''
00068           Restore the frame after a hibernate.
00069         '''
00070         pass
00071 
00072     ##########################################################################
00073     # Motion Callbacks
00074     ##########################################################################
00075 
00076 
00077     def stop(self):
00078         self._motion.stop()
00079         self._ui.start_button.setEnabled(True)
00080         self._ui.stop_button.setEnabled(False)
00081 
00082     def _run_finished(self):
00083         self._ui.start_button.setEnabled(True)
00084         self._ui.stop_button.setEnabled(False)
00085         
00086     ##########################################################################
00087     # Qt Callbacks
00088     ##########################################################################
00089     @Slot()
00090     def on_start_button_clicked(self):
00091         self._ui.start_button.setEnabled(False)
00092         self._ui.stop_button.setEnabled(True)
00093         self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
00094         self._motion_thread.start()
00095 
00096     @Slot()
00097     def on_stop_button_clicked(self):
00098         self.stop()
00099         
00100     @pyqtSlot(float)
00101     def on_speed_spinbox_valueChanged(self, value):
00102         # could use value, but easy to set like this
00103         self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
00104 
00105     @pyqtSlot(float)
00106     def on_angular_speed_spinbox_valueChanged(self, value):
00107         # could use value, but easy to set like this
00108         self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
00109 
00110     ##########################################################################
00111     # Ros Callbacks
00112     ##########################################################################
00113     def bumper_event_callback(self, msg):
00114         if msg.state == BumperEvent.PRESSED:
00115             if msg.bumper == BumperEvent.LEFT:
00116                 self._ui.left_bump_counter_lcd.display(self._ui.left_bump_counter_lcd.intValue()+1)
00117             elif msg.bumper == BumperEvent.RIGHT:
00118                 self._ui.right_bump_counter_lcd.display(self._ui.right_bump_counter_lcd.intValue()+1)
00119             else:
00120                 self._ui.centre_bump_counter_lcd.display(self._ui.centre_bump_counter_lcd.intValue()+1)
00121         


kobuki_qtestsuite
Author(s): Daniel Stonier
autogenerated on Wed Aug 26 2015 12:18:33