CO2Detection.py
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          # setup main widget
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         # Show _widget.windowTitle on left-top of each plugin (when 
00029         # it's set in _widget). This is useful when you open multiple 
00030         # plugins at once. Also if you open multiple instances of your 
00031         # plugin at once, these lines add number to make it easy to 
00032         # tell from pane to pane.
00033         if context.serial_number() > 1:
00034             self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00035         # Add widget to the user interface
00036         context.add_widget(self._widget)
00037 
00038         # setup subscribers  
00039         self._CO2Subscriber = rospy.Subscriber("/co2detected", Bool, self._on_co2_detected)
00040         
00041         # style settings
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         # Qt Signals
00052         #self.connect(self, QtCore.SIGNAL('setCO2Style(PyQt_PyObject)'), self._set_co2_style)
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         # TODO unregister all publishers here
00063         pass
00064 
00065     def save_settings(self, plugin_settings, instance_settings):
00066         # TODO save intrinsic configuration, usually using:
00067         # instance_settings.set_value(k, v)
00068         pass
00069 
00070     def restore_settings(self, plugin_settings, instance_settings):
00071         # TODO restore intrinsic configuration, usually using:
00072         # v = instance_settings.value(k)
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         #self.emit(QtCore.SIGNAL('setCO2Style(PyQt_PyObject)'), self._status_co2_style)
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        


hector_co2_detection_plugin
Author(s):
autogenerated on Thu Aug 27 2015 13:22:56