1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33 from python_qt_binding import loadUi
34 from python_qt_binding.QtCore import QRegExp, Qt, Signal
35 from python_qt_binding.QtGui import QKeySequence
36 from rosgraph.names import is_legal_name
37 import getpass
38 import os
39 import re
40 import roslib
41 import rospy
42 import socket
43 import sys
44 import time
45 import traceback
46 import uuid
47 import xmlrpclib
48
49 from master_discovery_fkie.common import get_hostname
50 from master_discovery_fkie.master_info import NodeInfo
51 from node_manager_fkie.common import masteruri_from_ros, get_packages, package_name, resolve_paths
52 from node_manager_fkie.default_cfg_handler import DefaultConfigHandler
53 from node_manager_fkie.detailed_msg_box import WarningMessageBox, DetailedError
54 from node_manager_fkie.html_delegate import HTMLDelegate
55 from node_manager_fkie.launch_config import LaunchConfig
56 from node_manager_fkie.launch_server_handler import LaunchServerHandler
57 from node_manager_fkie.node_tree_model import NodeTreeModel, NodeItem, GroupItem, HostItem
58 from node_manager_fkie.parameter_dialog import ParameterDialog, MasterParameterDialog, ServiceDialog
59 from node_manager_fkie.parameter_handler import ParameterHandler
60 from node_manager_fkie.parameter_list_model import ParameterModel, ParameterNameItem, ParameterValueItem
61 from node_manager_fkie.progress_queue import ProgressQueue, InteractionNeededError
62 from node_manager_fkie.select_dialog import SelectDialog
63 from node_manager_fkie.service_list_model import ServiceModel, ServiceItem
64 from node_manager_fkie.start_handler import AdvRunCfg
65 from node_manager_fkie.supervised_popen import SupervisedPopen
66 from node_manager_fkie.topic_list_model import TopicModel, TopicItem
67 import node_manager_fkie as nm
68 try:
69 from python_qt_binding.QtGui import QAction, QFileDialog, QMenu, QMessageBox, QShortcut, QWidget
70 from python_qt_binding.QtGui import QApplication, QVBoxLayout
71 except:
72 from python_qt_binding.QtWidgets import QAction, QFileDialog, QMenu, QMessageBox, QShortcut, QWidget
73 from python_qt_binding.QtWidgets import QApplication, QVBoxLayout
74
75
76 try:
77 from python_qt_binding.QtGui import QItemSelection, QItemSelectionModel, QItemSelectionRange, QSortFilterProxyModel
78 except:
79 from python_qt_binding.QtCore import QItemSelection, QItemSelectionModel, QItemSelectionRange, QSortFilterProxyModel
83 ''' Request needed to set the args of a launchfile from another thread.
84 @param args: a dictionary with args and values
85 @type args: dict
86 @param error: an error description
87 @type error: str
88 '''
89
90 - def __init__(self, launchfile, args, error):
91 Exception.__init__(self)
92 self.launchfile = launchfile
93 self.args_dict = args
94 self.error = error
95
97 return "LaunchArgsSelectionRequest for " + str(self.args_dict) + "::" + repr(self.error)
98
101 '''
102 This class stores the informations about a ROS master and shows it on request.
103 '''
104
105 updateHostRequest = Signal(str)
106 host_description_updated = Signal(str, str, str)
107 '''@ivar: the signal is emitted on description changes and contains the
108 ROS Master URI, host address and description a parameter.'''
109
110 capabilities_update_signal = Signal(str, str, str, list)
111 '''@ivar: the signal is emitted if a description with capabilities is received
112 and has the ROS master URI, host address, the name of the default_cfg node and a list with
113 descriptions (U{multimaster_msgs_fkie.srv.ListDescription<http://docs.ros.org/api/multimaster_msgs_fkie/html/srv/ListDescription.html>} Response) as parameter.'''
114 remove_config_signal = Signal(str)
115 '''@ivar: the signal is emitted if a default_cfg was removed'''
116
117 description_signal = Signal(str, str, bool)
118 '''@ivar: the signal is emitted to show a description (title, description)'''
119
120 request_xml_editor = Signal(list, str)
121 '''@ivar: the signal to open a xml editor dialog (list with files, search text)'''
122
123 stop_nodes_signal = Signal(str, list)
124 '''@ivar: the signal is emitted to stop on masteruri the nodes described in the list.'''
125
126 robot_icon_updated = Signal(str, str)
127 '''@ivar: the signal is emitted, if the robot icon was changed by a configuration (masteruri, path)'''
128
129 loaded_config = Signal(str, object)
130 '''@ivar: the signal is emitted, after a launchfile is successful loaded (launchfile, LaunchConfig)'''
131
132 DIAGNOSTIC_LEVELS = {0: 'OK',
133 1: 'WARN',
134 2: 'ERROR',
135 3: 'STALE',
136 4: 'UNKNOWN',
137 5: 'UNKNOWN'}
138
139 - def __init__(self, masteruri, parent=None):
140 '''
141 Creates a new master.
142 @param masteruri: the URI of the ROS master
143 @type masteruri: C{str}
144 '''
145 QWidget.__init__(self, parent)
146 self.setObjectName(' - '.join(['MasterViewProxy', masteruri]))
147 self.masteruri = masteruri
148 self.mastername = masteruri
149 try:
150 self.mastername = get_hostname(self.masteruri)
151 except:
152 pass
153 self.__current_path = os.path.expanduser('~')
154
155 self._tmpObjects = []
156 self.__master_state = None
157 self.__master_info = None
158 self.__force_update = False
159 self.__configs = dict()
160
161 self.__in_question = []
162
163 '''@ivar: stored the question dialogs for changed files '''
164 self._stop_ignores = ['rosout', rospy.get_name(), 'node_manager', 'master_discovery', 'master_sync', 'default_cfg', 'zeroconf']
165 ''' @todo: detect the names of master_discovery and master_sync ndoes'''
166
167 self.__echo_topics_dialogs = dict()
168 '''@ivar: stores the open EchoDialogs '''
169 self.__last_info_text = None
170 self.__use_sim_time = False
171 self.__current_user = nm.settings().host_user(self.mastername)
172 self.__robot_icons = []
173 self.__current_robot_icon = None
174 self.__current_parameter_robot_icon = ''
175 self.__republish_params = {}
176 self.__last_selection = 0
177 self._on_stop_kill_roscore = False
178 self._on_stop_poweroff = False
179
180 self.__running_nodes = dict()
181 self.default_cfg_handler = DefaultConfigHandler()
182 self.default_cfg_handler.node_list_signal.connect(self.on_default_cfg_nodes_retrieved)
183 self.default_cfg_handler.description_signal.connect(self.on_default_cfg_descr_retrieved)
184 self.default_cfg_handler.err_signal.connect(self.on_default_cfg_err)
185
186 self.__launch_servers = {}
187 self.launch_server_handler = LaunchServerHandler()
188 self.launch_server_handler.launch_server_signal.connect(self.on_launch_server_retrieved)
189 self.launch_server_handler.error_signal.connect(self.on_launch_server_err)
190
191 self.masterTab = QWidget()
192 ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'MasterTab.ui')
193 loadUi(ui_file, self.masterTab)
194 tabLayout = QVBoxLayout(self)
195 tabLayout.setContentsMargins(0, 0, 0, 0)
196 tabLayout.addWidget(self.masterTab)
197 self._progress_queue = ProgressQueue(self.masterTab.progressFrame, self.masterTab.progressBar, self.masterTab.progressCancelButton)
198
199
200 self.node_tree_model = NodeTreeModel(nm.nameres().address(self.masteruri), self.masteruri)
201 self.node_proxy_model = NodesSortFilterProxyModel(self)
202 self.node_proxy_model.setSourceModel(self.node_tree_model)
203 self.masterTab.nodeTreeView.setModel(self.node_proxy_model)
204 self.node_tree_model.hostInserted.connect(self.on_host_inserted)
205 for i, (_, width) in enumerate(NodeTreeModel.header):
206 self.masterTab.nodeTreeView.setColumnWidth(i, width)
207 self.nodeNameDelegate = HTMLDelegate()
208 self.masterTab.nodeTreeView.setItemDelegateForColumn(0, self.nodeNameDelegate)
209 self.masterTab.nodeTreeView.collapsed.connect(self.on_node_collapsed)
210 self.masterTab.nodeTreeView.expanded.connect(self.on_node_expanded)
211 sm = self.masterTab.nodeTreeView.selectionModel()
212 sm.selectionChanged.connect(self.on_node_selection_changed)
213 self.masterTab.nodeTreeView.activated.connect(self.on_node_activated)
214 self.masterTab.nodeTreeView.clicked.connect(self.on_node_clicked)
215
216
217
218
219 self.topic_model = TopicModel()
220 self.topic_proxyModel = TopicsSortFilterProxyModel(self)
221 self.topic_proxyModel.setSourceModel(self.topic_model)
222 self.masterTab.topicsView.setModel(self.topic_proxyModel)
223
224 for i, (_, width) in enumerate(TopicModel.header):
225 self.masterTab.topicsView.setColumnWidth(i, width)
226 self.topicNameDelegate = HTMLDelegate()
227 self.topicTypeDelegate = HTMLDelegate()
228 self.masterTab.topicsView.setItemDelegateForColumn(0, self.topicNameDelegate)
229 self.masterTab.topicsView.setItemDelegateForColumn(3, self.topicTypeDelegate)
230 sm = self.masterTab.topicsView.selectionModel()
231 sm.selectionChanged.connect(self.on_topic_selection_changed)
232 self.masterTab.topicsView.activated.connect(self.on_topic_activated)
233 self.masterTab.topicsView.clicked.connect(self.on_topic_clicked)
234 self.masterTab.topicsView.setSortingEnabled(True)
235
236
237 self.service_model = ServiceModel()
238 self.service_proxyModel = ServicesSortFilterProxyModel(self)
239 self.service_proxyModel.setSourceModel(self.service_model)
240 self.masterTab.servicesView.setModel(self.service_proxyModel)
241 for i, (_, width) in enumerate(ServiceModel.header):
242 self.masterTab.servicesView.setColumnWidth(i, width)
243 self.serviceNameDelegate = HTMLDelegate()
244 self.serviceTypeDelegate = HTMLDelegate()
245 self.masterTab.servicesView.setItemDelegateForColumn(0, self.serviceNameDelegate)
246 self.masterTab.servicesView.setItemDelegateForColumn(1, self.serviceTypeDelegate)
247 sm = self.masterTab.servicesView.selectionModel()
248 sm.selectionChanged.connect(self.on_service_selection_changed)
249 self.masterTab.servicesView.activated.connect(self.on_service_activated)
250 self.masterTab.servicesView.clicked.connect(self.on_service_clicked)
251 self.masterTab.servicesView.setSortingEnabled(True)
252
253
254 self.parameter_model = ParameterModel()
255 self.parameter_model.itemChanged.connect(self._on_parameter_item_changed)
256 self.parameter_proxyModel = ParameterSortFilterProxyModel(self)
257 self.parameter_proxyModel.setSourceModel(self.parameter_model)
258 self.masterTab.parameterView.setModel(self.parameter_proxyModel)
259 for i, (_, width) in enumerate(ParameterModel.header):
260 self.masterTab.parameterView.setColumnWidth(i, width)
261 self.parameterNameDelegate = HTMLDelegate()
262 self.masterTab.parameterView.setItemDelegateForColumn(0, self.parameterNameDelegate)
263 sm = self.masterTab.parameterView.selectionModel()
264 sm.selectionChanged.connect(self.on_parameter_selection_changed)
265 self.masterTab.parameterView.setSortingEnabled(True)
266
267
268
269
270
271 self.masterTab.startButton.clicked.connect(self.on_start_clicked)
272 self.masterTab.stopButton.clicked.connect(self.on_stop_clicked)
273
274 self.masterTab.ioButton.clicked.connect(self.on_io_clicked)
275 self.masterTab.logButton.clicked.connect(self.on_log_clicked)
276 self.masterTab.logDeleteButton.clicked.connect(self.on_log_delete_clicked)
277 self.masterTab.dynamicConfigButton.clicked.connect(self.on_dynamic_config_clicked)
278 self.masterTab.editConfigButton.clicked.connect(self.on_edit_config_clicked)
279 self.masterTab.editRosParamButton.clicked.connect(self.on_edit_rosparam_clicked)
280 self.masterTab.saveButton.clicked.connect(self.on_save_clicked)
281 self.masterTab.closeCfgButton.clicked.connect(self.on_close_clicked)
282
283 self.masterTab.echoTopicButton.clicked.connect(self.on_topic_echo_clicked)
284 self.masterTab.hzTopicButton.clicked.connect(self.on_topic_hz_clicked)
285 self.masterTab.hzSshTopicButton.clicked.connect(self.on_topic_hz_ssh_clicked)
286 self.masterTab.pubTopicButton.clicked.connect(self.on_topic_pub_clicked)
287 self.masterTab.pubStopTopicButton.clicked.connect(self.on_topic_pub_stop_clicked)
288
289 self.masterTab.callServiceButton.clicked.connect(self.on_service_call_clicked)
290 self.masterTab.nodeFilterInput.textChanged.connect(self.on_node_filter_changed)
291 self.masterTab.topicFilterInput.textChanged.connect(self.on_topic_filter_changed)
292 self.masterTab.serviceFilterInput.textChanged.connect(self.on_service_filter_changed)
293 self.masterTab.parameterFilterInput.textChanged.connect(self.on_parameter_filter_changed)
294 self.masterTab.getParameterButton.clicked.connect(self.on_get_parameter_clicked)
295 self.masterTab.addParameterButton.clicked.connect(self.on_add_parameter_clicked)
296 self.masterTab.deleteParameterButton.clicked.connect(self.on_delete_parameter_clicked)
297 self.masterTab.saveParameterButton.clicked.connect(self.on_save_parameter_clicked)
298
299
300 self.parameterHandler = ParameterHandler()
301 self.parameterHandler.parameter_list_signal.connect(self._on_param_list)
302 self.parameterHandler.parameter_values_signal.connect(self._on_param_values)
303 self.parameterHandler.delivery_result_signal.connect(self._on_delivered_values)
304
305 self.parameterHandler_sim = ParameterHandler()
306
307 self.parameterHandler_sim.parameter_values_signal.connect(self._on_sim_param_values)
308
309
310 self._shortcut_kill_node = QShortcut(QKeySequence(self.tr("Ctrl+Backspace", "Kill selected node")), self)
311 self._shortcut_kill_node.activated.connect(self.on_kill_nodes)
312 self._shortcut_kill_node = QShortcut(QKeySequence(self.tr("Ctrl+Delete", "Removes the registration of selected nodes from ROS master")), self)
313 self._shortcut_kill_node.activated.connect(self.on_unregister_nodes)
314
315 self.masterTab.ioButton.setEnabled(True)
316 self.masterTab.tabWidget.currentChanged.connect(self.on_tab_current_changed)
317 self._shortcut_screen_show_all = QShortcut(QKeySequence(self.tr("Shift+S", "Show all available screens")), self)
318 self._shortcut_screen_show_all.activated.connect(self.on_show_all_screens)
319 self._shortcut_screen_kill = QShortcut(QKeySequence(self.tr("Shift+Backspace", "Kill Screen")), self)
320 self._shortcut_screen_kill.activated.connect(self.on_kill_screens)
321
322 self.loaded_config.connect(self._apply_launch_config)
323
324
325 self._shortcut1 = QShortcut(QKeySequence(self.tr("Alt+1", "Select first group")), self)
326 self._shortcut1.activated.connect(self.on_shortcut1_activated)
327 self._shortcut2 = QShortcut(QKeySequence(self.tr("Alt+2", "Select second group")), self)
328 self._shortcut2.activated.connect(self.on_shortcut2_activated)
329 self._shortcut3 = QShortcut(QKeySequence(self.tr("Alt+3", "Select third group")), self)
330 self._shortcut3.activated.connect(self.on_shortcut3_activated)
331 self._shortcut4 = QShortcut(QKeySequence(self.tr("Alt+4", "Select fourth group")), self)
332 self._shortcut4.activated.connect(self.on_shortcut4_activated)
333 self._shortcut5 = QShortcut(QKeySequence(self.tr("Alt+5", "Select fifth group")), self)
334 self._shortcut5.activated.connect(self.on_shortcut5_activated)
335
336 self._shortcut_collapse_all = QShortcut(QKeySequence(self.tr("Alt+C", "Collapse all groups")), self)
337 self._shortcut_collapse_all.activated.connect(self.on_shortcut_collapse_all)
338 self._shortcut_expand_all = QShortcut(QKeySequence(self.tr("Alt+E", "Expand all groups")), self)
339 self._shortcut_expand_all.activated.connect(self.masterTab.nodeTreeView.expandAll)
340 self._shortcut_run = QShortcut(QKeySequence(self.tr("Alt+R", "run selected nodes")), self)
341 self._shortcut_run.activated.connect(self.on_start_clicked)
342 self._shortcut_stop = QShortcut(QKeySequence(self.tr("Alt+S", "stop selected nodes")), self)
343 self._shortcut_stop.activated.connect(self.on_stop_clicked)
344
345 self._shortcut_copy = QShortcut(QKeySequence(self.tr("Ctrl+C", "copy selected values to clipboard")), self)
346 self._shortcut_copy.activated.connect(self.on_copy_c_pressed)
347 self._shortcut_copy = QShortcut(QKeySequence(self.tr("Ctrl+X", "copy selected alternative values to clipboard")), self)
348 self._shortcut_copy.activated.connect(self.on_copy_x_pressed)
349
350
351
352
353
354
355
356
357
358
359
360
374
375 @property
377 return self.__current_user
378
379 @current_user.setter
383
384 @property
387
388 @property
390 return self.__master_state
391
392 @master_state.setter
395
396 @property
398 return self.__master_info
399
400 @master_info.setter
402 '''
403 Sets the new master information. To determine whether a node is running the
404 PID and his URI are needed. The PID of remote nodes (host of the ROS master
405 and the node are different) will be not determine by discovering. Thus this
406 information must be obtain from other MasterInfo object and stored while
407 updating.
408 @param master_info: the mater information object
409 @type master_info: U{master_discovery_fkie.msg.MasterInfo<http://docs.ros.org/kinetic/api/master_discovery_fkie/html/modules.html#module-master_discovery_fkie.master_info>}
410 '''
411 try:
412 update_result = (set(), set(), set(), set(), set(), set(), set(), set(), set())
413 if self.__master_info is None:
414 if (master_info.masteruri == self.masteruri):
415 self.__master_info = master_info
416 update_result[0].update(self.__master_info.node_names)
417 update_result[3].update(self.__master_info.topic_names)
418 update_result[6].update(self.__master_info.service_names)
419 else:
420 update_result = self.__master_info.updateInfo(master_info)
421
422
423 if self.__master_info is None:
424 return
425 try:
426 if (master_info.masteruri == self.masteruri):
427 self.update_system_parameter()
428
429 hosts2update = set([get_hostname(self.__master_info.getNode(nodename).uri) for nodename in update_result[0]])
430 hosts2update.update([get_hostname(self.__master_info.getService(nodename).uri) for nodename in update_result[6]])
431 for host in hosts2update:
432 if host != get_hostname(self.masteruri):
433 self.updateHostRequest.emit(host)
434 except:
435 pass
436
437
438
439 if update_result[0] or update_result[1] or update_result[2] or self.__force_update:
440 self.updateRunningNodesInModel(self.__master_info)
441 self.on_node_selection_changed(None, None)
442
443 if update_result[3] or update_result[4] or update_result[5] or self.__force_update:
444 self.topic_model.updateModelData(self.__master_info.topics, update_result[3], update_result[4], update_result[5])
445 self.on_topic_selection_changed(None, None)
446
447 if update_result[6] or update_result[7] or update_result[8] or self.__force_update:
448 self.service_model.updateModelData(self.__master_info.services, update_result[6], update_result[7], update_result[8])
449 self.on_service_selection_changed(None, None)
450
451 self.updateDefaultConfigs(self.__master_info)
452 self.__force_update = False
453
454
455
456 except:
457 print traceback.format_exc(1)
458
459 @property
461 return self.__use_sim_time
462
464 return self._progress_queue.count() > 0
465
467 self.__force_update = True
468
471
473 '''
474 Marks all nodes, which are not running and in a given list as a duplicates nodes.
475 @param running_nodes: The list with names of running nodes
476 @type running_nodes: C{[str]}
477 '''
478
479 self.__running_nodes = running_nodes
480 self.node_tree_model.markNodesAsDuplicateOf(running_nodes, (self.master_info is not None and self.master_info.getNodeEndsWith('master_sync')))
481
483 '''
484 Returns the list with all running nodes, which are registered by this ROS
485 master. Also the nodes, which are physically running on remote hosts.
486 @return: The list with names of running nodes
487 @rtype: C{[str]}
488 '''
489 if self.master_info is not None and self.master_info.getNodeEndsWith('master_sync'):
490 return self.master_info.node_names
491 return []
492
494 '''
495 Returns the list with all running nodes, which are running (has process) on this host.
496 The nodes registered on this ROS master, but running on remote hosts are not
497 returned.
498 @return: The dictionary with names of running nodes and their masteruri
499 @rtype: C{dict(str:str)}
500 '''
501 result = dict()
502 if self.master_info is not None:
503 for _, node in self.master_info.nodes.items():
504 if node.isLocal:
505 if not remove_system_nodes or not self._is_in_ignore_list(node.name):
506 result[node.name] = self.master_info.masteruri
507 return result
508
510 '''
511 Creates the dictionary with ExtendedNodeInfo objects and updates the nodes view.
512 @param master_info: the mater information object
513 @type master_info: U{master_discovery_fkie.msg.MasterInfo<http://docs.ros.org/kinetic/api/master_discovery_fkie/html/modules.html#module-master_discovery_fkie.master_info>}
514 '''
515 if master_info is not None:
516 self.node_tree_model.updateModelData(master_info.nodes)
517 self.updateButtons()
518
520 '''
521 @param node_name: The name of the node.
522 @type node_name: str
523 @return: The list the nodes with given name.
524 @rtype: []
525 '''
526 return self.node_tree_model.getNode("%s" % node_name, self.masteruri)
527
567
568
570 '''
571 @param path: the launch file
572 @type path: C{str}
573 @return: C{True} if the given launch file is open
574 @rtype: C{boolean}
575 '''
576 return path in self.launchfiles
577
578 @property
580 '''
581 Returns the copy of the dictionary with default configurations on this host
582 @rtype: C{[str(ROS node name)]}
583 '''
584 result = []
585 for (c, _) in self.__configs.items():
586 if isinstance(c, tuple):
587 result.append(c[0])
588 return result
589
590 @property
592 '''
593 Returns the copy of the dictionary with loaded launch files on this host
594 @rtype: C{dict(str(file) : L{LaunchConfig}, ...)}
595 '''
596 result = dict()
597 for (c, cfg) in self.__configs.items():
598 if not isinstance(c, tuple):
599 result[c] = cfg
600 return result
601
602 @launchfiles.setter
604 '''
605 Loads the launch file. If this file is already loaded, it will be reloaded.
606 After successful load the node view will be updated.
607 @param launchfile: the launch file path
608 @type launchfile: C{str}
609 '''
610 self._progress_queue.add2queue(str(uuid.uuid4()),
611 'Loading %s' % os.path.basename(launchfile),
612 self._load_launchfile,
613 (launchfile,))
614 self._progress_queue.start()
615
617 '''
618 This method will be called in another thread. The configuration parameter
619 of the launch file will be requested using `LaunchArgsSelectionRequest` and
620 `InteractionNeededError`. After the file is successful loaded a
621 `loaded_config` signal will be emitted.
622 '''
623 stored_argv = None
624 if launchfile in self.__configs:
625
626 stored_argv = self.__configs[launchfile].argv
627
628 try:
629
630 launchConfig = LaunchConfig(launchfile, masteruri=self.masteruri)
631 loaded = False
632
633 if stored_argv is None:
634 if argv_forced:
635
636 loaded = launchConfig.load(argv_forced)
637 else:
638
639 req_args = launchConfig.getArgs()
640 if req_args:
641 params = dict()
642 arg_dict = launchConfig.argvToDict(req_args)
643 for arg in arg_dict.keys():
644 params[arg] = ('string', [arg_dict[arg]])
645
646 req = LaunchArgsSelectionRequest(launchfile, params, 'Needs input for args')
647 raise nm.InteractionNeededError(req, self._load_launchfile, (launchfile,))
648
649 if not loaded or stored_argv is not None:
650 launchConfig.load(req_args if stored_argv is None else stored_argv)
651
652 for _, machine in launchConfig.Roscfg.machines.items():
653 if machine.name:
654 nm.nameres().add_info(machine.name, machine.address)
655
656 if self._progress_queue.has_id(pqid):
657 self.loaded_config.emit(launchfile, launchConfig)
658 except InteractionNeededError:
659 raise
660 except Exception as e:
661 err_text = ''.join([os.path.basename(launchfile), ' loading failed!'])
662 err_details = ''.join([err_text, '\n\n', e.__class__.__name__, ": ", str(e)])
663 rospy.logwarn("Loading launch file: %s", err_details)
664 raise DetailedError("Loading launch file", err_text, err_details)
665
666 except:
667 print traceback.format_exc(1)
668
670 stored_roscfg = None
671 expanded_items = None
672 if launchfile in self.__configs:
673
674 expanded_items = self._get_expanded_groups()
675
676 self.removeConfigFromModel(launchfile)
677 stored_roscfg = self.__configs[launchfile].Roscfg
678 del self.__configs[launchfile]
679 try:
680
681 self.__configs[launchfile] = launchConfig
682 self.appendConfigToModel(launchfile, launchConfig.Roscfg)
683 self.masterTab.tabWidget.setCurrentIndex(0)
684
685 try:
686 robot_descr = launchConfig.getRobotDescr()
687 capabilities = launchConfig.getCapabilitiesDesrc()
688 for (host, caps) in capabilities.items():
689 if not host:
690 host = nm.nameres().mastername(self.masteruri)
691 host_addr = nm.nameres().address(host)
692 self.node_tree_model.addCapabilities(nm.nameres().masteruri(host), host_addr, launchfile, caps)
693 for (host, descr) in robot_descr.items():
694 if not host:
695 host = nm.nameres().mastername(self.masteruri)
696 host_addr = nm.nameres().address(host)
697 tooltip = self.node_tree_model.updateHostDescription(nm.nameres().masteruri(host), host_addr, descr['type'], descr['name'], descr['description'])
698 self.host_description_updated.emit(self.masteruri, host_addr, tooltip)
699 except:
700 print traceback.format_exc(1)
701
702
703 self.updateRunningNodesInModel(self.__master_info)
704
705
706 if stored_roscfg and self.__configs[launchfile].Roscfg:
707 stored_values = [(name, str(p.value)) for name, p in stored_roscfg.params.items()]
708 new_values = [(name, str(p.value)) for name, p in self.__configs[launchfile].Roscfg.params.items()]
709
710 paramset = set(name for name, _ in (set(new_values) - set(stored_values)))
711
712 paramset |= (set(self.__configs[launchfile].Roscfg.params.keys()) - set(stored_roscfg.params.keys()))
713
714 paramset |= (set(stored_roscfg.params.keys()) - set(self.__configs[launchfile].Roscfg.params.keys()))
715
716 stored_nodes = [roslib.names.ns_join(item.namespace, item.name) for item in stored_roscfg.nodes]
717 new_nodes = [roslib.names.ns_join(item.namespace, item.name) for item in self.__configs[launchfile].Roscfg.nodes]
718 nodes2start = set(new_nodes) - set(stored_nodes)
719
720 for p in paramset:
721 for n in new_nodes:
722 if p.startswith(n):
723 nodes2start.add(n)
724
725 for n in stored_roscfg.nodes:
726 for new_n in self.__configs[launchfile].Roscfg.nodes:
727 if n.name == new_n.name and n.namespace == new_n.namespace:
728 if n.args != new_n.args or n.remap_args != new_n.remap_args:
729 nodes2start.add(roslib.names.ns_join(n.namespace, n.name))
730
731 nodes2start = [n for n in nodes2start if not re.search(r"\d{3,6}_\d{10,}", n)]
732
733 if nodes2start:
734 restart, ok = SelectDialog.getValue('Restart nodes?', "Select nodes to restart <b>@%s</b>:" % self.mastername, nodes2start, False, True, '', self)
735 if ok:
736 self.stop_nodes_by_name(restart)
737 self.start_nodes_by_name(restart, launchfile, True)
738
739 if launchfile in self.__robot_icons:
740 self.__robot_icons.remove(launchfile)
741 self.__robot_icons.insert(0, launchfile)
742 self.markNodesAsDuplicateOf(self.__running_nodes)
743
744 if expanded_items is not None:
745 self._expand_groups(expanded_items)
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766 except Exception as e:
767 err_text = ''.join([os.path.basename(launchfile), ' loading failed!'])
768 err_details = ''.join([err_text, '\n\n', e.__class__.__name__, ": ", str(e)])
769 rospy.logwarn("Loading launch file: %s", err_details)
770 WarningMessageBox(QMessageBox.Warning, "Loading launch file", err_text, err_details).exec_()
771 except:
772 print traceback.format_exc(1)
773 self.update_robot_icon(True)
774
781
783 '''
784 Returns a list of group names, which are expanded.
785 '''
786 result = []
787 try:
788 for r in range(self.masterTab.nodeTreeView.model().rowCount()):
789 index_host = self.masterTab.nodeTreeView.model().index(r, 0)
790 if index_host.isValid() and self.masterTab.nodeTreeView.isExpanded(index_host):
791 if self.masterTab.nodeTreeView.model().hasChildren(index_host):
792 for c in range(self.masterTab.nodeTreeView.model().rowCount(index_host)):
793 index_cap = self.masterTab.nodeTreeView.model().index(c, 0, index_host)
794 if index_cap.isValid() and self.masterTab.nodeTreeView.isExpanded(index_cap):
795 model_index = self.node_proxy_model.mapToSource(index_cap)
796 item = self.node_tree_model.itemFromIndex(model_index)
797 if isinstance(item, (GroupItem, HostItem)):
798 result.append(item.name)
799 except:
800 print traceback.format_exc(1)
801 return result
802
804 '''
805 Expands all groups, which are in the given list. If no list is given,
806 expands all groups of expanded hosts.
807 '''
808 try:
809 for r in range(self.masterTab.nodeTreeView.model().rowCount()):
810 index_host = self.masterTab.nodeTreeView.model().index(r, 0)
811 if index_host.isValid() and self.masterTab.nodeTreeView.isExpanded(index_host):
812 if self.masterTab.nodeTreeView.model().hasChildren(index_host):
813 for c in range(self.masterTab.nodeTreeView.model().rowCount(index_host)):
814 index_cap = self.masterTab.nodeTreeView.model().index(c, 0, index_host)
815 if index_cap.isValid():
816 model_index = self.node_proxy_model.mapToSource(index_cap)
817 item = self.node_tree_model.itemFromIndex(model_index)
818 if isinstance(item, (GroupItem, HostItem)):
819 if groups is None or item.name in groups:
820 self.masterTab.nodeTreeView.setExpanded(index_cap, True)
821 except:
822 print traceback.format_exc(1)
823
825 '''
826 Update the current robot icon. If the icon was changed a `robot_icon_updated`
827 signal will be emitted.
828 :return: the path to the current robot icon
829 :rtype: str
830 '''
831 for l in self.__robot_icons:
832 try:
833 icon = self.__configs[l].get_robot_icon()
834 if icon:
835 if icon != self.__current_robot_icon or force:
836 self.__current_robot_icon = icon
837 self.robot_icon_updated.emit(self.masteruri, icon)
838 return icon
839 except:
840 pass
841 self.__current_robot_icon = self.__current_parameter_robot_icon
842 self.robot_icon_updated.emit(self.masteruri, str(self.__current_robot_icon))
843 return self.__current_robot_icon
844
846 '''
847 Update the node view
848 @param launchfile: the launch file path
849 @type launchfile: C{str}
850 @param rosconfig: the configuration
851 @type rosconfig: L{LaunchConfig}
852 '''
853 hosts = dict()
854 for n in rosconfig.nodes:
855 addr = nm.nameres().address(self.masteruri)
856 masteruri = self.masteruri
857 if n.machine_name and not n.machine_name == 'localhost':
858 if n.machine_name not in rosconfig.machines:
859 raise Exception(''.join(["ERROR: unknown machine [", n.machine_name, "]"]))
860 addr = rosconfig.machines[n.machine_name].address
861 masteruri = nm.nameres().masteruri(n.machine_name)
862 node = roslib.names.ns_join(n.namespace, n.name)
863 if (masteruri, addr) not in hosts:
864 hosts[(masteruri, addr)] = dict()
865 hosts[(masteruri, addr)][node] = launchfile
866
867 for ((masteruri, addr), nodes) in hosts.items():
868 self.node_tree_model.appendConfigNodes(masteruri, addr, nodes)
869 self.updateButtons()
870
881
883 '''
884 Updates the default configuration view based on the current master information.
885 @param master_info: the mater information object
886 @type master_info: U{master_discovery_fkie.msg.MasterInfo<http://docs.ros.org/kinetic/api/master_discovery_fkie/html/modules.html#module-master_discovery_fkie.master_info>}
887 '''
888 if self.__master_info is None:
889 return
890 default_cfgs = []
891 for name in self.__master_info.service_names:
892 if name.endswith('list_nodes'):
893 srv = self.__master_info.getService(name)
894 default_cfgs.append((roslib.names.namespace(name).rstrip(roslib.names.SEP), srv.uri, srv.masteruri))
895
896 removed = list(set([c for c in self.__configs.keys() if isinstance(c, tuple)]) - set(default_cfgs))
897 if removed:
898 for r in removed:
899 self.node_tree_model.removeConfigNodes(r)
900
901 if r[2] == self.masteruri:
902 self.remove_config_signal.emit(r[0])
903 del self.__configs[r]
904 if len(self.__configs) == 0:
905 address = nm.nameres().address(master_info.masteruri)
906 tooltip = self.node_tree_model.updateHostDescription(master_info.masteruri, address, '', '', '')
907 self.host_description_updated.emit(master_info.masteruri, address, tooltip)
908
909 added = list(set(default_cfgs) - set(self.__configs.keys()))
910 for (name, uri, _) in added:
911 self.default_cfg_handler.requestNodeList(uri, roslib.names.ns_join(name, 'list_nodes'))
912
913 descr_service = self.__master_info.getService(roslib.names.ns_join(name, 'description'))
914 if descr_service is not None:
915 self.default_cfg_handler.requestDescriptionList(descr_service.uri, descr_service.name)
916 self.updateButtons()
917
919 '''
920 Handles the new list with nodes from default configuration service.
921 @param service_uri: the URI of the service provided the default configuration
922 @type service_uri: C{str}
923 @param config_name: the name of default configuration service
924 @type config_name: C{str}
925 @param nodes: the name of the nodes with name spaces
926 @type nodes: C{[str]}
927 '''
928
929 masteruri = self.masteruri
930 if self.__master_info is not None:
931 service = self.__master_info.getService(config_name)
932 if service is not None:
933 masteruri = service.masteruri
934 key = (roslib.names.namespace(config_name).rstrip(roslib.names.SEP), service_uri, masteruri)
935
936
937
938 node_cfgs = dict()
939 for n in nodes:
940 node_cfgs[n] = key
941 host = get_hostname(service_uri)
942 host_addr = nm.nameres().address(host)
943 if host_addr is None:
944 host_addr = host
945 self.node_tree_model.appendConfigNodes(masteruri, host_addr, node_cfgs)
946 self.__configs[key] = nodes
947 self.updateButtons()
948
950 '''
951 Handles the description list from default configuration service.
952 Emits a Qt signal L{host_description_updated} to notify about a new host
953 description and a Qt signal L{capabilities_update_signal} to notify about a capabilities
954 update.
955 @param service_uri: the URI of the service provided the default configuration
956 @type service_uri: C{str}
957 @param config_name: the name of default configuration service
958 @type config_name: C{str}
959 @param items: list with descriptions
960 @type items: C{[U{multimaster_msgs_fkie.srv.ListDescription<http://docs.ros.org/api/multimaster_msgs_fkie/html/srv/ListDescription.html>} Response]}
961 '''
962 if items:
963 masteruri = self.masteruri
964 if self.__master_info is not None:
965 service = self.__master_info.getService(config_name)
966 if service is not None:
967 masteruri = service.masteruri
968 key = (roslib.names.namespace(config_name).rstrip(roslib.names.SEP), service_uri, masteruri)
969 host = get_hostname(service_uri)
970 host_addr = nm.nameres().address(host)
971
972 caps = dict()
973 for c in items[0].capabilities:
974 if c.namespace not in caps:
975 caps[c.namespace] = dict()
976 caps[c.namespace][c.name.decode(sys.getfilesystemencoding())] = {'type': c.type, 'images': [resolve_paths(i) for i in c.images], 'description': resolve_paths(c.description.replace("\\n ", "\n").decode(sys.getfilesystemencoding())), 'nodes': list(c.nodes)}
977 if host_addr is None:
978 host_addr = get_hostname(key[1])
979 self.node_tree_model.addCapabilities(masteruri, host_addr, key, caps)
980
981 tooltip = self.node_tree_model.updateHostDescription(masteruri, host_addr, items[0].robot_type, items[0].robot_name.decode(sys.getfilesystemencoding()), resolve_paths(items[0].robot_descr.decode(sys.getfilesystemencoding())))
982 self.host_description_updated.emit(masteruri, host_addr, tooltip)
983 self.capabilities_update_signal.emit(masteruri, host_addr, roslib.names.namespace(config_name).rstrip(roslib.names.SEP), items)
984
986 '''
987 Handles the error messages from default configuration service.
988 @param service_uri: the URI of the service provided the default configuration
989 @type service_uri: C{str}
990 @param service: the name of default configuration service
991 @type service: C{str}
992 @param msg: the error message
993 @type msg: C{str}
994 '''
995 pass
996
997
998
999
1000 @property
1002 return self.__launch_servers
1003
1005 '''
1006 Returns `True` if the there are roslaunch server, which have no `master` as
1007 node or or have other nodes as `rosout-#` inside.
1008 '''
1009 for _, (_, nodes) in self.__launch_servers.items():
1010 if not self._is_master_launch_server(nodes):
1011 return True
1012 return False
1013
1015 if 'master' in nodes and len(nodes) < 3:
1016 return True
1017 return False
1018
1020 '''
1021 Handles the info about roslaunch server.
1022 Emits a Qt signal L{host_description_updated} to notify about a new host
1023 description and a Qt signal L{capabilities_update_signal} to notify about a capabilities
1024 update.
1025 @param serveruri: the URI of the roslaunch server
1026 @type serveruri: C{str}
1027 @param pid: the process id of the roslaunch server
1028 @type pid: C{str}
1029 @param nodes: list with nodes handled by the roslaunch server
1030 @type nodes: C{[L{str}]}
1031 '''
1032 self.__launch_servers[serveruri] = (pid, nodes)
1033
1035 '''
1036 Handles the error messages from launch server hanlder.
1037 @param serveruri: the URI of the launch server
1038 @type serveruri: C{str}
1039 @param msg: the error message
1040 @type msg: C{str}
1041 '''
1042 try:
1043 del self.__launch_servers[serveruri]
1044 except:
1045 pass
1046
1048 '''
1049 Kill all running launch server. The coresponding URIS are removed by master_monitor.
1050 '''
1051 for lsuri, (pid, nodes) in self.__launch_servers.items():
1052 try:
1053 if not self._is_master_launch_server(nodes):
1054 self._progress_queue.add2queue(str(uuid.uuid4()),
1055 ''.join(['kill roslaunch ', lsuri, '(', str(pid), ')']),
1056 nm.starter().kill,
1057 (get_hostname(lsuri), pid, False, self.current_user))
1058 self.launch_server_handler.updateLaunchServerInfo(lsuri, delayed_exec=3.0)
1059 except Exception as e:
1060 rospy.logwarn("Error while kill roslaunch %s: %s", str(lsuri), str(e))
1061 raise DetailedError("Kill error",
1062 ''.join(['Error while kill roslaunch ', lsuri]),
1063 str(e))
1064 self._progress_queue.start()
1065
1066
1067
1068
1069
1071 '''
1072 Depending of the state of the node, it will be run or the screen output will
1073 be open.
1074 @param index: The index of the activated node
1075 @type index: U{QtCore.QModelIndex<https://srinikom.github.io/pyside-docs/PySide/QtCore/QModelIndex.html>}
1076 '''
1077 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes(), False)
1078 if not selectedNodes:
1079 return
1080 has_running = False
1081 has_stopped = False
1082 has_invalid = False
1083 for node in selectedNodes:
1084 if node.uri is not None:
1085 has_running = True
1086 if node.pid is None:
1087 has_invalid = True
1088 else:
1089 has_stopped = True
1090
1091 if has_stopped:
1092 self.on_start_clicked()
1093 elif has_running and not has_invalid:
1094 self.on_io_clicked()
1095 else:
1096 self.on_log_clicked()
1097
1101
1103 '''
1104 @param index: The index of the activated topic
1105 @type index: U{QtCore.QModelIndex<https://srinikom.github.io/pyside-docs/PySide/QtCore/QModelIndex.html>}
1106 '''
1107 self.on_topic_echo_clicked()
1108
1112
1114 '''
1115 @param index: The index of the activated service
1116 @type index: U{QtCore.QModelIndex<https://srinikom.github.io/pyside-docs/PySide/QtCore/QModelIndex.html>}
1117 '''
1118 self.on_service_call_clicked()
1119
1123
1125 if item == (self.masteruri, get_hostname(self.masteruri)):
1126 index = self.node_tree_model.indexFromItem(item)
1127 model_index = self.node_proxy_model.mapFromSource(index)
1128 if model_index.isValid():
1129 self.masterTab.nodeTreeView.expand(model_index)
1130
1131
1133 if not index.parent().isValid():
1134 self.masterTab.nodeTreeView.selectionModel().clear()
1135
1138
1140 '''
1141 :param list_type: LAUNCH, TOPIC, NODE, SERVICE
1142 :type list_type: str
1143 '''
1144 result = ''
1145 if items:
1146 result = '%s<b><u>%s</u></b>' % (result, title)
1147 if len(items) > 1:
1148 result = '%s <span style="color:gray;">[%d]</span>' % (result, len(items))
1149 result = '%s<br><ul><span></span>' % result
1150 items.sort()
1151 for i in items:
1152 item = i
1153
1154 item_name = i
1155 if name:
1156 item_name = item_name.replace('%s%s' % (name, roslib.names.SEP), '~', 1)
1157 ns = roslib.names.namespace(name)
1158 if item_name.startswith(ns) and ns != roslib.names.SEP:
1159 item_name = item_name.replace(ns, '', 1)
1160 if list_type in ['NODE']:
1161 item = '<a href="node://%s%s">%s</a>' % (self.mastername, i, item_name)
1162 elif list_type in ['TOPIC_PUB', 'TOPIC_SUB']:
1163
1164 count = None
1165 try:
1166 tpc = self.__master_info.getTopic(i)
1167 if list_type == 'TOPIC_SUB':
1168 count = len(tpc.publisherNodes)
1169 if name not in tpc.subscriberNodes:
1170 count = None
1171 else:
1172 count = len(tpc.subscriberNodes)
1173 if name not in tpc.publisherNodes:
1174 count = None
1175 except:
1176 pass
1177
1178 if count is not None:
1179 item = '<a href="topic://%s">%s</a>' % (i, item_name)
1180 item += ' <a href="topicecho://%s%s"><span style="color:gray;"><i>echo</i></span></a>' % (self.mastername, i)
1181 item = '<span style="color:gray;">_%d_/ </span>%s' % (count, item)
1182 else:
1183 item = '<a>%s</a>' % (item_name)
1184 item = '<span style="color:red;">!sync </span>%s' % (item)
1185 elif list_type == 'SERVICE':
1186 try:
1187 srv = self.__master_info.getService(i)
1188 if name in srv.serviceProvider:
1189 item = '<a href="service://%s%s">%s</a>' % (self.mastername, i, item_name)
1190 item += ' <a href="servicecall://%s%s"><span style="color:gray;"><i>call</i></span></a>' % (self.mastername, i)
1191 else:
1192 item = '<span style="color:red;">!sync </span>%s' % (item_name)
1193 except:
1194 item = '<span style="color:red;">!sync </span>%s' % (item_name)
1195 elif list_type == 'LAUNCH':
1196 item = '<a href="launch://%s">%s</a>' % (i, item_name)
1197 if i in self.__configs and self.masteruri in self.__configs[i].global_param_done:
1198 item += '%s<br><a href="reload-globals://%s"><font color="#339900">reload global parameter @next start</font></a>' % (item, i)
1199 result += '\n%s<br>' % (item)
1200 result += '</ul>'
1201 return result
1202
1204 if self.masterTab.tabWidget.tabText(index) == 'Topics':
1205
1206 selections = self.masterTab.nodeTreeView.selectionModel().selectedIndexes()
1207 selectedNodes = self.nodesFromIndexes(selections)
1208 if len(selectedNodes) == 1:
1209 node = selectedNodes[0]
1210 selected_topics = self.topic_model.index_from_names(node.published, node.subscribed)
1211 for s in selected_topics:
1212 self.masterTab.topicsView.selectionModel().select(self.topic_proxyModel.mapFromSource(s), QItemSelectionModel.Select)
1213 elif self.masterTab.tabWidget.tabText(index) == 'Services':
1214
1215 selections = self.masterTab.nodeTreeView.selectionModel().selectedIndexes()
1216 selectedNodes = self.nodesFromIndexes(selections)
1217 if len(selectedNodes) == 1:
1218 node = selectedNodes[0]
1219 selected_services = self.service_model.index_from_names(node.services)
1220 for s in selected_services:
1221 self.masterTab.servicesView.selectionModel().select(self.service_proxyModel.mapFromSource(s), QItemSelectionModel.Select)
1222
1224 '''
1225 updates the Buttons, create a description and emit L{description_signal} to
1226 show the description of host, group or node.
1227 '''
1228 if selected is not None:
1229
1230 self.__last_selection = time.time()
1231 selectedGroups = []
1232 if node_name and self.master_info is not None:
1233
1234 selectedNodes = self.getNode(node_name)
1235 if not selectedNodes or selectedNodes[0] is None:
1236 if node_name:
1237 self.description_signal.emit(node_name, "<b>%s</b> not found" % node_name, True if selected or deselected or force_emit else False)
1238 return
1239 selectedHosts = []
1240 selections = []
1241 else:
1242
1243 if self.masterTab.tabWidget.tabText(self.masterTab.tabWidget.currentIndex()) != 'Nodes':
1244 return
1245 selections = self.masterTab.nodeTreeView.selectionModel().selectedIndexes()
1246 selectedHosts = self.hostsFromIndexes(selections)
1247 selectedNodes = self.nodesFromIndexes(selections)
1248 selectedGroups = self.groupsFromIndexes(selections)
1249 self.masterTab.topicsView.selectionModel().clear()
1250 self.masterTab.servicesView.selectionModel().clear()
1251 name = ''
1252 text = ''
1253
1254 if len(selectedNodes) > 1 or selectedGroups > 0:
1255 restartable_nodes = [sn for sn in selectedNodes if len(sn.cfgs) > 0 and not self._is_in_ignore_list(sn.name)]
1256 restartable_nodes_with_launchfiles = [sn for sn in selectedNodes if sn.has_launch_cfgs(sn.cfgs) > 0 and not self._is_in_ignore_list(sn.name)]
1257 killable_nodes = [sn for sn in selectedNodes if sn.node_info.pid is not None and not self._is_in_ignore_list(sn.name)]
1258 unregisterble_nodes = [sn for sn in selectedNodes if sn.node_info.pid is None and sn.node_info.uri is not None and sn.node_info.isLocal and not self._is_in_ignore_list(sn.name)]
1259
1260 if restartable_nodes or killable_nodes or unregisterble_nodes:
1261 text += '<b>Selected nodes:</b><br>'
1262 if restartable_nodes:
1263 text += '<a href="restart-node://all_selected_nodes" title="Restart %s selected nodes"><img src=":icons/sekkyumu_restart_24.png" alt="restart">[%d]</a>' % (len(restartable_nodes), len(restartable_nodes))
1264 if killable_nodes:
1265 text += ' <a href="kill-node://all_selected_nodes" title="Kill %s selected nodes"><img src=":icons/sekkyumu_kill_24.png" alt="kill">[%d]</a>' % (len(killable_nodes), len(killable_nodes))
1266 text += ' <a href="kill-screen://all_selected_nodes" title="Kill %s screens of selected nodes"><img src=":icons/sekkyumu_kill_screen_24.png" alt="killscreen">[%d]</a>' % (len(killable_nodes), len(killable_nodes))
1267 if restartable_nodes_with_launchfiles:
1268 text += ' <a href="start-node-at-host://all_selected_nodes" title="Start %s nodes at another host"><img src=":icons/sekkyumu_start_athost_24.png" alt="start@host">[%d]</a>' % (len(restartable_nodes_with_launchfiles), len(restartable_nodes_with_launchfiles))
1269 text += ' <a href="start-node-adv://all_selected_nodes" title="Start %s nodes with additional options, e.g. loglevel"><img src=":icons/sekkyumu_play_alt_24.png" alt="play alt">[%d]</a>' % (len(restartable_nodes_with_launchfiles), len(restartable_nodes_with_launchfiles))
1270 if unregisterble_nodes:
1271 text += '<br><a href="unregister-node://all_selected_nodes">unregister [%d]</a>' % len(unregisterble_nodes)
1272
1273 if len(selectedHosts) == 1:
1274 host = selectedHosts[0]
1275 name = '%s - Robot' % host.name
1276 text += host.generateDescription()
1277 text += '<br>'
1278 else:
1279
1280 if len(selectedGroups) == 1 and len(selections) / 2 == 1:
1281 group = selectedGroups[0]
1282 name = '%s - Group' % group.name
1283 text += group.generateDescription()
1284 text += '<br>'
1285
1286 if len(selectedHosts) != 1 and len(selectedNodes) == 1 and len(selectedGroups) == 0:
1287 node = selectedNodes[0]
1288 text = self.get_node_description(node_name, node)
1289 name = node.name
1290 current_tab = self.masterTab.tabWidget.tabText(self.masterTab.tabWidget.currentIndex())
1291 if (current_tab == 'Nodes' and self.__last_info_text != text) or force_emit:
1292 self.__last_info_text = text
1293 self.description_signal.emit(name, text, True if selected or deselected or force_emit else False)
1294 self.updateButtons()
1295
1297 text = ''
1298 if node_name and node is None and self.master_info is not None:
1299
1300 selectedNodes = self.getNode(node_name)
1301 if len(selectedNodes) == 1:
1302 node = selectedNodes[0]
1303
1304 if node is not None:
1305
1306 ns, sep, name = node.name.rpartition(rospy.names.SEP)
1307 text = '<font size="+1"><b><span style="color:gray;">%s%s</span><b>%s</b></font><br>' % (ns, sep, name)
1308 launches = [c for c in node.cfgs if not isinstance(c, tuple)]
1309 default_cfgs = [c[0] for c in node.cfgs if isinstance(c, tuple)]
1310 if launches or default_cfgs:
1311 text += '<a href="restart-node://%s" title="Restart node"><img src=":icons/sekkyumu_restart_24.png" alt="restart"></a>' % node.name
1312 text += ' <a href="kill-node://%s" title="Kill node with pid %s"><img src=":icons/sekkyumu_kill_24.png" alt="kill"></a>' % (node.name, node.pid)
1313 text += ' <a href="kill-screen://%s" title="Kill screen of the node"><img src=":icons/sekkyumu_kill_screen_24.png" alt="killscreen"></a>' % node.name
1314 if launches:
1315 text += ' <a href="start-node-at-host://%s" title="Start node at another host"><img src=":icons/sekkyumu_start_athost_24.png" alt="start@host"></a>' % node.name
1316
1317 text += ' <a href="start-node-adv://%s" title="Start node with additional options, e.g. loglevel"><img src=":icons/sekkyumu_play_alt_24.png" alt="play alt"></a>' % node.name
1318 text += ' <a href="copy-log-path://%s" title="copy log path to clipboard"><img src=":icons/crystal_clear_copy_log_path_24.png" alt="copy_log_path"></a>' % node.name
1319 text += '<dl>'
1320 text += '<dt><b>URI</b>: %s</dt>' % node.node_info.uri
1321 text += '<dt><b>PID</b>: %s</dt>' % node.node_info.pid
1322 text += '<dt><b>ORG.MASTERURI</b>: %s</dt>' % node.node_info.masteruri
1323 if not is_legal_name(node.name):
1324 text += '<dt><font color="#FF6600"><b>This node has an illegal <node> name.<br><a href="http://ros.org/wiki/Names">http://ros.org/wiki/Names</a><br>This will likely cause problems with other ROS tools.</b></font></dt>'
1325 if node.is_ghost:
1326 if node.name.endswith('master_sync') or node.name.endswith('node_manager'):
1327 text += '<dt><font color="#FF9900"><b>This node is not synchronized by default. To get info about this node select the related host.</b></font></dt>'
1328 else:
1329 text += '<dt><font color="#FF9900"><b>The node is running on remote host, but is not synchronized, because of filter or errors while sync, see log of <i>master_sync</i></b></font></dt>'
1330 text += '<dt><font color="#FF9900"><i>Are you use the same ROS packages?</i></font></dt>'
1331 if node.has_running and node.node_info.pid is None and node.node_info.uri is None:
1332 text += '<dt><font color="#FF9900"><b>There are nodes with the same name on remote hosts running. These will be terminated, if you run this node! (Only if master_sync is running or will be started somewhere!)</b></font></dt>'
1333 if node.node_info.uri is not None and node.node_info.masteruri != self.masteruri:
1334 text += '<dt><font color="#339900"><b>synchronized</b></font></dt>'
1335 if node.node_info.pid is None and node.node_info.uri is not None:
1336 if not node.node_info.isLocal:
1337 text += '<dt><font color="#FF9900"><b>remote nodes will not be ping, so they are always marked running</b></font>'
1338 else:
1339 text += '<dt><font color="#CC0000"><b>the node does not respond: </b></font>'
1340 text += '<a href="unregister-node://%s">unregister</a></dt>' % node.name
1341 if node.diagnostic_array and node.diagnostic_array[-1].level > 0:
1342 diag_status = node.diagnostic_array[-1]
1343 level_str = self.DIAGNOSTIC_LEVELS[diag_status.level]
1344 diag_color = '#FF6600'
1345 if diag_status.level == 2:
1346 diag_color = '#CC0000'
1347 elif diag_status.level == 3:
1348 diag_color = '#FFCC00'
1349 elif diag_status.level > 3:
1350 diag_color = '#0000CC'
1351 text += '<dt><font color="%s"><b>%s: %s</b></font></dt>' % (diag_color, level_str, node.diagnostic_array[-1].message)
1352
1353
1354 text += '</dl>'
1355 if nm.settings().transpose_pub_sub_descr:
1356 text += self._create_html_list('Subscribed Topics:', node.subscribed, 'TOPIC_SUB', node.name)
1357 text += self._create_html_list('Published Topics:', node.published, 'TOPIC_PUB', node.name)
1358 else:
1359 text += self._create_html_list('Published Topics:', node.published, 'TOPIC_PUB', node.name)
1360 text += self._create_html_list('Subscribed Topics:', node.subscribed, 'TOPIC_SUB', node.name)
1361 text += self._create_html_list('Services:', node.services, 'SERVICE', node.name)
1362
1363 text += self._create_html_list('Loaded Launch Files:', launches, 'LAUNCH')
1364 text += self._create_html_list('Default Configurations:', default_cfgs, 'NODE')
1365
1366 return text
1367
1369 '''
1370 updates the Buttons, create a description and emit L{description_signal} to
1371 show the description of selected topic
1372 '''
1373 if selected is not None:
1374
1375 self.__last_selection = time.time()
1376 selectedTopics = []
1377 if topic_name and self.master_info is not None:
1378 selectedTopics = [self.master_info.getTopic("%s" % topic_name)]
1379 if len(selectedTopics) == 0:
1380 return
1381 else:
1382 if self.masterTab.tabWidget.tabText(self.masterTab.tabWidget.currentIndex()) != 'Topics':
1383 return
1384 selectedTopics = self.topicsFromIndexes(self.masterTab.topicsView.selectionModel().selectedIndexes())
1385 topics_selected = (len(selectedTopics) > 0)
1386 self.masterTab.echoTopicButton.setEnabled(topics_selected)
1387 self.masterTab.hzTopicButton.setEnabled(topics_selected)
1388 self.masterTab.hzSshTopicButton.setEnabled(topics_selected)
1389 self.masterTab.pubStopTopicButton.setEnabled(topics_selected)
1390 if len(selectedTopics) == 1:
1391 topic = selectedTopics[0]
1392 text = self.get_topic_description(topic_name, topic)
1393 info_text = '<div>%s</div>' % text
1394 current_tab = self.masterTab.tabWidget.tabText(self.masterTab.tabWidget.currentIndex())
1395 if (current_tab == 'Topics' and self.__last_info_text != info_text) or force_emit:
1396 self.__last_info_text = info_text
1397 self.description_signal.emit(topic.name, info_text, True if selected or deselected or force_emit else False)
1398
1400 text = ''
1401 if topic is None:
1402 selectedTopics = []
1403 if topic_name and self.master_info is not None:
1404 selectedTopics = [self.master_info.getTopic("%s" % topic_name)]
1405 else:
1406 selectedTopics = self.topicsFromIndexes(self.masterTab.topicsView.selectionModel().selectedIndexes())
1407 if len(selectedTopics) == 1:
1408 topic = selectedTopics[0]
1409 if topic is not None:
1410 ns, sep, name = topic.name.rpartition(rospy.names.SEP)
1411 text = '<font size="+1"><b><span style="color:gray;">%s%s</span><b>%s</b></font><br>' % (ns, sep, name)
1412 text += ' <a href="topicecho://%s%s" title="Show the content of the topic"><img src=":icons/sekkyumu_topic_echo_24.png" alt="echo"></a>' % (self.mastername, topic.name)
1413 text += ' <a href="topichz://%s%s" title="Show only the receive rate of the topic.<br>All data is sent through the network"><img src=":icons/sekkyumu_topic_hz_24.png" alt="hz"></a>' % (self.mastername, topic.name)
1414 text += ' <a href="topichzssh://%s%s" title="Show only the receive rate of the topic.<br>Uses an SSH connection to execute `rostopic hz` on remote host."><img src=":icons/sekkyumu_topic_echo_ssh_hz_24.png" alt="sshhz"></a>' % (self.mastername, topic.name)
1415 text += ' <a href="topicpub://%s%s" title="Start a publisher for selected topic"><img src=":icons/sekkyumu_topic_pub_24.png" alt="pub"></a>' % (self.mastername, topic.name)
1416 if topic.name in self.__republish_params:
1417 text += ' <a href="topicrepub://%s%s" title="Start a publisher with last parameters"><img src=":icons/sekkyumu_topic_repub_24.png" alt="repub"></a>' % (self.mastername, topic.name)
1418 topic_publisher = []
1419 topic_prefix = '/rostopic_pub%s_' % topic.name
1420 node_names = self.master_info.node_names
1421 for n in node_names:
1422 if n.startswith(topic_prefix):
1423 topic_publisher.append(n)
1424 if topic_publisher:
1425 text += ' <a href="topicstop://%s%s"><img src=":icons/sekkyumu_topic_pub_stop_24.png" alt="stop"> [%d]</a>' % (self.mastername, topic.name, len(topic_publisher))
1426 text += '<p>'
1427 if nm.settings().transpose_pub_sub_descr:
1428 text += self._create_html_list('Subscriber:', topic.subscriberNodes, 'NODE')
1429 text += self._create_html_list('Publisher:', topic.publisherNodes, 'NODE')
1430 else:
1431 text += self._create_html_list('Publisher:', topic.publisherNodes, 'NODE')
1432 text += self._create_html_list('Subscriber:', topic.subscriberNodes, 'NODE')
1433 text += '<b><u>Type:</u></b> %s' % self._href_from_msgtype(topic.type)
1434 text += '<dl>'
1435 try:
1436 mclass = roslib.message.get_message_class(topic.type)
1437 if mclass is not None:
1438 for f in mclass.__slots__:
1439 idx = mclass.__slots__.index(f)
1440 idtype = mclass._slot_types[idx]
1441
1442
1443
1444
1445
1446
1447
1448
1449
1450
1451 text += '%s: <span style="color:gray;">%s</span><br>' % (f, idtype)
1452 text += '<br>'
1453 constants = {}
1454 for m in dir(mclass):
1455 if not m.startswith('_'):
1456 if type(getattr(mclass, m)) in [str, int, bool, float]:
1457 constants[m] = getattr(mclass, m)
1458 if constants:
1459 text += '<b><u>Constants:</u></b><br>'
1460 for n in sorted(constants.iterkeys()):
1461 text += '%s: <span style="color:gray;">%s</span><br>' % (n, constants[n])
1462 except ValueError:
1463 pass
1464 text += '</dl>'
1465 return text
1466
1468 result = msg_type
1469 if msg_type:
1470 result = '<a href="http://ros.org/doc/api/%s.html">%s</a>' % (msg_type.replace('/', '/html/msg/'), msg_type)
1471 return result
1472
1474 '''
1475 updates the Buttons, create a description and emit L{description_signal} to
1476 show the description of selected service
1477 '''
1478 if selected is not None:
1479
1480 self.__last_selection = time.time()
1481 if service_name and self.master_info is not None:
1482
1483 selectedServices = [self.master_info.getService("%s" % service_name)]
1484 if selectedServices[0] is None:
1485 return
1486 else:
1487
1488 selectedServices = self.servicesFromIndexes(self.masterTab.servicesView.selectionModel().selectedIndexes())
1489 self.masterTab.callServiceButton.setEnabled(len(selectedServices) > 0)
1490 if self.masterTab.tabWidget.tabText(self.masterTab.tabWidget.currentIndex()) != 'Services':
1491 return
1492 if len(selectedServices) == 1:
1493 service = selectedServices[0]
1494 ns, sep, name = service.name.rpartition(rospy.names.SEP)
1495 text = '<font size="+1"><b><span style="color:gray;">%s%s</span><b>%s</b></font><br>' % (ns, sep, name)
1496 text += '<a href="servicecall://%s%s" title="call service"><img src=":icons/sekkyumu_call_service_24.png" alt="call"></a>' % (self.mastername, service.name)
1497 text += '<dl>'
1498 text += '<dt><b>URI</b>: %s</dt>' % service.uri
1499 text += '<dt><b>ORG.MASTERURI</b>: %s</dt>' % service.masteruri
1500 text += self._create_html_list('Provider:', service.serviceProvider, 'NODE')
1501 if service.masteruri != self.masteruri:
1502 text += '<dt><font color="#339900"><b>synchronized</b></font></dt>'
1503 text += '</dl>'
1504 try:
1505 service_class = service.get_service_class(nm.is_local(get_hostname(service.uri)))
1506 text += '<h4>%s</h4>' % self._href_from_svrtype(service_class._type)
1507 text += '<b><u>Request:</u></b>'
1508 text += '<dl><dt>%s</dt></dl>' % service_class._request_class.__slots__
1509 text += '<b><u>Response:</u></b>'
1510 text += '<dl><dt>%s</dt></dl>' % service_class._response_class.__slots__
1511 except:
1512 text += '<h4><font color=red>Unknown service type</font></h4>'
1513 if service.isLocal:
1514 text += '<font color=red>Unable to communicate with service, is provider node running?</font>'
1515 else:
1516 text += '<font color=red>Try to refresh <b>all</b> hosts. Is provider node running?</font>'
1517 info_text = '<div>%s</div>' % text
1518 current_tab = self.masterTab.tabWidget.tabText(self.masterTab.tabWidget.currentIndex())
1519 if (current_tab == 'Services' and self.__last_info_text != info_text) or force_emit:
1520 self.__last_info_text = info_text
1521 self.description_signal.emit(service.name, info_text, True if selected or deselected or force_emit else False)
1522
1524 result = srv_type
1525 if srv_type:
1526 result = '<a href="http://ros.org/doc/api/%s.html">%s</a>' % (srv_type.replace('/', '/html/srv/'), srv_type)
1527 return result
1528
1530 selectedParameter = self.parameterFromIndexes(self.masterTab.parameterView.selectionModel().selectedIndexes())
1531 self.masterTab.deleteParameterButton.setEnabled(len(selectedParameter) > 0)
1532 self.masterTab.saveParameterButton.setEnabled(len(selectedParameter) > 0)
1533
1535 result = []
1536 for index in indexes:
1537 if index.column() == 0:
1538 model_index = self.node_proxy_model.mapToSource(index)
1539 item = self.node_tree_model.itemFromIndex(model_index)
1540 if item is not None:
1541 if isinstance(item, HostItem):
1542 result.append(item)
1543 return result
1544
1546 result = []
1547 for index in indexes:
1548 if index.column() == 0 and index.parent().isValid():
1549 model_index = self.node_proxy_model.mapToSource(index)
1550 item = self.node_tree_model.itemFromIndex(model_index)
1551 if item is not None:
1552 if isinstance(item, GroupItem):
1553 result.append(item)
1554 return result
1555
1557 result = []
1558 for index in indexes:
1559 if index.column() == 0:
1560 model_index = self.node_proxy_model.mapToSource(index)
1561 item = self.node_tree_model.itemFromIndex(model_index)
1562 res = self._nodesFromItems(item, recursive)
1563 for r in res:
1564 if r not in result:
1565 result.append(r)
1566 return result
1567
1569 result = []
1570 if item is not None:
1571 if isinstance(item, (GroupItem, HostItem)):
1572 if recursive:
1573 for j in range(item.rowCount()):
1574 result[len(result):] = self._nodesFromItems(item.child(j), recursive)
1575 elif isinstance(item, NodeItem):
1576 if item not in result:
1577 result.append(item)
1578 return result
1579
1581 result = []
1582 for index in indexes:
1583 model_index = self.topic_proxyModel.mapToSource(index)
1584 item = self.topic_model.itemFromIndex(model_index)
1585 if item is not None and isinstance(item, TopicItem):
1586 result.append(item.topic)
1587 return result
1588
1590 result = []
1591 for index in indexes:
1592 model_index = self.service_proxyModel.mapToSource(index)
1593 item = self.service_model.itemFromIndex(model_index)
1594 if item is not None and isinstance(item, ServiceItem):
1595 result.append(item.service)
1596 return result
1597
1599 result = []
1600 for index in indexes:
1601 model_index = self.parameter_proxyModel.mapToSource(index)
1602 item = self.parameter_model.itemFromIndex(model_index)
1603 if item is not None and isinstance(item, ParameterValueItem):
1604 result.append((item.name, item.value))
1605 return result
1606
1607
1608
1609
1610
1612 '''
1613 Starts the selected nodes. If for a node more then one configuration is
1614 available, the selection dialog will be show.
1615 '''
1616 cursor = self.cursor()
1617 self.masterTab.startButton.setEnabled(False)
1618 self.setCursor(Qt.WaitCursor)
1619 try:
1620 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
1621 self.start_nodes(selectedNodes)
1622 finally:
1623 self.setCursor(cursor)
1624 self.masterTab.startButton.setEnabled(True)
1625
1627 '''
1628 Starts the selected nodes with additional options.
1629 '''
1630 cursor = self.cursor()
1631 self.setCursor(Qt.WaitCursor)
1632 try:
1633 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
1634 self.start_nodes(selectedNodes, force=True, use_adv_cfg=True)
1635 finally:
1636 self.setCursor(cursor)
1637
1638 - def start_node(self, node, force, config, force_host=None, logging=None):
1639
1640 if node is None:
1641 raise DetailedError("Start error", 'None is not valid node name!')
1642 if node.pid is None or force:
1643
1644 if config is None:
1645 raise DetailedError("Start error",
1646 'Error while start %s:\nNo configuration found!' % node.name)
1647 if isinstance(config, LaunchConfig):
1648 try:
1649 nm.starter().runNode(AdvRunCfg(node.name, config, force_host, self.masteruri, logging=logging, user=self.current_user))
1650 except socket.error as se:
1651 rospy.logwarn("Error while start '%s': %s\n\n Start canceled!", node.name, str(se))
1652 raise DetailedError("Start error",
1653 'Error while start %s\n\nStart canceled!' % node.name,
1654 '%s' % se)
1655 return False
1656 except nm.InteractionNeededError as _:
1657 raise
1658 except (Exception, nm.StartException) as e:
1659 print type(e)
1660 print traceback.format_exc(3)
1661 rospy.logwarn("Error while start '%s': %s" % (node.name, e))
1662 raise DetailedError("Start error", 'Error while start %s' % node.name, '%s' % e)
1663 elif isinstance(config, (str, unicode)):
1664
1665 from multimaster_msgs_fkie.srv import Task
1666 try:
1667 nm.starter().callService(self.master_info.getService(config).uri, config, Task, [node.name])
1668 except (Exception, nm.StartException) as e:
1669 rospy.logwarn("Error while call a service of node '%s': %s" % (node.name, e))
1670 raise DetailedError("Service error",
1671 'Error while call a service of node %s [%s]' % (node.name, self.master_info.getService(config).uri),
1672 '%s' % e)
1673
1674 - def start_nodes(self, nodes, force=False, force_host=None, use_adv_cfg=False):
1675 '''
1676 Internal method to start a list with nodes
1677 @param nodes: the list with nodes to start
1678 @type nodes: C{[L{NodeItem}, ...]}
1679 @param force: force the start of the node, also if it is already started.
1680 @type force: C{bool}
1681 @param force_host: force the start of the node at specified host.
1682 @type force_host: C{str}
1683 '''
1684 cfg_choices = dict()
1685 cfg_nodes = dict()
1686 has_launch_files = False
1687 for node in nodes:
1688
1689 if (node.pid is None or (node.pid is not None and force)) and not node.is_ghost:
1690
1691 if node.uri is None and node.has_running:
1692 ret = QMessageBox.question(self, 'Question', ''.join(['Some nodes, e.g. ', node.name, ' are already running on another host. If you start this node the other node will be terminated.\n Do you want proceed?']), QMessageBox.Yes, QMessageBox.No)
1693 if ret == QMessageBox.No:
1694 return
1695
1696 choices = self._getCfgChoises(node)
1697 ch_keys = choices.keys()
1698 if ch_keys:
1699 ch_keys.sort()
1700 choises_str = str(ch_keys)
1701 if choises_str not in cfg_choices.keys():
1702 choice, ok = self._getUserCfgChoice(choices, node.name)
1703 if choice is not None:
1704 cfg_choices[choises_str] = choices[choice]
1705 cfg_nodes[node.name] = choices[choice]
1706 if isinstance(choices[choice], LaunchConfig):
1707 has_launch_files = True
1708 elif ok:
1709 WarningMessageBox(QMessageBox.Warning, "Start error",
1710 'Error while start %s:\nNo configuration selected!' % node.name).exec_()
1711 else:
1712 break
1713 else:
1714 cfg_nodes[node.name] = cfg_choices[choises_str]
1715
1716
1717 logging = None
1718 diag_canceled = False
1719 if use_adv_cfg and has_launch_files:
1720 log_params = {'Level': ('string', nm.settings().logging.get_alternatives('loglevel')),
1721 'Level (roscpp)': ('string', nm.settings().logging.get_alternatives('loglevel_roscpp')),
1722 'Level (super)': ('string', nm.settings().logging.get_alternatives('loglevel_superdebug')),
1723 'Format': ('string', nm.settings().logging.get_alternatives('console_format'))
1724 }
1725 params = {'Logging': ('dict', log_params)}
1726 dia = ParameterDialog(params)
1727 dia.setFilterVisible(False)
1728 dia.setWindowTitle('Start with parameters')
1729 dia.resize(480, 120)
1730 dia.setFocusField('Level')
1731 diag_canceled = not dia.exec_()
1732 if not diag_canceled:
1733 try:
1734 params = dia.getKeywords()
1735 nm.settings().logging.loglevel = params['Logging']['Level']
1736 nm.settings().logging.loglevel_roscpp = params['Logging']['Level (roscpp)']
1737 nm.settings().logging.loglevel_superdebug = params['Logging']['Level (super)']
1738 nm.settings().logging.console_format = params['Logging']['Format']
1739 nm.settings().store_logging()
1740 logging = nm.settings().logging
1741 except Exception, e:
1742 diag_canceled = True
1743 WarningMessageBox(QMessageBox.Warning, "Get advanced start parameter",
1744 'Error while parse parameter',
1745 str(e)).exec_()
1746 if not diag_canceled:
1747
1748 for node in nodes:
1749 if node.name in cfg_nodes:
1750 self._progress_queue.add2queue(str(uuid.uuid4()),
1751 ''.join(['start ', node.node_info.name]),
1752 self.start_node,
1753 (node.node_info, force, cfg_nodes[node.node_info.name], force_host, logging))
1754 self._progress_queue.start()
1755
1757 '''
1758 Start nodes given in a list by their names.
1759 @param nodes: a list with full node names
1760 @type nodes: C{[str]}
1761 '''
1762 result = []
1763 if self.master_info is not None:
1764 for n in nodes:
1765 node_info = NodeInfo(n, self.masteruri)
1766 node_item = NodeItem(node_info)
1767 node_item.addConfig(cfg)
1768 result.append(node_item)
1769 self.start_nodes(result, force)
1770
1772 '''
1773 Starts the selected nodes (also if it already running). If for a node more then one configuration is
1774 available, the selection dialog will be show.
1775 '''
1776 cursor = self.cursor()
1777 self.masterTab.startButton.setEnabled(False)
1778 self.setCursor(Qt.WaitCursor)
1779 try:
1780 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
1781 self.stop_nodes(selectedNodes)
1782 self.start_nodes(selectedNodes, True)
1783 finally:
1784 self.setCursor(cursor)
1785 self.masterTab.startButton.setEnabled(True)
1786
1788 '''
1789 Starts the selected nodes on an another host.
1790 '''
1791 cursor = self.cursor()
1792 self.masterTab.startButton.setEnabled(False)
1793 params = {'Host': ('string', 'localhost')}
1794 dia = ParameterDialog(params)
1795 dia.setFilterVisible(False)
1796 dia.setWindowTitle('Start node on...')
1797 dia.resize(350, 120)
1798 dia.setFocusField('host')
1799 if dia.exec_():
1800 try:
1801 params = dia.getKeywords()
1802 host = params['Host']
1803 self.setCursor(Qt.WaitCursor)
1804 try:
1805 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
1806 self.start_nodes(selectedNodes, True, host)
1807 finally:
1808 self.setCursor(cursor)
1809 except Exception, e:
1810 WarningMessageBox(QMessageBox.Warning, "Start error",
1811 'Error while parse parameter',
1812 str(e)).exec_()
1813 self.masterTab.startButton.setEnabled(True)
1814
1816 result = {}
1817 for c in node.cfgs:
1818 if isinstance(c, tuple):
1819 result[' '.join(['[default]', c[0]])] = roslib.names.ns_join(c[0], 'run')
1820 return result
1821
1823 result = {}
1824 for c in node.cfgs:
1825 if c:
1826 if not isinstance(c, tuple):
1827 launch = self.launchfiles[c]
1828 result[''.join([str(launch.LaunchName), ' [', str(launch.PackageName), ']'])] = self.launchfiles[c]
1829 elif not ignore_defaults:
1830 result[' '.join(['[default]', c[0]])] = roslib.names.ns_join(c[0], 'run')
1831 return result
1832
1834 value = None
1835 ok = False
1836
1837 if len(choices) == 1:
1838 value = choices.keys()[0]
1839 ok = True
1840 elif len(choices) > 0:
1841 items, ok = SelectDialog.getValue('Configuration selection', 'Select configuration to launch <b>%s</b>' % nodename, choices.keys(), True)
1842 if items:
1843 value = items[0]
1844 return value, ok
1845
1847 '''
1848 Stops the selected and running nodes. If the node can't be stopped using his
1849 RPC interface, it will be unregistered from the ROS master using the masters
1850 RPC interface.
1851 '''
1852 key_mod = QApplication.keyboardModifiers()
1853 if (key_mod & Qt.ShiftModifier or key_mod & Qt.ControlModifier):
1854 self.masterTab.stopButton.showMenu()
1855 else:
1856 cursor = self.cursor()
1857 self.setCursor(Qt.WaitCursor)
1858 try:
1859 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
1860 self.stop_nodes(selectedNodes)
1861 finally:
1862 self.setCursor(cursor)
1863
1865 if node is not None and node.uri is not None and (not self._is_in_ignore_list(node.name) or force):
1866 try:
1867 rospy.loginfo("Stop node '%s'[%s]", str(node.name), str(node.uri))
1868 nm.filewatcher().rem_binary(node.name)
1869
1870 socket.setdefaulttimeout(10)
1871
1872 p = xmlrpclib.ServerProxy(node.uri)
1873
1874 p.shutdown(rospy.get_name(), ''.join(['[node manager] request from ', self.mastername]))
1875
1876 except Exception, e:
1877 rospy.logwarn("Error while stop node '%s': %s", str(node.name), str(e))
1878 if str(e).find(' 111') == 1:
1879 raise DetailedError("Stop error",
1880 ''.join(['Error while stop node ', node.name]),
1881 str(e))
1882 finally:
1883 socket.setdefaulttimeout(None)
1884 elif isinstance(node, NodeItem) and node.is_ghost:
1885
1886
1887 self.stop_nodes_signal.emit(node.masteruri, [node.name])
1888 return True
1889
1891 '''
1892 Internal method to stop a list with nodes
1893 @param nodes: the list with nodes to stop
1894 @type nodes: C{[U{master_discovery_fkie.NodeInfo<http://docs.ros.org/kinetic/api/master_discovery_fkie/html/modules.html#master_discovery_fkie.master_info.NodeInfo>}, ...]}
1895 '''
1896
1897 for node in nodes:
1898 self._progress_queue.add2queue(str(uuid.uuid4()),
1899 'stop %s' % node.name,
1900 self.stop_node,
1901 (node, (len(nodes) == 1) or force))
1902 self._progress_queue.start()
1903
1905 '''
1906 Stop nodes given in a list by their names.
1907 @param nodes: a list with full node names
1908 @type nodes: C{[str]}
1909 '''
1910 result = []
1911 if self.master_info is not None:
1912 for n in nodes:
1913 if n not in ignore:
1914 node = self.master_info.getNode(n)
1915 if node is not None:
1916 result.append(node)
1917 self.stop_nodes(result, force)
1918
1920 if node is not None and node.uri is not None and (not self._is_in_ignore_list(node.name) or force):
1921 pid = node.pid
1922 if pid is None:
1923
1924 try:
1925 socket.setdefaulttimeout(10)
1926 rpc_node = xmlrpclib.ServerProxy(node.uri)
1927 _, _, pid = rpc_node.getPid(rospy.get_name())
1928 except:
1929 pass
1930 finally:
1931 socket.setdefaulttimeout(None)
1932
1933 if pid is not None:
1934 try:
1935 self._progress_queue.add2queue(str(uuid.uuid4()),
1936 ''.join(['kill ', node.name, '(', str(pid), ')']),
1937 nm.starter().kill,
1938 (self.getHostFromNode(node), pid, False, self.current_user))
1939 self._progress_queue.start()
1940 except Exception as e:
1941 rospy.logwarn("Error while kill the node %s: %s", str(node.name), str(e))
1942 raise DetailedError("Kill error",
1943 ''.join(['Error while kill the node ', node.name]),
1944 str(e))
1945 return True
1946
1965
1967 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
1968
1969
1970 for node in selectedNodes:
1971 self._progress_queue.add2queue(str(uuid.uuid4()),
1972 ''.join(['kill ', node.name]),
1973 self.kill_node,
1974 (node, (len(selectedNodes) == 1)))
1975 self._progress_queue.start()
1976
1978 if node is not None and node.uri is not None and (not self._is_in_ignore_list(node.name) or force):
1979
1980
1981
1982
1983
1984
1985
1986
1987 try:
1988 socket.setdefaulttimeout(10)
1989 master = xmlrpclib.ServerProxy(node.masteruri)
1990 master_multi = xmlrpclib.MultiCall(master)
1991
1992 for p in node.published:
1993 rospy.loginfo("unregister publisher '%s' [%s] from ROS master: %s", p, node.name, node.masteruri)
1994 master_multi.unregisterPublisher(node.name, p, node.uri)
1995 for t in node.subscribed:
1996 rospy.loginfo("unregister subscriber '%s' [%s] from ROS master: %s", t, node.name, node.masteruri)
1997 master_multi.unregisterSubscriber(node.name, t, node.uri)
1998 if self.master_state is not None:
1999 for s in node.services:
2000 rospy.loginfo("unregister service '%s' [%s] from ROS master: %s", s, node.name, node.masteruri)
2001 service = self.master_info.getService(s)
2002 if not (service is None):
2003 master_multi.unregisterService(node.name, s, service.uri)
2004 r = master_multi()
2005 for code, msg, _ in r:
2006 if code != 1:
2007 rospy.logwarn("unregistration failed: %s", msg)
2008 except Exception, e:
2009 rospy.logwarn("Error while unregister node %s: %s", str(node.name), str(e))
2010 raise DetailedError("Unregister error",
2011 ''.join(['Error while Unregister node ', node.name]),
2012 str(e))
2013 finally:
2014 socket.setdefaulttimeout(None)
2015 return True
2016
2018 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2019
2020 for node in selectedNodes:
2021 if node.pid is None or len(selectedNodes) == 1:
2022 self._progress_queue.add2queue(str(uuid.uuid4()),
2023 ''.join(['unregister node ', node.name]),
2024 self.unregister_node,
2025 (node, (len(selectedNodes) == 1)))
2026 self._progress_queue.start()
2027
2028 - def on_stop_context_toggled(self, state):
2029 menu = QMenu(self)
2030 self.killAct = QAction("&Kill Node", self, shortcut=QKeySequence.New, statusTip="Kill selected node", triggered=self.kill_nodes)
2031 self.unregAct = QAction("&Unregister Nodes...", self, shortcut=QKeySequence.Open, statusTip="Open an existing file", triggered=self.unreg_nodes)
2032 menu.addAction(self.killAct)
2033 menu.addAction(self.unregAct)
2034 menu.exec_(self.masterTab.stopContextButton.pos())
2035
2037 '''
2038 If the node is running the host the node URI will be returned. Otherwise
2039 tries to get the host from the launch configuration. If the configuration
2040 contains no machine assignment for this node the host of the ROS master URI
2041 will be used.
2042 @param node:
2043 @type node: U{master_discovery_fkie.NodeInfo<http://docs.ros.org/kinetic/api/master_discovery_fkie/html/modules.html#master_discovery_fkie.master_info.NodeInfo>}
2044 '''
2045 if node.uri is not None:
2046 return get_hostname(node.uri)
2047
2048 for c in node.cfgs:
2049 if not isinstance(c, tuple):
2050 launch_config = self.__configs[c]
2051 item = launch_config.getNode(node.name)
2052 if item is not None and item.machine_name and not item.machine_name == 'localhost':
2053 return launch_config.Roscfg.machines[item.machine_name].address
2054
2055 return get_hostname(node.masteruri)
2056
2058 '''
2059 Shows IO of the selected nodes.
2060 '''
2061 key_mod = QApplication.keyboardModifiers()
2062 if (key_mod & Qt.ShiftModifier or key_mod & Qt.ControlModifier):
2063 self.masterTab.ioButton.showMenu()
2064 else:
2065 cursor = self.cursor()
2066 self.setCursor(Qt.WaitCursor)
2067 try:
2068 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2069 if selectedNodes:
2070 ret = True
2071 if len(selectedNodes) > 5:
2072 ret = QMessageBox.question(self, "Show IO", "You are going to open the IO of " + str(len(selectedNodes)) + " nodes at once\nContinue?", QMessageBox.Ok, QMessageBox.Cancel)
2073 ret = (ret == QMessageBox.Ok)
2074 if ret:
2075 for node in selectedNodes:
2076 self._progress_queue.add2queue(str(uuid.uuid4()),
2077 ''.join(['show IO of ', node.name]),
2078 nm.screen().openScreen,
2079 (node.name, self.getHostFromNode(node), False, self.current_user))
2080 self._progress_queue.start()
2081 else:
2082 self.on_show_all_screens()
2083 finally:
2084 self.setCursor(cursor)
2085
2087 '''
2088 Kills selected screens, if some available.
2089 '''
2090 cursor = self.cursor()
2091 self.setCursor(Qt.WaitCursor)
2092 try:
2093 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2094 for node in selectedNodes:
2095 self._progress_queue.add2queue(str(uuid.uuid4()),
2096 ''.join(['kill screen of ', node.name]),
2097 nm.screen().killScreens,
2098 (node.name, self.getHostFromNode(node), False, self.current_user))
2099 self._progress_queue.start()
2100 finally:
2101 self.setCursor(cursor)
2102
2104 '''
2105 Shows all available screens.
2106 '''
2107 cursor = self.cursor()
2108 self.setCursor(Qt.WaitCursor)
2109 try:
2110 host = get_hostname(self.masteruri)
2111 sel_screen = []
2112 try:
2113 screens = nm.screen().getActiveScreens(host, auto_pw_request=True, user=self.current_user)
2114 sel_screen, _ = SelectDialog.getValue('Open screen', '', screens, False, False, self)
2115 except Exception, e:
2116 rospy.logwarn("Error while get screen list: %s", str(e))
2117 WarningMessageBox(QMessageBox.Warning, "Screen list error",
2118 ''.join(['Error while get screen list from ', host]),
2119 str(e)).exec_()
2120 for screen in sel_screen:
2121 try:
2122 if not nm.screen().openScreenTerminal(host, screen, screen, self.current_user):
2123 pass
2124 except Exception, e:
2125 rospy.logwarn("Error while show IO for %s: %s", str(screen), str(e))
2126 WarningMessageBox(QMessageBox.Warning, "Show IO error",
2127 ''.join(['Error while show IO ', screen, ' on ', host]),
2128 str(e)).exec_()
2129 finally:
2130 self.setCursor(cursor)
2131
2133 '''
2134 Shows log files of the selected nodes.
2135 '''
2136 try:
2137 only_screen = True
2138 key_mod = QApplication.keyboardModifiers()
2139 if (key_mod & Qt.ShiftModifier or key_mod & Qt.ControlModifier):
2140 only_screen = False
2141 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2142 ret = True
2143 if len(selectedNodes) > 5:
2144 ret = QMessageBox.question(self, "Show Log", "You are going to open the logs of " + str(len(selectedNodes)) + " nodes at once\nContinue?", QMessageBox.Ok, QMessageBox.Cancel)
2145 ret = (ret == QMessageBox.Ok)
2146 if ret:
2147 for node in selectedNodes:
2148 self._progress_queue.add2queue(str(uuid.uuid4()),
2149 ''.join(['show log of ', node.name]),
2150 nm.starter().openLog,
2151 (node.name, self.getHostFromNode(node), self.current_user, only_screen))
2152 self._progress_queue.start()
2153 except Exception, e:
2154 print traceback.format_exc(1)
2155 rospy.logwarn("Error while show log: %s", str(e))
2156 WarningMessageBox(QMessageBox.Warning, "Show log error",
2157 'Error while show Log',
2158 str(e)).exec_()
2159
2161 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2162 nodenames = []
2163 for n in selectedNodes:
2164 nodenames.append(n.name)
2165 try:
2166 host = get_hostname(self.masteruri)
2167 path_on_host = nm.starter().get_log_path(host, nodenames, True)
2168 QApplication.clipboard().setText(''.join([getpass.getuser() if self.is_local else self.current_user, '@', host, ':', path_on_host]))
2169 except Exception as e:
2170 WarningMessageBox(QMessageBox.Warning, "Get log path",
2171 'Error while get log path',
2172 str(e)).exec_()
2173
2174
2175
2176
2177
2178
2179
2180
2181
2182
2183
2184
2185
2186
2187
2188
2189
2191 '''
2192 Deletes log files of the selected nodes.
2193 '''
2194 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2195 for node in selectedNodes:
2196 self._progress_queue.add2queue(str(uuid.uuid4()),
2197 ''.join(['delete Log of ', node.name]),
2198 nm.starter().deleteLog,
2199 (node.name, self.getHostFromNode(node), False, self.current_user))
2200 self._progress_queue.start()
2201
2203 '''
2204 Opens the dynamic configuration dialogs for selected nodes.
2205 '''
2206 if self.master_info is not None:
2207 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2208 for n in selectedNodes:
2209 try:
2210 nodes = sorted([srv_name[:-len('/set_parameters')] for srv_name, srv in self.master_info.services.items() if (srv_name.endswith('/set_parameters') and n.name in srv.serviceProvider)])
2211 items = []
2212 if len(nodes) == 1:
2213 items = nodes
2214 elif len(nodes) > 1:
2215 items, _ = SelectDialog.getValue('Dynamic configuration selection', '', [i for i in nodes])
2216 if items is None:
2217 items = []
2218 if len(items) > 3:
2219 ret = QMessageBox.question(self, 'Start dynamic reconfigure', 'It will starts %s dynamic reconfigure nodes?\n\n Are you sure?' % str(len(items)), QMessageBox.Yes, QMessageBox.No)
2220 if ret != QMessageBox.Yes:
2221 return
2222 for node in items:
2223 env = dict(os.environ)
2224 env["ROS_MASTER_URI"] = str(self.master_info.masteruri)
2225 rospy.loginfo("Start dynamic reconfiguration for '%s'" % node)
2226 _ = SupervisedPopen(['rosrun', 'node_manager_fkie', 'dynamic_reconfigure', node, '__ns:=dynamic_reconfigure'], env=env, object_id=node, description='Start dynamic reconfiguration for %s failed' % node)
2227 except Exception, e:
2228 rospy.logwarn("Start dynamic reconfiguration for '%s' failed: %s" % (n.name, e))
2229 WarningMessageBox(QMessageBox.Warning, "Start dynamic reconfiguration error",
2230 'Start dynamic reconfiguration for %s failed!' % n.name,
2231 str(e)).exec_()
2232
2234 '''
2235 '''
2236 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2237 for node in selectedNodes:
2238 choices = self._getCfgChoises(node, True)
2239 choice, ok = self._getUserCfgChoice(choices, node.name)
2240 config = choices[choice] if choices and choice else ''
2241 if ok and isinstance(config, LaunchConfig):
2242
2243 node_cfg = config.getNode(node.name)
2244 files = [config.Filename]
2245 if node_cfg.filename not in files:
2246 files.append(node_cfg.filename)
2247 self.request_xml_editor.emit(files, ''.join(['name="', os.path.basename(node.name), '"']))
2248
2250 '''
2251 '''
2252 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2253 for node in selectedNodes:
2254
2255 try:
2256 inputDia = MasterParameterDialog(node.masteruri if node.masteruri is not None else self.masteruri, ''.join([node.name, roslib.names.SEP]), parent=self)
2257 inputDia.setWindowTitle(' - '.join([os.path.basename(node.name), "parameter"]))
2258 if node.has_launch_cfgs(node.cfgs):
2259 inputDia.add_warning("The changes may not have any effect, because the launch file was also loaded as not 'default' and the parameter in the launch file will be reloaded on start of the ROS node.")
2260 inputDia.show()
2261 except:
2262 rospy.logwarn("Error on retrieve parameter for %s: %s", str(node.name), traceback.format_exc(1))
2263
2265 (fileName, _) = QFileDialog.getSaveFileName(self,
2266 "New launch file",
2267 self.__current_path,
2268 "Config files (*.launch);;All files (*)")
2269 if fileName:
2270 self.__current_path = os.path.dirname(fileName)
2271 try:
2272 (pkg, _) = package_name(os.path.dirname(fileName))
2273 if pkg is None:
2274 ret = WarningMessageBox(QMessageBox.Warning, "New File Error",
2275 'The new file is not in a ROS package', buttons=QMessageBox.Ok | QMessageBox.Cancel).exec_()
2276 if ret == QMessageBox.Cancel:
2277 return
2278 with open(fileName, 'w+') as f:
2279 f.write("<launch>\n")
2280 for lfile in self.launchfiles.keys():
2281 with open(lfile, 'r') as lf:
2282 f.write(re.sub('<\/?launch\ *\t*>', '', lf.read()))
2283 f.write("</launch>\n")
2284 except EnvironmentError as e:
2285 WarningMessageBox(QMessageBox.Warning, "New File Error",
2286 'Error while create a new file',
2287 str(e)).exec_()
2288
2290 '''
2291 Opens a dialog to select configurations to close or stop all nodes
2292 (with roscore) or shutdown the host.
2293 '''
2294 choices = dict()
2295
2296 for path, _ in self.__configs.items():
2297 if isinstance(path, tuple):
2298 if path[2] == self.masteruri:
2299 choices['DEFAULT CFG: %s' % path[0]] = path
2300 else:
2301 package = str(package_name(os.path.dirname(path))[0])
2302 choices['%s [%s]' % (os.path.basename(path), package)] = path
2303 cfg_items = choices.keys()
2304 cfg_items.sort()
2305 res = SelectDialog.getValue('Close/Stop/Shutdown', '',
2306 cfg_items, False, False,
2307 self, checkitem1='stop ROS',
2308 checkitem2='shutdown host')
2309 cfgs, _, stop_nodes, shutdown = res[0], res[1], res[2], res[3]
2310
2311 for config in cfgs:
2312 self._close_cfg(choices[config])
2313 if stop_nodes:
2314 self._on_stop_kill_roscore = True
2315
2316 ignore_nodes = [rospy.get_name(), '/master_discovery', '/rosout']
2317 self.stop_nodes_by_name(self.getRunningNodesIfLocal(), True, ignore_nodes)
2318 if shutdown:
2319 self.poweroff()
2320 else:
2321 self.stop_nodes_by_name(['/master_discovery'], True)
2322 self.stop_nodes_by_name(['/node_manager'], True)
2323 elif shutdown:
2324 self.poweroff()
2325 self.updateButtons()
2326 self.update_robot_icon()
2327
2329 try:
2330 if nm.is_local(self.mastername):
2331 ret = QMessageBox.warning(self, "ROS Node Manager",
2332 "Do you really want to shutdown localhost?",
2333 QMessageBox.Ok | QMessageBox.Cancel)
2334 if ret == QMessageBox.Cancel:
2335 return
2336 self._on_stop_poweroff = True
2337
2338
2339 self.stop_nodes_by_name(['/master_discovery'], True)
2340 self._progress_queue.add2queue(str(uuid.uuid4()),
2341 'poweroff `%s`' % self.mastername,
2342 nm.starter().poweroff,
2343 ('%s' % self.mastername,))
2344 self._progress_queue.start()
2345 except (Exception, nm.StartException), emsg:
2346 rospy.logwarn("Error while poweroff %s: %s", self.mastername, str(emsg))
2347 WarningMessageBox(QMessageBox.Warning, "Run error",
2348 'Error while poweroff %s' % self.mastername,
2349 '%s' % emsg).exec_()
2350
2352 try:
2353 self.removeConfigFromModel(cfg)
2354 if isinstance(cfg, tuple):
2355 if self.master_info is not None:
2356
2357 node = self.master_info.getNode(cfg[0])
2358 if node is not None:
2359 self.stop_nodes([node])
2360 else:
2361
2362 try:
2363 for _, machine in self.__configs[cfg].Roscfg.machines.items():
2364 if machine.name:
2365 nm.nameres().remove_info(machine.name, machine.address)
2366 except:
2367 pass
2368 del self.__configs[cfg]
2369 except:
2370 print traceback.format_exc(1)
2371 pass
2372
2374 '''
2375 Shows the output of the topic in a terminal.
2376 '''
2377 self._show_topic_output(False)
2378
2380 '''
2381 Shows the hz of the topic in a terminal.
2382 '''
2383 self._show_topic_output(True)
2384
2386 '''
2387 Shows the hz of the topic using ssh.
2388 '''
2389 self._show_topic_output(True, use_ssh=True)
2390
2392 selectedTopics = self.topicsFromIndexes(self.masterTab.topicsView.selectionModel().selectedIndexes())
2393 if len(selectedTopics) > 0:
2394 for topic in selectedTopics:
2395 if not self._start_publisher(topic.name, topic.type):
2396 break
2397 else:
2398
2399
2400 root_paths = [os.path.normpath(p) for p in os.getenv("ROS_PACKAGE_PATH").split(':')]
2401 packages = {}
2402 msg_types = []
2403 for p in root_paths:
2404 ret = get_packages(p)
2405 packages = dict(ret.items() + packages.items())
2406 for (p, direc) in packages.items():
2407 import rosmsg
2408 for f in rosmsg._list_types('%s/msg' % direc, 'msg', rosmsg.MODE_MSG):
2409 msg_types.append("%s/%s" % (p, f))
2410 msg_types.sort()
2411 fields = {'Type': ('string', msg_types), 'Name': ('string', [''])}
2412
2413
2414 dia = ParameterDialog(fields, parent=self)
2415 dia.setWindowTitle('Publish to topic')
2416 dia.setFilterVisible(False)
2417 dia.resize(300, 95)
2418 dia.setFocusField('Name')
2419 if dia.exec_():
2420 params = dia.getKeywords()
2421 try:
2422 if params['Name'] and params['Type']:
2423 try:
2424 self._start_publisher(params['Name'], params['Type'])
2425 except Exception, e:
2426 print traceback.format_exc(1)
2427 rospy.logwarn("Publish topic '%s' failed: %s", str(params['Name']), str(e))
2428 WarningMessageBox(QMessageBox.Warning, "Publish topic error",
2429 ''.join(['Publish topic ', params['Name'], ' failed!']),
2430 str(e)).exec_()
2431 else:
2432 WarningMessageBox(QMessageBox.Warning, "Invalid name or type",
2433 "Can't publish to topic '%s' with type '%s'!" % (params['Name'], params['Type'])).exec_()
2434 except (KeyError, ValueError), e:
2435 WarningMessageBox(QMessageBox.Warning, "Warning",
2436 'Error while add a parameter to the ROS parameter server',
2437 str(e)).exec_()
2438
2440 '''
2441 Starts a publisher to given topic.
2442 '''
2443 if self.master_info is not None:
2444 topic = self.master_info.getTopic("%s" % topic_name)
2445 if topic is not None:
2446 self._start_publisher(topic.name, topic.type, republish)
2447 else:
2448 rospy.logwarn("Error while start publisher, topic not found: %s" % topic_name)
2449
2451 try:
2452 topic_name = roslib.names.ns_join(roslib.names.SEP, topic_name)
2453 mclass = roslib.message.get_message_class(topic_type)
2454 if mclass is None:
2455 WarningMessageBox(QMessageBox.Warning, "Publish error",
2456 'Error while publish to %s' % topic_name,
2457 ''.join(['invalid message type: ', topic_type, '.\nIf this is a valid message type, perhaps you need to run "rosmake"'])).exec_()
2458 return
2459 slots = mclass.__slots__
2460 types = mclass._slot_types
2461 default_topic_values = {}
2462 rate_values = ['once', 'latch', '1']
2463 if republish and topic_name in self.__republish_params:
2464 default_topic_values = self.__republish_params[topic_name][topic_type]
2465 rate_values = self.__republish_params[topic_name]['! Publish rate']
2466 args = ServiceDialog._params_from_slots(slots, types, default_topic_values)
2467 p = {'! Publish rate': ('string', rate_values), topic_type: ('dict', args)}
2468 dia = ParameterDialog(p)
2469 dia.setWindowTitle(''.join(['Publish to ', topic_name]))
2470 dia.showLoadSaveButtons()
2471 dia.resize(450, 300)
2472 dia.setFocusField('! Publish rate')
2473
2474 if dia.exec_():
2475 params = dia.getKeywords()
2476
2477 self.__republish_params[topic_name] = params
2478 rate = params['! Publish rate']
2479 opt_str = ''
2480 opt_name_suf = '__latch_'
2481 if rate == 'latch':
2482 opt_str = ''
2483 elif rate == 'once' or rate == '-1':
2484 opt_str = '--once'
2485 opt_name_suf = '__once_'
2486 else:
2487 try:
2488 i = 0
2489 try:
2490 i = int(rate)
2491 except:
2492 i = float(rate)
2493 if i > 0:
2494 opt_str = ''.join(['-r ', rate])
2495 opt_name_suf = '__%sHz_' % (str(rate).replace('.', '_'))
2496 except:
2497 pass
2498
2499 topic_params = dict()
2500 if topic_type in params:
2501 topic_params = self._rem_empty_lists(params[topic_type])
2502 pub_cmd = ' '.join(['pub', topic_name, topic_type, '"', str(topic_params), '"', opt_str])
2503 self._progress_queue.add2queue(str(uuid.uuid4()),
2504 'start publisher for %s' % topic_name,
2505 nm.starter().runNodeWithoutConfig,
2506 (nm.nameres().address(self.masteruri), 'rostopic', 'rostopic', 'rostopic_pub%s%s%s' % (topic_name, opt_name_suf, str(rospy.Time.now())), [pub_cmd], self.masteruri, False, self.current_user))
2507 self._progress_queue.start()
2508 return True
2509 else:
2510 return False
2511 except Exception, e:
2512 rospy.logwarn("Publish topic '%s' failed: %s", str(topic_name), str(e))
2513 WarningMessageBox(QMessageBox.Warning, "Publish topic error",
2514 ''.join(['Publish topic ', topic_name, ' failed!']),
2515 str(e)).exec_()
2516 print traceback.format_exc(1)
2517 return False
2518
2520 result = dict()
2521 for key, value in param_dict.iteritems():
2522 if isinstance(value, dict):
2523 result[key] = self._rem_empty_lists(value)
2524 elif not (isinstance(value, list) and not value):
2525 result[key] = value
2526 return result
2527
2529 topic_names = []
2530 if topic_name:
2531 topic_names.append(topic_name)
2532 else:
2533 selectedTopics = self.topicsFromIndexes(self.masterTab.topicsView.selectionModel().selectedIndexes())
2534 topic_names = ['%s' % topic.name for topic in selectedTopics]
2535 if self.master_info is not None:
2536 nodes2stop = []
2537 for topic in topic_names:
2538 topic_prefix = '/rostopic_pub%s_' % topic
2539 node_names = self.master_info.node_names
2540 for n in node_names:
2541 if n.startswith(topic_prefix):
2542 nodes2stop.append(n)
2543 self.stop_nodes_by_name(nodes2stop)
2544
2546 '''
2547 Shows the output of the topic in a terminal.
2548 '''
2549 selectedTopics = self.topicsFromIndexes(self.masterTab.topicsView.selectionModel().selectedIndexes())
2550 ret = True
2551 if len(selectedTopics) > 5:
2552 ret = QMessageBox.question(self, "Show echo", "You are going to open the echo of " + str(len(selectedTopics)) + " topics at once\nContinue?", QMessageBox.Ok, QMessageBox.Cancel)
2553 ret = (ret == QMessageBox.Ok)
2554 if ret:
2555 for topic in selectedTopics:
2556 self._add_topic_output2queue(topic, show_hz_only, use_ssh)
2557
2559 '''
2560 Shows the topic output in a new window.
2561 '''
2562 if self.master_info is not None:
2563 topic = self.master_info.getTopic("%s" % topic_name)
2564 if topic is not None:
2565 self._add_topic_output2queue(topic, show_hz_only, use_ssh)
2566 else:
2567 rospy.logwarn("topic not found: %s" % topic_name)
2568
2570 try:
2571
2572 import shlex
2573 env = dict(os.environ)
2574 env["ROS_MASTER_URI"] = str(self.masteruri)
2575 nodename = 'echo_%s%s%s%s' % ('hz_' if show_hz_only else '', 'ssh_' if use_ssh else '', str(get_hostname(self.masteruri)), topic.name)
2576 cmd = 'rosrun node_manager_fkie node_manager --echo %s %s %s %s __name:=%s' % (topic.name, topic.type, '--hz' if show_hz_only else '', '--ssh' if use_ssh else '', nodename)
2577 rospy.loginfo("Echo topic: %s" % cmd)
2578 ps = SupervisedPopen(shlex.split(cmd), env=env, stderr=None, close_fds=True, object_id=topic.name, description='Echo topic: %s' % topic.name)
2579 ps.finished.connect(self._topic_dialog_closed)
2580 self.__echo_topics_dialogs[topic.name] = ps
2581 except Exception, e:
2582 rospy.logwarn("Echo topic '%s' failed: %s" % (topic.name, e))
2583 WarningMessageBox(QMessageBox.Warning, "Echo of topic error",
2584 'Echo of topic %s failed!' % topic.name,
2585 '%s' % e).exec_()
2586
2588 if topic_name in self.__echo_topics_dialogs:
2589 del self.__echo_topics_dialogs[topic_name]
2590
2592 '''
2593 calls a service.
2594 '''
2595 selectedServices = self.servicesFromIndexes(self.masterTab.servicesView.selectionModel().selectedIndexes())
2596 for service in selectedServices:
2597 param = ServiceDialog(service, self)
2598 param.show()
2599
2601 service = self.master_info.getService(str(service_name))
2602 if service is not None:
2603 param = ServiceDialog(service, self)
2604 param.show()
2605
2607 '''
2608 Filter the displayed nodes
2609 '''
2610 self.node_proxy_model.setFilterRegExp(QRegExp(text, Qt.CaseInsensitive, QRegExp.Wildcard))
2611
2613 '''
2614 Filter the displayed topics
2615 '''
2616 self.topic_proxyModel.setFilterRegExp(QRegExp(text, Qt.CaseInsensitive, QRegExp.Wildcard))
2617
2619 '''
2620 Filter the displayed services
2621 '''
2622 self.service_proxyModel.setFilterRegExp(QRegExp(text, Qt.CaseInsensitive, QRegExp.Wildcard))
2623
2625 '''
2626 Filter the displayed parameter
2627 '''
2628 self.parameter_proxyModel.setFilterRegExp(QRegExp(text, Qt.CaseInsensitive, QRegExp.Wildcard))
2629
2635
2637 '''
2638 Adds a parameter to the ROS parameter server.
2639 '''
2640 selectedParameter = self.parameterFromIndexes(self.masterTab.parameterView.selectionModel().selectedIndexes())
2641 ns = '/'
2642 if selectedParameter:
2643 ns = roslib.names.namespace(selectedParameter[0][0])
2644 fields = {'name': ('string', ns), 'type': ('string', ['string', 'int', 'float', 'bool', 'list']), 'value': ('string', '')}
2645 newparamDia = ParameterDialog(fields, parent=self)
2646 newparamDia.setWindowTitle('Add new parameter')
2647 newparamDia.setFilterVisible(False)
2648 newparamDia.resize(400, 120)
2649 newparamDia.accepted.connect(self._on_add_parameter_accepted)
2650 newparamDia.setFocusField('name')
2651 newparamDia.show()
2652 newparamDia.raise_()
2653 newparamDia.activateWindow()
2654
2656 if isinstance(self.sender(), ParameterDialog):
2657 params = self.sender().getKeywords()
2658 try:
2659 if params['type'] == 'int':
2660 value = int(params['value'])
2661 elif params['type'] == 'float':
2662 value = float(params['value'])
2663 elif params['type'] == 'bool':
2664 value = bool(params['value'].lower() in ("yes", "true", "t", "1"))
2665 elif params['type'] == 'list':
2666 try:
2667 import yaml
2668 value = [yaml.load(params['value'])]
2669
2670
2671
2672 if value is None:
2673 value = []
2674 except yaml.MarkedYAMLError, e:
2675 QMessageBox.warning(self, self.tr("Warning"), "yaml error: %s" % str(e), QMessageBox.Ok)
2676 return
2677 else:
2678 value = params['value']
2679 self.parameterHandler.deliverParameter(self.masteruri, {params['name']: value})
2680 self.parameterHandler.requestParameterList(self.masteruri)
2681 self.sender().close()
2682 except (KeyError, ValueError), e:
2683 WarningMessageBox(QMessageBox.Warning, "Warning",
2684 'Error while add a parameter to the ROS parameter server',
2685 str(e)).exec_()
2686
2688 '''
2689 Deletes the parameter from the ROS parameter server.
2690 '''
2691 selectedParameter = self.parameterFromIndexes(self.masterTab.parameterView.selectionModel().selectedIndexes())
2692 try:
2693 socket.setdefaulttimeout(15)
2694 name = rospy.get_name()
2695 master = xmlrpclib.ServerProxy(self.masteruri)
2696 master_multi = xmlrpclib.MultiCall(master)
2697 for (key, _) in selectedParameter:
2698 master_multi.deleteParam(name, key)
2699 r = master_multi()
2700 for code, msg, parameter in r:
2701 if code != 1:
2702 rospy.logwarn("Error on delete parameter '%s': %s", parameter, msg)
2703 except:
2704 rospy.logwarn("Error on delete parameter: %s", traceback.format_exc(1))
2705 WarningMessageBox(QMessageBox.Warning, "Warning",
2706 'Error while delete a parameter to the ROS parameter server',
2707 traceback.format_exc(1)).exec_()
2708 else:
2709 self.on_get_parameter_clicked()
2710 finally:
2711 socket.setdefaulttimeout(None)
2712
2714 '''
2715 Stores selected parameter to a file.
2716 '''
2717 selectedParameter = self.parameterFromIndexes(self.masterTab.parameterView.selectionModel().selectedIndexes())
2718 if selectedParameter:
2719
2720 (fileName, _) = QFileDialog.getSaveFileName(self,
2721 "Save parameter",
2722 self.__current_path,
2723 "YAML files (*.yaml);;All files (*)")
2724 if fileName:
2725 self.__current_path = os.path.dirname(fileName)
2726 try:
2727 with open(fileName, 'w+') as f:
2728 values = dict()
2729
2730 for (key, value) in selectedParameter:
2731 keys = key.strip(rospy.names.SEP).split(rospy.names.SEP)
2732 curr_v = values
2733 for k in keys:
2734 if k in curr_v:
2735 curr_v = curr_v[k]
2736 elif k != keys[-1]:
2737 curr_v[k] = dict()
2738 curr_v = curr_v[k]
2739 else:
2740 curr_v[k] = value
2741 import yaml
2742
2743 f.write(yaml.dump(values, default_flow_style=False))
2744 except Exception as e:
2745 print traceback.format_exc(1)
2746 WarningMessageBox(QMessageBox.Warning, "Save parameter Error",
2747 'Error while save parameter',
2748 str(e)).exec_()
2749
2751 '''
2752 used to avoid the adding of \\ for each \ in a string of a list
2753 '''
2754 if liste and isinstance(liste, list):
2755 result = []
2756 for l in liste:
2757 val = l
2758 if isinstance(l, (str, unicode)):
2759 val = l.replace("\\n", "\n")
2760
2761 elif isinstance(l, list):
2762 val = self._replaceDoubleSlash(l)
2763 result.append(val)
2764 return result
2765 return liste
2766
2768 '''
2769 add changes to the ROS parameter server
2770 '''
2771 if isinstance(item, ParameterValueItem):
2772 try:
2773 if isinstance(item.value, bool):
2774 value = bool(item.text().lower() in ("yes", "true", "t", "1"))
2775 elif isinstance(item.value, int):
2776 value = int(item.text())
2777 elif isinstance(item.value, float):
2778 value = float(item.text())
2779 elif isinstance(item.value, list):
2780 try:
2781 import yaml
2782 value = yaml.load(item.text())
2783
2784
2785
2786 if value is None:
2787 value = []
2788 value = self._replaceDoubleSlash(value)
2789 except yaml.MarkedYAMLError, e:
2790 QMessageBox.warning(self, self.tr("Warning"), "yaml error: %s" % str(e), QMessageBox.Ok)
2791 item.setText(unicode(item.value))
2792 return
2793 else:
2794 value = item.text()
2795 self.parameterHandler.deliverParameter(self.masteruri, {item.name: value})
2796 item.value = value
2797 except ValueError, e:
2798 WarningMessageBox(QMessageBox.Warning, "Warning",
2799 'Error while add changes to the ROS parameter server',
2800 str(e)).exec_()
2801 item.setText(item.value)
2802
2804 '''
2805 @param masteruri: The URI of the ROS parameter server
2806 @type masteruri: C{str}
2807 @param code: The return code of the request. If not 1, the message is set and the list can be ignored.
2808 @type code: C{int}
2809 @param msg: The message of the result.
2810 @type msg: C{str}
2811 @param params: The list the parameter names.
2812 @type params: C{[str]}
2813 '''
2814 if code == 1:
2815 params.sort()
2816 self.parameterHandler.requestParameterValues(masteruri, params)
2817
2819 '''
2820 @param masteruri: The URI of the ROS parameter server
2821 @type masteruri: C{str}
2822 @param code: The return code of the request. If not 1, the message is set and the list can be ignored.
2823 @type code: C{int}
2824 @param msg: The message of the result.
2825 @type msg: C{str}
2826 @param params: The dictionary the parameter names and request result.
2827 @type params: C{dict(paramName : (code, statusMessage, parameterValue))}
2828 '''
2829 if code == 1:
2830 result = {}
2831 for p, (code_n, _, val) in params.items():
2832 if code_n == 1:
2833 result[p] = val
2834 else:
2835 result[p] = ''
2836 if p == '/use_sim_time':
2837 self.__use_sim_time = (code_n == 1 and val)
2838 self.parameter_model.updateModelData(result)
2839 else:
2840 rospy.logwarn("Error on retrieve parameter from %s: %s", str(masteruri), str(msg))
2841
2843 '''
2844 @param masteruri: The URI of the ROS parameter server
2845 @type masteruri: C{str}
2846 @param code: The return code of the request. If not 1, the message is set and the list can be ignored.
2847 @type code: C{int}
2848 @param msg: The message of the result.
2849 @type msg: C{str}
2850 @param params: The dictionary the parameter names and request result.
2851 @type params: C{dict(paramName : (code, statusMessage, parameterValue))}
2852 '''
2853 errmsg = ''
2854 if code == 1:
2855 for p, (code_n, msg, _) in params.items():
2856 if code_n != 1:
2857 errmsg = '%s: %s\n%s' % (p, errmsg, msg)
2858 else:
2859 errmsg = msg if msg else 'Unknown error on set parameter'
2860 if errmsg:
2861 WarningMessageBox(QMessageBox.Warning, "Warning",
2862 'Error while delivering parameter to the ROS parameter server',
2863 errmsg).exec_()
2864
2866 '''
2867 @param masteruri: The URI of the ROS parameter server
2868 @type masteruri: C{str}
2869 @param code: The return code of the request. If not 1, the message is set and the list can be ignored.
2870 @type code: C{int}
2871 @param msg: The message of the result.
2872 @type msg: C{str}
2873 @param params: The dictionary the parameter names and request result.
2874 @type params: C{dict(paramName : (code, statusMessage, parameterValue))}
2875 '''
2876 robot_icon_found = False
2877 if code == 1:
2878 for p, (code_n, _, val) in params.items():
2879 if p == '/use_sim_time':
2880 self.__use_sim_time = (code_n == 1 and val)
2881 elif p == '/robot_icon':
2882 robot_icon_found = True
2883 self.__current_parameter_robot_icon = val if code_n == 1 else ''
2884 self.update_robot_icon()
2885 elif p.startswith('/roslaunch/uris'):
2886 if code_n == 1:
2887 for _, value in val.items():
2888 self.launch_server_handler.updateLaunchServerInfo(value)
2889 else:
2890 rospy.logwarn("Error on retrieve sim parameter value from %s: %s", str(masteruri), msg)
2891 if not robot_icon_found:
2892 self.__current_parameter_robot_icon = ''
2893 self.update_robot_icon()
2894
2896 '''
2897 Requests the ROS master URI from the ROS master through the RPC interface and
2898 returns it. The 'materuri' attribute will be set to the requested value.
2899 @return: ROS master URI
2900 @rtype: C{str} or C{None}
2901 '''
2902 if not hasattr(self, '_nm_materuri') or self._nm_materuri is None:
2903 masteruri = masteruri_from_ros()
2904 master = xmlrpclib.ServerProxy(masteruri)
2905 _, _, self._nm_materuri = master.getUri(rospy.get_name())
2906 return self._nm_materuri
2907
2909 nodes = self.getNode(diagnostic_status.name)
2910 for node in nodes:
2911 node.append_diagnostic_status(diagnostic_status)
2912 if nodes:
2913
2914 if self.masterTab.tabWidget.tabText(self.masterTab.tabWidget.currentIndex()) != 'Nodes':
2915 return
2916 selections = self.masterTab.nodeTreeView.selectionModel().selectedIndexes()
2917 selectedNodes = self.nodesFromIndexes(selections)
2918 if len(selectedNodes) == 1:
2919 node = selectedNodes[0]
2920 if node.name == diagnostic_status.name:
2921 self.on_node_selection_changed(None, None)
2922
2923
2924
2925
2926
2928 '''
2929 Selects all nodes of a host with given index
2930 @param index: the index of the host in the tree model
2931 @type index: C{int}
2932 '''
2933 root = self.masterTab.nodeTreeView.model().index(index, 0)
2934 if not root.isValid():
2935 return
2936 self.masterTab.nodeTreeView.expand(root)
2937
2938 last_row_index = len(self.node_tree_model.header) - 1
2939
2940 i = 0
2941 selection = QItemSelection()
2942 while root.child(i, 0).isValid():
2943 index = root.child(i, 0)
2944 model_index = self.node_proxy_model.mapToSource(index)
2945 item = self.node_tree_model.itemFromIndex(model_index)
2946 if item is not None and not self._is_in_ignore_list(item.name):
2947 selection.append(QItemSelectionRange(index, root.child(i, last_row_index)))
2948 i = i + 1
2949
2950 self.masterTab.nodeTreeView.selectionModel().select(selection, QItemSelectionModel.ClearAndSelect)
2951
2953 for i in self._stop_ignores:
2954 if name.endswith(i):
2955 return True
2956 return False
2957
2960
2963
2966
2969
2972
2974 self.masterTab.nodeTreeView.selectionModel().clearSelection()
2975 self.masterTab.nodeTreeView.collapseAll()
2976
2978 result = ''
2979 if self.masterTab.nodeTreeView.hasFocus():
2980 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
2981 for node in selectedNodes:
2982 try:
2983 result = '%s %s' % (result, node.name)
2984 except Exception:
2985 pass
2986 elif self.masterTab.topicsView.hasFocus():
2987 selectedTopics = self.topicsFromIndexes(self.masterTab.topicsView.selectionModel().selectedIndexes())
2988 for topic in selectedTopics:
2989 try:
2990 result = '%s %s' % (result, topic.name)
2991 except Exception:
2992 pass
2993 elif self.masterTab.servicesView.hasFocus():
2994 selectedServices = self.servicesFromIndexes(self.masterTab.servicesView.selectionModel().selectedIndexes())
2995 for service in selectedServices:
2996 try:
2997 result = '%s %s' % (result, service.name)
2998 except Exception:
2999 pass
3000 elif self.masterTab.parameterView.hasFocus():
3001 selectedParameter = self.parameterFromIndexes(self.masterTab.parameterView.selectionModel().selectedIndexes())
3002 for (name, _value) in selectedParameter:
3003 try:
3004 result = '%s %s' % (result, name)
3005 except Exception:
3006 pass
3007 QApplication.clipboard().setText(result.strip())
3008
3010 result = ''
3011 if self.masterTab.nodeTreeView.hasFocus():
3012 selectedNodes = self.nodesFromIndexes(self.masterTab.nodeTreeView.selectionModel().selectedIndexes())
3013 for node in selectedNodes:
3014 try:
3015 result = '%s %s' % (result, node.pid)
3016 except Exception:
3017 pass
3018 elif self.masterTab.topicsView.hasFocus():
3019 selectedTopics = self.topicsFromIndexes(self.masterTab.topicsView.selectionModel().selectedIndexes())
3020 for topic in selectedTopics:
3021 try:
3022 result = '%s %s' % (result, topic.type)
3023 except Exception:
3024 pass
3025 elif self.masterTab.servicesView.hasFocus():
3026 selectedServices = self.servicesFromIndexes(self.masterTab.servicesView.selectionModel().selectedIndexes())
3027 for service in selectedServices:
3028 try:
3029 result = '%s %s' % (result, service.type)
3030 except Exception:
3031 pass
3032 elif self.masterTab.parameterView.hasFocus():
3033 selectedParameter = self.parameterFromIndexes(self.masterTab.parameterView.selectionModel().selectedIndexes())
3034 for (_, value) in selectedParameter:
3035 try:
3036 result = '%s %s' % (result, value)
3037 except Exception:
3038 pass
3039 QApplication.clipboard().setText(result.strip())
3040
3047
3049 '''
3050 Perform filtering on column 0 (Name)
3051 '''
3052 if not self.filterRegExp().pattern():
3053 return True
3054 if (self.filterAcceptsRowItself(sourceRow, sourceParent)):
3055 return True
3056
3057
3058
3059
3060
3061
3062
3063 if (self.hasAcceptedChildren(sourceRow, sourceParent)):
3064 return True
3065 return False
3066
3068 index = self.sourceModel().index(sourceRow, 0, sourceParent)
3069 if not index.isValid():
3070 return False
3071
3072 childCount = index.model().rowCount(index)
3073 if childCount == 0:
3074 return False
3075 for i in range(childCount):
3076 if (self.filterAcceptsRowItself(i, index)):
3077 return True
3078
3079 if (self.hasAcceptedChildren(i, index)):
3080 return True
3081 return False
3082
3084 index0 = self.sourceModel().index(sourceRow, 0, sourceParent)
3085 item = self.sourceModel().data(index0)
3086 if item is not None:
3087
3088 if '{' not in item:
3089 regex = self.filterRegExp()
3090 return (regex.indexIn(self.sourceModel().data(index0)) != -1)
3091 return False
3092
3095
3097 '''
3098 Perform filtering on columns 0 and 3 (Name, Type)
3099 '''
3100 index0 = self.sourceModel().index(sourceRow, 0, sourceParent)
3101 index3 = self.sourceModel().index(sourceRow, 3, sourceParent)
3102 regex = self.filterRegExp()
3103 return (regex.indexIn(self.sourceModel().data(index0, TopicItem.NAME_ROLE)) != -1 or
3104 regex.indexIn(self.sourceModel().data(index3)) != -1)
3105
3108
3110 '''
3111 Perform filtering on columns 0 and 1 (Name, Type)
3112 '''
3113 index0 = self.sourceModel().index(sourceRow, 0, sourceParent)
3114
3115 regex = self.filterRegExp()
3116 return (regex.indexIn(self.sourceModel().data(index0, ServiceItem.NAME_ROLE)) != -1 or
3117 regex.indexIn(self.sourceModel().data(index0, ServiceItem.TYPE_ROLE)) != -1)
3118
3121
3123 '''
3124 Perform filtering on columns 0 and 1 (Name, Value)
3125 '''
3126 index0 = self.sourceModel().index(sourceRow, 0, sourceParent)
3127
3128 index2 = self.sourceModel().index(sourceRow, 2, sourceParent)
3129 regex = self.filterRegExp()
3130 return (regex.indexIn(self.sourceModel().data(index0, ParameterNameItem.NAME_ROLE)) != -1 or
3131 regex.indexIn(self.sourceModel().data(index2, ParameterValueItem.VALUE_ROLE)) != -1)
3132