Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import rospy
00019 import uuid
00020 import os
00021 import sys
00022
00023 import __builtin__
00024 import traceback
00025 from xml.etree import ElementTree
00026 from roslib.packages import get_pkg_dir
00027
00028 from python_qt_binding.QtGui import *
00029 from python_qt_binding.QtCore import *
00030
00031 from airbus_pyqt_extend.QtAgiCore import QAgiPackages, get_pkg_dir_from_prefix
00032 from airbus_pyqt_extend.QtAgiGui import QAgiPopup
00033
00034 from airbus_cobot_gui.util import Parameters, CobotGuiException
00035
00036
00037
00038
00039
00040
00041
00042 class DashboardProvider:
00043
00044 """
00045 PluginProvider interacts with ros plugin package. The first is its
00046 import plugin, and the second is the set plugin configuration which
00047 it reads.
00048 """
00049
00050 DASHBOARD_SOURCES_LOCATION = 'src'
00051
00052 def __init__(self, parent, xml_register_dir):
00053 """! The constructor."""
00054
00055 self._context = parent.getContext()
00056
00057
00058 if not os.path.isfile(xml_register_dir):
00059 raise CobotGuiException('Dashboard register file "%s" in package "airbus_cobot_gui" not found'
00060 %(xml_register_dir))
00061
00062
00063 try:
00064 self._dashboard_register = ElementTree.parse(xml_register_dir)
00065 except Exception as e:
00066 raise CobotGuiException(str(e))
00067
00068 def getPkgByName(self, name):
00069
00070 root = self._dashboard_register.getroot()
00071
00072
00073 dashboard_desc = root.find('./dashboard[@label="%s"]'%name)
00074
00075 if dashboard_desc is None:
00076 raise CobotGuiException('Cannot foud package from dashboard named "%s"'%name)
00077
00078 return dashboard_desc.attrib['package']
00079
00080 def getInstance(self, dashboard_name, dashboard_node=None):
00081 """! Load Python package.
00082 @param descriptor: package descriptor xml node.
00083 @type descriptor: Element.
00084
00085 @param uuid: dashboard id.
00086 @type uuid: string.
00087
00088 @return dashboard_instance: dashboard instance.
00089 @type dashboard_instance: Dashboard.
00090 """
00091
00092 dashboard_pkg_name = self.getPkgByName(dashboard_name)
00093
00094 dashboard_dir = get_pkg_dir(dashboard_pkg_name)
00095
00096 dashboard_descriptor_file = os.path.join(dashboard_dir,"dashboard_descriptor.xml")
00097
00098 if not os.path.isfile(dashboard_descriptor_file):
00099 self._context.getLogger().err('Cannot found dashboard_descriptor.xml into plugin %s'%dashboard_name)
00100 return None
00101
00102 dashboard_descriptor_root = ElementTree.parse(dashboard_descriptor_file).getroot()
00103
00104 dashboard_import = dashboard_descriptor_root.find('import')
00105
00106 dashboard_module_path = dashboard_import.attrib['module']
00107 dashboard_class_name = dashboard_import.attrib['class']
00108
00109 sys.path.append(os.path.join(dashboard_dir,self.DASHBOARD_SOURCES_LOCATION))
00110
00111 dashboard_class_ref = None
00112
00113
00114 try:
00115 module = __builtin__.__import__(dashboard_module_path,
00116 fromlist=[dashboard_class_name],
00117 level=0)
00118
00119 except Exception as ex:
00120 self._context.getLogger().err("Cannot import plugin '%s' !\n%s"%(dashboard_name, str(ex)))
00121 return None
00122
00123
00124 dashboard_class_ref = getattr(module, dashboard_class_name)
00125
00126 if dashboard_class_ref is None:
00127 self._context.getLogger().err("Cannot found plugin class '%s' !"%dashboard_class_name)
00128 return None
00129
00130 dashboard_instance = dashboard_class_ref(self._context)
00131
00132 dashboard_params = DashboardProvider.getParameters(dashboard_descriptor_root, dashboard_node)
00133
00134 dashboard_instance.setup(dashboard_descriptor_root, dashboard_params)
00135
00136 return dashboard_instance
00137
00138 @staticmethod
00139 def getParameters(dashboard_descriptor, dashboard_node):
00140
00141 parameters = Parameters()
00142
00143
00144 descriptor_params = dashboard_descriptor.find("setup/parameters")
00145
00146
00147 if descriptor_params is not None:
00148 for param in descriptor_params:
00149
00150 parameters.putParam(param.attrib['name'], param.attrib['value'])
00151
00152 if dashboard_node is not None:
00153
00154 if dashboard_node.find("param") is not None:
00155
00156 for param in dashboard_node.iter('param'):
00157
00158 parameters.putParam(param.attrib['name'], param.attrib['value'])
00159
00160 return parameters
00161
00162
00163 if __name__ == "__main__":
00164
00165 from python_qt_binding.QtGui import *
00166 from python_qt_binding.QtCore import *
00167 from airbus_cobot_gui.context import Context
00168
00169 rospy.init_node('dashboard_privider_test')
00170
00171 a = QApplication(sys.argv)
00172 utt_appli = QMainWindow()
00173
00174 context = Context(utt_appli)
00175
00176 provider = DashboardProvider(context, "/opt/ros/indigo/workspace/src/gui/dashboard/dashboard_register.xml")
00177
00178 dashboard = provider.getDashboardInstance("IIWA")
00179
00180 utt_appli.setCentralWidget(dashboard)
00181
00182 plugin.onStart()
00183
00184 utt_appli.show()
00185 a.exec_()
00186
00187
00188
00189
00190