00001
00002
00003 import os
00004
00005 import rospy
00006 import rospkg
00007 import rosparam
00008 import actionlib
00009
00010 from rqt_gui_py.plugin import Plugin
00011 from python_qt_binding import loadUi
00012 from python_qt_binding.QtCore import Qt, Signal, Slot, QSignalMapper, QObject, QAbstractItemModel
00013 from python_qt_binding.QtGui import QAbstractItemView, QWidget, QMenu, QAction, QIcon, QHBoxLayout, QVBoxLayout, QComboBox
00014
00015 from vigir_pluginlib_manager.plugin_tree_model import *
00016 from vigir_pluginlib_msgs.msg import PluginStates, GetPluginDescriptionsAction, GetPluginDescriptionsGoal, GetPluginStatesAction, GetPluginStatesGoal, GetPluginStatesResult, PluginManagementAction, PluginManagementGoal, PluginManagementResult
00017
00018
00019
00020 class PluginManagerDialog(Plugin):
00021
00022 def __init__(self, context):
00023 super(PluginManagerDialog, self).__init__(context)
00024 self.setObjectName('PluginManagerDialog')
00025
00026 self._parent = QWidget()
00027 self._widget = PluginManagerWidget(self._parent)
00028
00029 context.add_widget(self._parent)
00030
00031 def shutdown_plugin(self):
00032 self._widget.shutdown_plugin()
00033
00034
00035
00036 class PluginManagerWidget(QObject):
00037
00038 _NUM_DESC_ATTRIBUTES = 5
00039
00040 plugin_states_updated_signal = Signal(list)
00041
00042 def __init__(self, context):
00043 super(PluginManagerWidget, self).__init__()
00044
00045 self.namespace = '/'
00046 self.plugin_states_update_sub = None
00047 self.load_plugin_set_client = None
00048 self.get_plugin_descriptions_client = None
00049 self.get_plugin_states_client = None
00050 self.add_plugin_client = None
00051 self.remove_plugin_client = None
00052 self.plugin_descriptions = []
00053 self.add_plugin_selection_filter = PluginDescription()
00054
00055
00056 widget = context
00057 vbox = QVBoxLayout()
00058
00059
00060 self.plugin_manager_widget = QWidget()
00061 rp = rospkg.RosPack()
00062 ui_file = os.path.join(rp.get_path('vigir_pluginlib_manager'), 'resource', 'plugin_manager.ui')
00063 loadUi(ui_file, self.plugin_manager_widget, {'QWidget': QWidget})
00064 vbox.addWidget(self.plugin_manager_widget)
00065
00066
00067 icon = QIcon.fromTheme("view-refresh")
00068 self.plugin_manager_widget.refreshAllPushButton.setIcon(icon)
00069 self.plugin_manager_widget.refreshPluginStatesPushButton.setIcon(icon)
00070
00071
00072 tree_view = self.plugin_manager_widget.plugin_tree_view
00073 tree_view.setSelectionMode(QAbstractItemView.ExtendedSelection)
00074
00075 tree_view.setContextMenuPolicy(Qt.CustomContextMenu)
00076 tree_view.customContextMenuRequested.connect(self._open_context_menu)
00077
00078 self.plugin_tree_model = PluginTreeModel()
00079 tree_view.setModel(self.plugin_tree_model)
00080
00081
00082 self.plugin_manager_widget.pluginNameComboBox.setInsertPolicy(QComboBox.NoInsert)
00083
00084
00085 self.plugin_cb = []
00086 self.plugin_cb.append(self.plugin_manager_widget.pluginNameComboBox)
00087 self.plugin_cb.append(self.plugin_manager_widget.pluginTypeClassComboBox)
00088 self.plugin_cb.append(self.plugin_manager_widget.pluginTypePackageComboBox)
00089 self.plugin_cb.append(self.plugin_manager_widget.pluginBaseClassComboBox)
00090 self.plugin_cb.append(self.plugin_manager_widget.pluginBasePackageComboBox)
00091
00092
00093 self.plugin_cb_mapper = QSignalMapper(self)
00094 self.plugin_cb_mapper.mapped.connect(self.add_plugin_selection_changed)
00095
00096
00097 for i in range(len(self.plugin_cb)):
00098 self.plugin_cb_mapper.setMapping(self.plugin_cb[i], i)
00099 self.plugin_cb[i].currentIndexChanged.connect(self.plugin_cb_mapper.map)
00100 self.plugin_manager_widget.namespaceComboBox.currentIndexChanged[str].connect(self.set_namespace)
00101 self.plugin_manager_widget.refreshAllPushButton.clicked[bool].connect(self.search_namespace)
00102 self.plugin_manager_widget.refreshAllPushButton.clicked[bool].connect(self.refresh_plugin_descriptions)
00103 self.plugin_manager_widget.refreshAllPushButton.clicked[bool].connect(self.refresh_plugin_states)
00104 self.plugin_manager_widget.loadPluginSetPushButton.clicked[bool].connect(self.load_plugin_set)
00105 self.plugin_manager_widget.refreshPluginStatesPushButton.clicked[bool].connect(self.refresh_plugin_sets)
00106 self.plugin_manager_widget.refreshPluginStatesPushButton.clicked[bool].connect(self.refresh_plugin_descriptions)
00107 self.plugin_manager_widget.refreshPluginStatesPushButton.clicked[bool].connect(self.refresh_plugin_states)
00108 self.plugin_manager_widget.addPluginPushButton.clicked[bool].connect(self.add_plugin)
00109 self.plugin_manager_widget.clearAddPluginSelectionPushButton.clicked[bool].connect(self.clear_add_plugin_selection)
00110 self.plugin_manager_widget.removePluginsPushButton.clicked[bool].connect(self.remove_plugins)
00111
00112
00113 self.plugin_states_updated_signal.connect(self.update_plugin_tree_view)
00114
00115
00116
00117 widget.setLayout(vbox)
00118
00119
00120
00121 self.search_namespace()
00122
00123 def shutdown_plugin(self):
00124 print 'Shutting down ...'
00125 self.plugin_states_update_sub.unregister()
00126 print 'Done!'
00127
00128 def _open_context_menu(self, position):
00129 indexes = self.plugin_manager_widget.plugin_tree_view.selectedIndexes()
00130 level = -1
00131 if len(indexes) > 0:
00132 level = 0
00133 index = indexes[0]
00134 while index.parent().isValid():
00135 index = index.parent()
00136 level += 1
00137
00138 menu = QMenu()
00139 if level == 0:
00140 expand_action = QAction(self.tr('Expand'), None)
00141 expand_action.triggered.connect(self.plugin_manager_widget.plugin_tree_view.expandAll)
00142 menu.addAction(expand_action)
00143 if level == 0 or level == 1:
00144 remove_action = QAction(self.tr('Remove'), None)
00145 remove_action.triggered.connect(self.remove_plugins)
00146 menu.addAction(remove_action)
00147
00148 menu.exec_(self.plugin_manager_widget.plugin_tree_view.viewport().mapToGlobal(position))
00149
00150 def init_topics(self, namespace):
00151
00152 self.plugin_states_update_sub = rospy.Subscriber(namespace + 'plugin_manager/plugin_states_update', PluginStates, self.plugin_states_update)
00153
00154
00155 self.load_plugin_set_client = actionlib.SimpleActionClient(namespace + 'plugin_manager/load_plugin_set', PluginManagementAction)
00156 self.get_plugin_descriptions_client = actionlib.SimpleActionClient(namespace + 'plugin_manager/get_plugin_descriptions', GetPluginDescriptionsAction)
00157 self.get_plugin_states_client = actionlib.SimpleActionClient(namespace + 'plugin_manager/get_plugin_states', GetPluginStatesAction)
00158 self.add_plugin_client = actionlib.SimpleActionClient(namespace + 'plugin_manager/add_plugin', PluginManagementAction)
00159 self.remove_plugin_client = actionlib.SimpleActionClient(namespace + 'plugin_manager/remove_plugin', PluginManagementAction)
00160
00161 print("Switched to namespace '" + namespace + "'")
00162
00163 def _set_data_in_description(self, description, index, data):
00164 if index == 0:
00165 description.name.data = data
00166 if index == 1:
00167 description.type_class.data = data
00168 if index == 2:
00169 description.type_class_package.data = data
00170 if index == 3:
00171 description.base_class.data = data
00172 if index == 4:
00173 description.base_class_package.data = data
00174 return description
00175
00176 def _get_data_from_description(self, description, index):
00177 if index == 0:
00178 return description.name.data
00179 if index == 1:
00180 return description.type_class.data
00181 if index == 2:
00182 return description.type_class_package.data
00183 if index == 3:
00184 return description.base_class.data
00185 if index == 4:
00186 return description.base_class_package.data
00187
00188 def filter_descriptions(self, filtered_list, description_filter):
00189 result = filtered_list
00190 for i in range(self._NUM_DESC_ATTRIBUTES):
00191 if not self._get_data_from_description(description_filter, i):
00192 continue
00193 result = filter(lambda d: self._get_data_from_description(description_filter, i) == self._get_data_from_description(d, i), result)
00194 return result
00195
00196 @Slot()
00197 def search_namespace(self):
00198 cb = self.plugin_manager_widget.namespaceComboBox
00199 cb.blockSignals(True)
00200 cb.setEnabled(False)
00201 cb.clear()
00202 cb.addItem('Updating...')
00203
00204
00205 _, _, topic_type = rospy.get_master().getTopicTypes()
00206 topic_dict = dict(topic_type)
00207
00208 topic_dict_filtered = dict()
00209 for k, v in topic_dict.items():
00210 if v == 'vigir_pluginlib_msgs/GetPluginStatesActionGoal':
00211 topic_dict_filtered[k] = v
00212
00213
00214 cb.clear()
00215
00216 namespaces = [ns[:-37] for ns in sorted(topic_dict_filtered.keys())]
00217 cb.addItems(namespaces)
00218
00219 if cb.count() > 0:
00220 self.set_namespace(cb.currentText())
00221 cb.setEnabled(True)
00222 cb.blockSignals(False)
00223 else:
00224 cb.addItem('No topics available!')
00225
00226 @Slot(str)
00227 def set_namespace(self, namespace):
00228 self.namespace = namespace
00229 self.init_topics(namespace)
00230 self.refresh_plugin_sets()
00231 self.refresh_plugin_descriptions()
00232 self.refresh_plugin_states()
00233
00234 @Slot()
00235 def refresh_plugin_sets(self):
00236 plugin_sets = []
00237 if rospy.has_param(self.namespace+'/plugin_sets'):
00238 plugin_sets = rospy.get_param(self.namespace+'/plugin_sets').keys()
00239
00240 cb = self.plugin_manager_widget.loadPluginSetComboBox
00241 cb.clear()
00242
00243 if plugin_sets:
00244 cb.addItems(plugin_sets)
00245 cb.setEnabled(True)
00246 self.plugin_manager_widget.loadPluginSetPushButton.setEnabled(True)
00247 else:
00248 cb.setEnabled(False)
00249 self.plugin_manager_widget.loadPluginSetPushButton.setEnabled(False)
00250
00251 @Slot()
00252 def load_plugin_set(self):
00253 if self.load_plugin_set_client.wait_for_server(rospy.Duration(1.0)):
00254
00255 goal = PluginManagementGoal()
00256 goal.name.data = self.plugin_manager_widget.loadPluginSetComboBox.currentText()
00257 self.load_plugin_set_client.send_goal(goal)
00258
00259 @Slot(int)
00260 def add_plugin_selection_changed(self, index):
00261
00262 self._set_data_in_description(self.add_plugin_selection_filter, index, self.plugin_cb[index].currentText())
00263
00264
00265 for cb in self.plugin_cb:
00266 cb.blockSignals(True)
00267
00268
00269 filtered_descriptions = self.filter_descriptions(self.plugin_descriptions, self.add_plugin_selection_filter)
00270
00271 for cb_index in range(self._NUM_DESC_ATTRIBUTES):
00272 if cb_index != index:
00273 rows_enabled = 0
00274 last_enabled_row_index = 0
00275
00276 data = [self._get_data_from_description(d, cb_index) for d in filtered_descriptions]
00277 item_texts = [self.plugin_cb[cb_index].itemText(i) for i in range(self.plugin_cb[cb_index].count())]
00278 for row in range(1, len(item_texts)):
00279 if not item_texts[row] or item_texts[row] in data:
00280 self.plugin_cb[cb_index].setItemData(row, 33, Qt.UserRole - 1)
00281 rows_enabled += 1
00282 last_enabled_row_index = row
00283 else:
00284 self.plugin_cb[cb_index].setItemData(row, 0, Qt.UserRole - 1)
00285
00286
00287 if rows_enabled == 1:
00288 self.plugin_cb[cb_index].setCurrentIndex(last_enabled_row_index)
00289
00290
00291 for cb in self.plugin_cb:
00292 cb.blockSignals(False)
00293
00294 self.plugin_manager_widget.addPluginPushButton.setEnabled(True)
00295
00296 @Slot()
00297 def clear_add_plugin_selection(self):
00298
00299 for cb in self.plugin_cb:
00300 cb.blockSignals(True)
00301
00302 self.plugin_cb[0].clearEditText()
00303 for cb in self.plugin_cb:
00304 cb.setCurrentIndex(0)
00305
00306
00307 self.add_plugin_selection_filter = PluginDescription()
00308 for cb in self.plugin_cb:
00309 for row in range(cb.count()):
00310 cb.setItemData(row, 33, Qt.UserRole - 1)
00311
00312
00313 for cb in self.plugin_cb:
00314 cb.blockSignals(False)
00315
00316 self.plugin_manager_widget.addPluginPushButton.setEnabled(False)
00317
00318 @Slot()
00319 def refresh_plugin_descriptions(self):
00320
00321 self.plugin_descriptions = []
00322
00323 for cb in self.plugin_cb:
00324 cb.blockSignals(True)
00325 cb.clear()
00326
00327 self.plugin_manager_widget.addPluginPushButton.setEnabled(False)
00328
00329
00330 if self.get_plugin_descriptions_client.wait_for_server(rospy.Duration(1.0)):
00331 self.get_plugin_descriptions_client.send_goal(GetPluginDescriptionsGoal())
00332 if self.get_plugin_descriptions_client.wait_for_result(rospy.Duration(5.0)):
00333 self.plugin_descriptions = self.get_plugin_descriptions_client.get_result().descriptions
00334
00335
00336 all_params = rosparam.list_params(self.namespace)
00337 for pname in all_params:
00338
00339 if self.namespace == '/':
00340 pname_sub = pname
00341 else:
00342 pname_sub = pname[len(self.namespace):]
00343 psplit = pname_sub.split('/')
00344
00345
00346 if len(psplit) >= 2 and psplit[1] == 'type_class':
00347 description = PluginDescription()
00348 description.name.data = psplit[0]
00349 description.type_class.data = rospy.get_param(pname)
00350 if rospy.has_param(self.namespace+psplit[0]+'/type_class_package'):
00351 description.type_class_package.data = rospy.get_param(self.namespace+psplit[0]+'/type_class_package')
00352 if rospy.has_param(self.namespace+psplit[0]+'/base_class'):
00353 description.base_class.data = rospy.get_param(self.namespace+psplit[0]+'/base_class')
00354 if rospy.has_param(self.namespace+psplit[0]+'/base_class_package'):
00355 description.base_class_package.data = rospy.get_param(self.namespace+psplit[0]+'/base_class_package')
00356 self.plugin_descriptions.append(description)
00357
00358
00359 description = [[''] for i in range(self._NUM_DESC_ATTRIBUTES)]
00360 for pd in self.plugin_descriptions:
00361 for i in range(self._NUM_DESC_ATTRIBUTES):
00362 description[i].append(self._get_data_from_description(pd, i))
00363
00364
00365 for i in range(len(self.plugin_cb)):
00366 description[i] = sorted(list(set(description[i])))
00367 self.plugin_cb[i].addItems(description[i])
00368
00369 for cb in self.plugin_cb:
00370 cb.blockSignals(False)
00371
00372 @Slot()
00373 def refresh_plugin_states(self):
00374 if self.get_plugin_states_client.wait_for_server(rospy.Duration(1.0)):
00375 self.get_plugin_states_client.send_goal(GetPluginStatesGoal())
00376 if self.get_plugin_states_client.wait_for_result(rospy.Duration(5.0)):
00377 self.plugin_states_updated_signal.emit(self.get_plugin_states_client.get_result().states)
00378
00379 @Slot(PluginStates)
00380 def plugin_states_update(self, plugin_states_msg):
00381 self.plugin_states_updated_signal.emit(plugin_states_msg.states)
00382
00383 @Slot(list)
00384 def update_plugin_tree_view(self, states):
00385 self.plugin_tree_model.updateData(states)
00386
00387
00388
00389
00390
00391 @Slot()
00392 def add_plugin(self):
00393 if self.add_plugin_client.wait_for_server(rospy.Duration(1.0)):
00394
00395 description = PluginDescription()
00396 for i in range(self._NUM_DESC_ATTRIBUTES):
00397 self._set_data_in_description(description, i, self.plugin_cb[i].currentText())
00398
00399
00400 goal = PluginManagementGoal()
00401 goal.descriptions.append(description)
00402 self.add_plugin_client.send_goal(goal)
00403
00404 @Slot()
00405 def remove_plugins(self):
00406 indexes = self.plugin_manager_widget.plugin_tree_view.selectionModel().selectedIndexes()
00407 indexes = filter(lambda index: index.column() == 0, indexes)
00408
00409
00410 descriptions = []
00411 for index in indexes:
00412 descriptions.append(index.internalPointer().getPluginState().description)
00413
00414
00415 if self.remove_plugin_client.wait_for_server(rospy.Duration(1.0)):
00416 goal = PluginManagementGoal()
00417 goal.descriptions = descriptions
00418 self.remove_plugin_client.send_goal(goal)