def init_model(title, view): model = QStandardItemModel(view) model.setColumnCount(1) model.setHeaderData(0, Qt.Horizontal, title) return model
class LaunchWidget(QDialog): # To be connected to PluginContainerWidget sig_sysmsg = Signal(str) def __init__(self, parent): """ @type parent: LaunchMain """ super(LaunchWidget, self).__init__() self._parent = parent self._config = None self._settings = QSettings('ros', 'rqt_launch') self._settings.sync() self._package_update = False self._launchfile_update = False # TODO: should be configurable from gui self._port_roscore = 11311 self._run_id = None self._rospack = rospkg.RosPack() ui_file = os.path.join( self._rospack.get_path('rqt_launch'), 'resource', 'launch_widget.ui' ) loadUi(ui_file, self) # row=0 allows any number of rows to be added. self._datamodel = QStandardItemModel(0, 1) master_uri = rosenv.get_master_uri() rospy.loginfo('LaunchWidget master_uri={}'.format(master_uri)) self._delegate = NodeDelegate(master_uri, self._rospack) self._treeview.setModel(self._datamodel) self._treeview.setItemDelegate(self._delegate) # NodeController used in controller class for launch operation. self._node_controllers = [] self._pushbutton_load_params.clicked.connect(self._parent.load_params) self._pushbutton_start_all.clicked.connect(self._parent.start_all) self._pushbutton_stop_all.clicked.connect(self._parent.stop_all) self._pushbutton_refresh.clicked.connect( self._update_pkgs_contain_launchfiles ) # Bind package selection with .launch file selection. self._combobox_pkg.currentIndexChanged[str].connect( self._refresh_launchfiles ) # Bind a launch file selection with launch GUI generation. self._combobox_launchfile_name.currentIndexChanged[str].connect( self._load_launchfile_slot ) self._update_pkgs_contain_launchfiles() def _load_launchfile_slot(self, launchfile_name): # Not yet sure why, but everytime combobox.currentIndexChanged occurs, # this method gets called twice with launchfile_name=='' in 1st call. if ( launchfile_name is None or launchfile_name == '' or self._launchfile_update ): return self._settings.setValue('launchfile_name', launchfile_name) self._settings.sync() _config = None rospy.logdebug( '_load_launchfile_slot launchfile_name={}'.format(launchfile_name) ) try: _config = self._create_launchconfig( launchfile_name, self._port_roscore ) # TODO: folder_name_launchfile should be able to specify arbitrarily # _create_launchconfig takes 3rd arg for it. except IndexError as e: msg = 'IndexError={} launchfile={}'.format(e, launchfile_name) rospy.logerr(msg) self.sig_sysmsg.emit(msg) return except RLException as e: msg = 'RLException={} launchfile={}'.format(e, launchfile_name) rospy.logerr(msg) self.sig_sysmsg.emit(msg) return self._create_widgets_for_launchfile(_config) def _create_launchconfig( self, launchfile_name, port_roscore, folder_name_launchfile='launch' ): """ @rtype: ROSLaunchConfig @raises RLException: raised by roslaunch.config.load_config_default. """ pkg_name = self._combobox_pkg.currentText() try: launchfile = os.path.join( self._rospack.get_path(pkg_name), folder_name_launchfile, launchfile_name, ) except IndexError as e: raise RLException('IndexError: {}'.format(e)) try: launch_config = roslaunch.config.load_config_default( [launchfile], port_roscore ) except rospkg.common.ResourceNotFound as e: raise RLException('ResourceNotFound: {}'.format(e)) except RLException as e: raise e return launch_config def _create_widgets_for_launchfile(self, config): self._config = config # Delete old nodes' GUIs. del self._node_controllers[:] self._delegate.clear_node_widgets() # reset the data model self._datamodel.clear() self._datamodel.setColumnCount(1) self._datamodel.setRowCount(len(self._config.nodes)) # Loop per xml element for i, node in enumerate(self._config.nodes): proxy = NodeProxy(self._run_id, self._config.master.uri, node) nodewidget_index = self._datamodel.index(i, 0, QModelIndex()) node_widget = self._delegate.create_node_widget( nodewidget_index, proxy.config, StatusIndicator() ) # TODO: use tree view delegates correctly instead of # empty QStandardItemModel self._datamodel.setItem(i, QStandardItem()) self._treeview.setIndexWidget(nodewidget_index, node_widget) node_controller = NodeController(proxy, node_widget) self._node_controllers.append(node_controller) rospy.logdebug( 'loop #%d proxy.config.namespace=%s ' + 'proxy.config.name=%s', i, proxy.config.namespace, proxy.config.name, ) self._parent.set_node_controllers(self._node_controllers) def _update_pkgs_contain_launchfiles(self): """ Inspired by rqt_msg.MessageWidget._update_pkgs_contain_launchfiles """ self._package_update = True packages = sorted( [ pkg_tuple[0] for pkg_tuple in RqtRoscommUtil.iterate_packages('launch') ] ) self._package_list = packages rospy.logdebug('pkgs={}'.format(self._package_list)) previous_package = self._settings.value('package', '') self._combobox_pkg.clear() self._combobox_pkg.addItems(self._package_list) if previous_package in self._package_list: index = self._package_list.index(previous_package) else: index = 0 self._package_update = False self._combobox_pkg.setCurrentIndex(index) def _refresh_launchfiles(self, package=None): """ Inspired by rqt_msg.MessageWidget._refresh_msgs """ if package is None or len(package) == 0 or self._package_update: return self._launchfile_update = True previous_launchfile = self._settings.value('launchfile_name', '') self._settings.setValue('package', package) self._settings.sync() self._launchfile_instances = [] # Launch[] # TODO: RqtRoscommUtil.list_files's 2nd arg 'subdir' should NOT be # hardcoded later. _launch_instance_list = RqtRoscommUtil.list_files(package, 'launch') rospy.logdebug( '_refresh_launches package={} instance_list={}'.format( package, _launch_instance_list ) ) self._launchfile_instances = [ x.split('/')[1] for x in _launch_instance_list ] self._combobox_launchfile_name.clear() self._combobox_launchfile_name.addItems(self._launchfile_instances) if previous_launchfile in self._launchfile_instances: index = self._launchfile_instances.index(previous_launchfile) else: index = 0 self._launchfile_update = False self._combobox_launchfile_name.setCurrentIndex(index) def load_parameters(self): """ Loads all global parameters into roscore. """ run_id = ( self._run_id if self._run_id is not None else roslaunch.rlutil.get_or_generate_uuid(None, True) ) runner = roslaunch.ROSLaunchRunner(run_id, self._config) runner._load_parameters() msg = 'Loaded %d parameters to parameter server.' % len( self._config.params ) self.sig_sysmsg.emit(msg) rospy.logdebug(msg) def save_settings(self, plugin_settings, instance_settings): # instance_settings.set_value('splitter', self._splitter.saveState()) pass def restore_settings(self, plugin_settings, instance_settings): # if instance_settings.contains('splitter'): # self._splitter.restoreState(instance_settings.value('splitter')) # else: # self._splitter.setSizes([100, 100, 200]) pass
class ChatbotGUI(Plugin): def __init__(self, context): super(ChatbotGUI, self).__init__(context) self.setObjectName('ChatbotGUI') from argparse import ArgumentParser parser = ArgumentParser() parser.add_argument("-q", "--quiet", action="store_true", dest="quiet", help="Put plugin in silent mode") args, unknowns = parser.parse_known_args(context.argv()) if not args.quiet: print 'arguments: ', args print 'unknowns: ', unknowns self._widget = QWidget() ui_file = os.path.join(rospkg.RosPack().get_path('chatbot_gui'), 'resource', 'ChatbotGUI.ui') loadUi(ui_file, self._widget, {'NavViewWidget': NavViewWidget}) self._widget.setObjectName('ChatbotGUIUi') if context.serial_number() > 1: self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number())) context.add_widget(self._widget) self._widget.pickDone.clicked[bool].connect(self._handle_pick_clicked) self._widget.placeDone.clicked[bool].connect( self._handle_place_clicked) self._widget.textSay.keyPressEvent = self._handle_custom_keypress #ros stuff self.pubPick = rospy.Publisher('picker', String, queue_size=10) self.pubPlace = rospy.Publisher('placer', String, queue_size=10) self.pubRecog = rospy.Publisher('recognition/raw_result', String, queue_size=10) self.subRecog = rospy.Subscriber("recognition/raw_result", String, self._recog_callback) self.subLog = rospy.Subscriber("chatbot_gui/log", String, self._log_callback) self.subStatus = rospy.Subscriber("chatbot_gui/status", String, self._status_callback) self.model = QStandardItemModel() self.model.setColumnCount(2) headerNames = [] headerNames.append("Timestamp") headerNames.append("Message") self.model.setHorizontalHeaderLabels(headerNames) self._widget.tableLog.setModel(self.model) self._widget.tableLog.horizontalHeader().setStretchLastSection(True) self._widget.tableLog.setColumnWidth(0, 170) self._message_limit = 20000 self._message_count = 0 def _add_log(self, data): timestamp = QStandardItem( QDateTime.currentDateTime().toString('d.M.yyyy hh:mm:ss.zzz')) timestamp.setTextAlignment(Qt.AlignRight) timestamp.setEditable(False) message = QStandardItem(data) message.setEditable(False) row = [] row.append(timestamp) row.append(message) self._message_count = self._message_count + 1 self.model.insertRow(0, row) if self._message_count > self._message_limit: self.model.removeRow(self.model.rowCount() - 1) self._message_count = self._message_count - 1 def _handle_pick_clicked(self): self.pubPick.publish("[pick done]") def _handle_place_clicked(self): self.pubPlace.publish("[place done]") def _handle_custom_keypress(self, event): if event.key() == Qt.Key_Return or event.key() == Qt.Key_Enter: self.pubRecog.publish(self._widget.textSay.toPlainText()) self._widget.textSay.setPlainText("") else: QPlainTextEdit.keyPressEvent(self._widget.textSay, event) def _recog_callback(self, data): self._add_log("heard: '" + data.data + "'") def _log_callback(self, data): self._add_log(data.data) def _status_callback(self, data): self._widget.labelStatus.setText(data.data) def shutdown_plugin(self): print("shutdown_plugin: clearing ros publishers.") self.subRecog.unregister() self.subStatus.unregister() self.subLog.unregister() self.pubPick.unregister() self.pubPlace.unregister() self.pubRecog.unregister() pass def save_settings(self, plugin_settings, instance_settings): # TODO save intrinsic configuration, usually using: # instance_settings.set_value(k, v) pass def restore_settings(self, plugin_settings, instance_settings): # TODO restore intrinsic configuration, usually using: # v = instance_settings.value(k) pass