wandering_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 from python_qt_binding.QtCore import Signal, Slot, pyqtSlot
12 try: # indigo
13  from python_qt_binding.QtGui import QFrame
14 except ImportError: # kinetic+ (pyqt5)
15  from python_qt_binding.QtWidgets import QFrame
16 import math
17 
18 import rospy
19 from kobuki_testsuite import SafeWandering
20 from kobuki_msgs.msg import BumperEvent
21 
22 # Local resource imports
23 import detail.common_rc
24 import detail.text_rc
25 from detail.wandering_frame_ui import Ui_wandering_frame
26 from qt_gui_py_common.worker_thread import WorkerThread
27 
28 ##############################################################################
29 # Classes
30 ##############################################################################
31 
32 class WanderingFrame(QFrame):
33  def __init__(self, parent=None):
34  super(WanderingFrame, self).__init__(parent)
35  self._ui = Ui_wandering_frame()
36  self.bump_subscriber = rospy.Subscriber('/mobile_base/events/bumper', BumperEvent, self.bumper_event_callback)
37  self._motion = SafeWandering('/mobile_base/commands/velocity','/odom', '/mobile_base/events/bumper', '/mobile_base/events/cliff')
38  self._motion_thread = None
39  self._is_alive = False # Used to indicate whether the frame is alive or not (see hibernate/restore methods)
40 
41  def setupUi(self):
42  self._ui.setupUi(self)
43  self._ui.start_button.setEnabled(True)
44  self._ui.stop_button.setEnabled(False)
45  self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
46 
47  def shutdown(self):
48  '''
49  Used to terminate the plugin
50  '''
51  rospy.loginfo("Kobuki TestSuite: wandering test shutdown")
52  self._motion.shutdown()
53  self.bump_subscriber.unregister()
54 
55  ##########################################################################
56  # Widget Management
57  ##########################################################################
58 
59  def hibernate(self):
60  '''
61  This gets called when the frame goes out of focus (tab switch).
62  Disable everything to avoid running N tabs in parallel when in
63  reality we are only running one.
64  '''
65  pass
66 
67  def restore(self):
68  '''
69  Restore the frame after a hibernate.
70  '''
71  pass
72 
73  ##########################################################################
74  # Motion Callbacks
75  ##########################################################################
76 
77 
78  def stop(self):
79  self._motion.stop()
80  self._ui.start_button.setEnabled(True)
81  self._ui.stop_button.setEnabled(False)
82 
83  def _run_finished(self):
84  self._ui.start_button.setEnabled(True)
85  self._ui.stop_button.setEnabled(False)
86 
87  ##########################################################################
88  # Qt Callbacks
89  ##########################################################################
90  @Slot()
92  self._ui.start_button.setEnabled(False)
93  self._ui.stop_button.setEnabled(True)
94  self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
95  self._motion_thread.start()
96 
97  @Slot()
99  self.stop()
100 
101  @pyqtSlot(float)
103  # could use value, but easy to set like this
104  self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
105 
106  @pyqtSlot(float)
108  # could use value, but easy to set like this
109  self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
110 
111  ##########################################################################
112  # Ros Callbacks
113  ##########################################################################
114  def bumper_event_callback(self, msg):
115  if msg.state == BumperEvent.PRESSED:
116  if msg.bumper == BumperEvent.LEFT:
117  self._ui.left_bump_counter_lcd.display(self._ui.left_bump_counter_lcd.intValue()+1)
118  elif msg.bumper == BumperEvent.RIGHT:
119  self._ui.right_bump_counter_lcd.display(self._ui.right_bump_counter_lcd.intValue()+1)
120  else:
121  self._ui.centre_bump_counter_lcd.display(self._ui.centre_bump_counter_lcd.intValue()+1)
122 
def bumper_event_callback(self, msg)
Ros Callbacks.


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