pds_gui.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2017, Dataspeed Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without modification,
9 # are permitted provided that the following conditions are met:
10 #
11 # * Redistributions of source code must retain the above copyright notice,
12 # this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above copyright notice,
14 # this list of conditions and the following disclaimer in the documentation
15 # and/or other materials provided with the distribution.
16 # * Neither the name of Dataspeed Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived from this
18 # software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
21 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
22 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30 
31 import os
32 import rospy
33 import rospkg
34 import time
35 
36 from qt_gui.plugin import Plugin
37 from python_qt_binding import loadUi
38 from python_qt_binding.QtWidgets import QWidget, QGraphicsScene, QLabel, QGraphicsEllipseItem, QGraphicsLineItem, QGraphicsTextItem
39 from python_qt_binding.QtCore import Qt, Signal, QTimer, QDateTime, QDate, QTime, QPoint, QEvent, QObject, pyqtSignal
40 from python_qt_binding.QtGui import QPixmap, QFont, QPen, QColor, QBrush, QImage
41 
42 from cmath import *
43 from math import *
44 from rospy.rostime import Time
45 from numpy import isfinite
46 
47 from dataspeed_pds_msgs.msg import Status, Channel, Relay, Mode, Script
48 
49 # In order to style the buttons I had to make them labels instead,
50 # but in order to make them clickable I had to use the below code.
51 def clickable(widget):
52  class Filter(QObject):
53  clicked = pyqtSignal()
54  def eventFilter(self, obj, event):
55 
56  if obj == widget:
57  if event.type() == QEvent.MouseButtonRelease:
58  if obj.rect().contains(event.pos()):
59  self.clicked.emit()
60  # The developer can opt for .emit(obj) to get the object within the slot.
61  return True
62 
63  return False
64 
65  filter = Filter(widget)
66  widget.installEventFilter(filter)
67  return filter.clicked
68 
70  gui_update_timer = QTimer()
71 
72  # Channel Status
73  current_status = None
74  # Channel Current in amps
75  current_amps = None
76 
77  # Switching between tabs and full GUI
78  is_currently_tab = False
79  widget_count = 0
80  current_tab_idx = -1
81  raw_data_tab_idx = 5
82 
83  def __init__(self, context):
84  super(PowerDistributionGui, self).__init__(context)
85 
86  # Qt setup
87  self.context_ = context
88  self.init_gui('full')
89 
90  # ROS setup
91  self.subscribe_topics()
92  self.advertise_topics()
93  self.last_update = 0
94 
95  def init_gui(self, gui_type):
96  if gui_type == 'full':
97  self.spawn_full_gui()
98 
99  self.bind_callbacks()
100  self.reset_gui_timer()
101 
103  for index in range(0, 24):
104  channelStatusName = "NONE"
105  buttonStyle = ""
106 
107  if self.current_status.chan[index].status == Channel.ON:
108  buttonStyle += 'background-color: rgb(78, 154, 6);' # Green
109  channelStatusName = "ON"
110  elif self.current_status.chan[index].status == Channel.NO_LOAD:
111  buttonStyle += 'background-color: rgb(78, 154, 6);' # Green
112  channelStatusName = "NO LOAD"
113  elif self.current_status.chan[index].status == Channel.OVER_CURRENT:
114  buttonStyle += 'background-color: rgb(252, 175, 62);' # Orange
115  channelStatusName = "OVER CURRENT"
116  elif self.current_status.chan[index].status == Channel.OFF:
117  buttonStyle += 'background-color: rgb(130, 130, 130);' # Gray
118  channelStatusName = "OFF"
119  elif self.current_status.chan[index].status == Channel.BAD_RELAY:
120  buttonStyle += 'background-color: rgb(229, 90, 90);' # Red
121  channelStatusName = "BAD RELAY"
122  elif self.current_status.chan[index].status == Channel.BAD_FUSE:
123  buttonStyle += 'background-color: rgb(229, 90, 90);' # Red
124  channelStatusName = "BAD FUSE"
125 
126  buttonText = '<html><head/><body><p align="center"><span style=" font-size:12pt;">'
127  buttonText += '#{} {}'.format(index + 1, channelStatusName)
128  buttonText += '</span></p><p align="center"><span style=" font-size:28pt;">'
129  buttonText += '{0:.2f} A'.format(self.current_status.chan[index].current)
130  buttonText += '</span></p><p align="center"><span style=" font-size:8pt;">'
131  buttonText += '</span></p></body></html>'
132  getattr(self._widget, "buttonChannel{:0>2d}".format(index + 1)).setText(buttonText)
133 
134  buttonStyle += 'color: rgb(0, 0, 0);'
135  buttonStyle += 'border-radius: 12px;'
136  buttonStyle += 'padding: 12px;'
137  getattr(self._widget, "buttonChannel{:0>2d}".format(index + 1)).setStyleSheet(buttonStyle)
138 
140  # Update text on Master Inverter Button
141  buttonTextMaster = '<html><head/><body><p align="center"><span style=" font-size:20pt;">Toggle Master</span></p><p align="center"><span style=" font-size:28pt;">'
142  buttonTextMaster += 'ON' if self.current_status.master.inverter.status else 'OFF'
143  buttonTextMaster += '</span></p></body></html>'
144  self._widget.buttonInverterMaster.setText(buttonTextMaster)
145 
146  # Update colors on Master Inverter Button
147  buttonStyleMaster = 'color: rgb(0, 0, 0);'
148  buttonStyleMaster += 'border-radius: 12px;'
149  buttonStyleMaster += 'padding: 12px;'
150  buttonStyleMaster += 'background-color: rgb(78, 154, 6);' if self.current_status.master.inverter.status else 'background-color: rgb(229, 90, 90);'
151  self._widget.buttonInverterMaster.setStyleSheet(buttonStyleMaster)
152 
153  # Update text on Slave Inverter Button
154  buttonTextSlave = '<html><head/><body><p align="center"><span style=" font-size:20pt;">Toggle Slave</span></p><p align="center"><span style=" font-size:28pt;">'
155  buttonTextSlave += 'ON' if self.current_status.slave[0].inverter.status else 'OFF'
156  buttonTextSlave += '</span></p></body></html>'
157  self._widget.buttonInverterSlave.setText(buttonTextSlave)
158 
159  # Update colors on Slave Inverter Button
160  buttonStyleSlave = 'color: rgb(0, 0, 0);'
161  buttonStyleSlave += 'border-radius: 12px;'
162  buttonStyleSlave += 'padding: 12px;'
163  buttonStyleSlave += 'background-color: rgb(78, 154, 6);' if self.current_status.slave[0].inverter.status else 'background-color: rgb(229, 90, 90);'
164  self._widget.buttonInverterSlave.setStyleSheet(buttonStyleSlave)
165 
166  def update_mode(self):
167  self._widget.radioButtonAuto.setChecked(self.current_status.mode.mode == Mode.AUTO)
168  self._widget.radioButtonManual.setChecked(self.current_status.mode.mode == Mode.MANUAL)
169  self._widget.radioButtonValet.setChecked(self.current_status.mode.mode == Mode.VALET)
170 
171  def click_mode_auto(self):
172  out_msg = Mode()
173  out_msg.mode = Mode.AUTO
174  self.pub_cmd_mode.publish(out_msg)
175 
176  def click_mode_manual(self):
177  out_msg = Mode()
178  out_msg.mode = Mode.MANUAL
179  self.pub_cmd_mode.publish(out_msg)
180 
181  def click_mode_valet(self):
182  out_msg = Mode()
183  out_msg.mode = Mode.VALET
184  self.pub_cmd_mode.publish(out_msg)
185 
186  def recv_status(self, msg):
187  self.current_status = msg
188  self.last_update = time.time()
189 
190  def subscribe_topics(self):
191  sub_status = rospy.Subscriber('/pds/status', Status, self.recv_status)
192 
193  def advertise_topics(self):
194  self.pub_cmd_request = rospy.Publisher('/pds/relay', Relay, queue_size=1)
195  self.pub_cmd_mode = rospy.Publisher('/pds/mode', Mode, queue_size=1)
196  self.pub_cmd_script = rospy.Publisher('/pds/script', Script, queue_size=1)
197 
198  def reset_gui_timer(self):
199  self.gui_update_timer = QTimer(self._widget)
200  self.gui_update_timer.setInterval(100)
201  self.gui_update_timer.setSingleShot(False)
202  self.gui_update_timer.timeout.connect(lambda: self.update_gui_cb())
203  self.gui_update_timer.start()
204 
205  def click_script_stop(self):
206  out_msg = Script()
207  out_msg.script = Script.NONE
208  self.pub_cmd_script.publish(out_msg)
209 
211  out_msg = Script()
212  out_msg.script = Script.STARTUP
213  self.pub_cmd_script.publish(out_msg)
214 
216  out_msg = Script()
217  out_msg.script = Script.SHUTDOWN
218  self.pub_cmd_script.publish(out_msg)
219 
221  out_msg = Relay()
222  # Inverter 1 is Channel 48
223  out_msg.channel = 48
224  out_msg.request = Relay.TOGGLE
225  self.pub_cmd_request.publish(out_msg)
226 
228  out_msg = Relay()
229  # Inverter 2 is Channel 49
230  out_msg.channel = 49
231  out_msg.request = Relay.TOGGLE
232  self.pub_cmd_request.publish(out_msg)
233 
234  def update_gui_cb(self):
235  # Reposition the hovering data label.
236  self._widget.labelNoData.move(
237  self._widget.width()/2 - self._widget.labelNoData.width()/2,
238  self._widget.height()/2 - self._widget.labelNoData.height()/2)
239 
240  if time.time() - self.last_update > 3:
241  # Clear status info if we haven't gotten an update in 3 seoncds.
242  self.current_status = None
243  if self.current_status is None:
244  self._widget.labelNoData.show()
245  return
246  else:
247  self._widget.labelNoData.hide()
250  self.update_mode()
251 
252  def get_size(self, widget):
253  print(str(widget.width()) + "," + str(widget.height()))
254 
255  def spawn_full_gui(self):
256  super(PowerDistributionGui, self).__init__(self.context_)
257  # Give QObjects reasonable names
258  self.setObjectName('PowerDistributionGui')
259 
260  # Create QWidget
261  self._widget = QWidget()
262 
263  # Get path to UI file which should be in the "resource" folder of this package
264  ui_file = os.path.join(rospkg.RosPack().get_path('dataspeed_pds_rqt'), 'resource', 'PowerDistributionGui.ui')
265  # Extend the widget with all attributes and children from UI file
266  loadUi(ui_file, self._widget)
267  # Give QObjects reasonable names
268  self._widget.setObjectName('PowerDistributionGui' + str(self.widget_count))
269  self.widget_count += 1
270  # Add widget to the user interface
271  self.context_.add_widget(self._widget)
272 
273  def spawn_tab_gui(self):
274  super(PowerDistributionGui, self).__init__(self.context_)
275  # Give QObjects reasonable names
276  self.setObjectName('PowerDistributionGui')
277 
278  # Create QWidget
279  self._widget = QWidget()
280 
281  # Get path to UI file which should be in the "resource" folder of this package
282  ui_file = os.path.join(rospkg.RosPack().get_path('dataspeed_pds_rqt'), 'resource', 'PowerDistributionGuiTabs.ui')
283  # Extend the widget with all attributes and children from UI file
284  loadUi(ui_file, self._widget)
285  # Give QObjects reasonable names
286  self._widget.setObjectName('PowerDistributionGui' + str(self.widget_count))
287  self.widget_count += 1
288  # Add widget to the user interface
289  self.context_.add_widget(self._widget)
290 
291  def create_click_channel(self, number):
292  def click_channel():
293  out_msg = Relay()
294  # Indexes 0-23 represent Channels 1-24
295  out_msg.channel = number - 1
296  out_msg.request = Relay.TOGGLE
297  self.pub_cmd_request.publish(out_msg)
298  return click_channel
299 
300  def bind_callbacks(self):
301  clickable(self._widget.buttonInverterMaster).connect(self.click_inverter_master)
302  clickable(self._widget.buttonInverterSlave).connect(self.click_inverter_slave)
303  self._widget.radioButtonAuto.clicked.connect(self.click_mode_auto)
304  self._widget.radioButtonManual.clicked.connect(self.click_mode_manual)
305  self._widget.radioButtonValet.clicked.connect(self.click_mode_valet)
306  self._widget.buttonScriptStop.clicked.connect(self.click_script_stop)
307  self._widget.buttonScriptStartup.clicked.connect(self.click_script_startup)
308  self._widget.buttonScriptShutdown.clicked.connect(self.click_script_shutdown)
309 
310  for index in range(1, 24 + 1):
311  clickable(getattr(self._widget, "buttonChannel{:0>2d}".format(index))).connect(self.create_click_channel(index))
312 
313  @staticmethod
314  def add_arguments(parser):
315  group = parser.add_argument_group('Options for dataspeed_pds_rqt plugin')
316  #group.add_argument('node_name', nargs='*', default=[], help='Node(s) to open automatically')
317 
318  def shutdown_plugin(self):
319  pass
def clickable(widget)
Definition: pds_gui.py:51


dataspeed_pds_rqt
Author(s): Kevin Hallenbeck , Eric Myllyoja
autogenerated on Sat Jul 11 2020 03:09:55