cliff_sensor_frame.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # License: BSD
4 # https://raw.github.com/yujinrobot/kobuki_desktop/master/kobuki_qtestsuite/LICENSE
5 #
6 ##############################################################################
7 # Imports
8 ##############################################################################
9 
10 import os
11 import numpy
12 import operator
13 from python_qt_binding.QtCore import Signal, Slot, pyqtSlot
14 try: # indigo
15  from python_qt_binding.QtGui import QFrame, QVBoxLayout
16 except ImportError: # kinetic+ (pyqt5)
17  from python_qt_binding.QtWidgets import QFrame, QVBoxLayout
18 import math
19 
20 import roslib
21 roslib.load_manifest('kobuki_qtestsuite')
22 import rospy
23 from qt_gui_py_common.worker_thread import WorkerThread
24 from kobuki_testsuite import TravelForward
25 
26 # Local resource imports
27 import detail.common_rc
28 import detail.text_rc
29 from detail.cliff_sensor_frame_ui import Ui_cliff_sensor_frame
30 
31 ##############################################################################
32 # Classes
33 ##############################################################################
34 
35 class CliffSensorFrame(QFrame):
36  STATE_FORWARD = "forward"
37  STATE_BACKWARD = "backward"
38  STATE_STOPPED = "stopped"
39 
40  def __init__(self, parent=None):
41  super(CliffSensorFrame, self).__init__(parent)
42  self._ui = Ui_cliff_sensor_frame()
43  self._motion = TravelForward('/mobile_base/commands/velocity','/odom', '/mobile_base/events/cliff')
44  self._motion_thread = None
45  self._distance = 1.2
46  self._state = CliffSensorFrame.STATE_FORWARD
47  self._is_alive = False # Used to indicate whether the frame is alive or not (see hibernate/restore methods)
48 
49 
50  def setupUi(self):
51  self._ui.setupUi(self)
52  self._ui.start_button.setEnabled(True)
53  self._ui.stop_button.setEnabled(False)
54  self._motion.init(self._ui.speed_spinbox.value(), self._distance)
55 
56  def shutdown(self):
57  '''
58  Used to terminate the plugin
59  '''
60  rospy.loginfo("Kobuki TestSuite: cliff sensor shutdown")
61  self._motion.shutdown()
62 
63  ##########################################################################
64  # Widget Management
65  ##########################################################################
66 
67  def hibernate(self):
68  '''
69  This gets called when the frame goes out of focus (tab switch).
70  Disable everything to avoid running N tabs in parallel when in
71  reality we are only running one.
72  '''
73  pass
74 
75  def restore(self):
76  '''
77  Restore the frame after a hibernate.
78  '''
79  pass
80 
81 
82  ##########################################################################
83  # Motion Callbacks
84  ##########################################################################
85 
86  def _run_finished(self):
87  if self._state == CliffSensorFrame.STATE_STOPPED:
88  return
89  elif self._state == CliffSensorFrame.STATE_FORWARD:
90  self._state = CliffSensorFrame.STATE_BACKWARD
91  self._motion.init(-self._motion.speed, 0.2)
92  self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
93  self._motion_thread.start()
94  else:
95  self._state = CliffSensorFrame.STATE_FORWARD
96  self._motion.init(-self._motion.speed, self._distance)
97  self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
98  self._motion_thread.start()
99 
100  ##########################################################################
101  # Qt Callbacks
102  ##########################################################################
103  @Slot()
105  self._ui.start_button.setEnabled(False)
106  self._ui.stop_button.setEnabled(True)
107  self._state = CliffSensorFrame.STATE_FORWARD
108  self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
109  self._motion_thread.start()
110 
111  @Slot()
113  self._state = CliffSensorFrame.STATE_STOPPED
114  self.stop()
115 
116  def stop(self):
117  self._motion.stop()
118  if self._motion_thread:
119  self._motion_thread.wait()
120  self._ui.start_button.setEnabled(True)
121  self._ui.stop_button.setEnabled(False)
122 
123  @pyqtSlot(float)
125  self._motion.init(self._ui.speed_spinbox.value(), self._distance)
126 
127  ##########################################################################
128  # Ros Callbacks
129  ##########################################################################
130 
131  #def robot_state_callback(self, data):
132  # if data.state == RobotStateEvent.OFFLINE:
133  # self.stop()
134 
135 #


kobuki_qtestsuite
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:53:02