11 from python_qt_binding.QtCore
import Signal, Slot, pyqtSlot
13 from python_qt_binding.QtGui
import QFrame
15 from python_qt_binding.QtWidgets
import QFrame
19 from kobuki_testsuite
import SafeWandering
20 from kobuki_msgs.msg
import BumperEvent
23 import detail.common_rc
25 from detail.wandering_frame_ui
import Ui_wandering_frame
34 super(WanderingFrame, self).
__init__(parent)
35 self.
_ui = Ui_wandering_frame()
37 self.
_motion = SafeWandering(
'/mobile_base/commands/velocity',
'/odom',
'/mobile_base/events/bumper',
'/mobile_base/events/cliff')
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())
49 Used to terminate the plugin 51 rospy.loginfo(
"Kobuki TestSuite: wandering test shutdown")
52 self._motion.shutdown()
53 self.bump_subscriber.unregister()
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. 69 Restore the frame after a hibernate. 80 self._ui.start_button.setEnabled(
True)
81 self._ui.stop_button.setEnabled(
False)
84 self._ui.start_button.setEnabled(
True)
85 self._ui.stop_button.setEnabled(
False)
92 self._ui.start_button.setEnabled(
False)
93 self._ui.stop_button.setEnabled(
True)
95 self._motion_thread.start()
104 self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
109 self._motion.init(self._ui.speed_spinbox.value(), -0.1, self._ui.angular_speed_spinbox.value())
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)
121 self._ui.centre_bump_counter_lcd.display(self._ui.centre_bump_counter_lcd.intValue()+1)
def __init__(self, parent=None)
def stop(self)
Motion Callbacks.
def on_speed_spinbox_valueChanged(self, value)
def on_stop_button_clicked(self)
def on_start_button_clicked(self)
Qt Callbacks.
def on_angular_speed_spinbox_valueChanged(self, value)
def bumper_event_callback(self, msg)
Ros Callbacks.
def hibernate(self)
Widget Management.