Go to the documentation of this file.00001 import os
00002 import rospy
00003 import rospkg
00004 import math
00005
00006 from qt_gui.plugin import Plugin
00007 from python_qt_binding import loadUi
00008 from python_qt_binding.QtCore import QEvent, QModelIndex, QObject, Qt, QTimer, Signal, Slot
00009 from python_qt_binding.QtGui import QShortcut, QTableWidgetItem, QWidget, QLCDNumber, QItemDelegate, QAbstractItemView, QColor, QFont
00010 from rospy import Time
00011 from std_msgs.msg import Bool
00012 from std_msgs.msg import Float32
00013
00014
00015 class CO2Detection(QObject):
00016 _update_co2_color = Signal()
00017 _update_no_co2_color = Signal()
00018
00019 def __init__(self, context):
00020 QObject.__init__(self, context)
00021 self.setObjectName('CO2Detection')
00022
00023 self._widget = QWidget()
00024 ui_file = os.path.join(rospkg.RosPack().get_path('hector_co2_detection_plugin'), 'lib', 'CO2Detection.ui')
00025 loadUi(ui_file, self._widget)
00026 self._widget.setObjectName('CO2Detection')
00027
00028
00029
00030
00031
00032
00033 if context.serial_number() > 1:
00034 self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00035
00036 context.add_widget(self._widget)
00037
00038
00039 self._CO2Subscriber = rospy.Subscriber("/co2detected", Bool, self._on_co2_detected)
00040
00041
00042 self._co2_detected_color = QColor(0, 0, 0, 255)
00043 self._status_no_co2_style = "background-color: rgb(50, 255, 50);"
00044 self._status_co2_style = "background-color: rgb(255, 50, 50);"
00045
00046 self._co2_font = QFont()
00047 self._co2_font.setBold(True)
00048
00049
00050
00051
00052
00053 self._update_co2_color.connect(self._set_co2_style)
00054 self._update_no_co2_color.connect(self._set_no_co2_style)
00055
00056 self._widget.co2detectbutton.setText("Clear Air")
00057 self._update_no_co2_color.emit()
00058
00059
00060
00061 def shutdown_plugin(self):
00062
00063 pass
00064
00065 def save_settings(self, plugin_settings, instance_settings):
00066
00067
00068 pass
00069
00070 def restore_settings(self, plugin_settings, instance_settings):
00071
00072
00073 pass
00074
00075 def _on_co2_detected(self,msg):
00076
00077 self._widget.co2detectbutton.setText("Warning: CO2 detected !!!" if msg.data else "Clear Air")
00078
00079 if msg.data:
00080 self._update_co2_color.emit()
00081 else:
00082 self._update_no_co2_color.emit()
00083
00084 def _set_co2_style(self):
00085 style_sheet_string = self._status_co2_style
00086 self._widget.co2detectbutton.setStyleSheet(style_sheet_string)
00087
00088 def _set_no_co2_style(self):
00089 style_sheet_string = self._status_no_co2_style
00090 self._widget.co2detectbutton.setStyleSheet(style_sheet_string)
00091