gyro_drift_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 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 # Local resource imports
00025 import detail.common_rc
00026 import detail.text_rc
00027 from detail.gyro_drift_frame_ui import Ui_gyro_drift_frame
00028 from rqt_plot.data_plot import DataPlot
00029 
00030 ##############################################################################
00031 # Classes
00032 ##############################################################################
00033 
00034 class GyroDriftFrame(QFrame):
00035     def __init__(self, parent=None):
00036         super(GyroDriftFrame, self).__init__(parent)
00037         self._ui = Ui_gyro_drift_frame()
00038         self._laser_scan_angle_topic_name = '/laser_scan_angle'
00039         self._gyro_scan_angle_topic_name = '/gyro_scan_angle'
00040         self._error_scan_angle_topic_name = '/error_scan_angle'
00041         self._cmd_vel_topic_name = '/mobile_base/commands/velocity'
00042         self._gyro_topic_name = '/mobile_base/sensors/imu_data'
00043         self._motion = None
00044         self._scan_to_angle = None
00045         self._motion_thread = None
00046 
00047     def setupUi(self):
00048         self._ui.setupUi(self)
00049         self._plot_layout = QVBoxLayout(self._ui.scan_angle_group_box)
00050         self._plot_widget = PlotWidget()
00051         self._plot_widget.setWindowTitle("Error")
00052         self._plot_layout.addWidget(self._plot_widget)
00053         self._plot_widget.switch_data_plot_widget(DataPlot(self._plot_widget))
00054         self._plot_widget.data_plot.dynamic_range = True
00055         self._plot_widget_live = PlotWidget()
00056         self._plot_widget_live.setWindowTitle("Live Graphs")
00057         self._plot_widget_live.switch_data_plot_widget(DataPlot(self._plot_widget_live))
00058         self._plot_layout.addWidget(self._plot_widget_live)
00059         self._ui.start_button.setEnabled(True)
00060         self._ui.stop_button.setEnabled(False)
00061 
00062     def shutdown(self):
00063         '''
00064           Used to terminate the plugin
00065         '''
00066         rospy.loginfo("Kobuki TestSuite: gyro drift shutdown")
00067         self._stop()
00068 
00069     ##########################################################################
00070     # Widget Management
00071     ##########################################################################
00072         
00073     def _pause_plots(self):
00074         '''
00075          Pause plots, more importantly, pause greedy plot rendering
00076         '''
00077         self._plot_widget.enable_timer(False)
00078         self._plot_widget_live.enable_timer(False)
00079 
00080     def hibernate(self):
00081         '''
00082           This gets called when the frame goes out of focus (tab switch). 
00083           Disable everything to avoid running N tabs in parallel when in
00084           reality we are only running one.
00085         '''
00086         self._stop()
00087     
00088     def restore(self):
00089         '''
00090           Restore the frame after a hibernate.
00091         '''
00092         pass
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._scan_to_angle:
00102             self._scan_to_angle = ScanToAngle('/scan',self._laser_scan_angle_topic_name)
00103         if not self._motion:
00104             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)
00105             self._motion.init(self._ui.angular_speed_spinbox.value())
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._error_scan_angle_topic_name+'/scan_angle')
00111             self._plot_widget_live.remove_topic(self._laser_scan_angle_topic_name+'/scan_angle')
00112             self._plot_widget_live.remove_topic(self._gyro_scan_angle_topic_name+'/scan_angle')
00113             self._plot_widget_live.remove_topic(self._cmd_vel_topic_name+'/angular/z')
00114         except KeyError:
00115             pass
00116         self._plot_widget_live.add_topic(self._cmd_vel_topic_name+'/angular/z')
00117         self._plot_widget_live.add_topic(self._laser_scan_angle_topic_name+'/scan_angle')
00118         self._plot_widget_live.add_topic(self._gyro_scan_angle_topic_name+'/scan_angle')
00119         self._plot_widget.add_topic(self._error_scan_angle_topic_name+'/scan_angle')
00120         self._motion_thread = WorkerThread(self._motion.execute, None)
00121         self._motion_thread.start()
00122 
00123     @Slot()
00124     def on_stop_button_clicked(self):
00125         self._stop()
00126         
00127     def _stop(self):
00128         self._pause_plots()
00129         if self._scan_to_angle:
00130             self._scan_to_angle.shutdown()
00131             self._scan_to_angle = None
00132         if self._motion:
00133             self._motion.stop()
00134         if self._motion_thread:
00135             self._motion_thread.wait()
00136             self._motion_thread = None
00137         if self._motion:
00138             self._motion.shutdown()
00139             self._motion = None
00140         self._ui.start_button.setEnabled(True)
00141         self._ui.stop_button.setEnabled(False)
00142         
00143     @pyqtSlot(float)
00144     def on_angular_speed_spinbox_valueChanged(self, value):
00145         if self._motion:
00146             self._motion.init(self._ui.angular_speed_spinbox.value())
00147 


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