11 from python_qt_binding.QtCore
import Signal, Slot, pyqtSlot
13 from python_qt_binding.QtGui
import QFrame, QVBoxLayout
15 from python_qt_binding.QtWidgets
import QFrame, QVBoxLayout
21 from kobuki_testsuite
import Rotate
22 from kobuki_msgs.msg
import RobotStateEvent
25 import detail.common_rc
27 from detail.battery_profile_frame_ui
import Ui_battery_profile_frame
28 from full_size_data_plot
import FullSizeDataPlot
37 super(BatteryProfileFrame, self).
__init__(parent)
40 self.
_ui = Ui_battery_profile_frame()
47 self._ui.setupUi(self)
49 self.
_plot_layout = QVBoxLayout(self._ui.battery_profile_group_box)
50 self._ui.start_button.setEnabled(
True)
51 self._ui.stop_button.setEnabled(
False)
56 Used to terminate the plugin 58 rospy.loginfo(
"Kobuki TestSuite: battery test shutdown")
67 This gets called when the frame goes out of focus (tab switch). 68 Disable everything to avoid running N tabs in parallel when in 69 reality we are only running one. 77 Restore the frame after a hibernate. 80 self._plot_widget.setWindowTitle(
"Battery Profile")
85 self._data_plot.set_autoscale(y=
False)
86 self._data_plot.set_ylim([0, 180])
87 self._plot_widget.switch_data_plot_widget(self.
_data_plot)
95 self._ui.start_button.setEnabled(
True)
96 self._ui.stop_button.setEnabled(
False)
103 self._ui.start_button.setEnabled(
False)
104 self._ui.stop_button.setEnabled(
True)
107 self._motion.init(self._ui.angular_speed_spinbox.value())
111 self._plot_widget._start_time = rospy.get_time()
112 self._plot_widget.enable_timer(
True)
119 self._motion_thread.start()
124 Hardcore stoppage - straight to zero. 130 self._plot_widget.enable_timer(
False)
133 self._motion_thread.wait()
136 self._motion.shutdown()
139 self.robot_state_subscriber.unregister()
141 self._ui.start_button.setEnabled(
True)
142 self._ui.stop_button.setEnabled(
False)
147 self._motion.init(self._ui.angular_speed_spinbox.value())
155 To be connected to the configuration dock combo box (via the main testsuite frame) 158 print(
"DudetteBattery %s" % topic_name)
165 if data.state == RobotStateEvent.OFFLINE:
def hibernate(self)
Widget Management.
def robot_state_callback(self, data)
Ros Callbacks.
def on_start_button_clicked(self)
Qt Callbacks.
def on_stop_button_clicked(self)
def setupUi(self, cmd_vel_topic_name)
def _run_finished(self)
Motion Callbacks.
def __init__(self, parent=None)
def on_cmd_vel_topic_combo_box_currentIndexChanged(self, topic_name)
External Slot Callbacks.
def on_angular_speed_spinbox_valueChanged(self, value)