Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 import os
00011 import numpy
00012 import operator
00013 from python_qt_binding.QtCore import Signal, Slot, pyqtSlot
00014 from python_qt_binding.QtGui import QFrame, QVBoxLayout
00015 import math
00016
00017 import roslib
00018 roslib.load_manifest('kobuki_qtestsuite')
00019 import rospy
00020 from qt_gui_py_common.worker_thread import WorkerThread
00021 from kobuki_testsuite import ScanToAngle, DriftEstimation
00022 from rqt_plot.plot_widget import PlotWidget
00023
00024
00025 import detail.common_rc
00026 import detail.text_rc
00027 from detail.gyro_drift_frame_ui import Ui_gyro_drift_frame
00028 from full_size_data_plot import FullSizeDataPlot
00029 from rqt_plot.mat_data_plot import MatDataPlot
00030
00031
00032
00033
00034
00035 class GyroDriftFrame(QFrame):
00036 def __init__(self, parent=None):
00037 super(GyroDriftFrame, self).__init__(parent)
00038 self._ui = Ui_gyro_drift_frame()
00039 self._laser_scan_angle_topic_name = '/laser_scan_angle'
00040 self._gyro_scan_angle_topic_name = '/gyro_scan_angle'
00041 self._error_scan_angle_topic_name = '/error_scan_angle'
00042 self._cmd_vel_topic_name = '/mobile_base/commands/velocity'
00043 self._gyro_topic_name = '/mobile_base/sensors/imu_data'
00044 self._motion = None
00045 self._scan_to_angle = None
00046 self._motion_thread = None
00047
00048 def setupUi(self):
00049 self._ui.setupUi(self)
00050 self._plot_layout = QVBoxLayout(self._ui.scan_angle_group_box)
00051 self._plot_widget = PlotWidget()
00052 self._plot_widget.setWindowTitle("Error")
00053 self._plot_layout.addWidget(self._plot_widget)
00054 self._plot_widget.switch_data_plot_widget(FullSizeDataPlot(self._plot_widget))
00055 self._plot_widget.data_plot.dynamic_range = True
00056 self._plot_widget_live = PlotWidget()
00057 self._plot_widget_live.setWindowTitle("Live Graphs")
00058 self._plot_widget_live.switch_data_plot_widget(MatDataPlot(self._plot_widget_live))
00059 self._plot_layout.addWidget(self._plot_widget_live)
00060 self._ui.start_button.setEnabled(True)
00061 self._ui.stop_button.setEnabled(False)
00062
00063 def shutdown(self):
00064 '''
00065 Used to terminate the plugin
00066 '''
00067 rospy.loginfo("Kobuki TestSuite: gyro drift shutdown")
00068 self._stop()
00069
00070
00071
00072
00073
00074 def _pause_plots(self):
00075 '''
00076 Pause plots, more importantly, pause greedy plot rendering
00077 '''
00078 self._plot_widget.enable_timer(False)
00079 self._plot_widget_live.enable_timer(False)
00080
00081 def hibernate(self):
00082 '''
00083 This gets called when the frame goes out of focus (tab switch).
00084 Disable everything to avoid running N tabs in parallel when in
00085 reality we are only running one.
00086 '''
00087 self._stop()
00088
00089 def restore(self):
00090 '''
00091 Restore the frame after a hibernate.
00092 '''
00093 pass
00094
00095
00096
00097
00098 @Slot()
00099 def on_start_button_clicked(self):
00100 self._ui.start_button.setEnabled(False)
00101 self._ui.stop_button.setEnabled(True)
00102 if not self._scan_to_angle:
00103 self._scan_to_angle = ScanToAngle('/scan',self._laser_scan_angle_topic_name)
00104 if not self._motion:
00105 self._motion = DriftEstimation(self._laser_scan_angle_topic_name, self._gyro_scan_angle_topic_name, self._error_scan_angle_topic_name, self._cmd_vel_topic_name,self._gyro_topic_name)
00106 self._motion.init(self._ui.angular_speed_spinbox.value())
00107 rospy.sleep(0.5)
00108 self._plot_widget.data_plot.reset()
00109 self._plot_widget._start_time = rospy.get_time()
00110 self._plot_widget.enable_timer(True)
00111 try:
00112 self._plot_widget.remove_topic(self._error_scan_angle_topic_name+'/scan_angle')
00113 self._plot_widget_live.remove_topic(self._laser_scan_angle_topic_name+'/scan_angle')
00114 self._plot_widget_live.remove_topic(self._gyro_scan_angle_topic_name+'/scan_angle')
00115 self._plot_widget_live.remove_topic(self._cmd_vel_topic_name+'/angular/z')
00116 except KeyError:
00117 pass
00118 self._plot_widget_live.add_topic(self._cmd_vel_topic_name+'/angular/z')
00119 self._plot_widget_live.add_topic(self._laser_scan_angle_topic_name+'/scan_angle')
00120 self._plot_widget_live.add_topic(self._gyro_scan_angle_topic_name+'/scan_angle')
00121 self._plot_widget.add_topic(self._error_scan_angle_topic_name+'/scan_angle')
00122 self._motion_thread = WorkerThread(self._motion.execute, None)
00123 self._motion_thread.start()
00124
00125 @Slot()
00126 def on_stop_button_clicked(self):
00127 self._stop()
00128
00129 def _stop(self):
00130 self._pause_plots()
00131 if self._scan_to_angle:
00132 self._scan_to_angle.shutdown()
00133 self._scan_to_angle = None
00134 if self._motion:
00135 self._motion.stop()
00136 if self._motion_thread:
00137 self._motion_thread.wait()
00138 self._motion_thread = None
00139 if self._motion:
00140 self._motion.shutdown()
00141 self._motion = None
00142 self._ui.start_button.setEnabled(True)
00143 self._ui.stop_button.setEnabled(False)
00144
00145 @pyqtSlot(float)
00146 def on_angular_speed_spinbox_valueChanged(self, value):
00147 if self._motion:
00148 self._motion.init(self._ui.angular_speed_spinbox.value())
00149