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 
00029 ##############################################################################
00030 # Classes
00031 ##############################################################################
00032 
00033 class BatteryProfileFrame(QFrame):
00034     def __init__(self, parent=None):
00035         super(BatteryProfileFrame, self).__init__(parent)
00036         self._cmd_vel_topic_name = '/mobile_base/commands/velocity'
00037         self._battery_topic_name = "/mobile_base/sensors/core/battery"
00038         self._ui = Ui_battery_profile_frame()
00039         self._motion = None
00040         self.robot_state_subscriber = None
00041         self._motion_thread = None
00042 
00043     def setupUi(self):
00044         self._ui.setupUi(self)
00045         self._plot_layout = QVBoxLayout(self._ui.battery_profile_group_box)
00046         self._plot_widget = PlotWidget()
00047         self._plot_widget.setWindowTitle("Battery Profile")
00048         self._plot_widget.topic_edit.setText(self._battery_topic_name)
00049         self._plot_layout.addWidget(self._plot_widget)
00050         self._plot_widget.switch_data_plot_widget(FullSizeDataPlot(self._plot_widget))
00051         self._ui.start_button.setEnabled(True)
00052         self._ui.stop_button.setEnabled(False)
00053 
00054     def shutdown(self):
00055         '''
00056           Used to terminate the plugin
00057         '''
00058         rospy.loginfo("Kobuki TestSuite: battery test shutdown")
00059         self._stop()
00060 
00061     ##########################################################################
00062     # Widget Management
00063     ##########################################################################
00064         
00065     def hibernate(self):
00066         '''
00067           This gets called when the frame goes out of focus (tab switch). 
00068           Disable everything to avoid running N tabs in parallel when in
00069           reality we are only running one.
00070         '''
00071         self._stop()
00072     
00073     def restore(self):
00074         '''
00075           Restore the frame after a hibernate.
00076         '''
00077         pass
00078 
00079 
00080     ##########################################################################
00081     # Motion Callbacks
00082     ##########################################################################
00083 
00084     def _run_finished(self):
00085         self._ui.start_button.setEnabled(True)
00086         self._ui.stop_button.setEnabled(False)
00087         
00088     ##########################################################################
00089     # Qt Callbacks
00090     ##########################################################################
00091     @Slot()
00092     def on_start_button_clicked(self):
00093         self._ui.start_button.setEnabled(False)
00094         self._ui.stop_button.setEnabled(True)
00095         if not self._motion: 
00096             self._motion = Rotate(self._cmd_vel_topic_name)
00097             self._motion.init(self._ui.angular_speed_spinbox.value())
00098         if not self.robot_state_subscriber:
00099             self.robot_state_subscriber = rospy.Subscriber("/mobile_base/events/robot_state", RobotStateEvent, self.robot_state_callback)
00100         rospy.sleep(0.5)
00101         self._plot_widget._start_time = rospy.get_time()
00102         self._plot_widget.enable_timer(True)
00103         try:
00104             self._plot_widget.remove_topic(self._battery_topic_name)
00105         except KeyError:
00106             pass
00107         self._plot_widget.add_topic(self._battery_topic_name)
00108         self._motion_thread = WorkerThread(self._motion.execute, self._run_finished)
00109         self._motion_thread.start()
00110 
00111     @Slot()
00112     def on_stop_button_clicked(self):
00113         '''
00114           Hardcore stoppage - straight to zero.
00115         '''
00116         self._stop()
00117         
00118     def _stop(self):
00119         self._plot_widget.enable_timer(False) # pause plot rendering
00120         if self._motion_thread:
00121             self._motion.stop()
00122             self._motion_thread.wait()
00123             self._motion_thread = None
00124         if self._motion:
00125             self._motion.shutdown()
00126             self._motion = None
00127         if self.robot_state_subscriber:
00128             self.robot_state_subscriber.unregister()
00129             self.robot_state_subscriber = None
00130         self._ui.start_button.setEnabled(True)
00131         self._ui.stop_button.setEnabled(False)
00132         
00133     @pyqtSlot(float)
00134     def on_angular_speed_spinbox_valueChanged(self, value):
00135         if self._motion:
00136             self._motion.init(self._ui.angular_speed_spinbox.value())
00137 
00138     ##########################################################################
00139     # Ros Callbacks
00140     ##########################################################################
00141 
00142     def robot_state_callback(self, data):
00143         if data.state == RobotStateEvent.OFFLINE:
00144             self.stop()


kobuki_qtestsuite
Author(s): Daniel Stonier
autogenerated on Mon Oct 6 2014 01:31:16