airbus_cobot_gui_main.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 ################################################################################
3 #
4 # Copyright Airbus Group SAS 2015
5 # All rigths reserved.
6 #
7 # File Name : airbus_cobot_gui_main.py
8 # Authors : Martin Matignon
9 #
10 # If you find any bug or if you have any question please contact
11 # Adolfo Suarez Roos <adolfo.suarez@airbus.com>
12 # Martin Matignon <martin.matignon.external@airbus.com>
13 #
14 #
15 ################################################################################
16 
17 ## @package: airbus_cobot_gui_setup
18 ## @version 4.0
19 ## @author Matignon Martin
20 ## @date Last modified 22/08/2014
21 
22 import rospy
23 import os
24 from roslib.packages import get_pkg_dir
25 from xml.etree import ElementTree
26 
27 from python_qt_binding.QtGui import *
28 from python_qt_binding.QtCore import *
29 
30 from python_qt_binding import loadUi
31 
32 from airbus_pyqt_extend.QtAgiCore import get_pkg_dir_from_prefix
33 
34 from account import User, \
35  Privilege, \
36  LoginDialog, \
37  UserAccountsWidget, \
38  GUserAccountCommunicate
39 
40 from plugin.plugin_provider import PluginProvider, PluginsGroup
41 from widget.widget_provider import WidgetProvider
42 
43 from alarm.alarm import AlarmCategory
45 from pkg_dir import airbus_cobot_gui_dir, resources_dir
46 from exception import CobotGuiException
47 from emergency import EmergencyStopButton, EmergencyStopState
48 # from control_mode import ControlMode
49 from airbus_cobot_gui.control_mode import ControlModeWidget, ControlMode
50 
51 import time
52 
53 from std_msgs.msg import String
54 
55 class CobotGuiSplash(QSplashScreen):
56 
57  def __init__(self):
58  QSplashScreen.__init__(self)
59 
60  ui_file = resources_dir('ui','welcome.ui')
61  # Extend the widget with all attributes and children from UI file
62  loadUi(ui_file, self)
63 
64  background = QPixmap(resources_dir('icons','wellcome_background.png'))
65  background = background.scaled(600, 400,
66  Qt.KeepAspectRatio,
67  Qt.SmoothTransformation)
68  self.setPixmap(background)
69 
70  self.loading_progess.setText("Loading ...")
71 
72  def start(self):
73  self.show()
74  self.showMessage(" ")
75 
76  def update(self, txt):
77  self.loading_progess.setText("Loading %s ..."%txt)
78  self.showMessage(" ")
79 
80 
81 ## @class CobotGuiMain
82 ## @brief Setup all graphics components (window, plugins, widgets).
83 class CobotGuiMain(QWidget):
84  """! CobotGuiMain class inherit QWidget.
85  This class setup all graphics components difinit on your config file:
86  - Setup default rules : Language, size, account, ...
87  - Setup dashboard : load widgets on dashboard registered in section <dashboard>,
88  - Setup launchers : load plugins on launchers registered in section <launcher>,
89  - Setup footer : load widgets on footer registered in section <footer>.
90  """
91 
92  def __init__(self, config_xml, splash):
93  """! The constructor.
94  @param config: Config file (*.xml).
95  """
96 
97  QWidget.__init__(self)
98 
99  self.setAttribute(Qt.WA_AcceptTouchEvents)
100 
101  self._splash = splash
102 
103  self.show_mode = ''
104 
105  #Get path to UI file which is a sibling of this file.
106  ui_file = resources_dir('ui','mainwindow.ui')
107  # Extend the widget with all attributes and children from UI file
108  loadUi(ui_file, self)
109 
110  self._emergency_stop = EmergencyStopButton()
111  self.connect(self._emergency_stop,
112  SIGNAL("emergencyStopStatusChanged"),
114 
115  #Default size of the launch and the dashboard.
116  self._launcher_width = 100
118 
119  #Container plugins instance
120  self._plugins_list = []
122  #Variable to link default plugin in config file
123  self.default_plugin = None
124  #Variable to link current plugin loaded on viewer
125  self._current_plugin = None
126 
127  #Container widgets instance
128  self._widgets_list = []
129 
130  self._default_control_mode = 'auto'
131  self.control_mode_widget = ControlModeWidget()
132  trUtf8.translate.connect(self.control_mode_widget.retranslate)
133 
134  #Parse configuration file from airbus_cobot_gui
135  self._parse_config_xml(config_xml)
136 
137  #Label area from airbus_cobot_gui logo
138  self.logo_label.setFixedSize(self._launcher_width,
139  self._dashboard_height)
140 
141  #Load and display Airbus Group logo
142  logo = QPixmap(resources_dir('icons','logo_airbus_group.png'))
143  logo = logo.scaled(self.logo_label.width()-10,
144  self.logo_label.height()-10,
145  Qt.KeepAspectRatio,
146  Qt.SmoothTransformation)
147  self.logo_label.setPixmap(logo)
148 
149  if self.default_plugin is not None:
150  self.default_plugin._get_launcher().click()
151 
152  if self._default_control_mode in ['automatic', 'auto','-a','--a']:
153  self.control_mode_widget.set_default_mode(ControlMode.AUTOMATIC)
154  elif self._default_control_mode in ['manual', 'manu','-m','--m']:
155  self.control_mode_widget.set_default_mode(ControlMode.MANUAL)
156  else:
157  rospy.logwarn('Unknow default-mode="%s"'%default_mode)
158  self.control_mode_widget.set_default_mode(ControlMode.AUTOMATIC)
159 
160  def _parse_config_xml(self, config_xml):
161  """! Parser xml configuration file.
162  @param config_xml: airbus_cobot_gui configuration path.
163  @type config_xml: string.
164  """
165 
166  #Check validity path
167  if not os.path.isfile(config_xml):
168  raise CobotGuiException('Config file "%s" not found !'%config_xml)
169 
170  #Open and parse xml file
171  tree = ElementTree.parse(config_xml)
172 
173  #Load default language and install traductor
174  language = tree.getroot().find('translate').attrib['type'].lower()
175  lng_dir = resources_dir('translations', language+'.qm')
176  #Check validity path
177  if not os.path.isfile(lng_dir):
178  rospy.logerr('Translator from language "%s" could not be found !'%language)
179  else:
180  #Install translator
181  trUtf8.load(language, lng_dir)
182 
183  #Find node window
184  node_window = tree.getroot().find('window')
185 
186  #Find display mode
187  self.show_mode = node_window.attrib['display-mode'].lower()
188 
189  #Read node window
190  for node in node_window:
191  if node.tag == 'default-size':
192  width = int(node[0].text)
193  height = int(node[1].text)
194  self.resize(width, height)
195  elif node.tag == 'dashboard':
196  self._setup_dashboard(node)
197  elif node.tag == 'launcher':
198  self._setup_launchers(node)
199  elif node.tag == 'footer':
200  self._setup_footer(node)
201  else:
202  rospy.logwarn('Invalid tag name from "%s" !'%node.tag)
203 
204  #Setup connections
207 
208  self.connect(GUserAccountCommunicate,
209  SIGNAL('userAccountChanged'),
211 
212  #Read window mode for start application with debug or release mode
213  application_mode = tree.getroot().attrib['mode'].lower()
214  if application_mode == 'dev' or application_mode == 'debug':
215  GUserAccountCommunicate.update(User('Airbus Group', Privilege.EXPERT))
216  else:
217  # Load default user none -> open login dialog
218  GUserAccountCommunicate.update(User())
219  login = LoginDialog(self)
220  QTimer.singleShot(500, login.show)
221 
223 
224  for widget in self._widgets_list:
225  self.connect(GUserAccountCommunicate,
226  SIGNAL('userAccountChanged'),
227  widget.userChangedEvent)
228 
229  self.connect(self.control_mode_widget,
230  SIGNAL('controlModeChanged'),
231  widget.controlModeChangedEvent)
232 
233  self.connect(self._emergency_stop,
234  SIGNAL("emergencyStopStatusChanged"),
235  widget.emergencyStoppedEvent)
236 
237  trUtf8.translate.connect(widget.retranslateEvent)
238 
240 
241  for plugin in self._plugins_list:
242 
243  self.connect(plugin._launcher,
244  SIGNAL("clicked()"),
246 
247  self.connect(self._emergency_stop,
248  SIGNAL("emergencyStopStatusChanged"),
249  plugin.emergencyStoppedEvent)
250 
251  self.connect(GUserAccountCommunicate,
252  SIGNAL('userAccountChanged'),
253  plugin._update_user)
254 
255  self.connect(self.control_mode_widget,
256  SIGNAL('controlModeChanged'),
257  plugin.controlModeChangedEvent)
258 
259  trUtf8.translate.connect(plugin.retranslateEvent)
260 
261  def _setup_dashboard(self, tree):
262  """! Setup all widgets on dashbord registered on config file.
263  @param tree: node dashbord.
264  @type tree: ElementTree.
265  """
266 
267  #Master layout container
268  central_layout = QHBoxLayout(self.dashboard_widget)
269  central_layout.setContentsMargins(5, 5, 5, 5)
270  central_layout.setSpacing(20)
271 
272  my_board_left = QHBoxLayout()
273  my_board_left.setSpacing(20)
274 
275  central_layout.addLayout(my_board_left)
276 
277  spacer = QSpacerItem(40, 20,
278  QSizePolicy.Expanding,
279  QSizePolicy.Minimum)
280  central_layout.addItem(spacer)
281 
282  my_board_right = QHBoxLayout()
283  my_board_right.setSpacing(20)
284  my_board_left.addWidget(self.control_mode_widget)
285 
286  central_layout.addLayout(my_board_right)
287 
288  for node in tree:
289  if node.tag == 'fixed-height':
290  self._dashboard_height = int(node.text)
291  self.dashboard_widget.setFixedHeight(self._dashboard_height)
292  elif node.tag == 'widgets':
293 
294  register_dir = node.attrib['src']
295  register_dir = get_pkg_dir_from_prefix(register_dir)
296 
297  if not os.path.isfile(register_dir):
298  rospy.logerr('widgets register file "%s" not found !'%register_dir)
299  return
300 
301  widget_provider = WidgetProvider(register_dir)
302 
303  for child in node:
304  if child.tag == 'widget':
305 
306  self._splash.update(child.attrib['name'])
307 
308  try:
309  pkg, xml = widget_provider.get_widget_registered(child.attrib['name'])
310  widget = widget_provider.load(pkg, xml)
311  widget.retranslateEvent()
312  self._widgets_list.append(widget)
313  except Exception as e:
314  rospy.logerr('WidgetProvider::load(%s) raised with exception %s !'
315  %(child.attrib['name'],str(e)))
316  continue
317 
318  if child.attrib['position'] == 'left':
319  my_board_left.addWidget(widget.get_widget())
320  else:
321  my_board_right.addWidget(widget.get_widget())
322 
323 # my_board_left.addWidget(self.control_mode_widget)
324 
325  # Load defaults fixed Widgets on airbus_cobot_gui dashboard
326 
327  my_board_right.addWidget(UserAccountsWidget())
328 
329  from airbus_cobot_gui.translator import TranslatorWidget
330 
331  translator_widget = TranslatorWidget()
332  self._widgets_list.append(translator_widget)
333  my_board_right.addWidget(translator_widget.get_widget())
334 
335  def _setup_launchers(self, tree):
336  """! Setup buttons plugins on launcher.
337  @param tree: node launcher.
338  @type tree: ElementTree.
339  """
340  #Master layout container
341  self._launcher_layout = QVBoxLayout(self.launcher_widget)
342  self._launcher_layout.setContentsMargins(10, 20, 10, 20)
343  self._launcher_layout.setSpacing(20)
344  self._launcher_layout.setSizeConstraint(QLayout.SetMaximumSize)
345 
346  self._default_control_mode = tree.attrib['default-mode'].lower()
347 
348  for node in tree:
349  if node.tag == 'fixed-width':
350  self._launcher_width = int(node.text)
351  self.scroll_area_launcher.setFixedWidth(self._launcher_width)
352  elif node.tag == 'plugins':
353 
354  register_dir = node.attrib['src']
355  register_dir = get_pkg_dir_from_prefix(register_dir)
356 
357  if not os.path.isfile(register_dir):
358  rospy.logerr('Plugins register file "%s" not found !'%register_dir)
359  return
360 
361  plugin_provider = PluginProvider(register_dir)
362 
363  for child in node:
364 
365  if child.tag == 'plugin':
366 
367  self._splash.update(child.attrib['name'])
368 
369  try:
370 
371  plugin = plugin_provider.load(child, child.attrib['name'])
372  plugin.retranslateEvent()
373 
374  if child.attrib['name'] == tree.attrib['default-view']:
375  self.default_plugin = plugin
376 
377  self._plugins_list.append(plugin)
378  self._launcher_layout.addWidget(plugin._get_launcher())
379 
380  except Exception as e:
381  rospy.logerr('Load plugin "%s" raised with execption "%s"'
382  %(child.attrib['name'], str(e)))
383  elif child.tag == 'group':
384 
385  plugins_group = PluginsGroup(self,
386  child.attrib['name'],
387  child.attrib['icon'])
388 
389  for p in child:
390 
391  self._splash.update(p.attrib['name'])
392 
393  try:
394 
395  plugin = plugin_provider.load(p, p.attrib['name'])
396  plugin.retranslateEvent()
397  self._plugins_list.append(plugin)
398  plugins_group.add(plugin._get_launcher())
399 
400  if p.attrib['name'] == tree.attrib['default-view']:
401  self.default_plugin = plugin
402 
403  except Exception as e:
404  rospy.logerr('Load plugin "%s" raised with execption "%s"'
405  %(p.attrib['name'], str(e)))
406 
407  self._plugins_group_list.append(plugins_group)
408  self._launcher_layout.addWidget(plugins_group)
409 
410  icon_size = QSize(self._launcher_width-20,
411  self._launcher_width-20)
412 
413  for plugin in self._plugins_list:
414  launcher_button = plugin._get_launcher()
415  launcher_button.setIconSize(icon_size)
416 
417  for launcher in self._plugins_group_list:
418  launcher.setIconSize(icon_size)
419  launcher.resizeLaunchers(icon_size)
420 
421  spacer = QSpacerItem(20, 10,
422  QSizePolicy.Expanding,
423  QSizePolicy.Expanding)
424  self._launcher_layout.addItem(spacer)
425 
426  self._emergency_stop.setIconSize(icon_size)
427  self._launcher_layout.addWidget(self._emergency_stop)
428 
429  def _get_plugin_sender_id(self, sender_id):
430  """! Find and return plugin selected by user.
431  @param sender_id: launcher id.
432  @type sender_id: String.
433 
434  @return plugin: plugin ui.
435  @type plugin: CobotUiPlugin.
436  """
437 
438  for plugin in self._plugins_list:
439  launcher = plugin._get_launcher()
440  if launcher.objectName() == sender_id:
441  return plugin
442  else:
443  return None
444 
446  """! Display plugin on viewer, function called when user select launcher.
447  """
448 
449  #Close activity
450  if self._current_plugin is not None:
451  self._current_plugin.backgroundEvent()
452 
453  #Find the launcher emit signal for load plugin view
454  b_sender = self.sender()
455  self._current_plugin = self._get_plugin_sender_id(b_sender.objectName())
456 
457  if self._current_plugin is not None:
458  #Clear current plugin on viewer
459  self.viewer_widget.takeWidget()
460  #Load plugin
461  launcher = self._current_plugin._get_launcher()
462 
463  self.viewer_widget.setWidget(self._current_plugin.get_widget())
464 
465  #Start activity
466  self._current_plugin.foregroundEvent()
467 
468  else:
469  rospy.logerr('Invalid launcher id "%s"'%b_sender.objectName())
470 
471  def _setup_footer(self, tree):
472  """! Setup footer.
473  @param tree: node footer.
474  @type tree: ElementTree.
475  """
476 
477  from footer import Footer_v2
478 
479  self.footer_ui = Footer_v2(self)
480 
481  for node in tree:
482  if node.tag == 'maximum-height':
483  self.footer_ui.set_maximum_height(int(node.text))
484  elif node.tag == 'widgets':
485 
486  register_dir = node.attrib['src']
487  register_dir = get_pkg_dir_from_prefix(register_dir)
488 # register_dir = register_dir.replace('${prefix}',airbus_cobot_gui_dir())
489 
490  if not os.path.isfile(register_dir):
491  rospy.logerr('widgets register file "%s" not found !'%register_dir)
492  return
493 
494  widget_provider = WidgetProvider(register_dir)
495 
496  for child in node:
497  if child.tag == 'widget':
498 
499  self._splash.update(child.attrib['name'])
500 
501  pkg, xml = widget_provider.get_widget_registered(child.attrib['name'])
502  widget = widget_provider.load(pkg, xml)
503  widget.retranslateEvent()
504  self._widgets_list.append(widget)
505 
506  self.footer_ui.central_layout.addWidget(widget.get_widget(),
507  int(child.attrib['row']),
508  int(child.attrib['column']),
509  int(child.attrib['row-span']),
510  int(child.attrib['column-span']))
511  try:
512  widget.get_widget().alarm.connect(self.footer_ui.update_alarm)
513  except:
514  pass
515 
516  end_item = self.footer_ui.central_layout.columnCount()
517  spacer = QSpacerItem(20, 20,
518  QSizePolicy.Expanding,
519  QSizePolicy.Minimum)
520  self.footer_ui.central_layout.addItem(spacer, 0, end_item)
521 
522  self.central_layout.addWidget(self.footer_ui, 5, 1)
523 
524 
525  def _take_current_plugin(self, user):
526  """! Take current plugin, called when user changed or disconnected.
527  @param user: user logged informations.
528  @type user: User.
529  """
530  if self._current_plugin is not None:
531  if user.privilege == Privilege.NONE:
532  #{
533  self.viewer_widget.takeWidget()
534  #}
535  elif self._current_plugin.get_access_right() > user.privilege:
536  #{
537  self.viewer_widget.takeWidget()
538  #}
539  else:
540  pass
541  else:
542  pass
543 
544  def emergency_stop_event(self, status):
545  """! Called when emergency stop status changed.
546  @param status: emergency stop status.
547  @type status: bool.
548  """
549  if status == EmergencyStopState.LOCKED:
550  self.dashboard_widget.setStyleSheet("QWidget{background-color: #fed500;}")
551  self.logo_label.setStyleSheet("QWidget{background-color: #fed500;}")
552  else:
553  self.dashboard_widget.setStyleSheet("QWidget{background-color: #d9d9d9;}")
554  self.logo_label.setStyleSheet("QWidget{background-color: #d9d9d9;}")
555 
556  def resizeEvent(self, event):
557  """! Resize application.
558  @param event: event object.
559  @type event: QEvent.
560  """
561  pass
562 
563  def shutdown(self):
564  """! This methode call Plugins::shutdown() and Widgets::shutdown().
565  """
566  rospy.loginfo('Shutdown requested ...')
567  rospy.loginfo(' - Shutdown Plugins :')
568 
569  for plugin in self._plugins_list:
570  plugin.shutdown()
571  rospy.loginfo(" - "+plugin.__class__.__name__+" -> shutting done.")
572 
573  rospy.loginfo(' - Shutdown Widgets :')
574 
575  for widget in self._widgets_list:
576  widget.shutdown()
577  rospy.loginfo(" - "+widget.__class__.__name__+" -> shutting done.")
578 
579  self._emergency_stop.shutdown()
580 
581  rospy.loginfo('Shutting done.')
582 
583 #End of file
584 
def _setup_launchers
Setup buttons plugins on launcher.
def emergency_stop_event
Called when emergency stop status changed.
def _load_plugin_on_viewer
Display plugin on viewer, function called when user select launcher.
def _get_plugin_sender_id
Find and return plugin selected by user.
def _take_current_plugin
Take current plugin, called when user changed or disconnected.
def _setup_dashboard
Setup all widgets on dashbord registered on config file.
def shutdown
This methode call Plugins::shutdown() and Widgets::shutdown().


airbus_cobot_gui
Author(s):
autogenerated on Thu Dec 17 2015 11:42:05