CO2Detection.py
Go to the documentation of this file.
1 import os
2 import rospy
3 import rospkg
4 import math
5 
6 from qt_gui.plugin import Plugin
7 from python_qt_binding import loadUi
8 from python_qt_binding.QtCore import QEvent, QModelIndex, QObject, Qt, QTimer, Signal, Slot
9 from python_qt_binding.QtGui import QShortcut, QTableWidgetItem, QWidget, QLCDNumber, QItemDelegate, QAbstractItemView, QColor, QFont
10 from rospy import Time
11 from std_msgs.msg import Bool
12 from std_msgs.msg import Float32
13 
14 
15 class CO2Detection(QObject):
16  _update_co2_color = Signal()
17  _update_no_co2_color = Signal()
18 
19  def __init__(self, context):
20  QObject.__init__(self, context)
21  self.setObjectName('CO2Detection')
22  # setup main widget
23  self._widget = QWidget()
24  ui_file = os.path.join(rospkg.RosPack().get_path('hector_co2_detection_plugin'), 'lib', 'CO2Detection.ui')
25  loadUi(ui_file, self._widget)
26  self._widget.setObjectName('CO2Detection')
27 
28  # Show _widget.windowTitle on left-top of each plugin (when
29  # it's set in _widget). This is useful when you open multiple
30  # plugins at once. Also if you open multiple instances of your
31  # plugin at once, these lines add number to make it easy to
32  # tell from pane to pane.
33  if context.serial_number() > 1:
34  self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
35  # Add widget to the user interface
36  context.add_widget(self._widget)
37 
38  # setup subscribers
39  self._CO2Subscriber = rospy.Subscriber("/co2detected", Bool, self._on_co2_detected)
40 
41  # style settings
42  self._co2_detected_color = QColor(0, 0, 0, 255)
43  self._status_no_co2_style = "background-color: rgb(50, 255, 50);"
44  self._status_co2_style = "background-color: rgb(255, 50, 50);"
45 
46  self._co2_font = QFont()
47  self._co2_font.setBold(True)
48 
49 
50 
51  # Qt Signals
52  #self.connect(self, QtCore.SIGNAL('setCO2Style(PyQt_PyObject)'), self._set_co2_style)
53  self._update_co2_color.connect(self._set_co2_style)
54  self._update_no_co2_color.connect(self._set_no_co2_style)
55 
56  self._widget.co2detectbutton.setText("Clear Air")
57  self._update_no_co2_color.emit()
58 
59 
60 
61  def shutdown_plugin(self):
62  # TODO unregister all publishers here
63  pass
64 
65  def save_settings(self, plugin_settings, instance_settings):
66  # TODO save intrinsic configuration, usually using:
67  # instance_settings.set_value(k, v)
68  pass
69 
70  def restore_settings(self, plugin_settings, instance_settings):
71  # TODO restore intrinsic configuration, usually using:
72  # v = instance_settings.value(k)
73  pass
74 
75  def _on_co2_detected(self,msg):
76 
77  self._widget.co2detectbutton.setText("Warning: CO2 detected !!!" if msg.data else "Clear Air")
78  #self.emit(QtCore.SIGNAL('setCO2Style(PyQt_PyObject)'), self._status_co2_style)
79  if msg.data:
80  self._update_co2_color.emit()
81  else:
82  self._update_no_co2_color.emit()
83 
84  def _set_co2_style(self):
85  style_sheet_string = self._status_co2_style
86  self._widget.co2detectbutton.setStyleSheet(style_sheet_string)
87 
88  def _set_no_co2_style(self):
89  style_sheet_string = self._status_no_co2_style
90  self._widget.co2detectbutton.setStyleSheet(style_sheet_string)
91 
def __init__(self, context)
Definition: CO2Detection.py:19
def restore_settings(self, plugin_settings, instance_settings)
Definition: CO2Detection.py:70
def _on_co2_detected(self, msg)
Definition: CO2Detection.py:75
def save_settings(self, plugin_settings, instance_settings)
Definition: CO2Detection.py:65


hector_co2_detection_plugin
Author(s):
autogenerated on Mon Jun 10 2019 13:36:31