battery_profile_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, QVBoxLayout
00013 import math
00014 
00015 import roslib
00016 roslib.load_manifest('kobuki_qtestsuite')
00017 import rospy
00018 from qt_gui_py_common.worker_thread import WorkerThread
00019 from rqt_plot.plot_widget import PlotWidget
00020 from kobuki_testsuite import Rotate
00021 from kobuki_msgs.msg import RobotStateEvent
00022 
00023 # Local resource imports
00024 import detail.common_rc
00025 import detail.text_rc
00026 from detail.battery_profile_frame_ui import Ui_battery_profile_frame
00027 from full_size_data_plot import FullSizeDataPlot
00028 from rqt_plot.data_plot import DataPlot
00029 
00030 ##############################################################################
00031 # Classes
00032 ##############################################################################
00033 
00034 class BatteryProfileFrame(QFrame):
00035     def __init__(self, parent=None):
00036         super(BatteryProfileFrame, self).__init__(parent)
00037         self._cmd_vel_topic_name = '/mobile_base/commands/velocity'
00038         self._battery_topic_name = "/mobile_base/sensors/core/battery"
00039         self._ui = Ui_battery_profile_frame()
00040         self._motion = None
00041         self.robot_state_subscriber = None
00042         self._motion_thread = None
00043 
00044     def setupUi(self, cmd_vel_topic_name):
00045         self._ui.setupUi(self)
00046         self._cmd_vel_topic_name = cmd_vel_topic_name
00047         self._plot_layout = QVBoxLayout(self._ui.battery_profile_group_box)
00048         self._plot_widget = PlotWidget()
00049         self._plot_widget.setWindowTitle("Battery Profile")
00050         self._plot_widget.topic_edit.setText(self._battery_topic_name)
00051         self._plot_layout.addWidget(self._plot_widget)
00052 
00053         self._data_plot = DataPlot(self._plot_widget)
00054         self._data_plot.set_autoscale(y=False)
00055         self._data_plot.set_ylim([0, 180])
00056         self._plot_widget.switch_data_plot_widget(self._data_plot)
00057         self._ui.start_button.setEnabled(True)
00058         self._ui.stop_button.setEnabled(False)
00059 
00060     def shutdown(self):
00061         '''
00062           Used to terminate the plugin
00063         '''
00064         rospy.loginfo("Kobuki TestSuite: battery test shutdown")
00065         self._stop()
00066 
00067     ##########################################################################
00068     # Widget Management
00069     ##########################################################################
00070         
00071     def hibernate(self):
00072         '''
00073           This gets called when the frame goes out of focus (tab switch). 
00074           Disable everything to avoid running N tabs in parallel when in
00075           reality we are only running one.
00076         '''
00077         self._stop()
00078     
00079     def restore(self):
00080         '''
00081           Restore the frame after a hibernate.
00082         '''
00083         pass
00084 
00085 
00086     ##########################################################################
00087     # Motion Callbacks
00088     ##########################################################################
00089 
00090     def _run_finished(self):
00091         self._ui.start_button.setEnabled(True)
00092         self._ui.stop_button.setEnabled(False)
00093         
00094     ##########################################################################
00095     # Qt Callbacks
00096     ##########################################################################
00097     @Slot()
00098     def on_start_button_clicked(self):
00099         self._ui.start_button.setEnabled(False)
00100         self._ui.stop_button.setEnabled(True)
00101         if not self._motion: 
00102             self._motion = Rotate(self._cmd_vel_topic_name)
00103             self._motion.init(self._ui.angular_speed_spinbox.value())
00104         if not self.robot_state_subscriber:
00105             self.robot_state_subscriber = rospy.Subscriber("/mobile_base/events/robot_state", RobotStateEvent, self.robot_state_callback)
00106         rospy.sleep(0.5)
00107         self._plot_widget._start_time = rospy.get_time()
00108         self._plot_widget.enable_timer(True)
00109         try:
00110             self._plot_widget.remove_topic(self._battery_topic_name)
00111         except KeyError:
00112             pass
00113         self._plot_widget.add_topic(self._battery_topic_name)
00114         self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
00115         self._motion_thread.start()
00116 
00117     @Slot()
00118     def on_stop_button_clicked(self):
00119         '''
00120           Hardcore stoppage - straight to zero.
00121         '''
00122         self._stop()
00123         
00124     def _stop(self):
00125         self._plot_widget.enable_timer(False) # pause plot rendering
00126         if self._motion_thread:
00127             self._motion.stop()
00128             self._motion_thread.wait()
00129             self._motion_thread = None
00130         if self._motion:
00131             self._motion.shutdown()
00132             self._motion = None
00133         if self.robot_state_subscriber:
00134             self.robot_state_subscriber.unregister()
00135             self.robot_state_subscriber = None
00136         self._ui.start_button.setEnabled(True)
00137         self._ui.stop_button.setEnabled(False)
00138         
00139     @pyqtSlot(float)
00140     def on_angular_speed_spinbox_valueChanged(self, value):
00141         if self._motion:
00142             self._motion.init(self._ui.angular_speed_spinbox.value())
00143 
00144     ##########################################################################
00145     # External Slot Callbacks
00146     ##########################################################################
00147     @Slot(str)
00148     def on_cmd_vel_topic_combo_box_currentIndexChanged(self, topic_name):
00149         '''
00150           To be connected to the configuration dock combo box (via the main testsuite frame)
00151         '''
00152         self._cmd_vel_topic_name = topic_name
00153         print("DudetteBattery %s" % topic_name)
00154 
00155     ##########################################################################
00156     # Ros Callbacks
00157     ##########################################################################
00158 
00159     def robot_state_callback(self, data):
00160         if data.state == RobotStateEvent.OFFLINE:
00161             self.stop()


kobuki_qtestsuite
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 19:42:56