launch_widget.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Isaac Saito
00034 
00035 import os
00036 import sys
00037 
00038 from python_qt_binding import loadUi
00039 from python_qt_binding.QtCore import QModelIndex, Signal
00040 from python_qt_binding.QtGui import QStandardItem, QStandardItemModel
00041 from python_qt_binding.QtWidgets import QDialog
00042 from rosgraph import rosenv
00043 import roslaunch
00044 from roslaunch.core import RLException
00045 import rospkg
00046 import rospy
00047 
00048 # from rqt_console.console_widget import ConsoleWidget
00049 from rqt_launch.node_proxy import NodeProxy
00050 from rqt_launch.node_controller import NodeController
00051 from rqt_launch.node_delegate import NodeDelegate
00052 from rqt_launch.status_indicator import StatusIndicator
00053 from rqt_py_common.rqt_roscomm_util import RqtRoscommUtil
00054 
00055 
00056 class LaunchWidget(QDialog):
00057 
00058     '''#TODO: comment
00059     '''
00060 
00061     # To be connected to PluginContainerWidget
00062     sig_sysmsg = Signal(str)
00063 
00064     def __init__(self, parent):
00065         '''
00066         @type parent: LaunchMain
00067         '''
00068         super(LaunchWidget, self).__init__()
00069         self._parent = parent
00070 
00071         self._config = None
00072 
00073         # TODO: should be configurable from gui
00074         self._port_roscore = 11311
00075 
00076         self._run_id = None
00077 
00078         self._rospack = rospkg.RosPack()
00079         ui_file = os.path.join(self._rospack.get_path('rqt_launch'),
00080                                'resource', 'launch_widget.ui')
00081         loadUi(ui_file, self)
00082 
00083         # row=0 allows any number of rows to be added.
00084         self._datamodel = QStandardItemModel(0, 1)
00085 
00086         master_uri = rosenv.get_master_uri()
00087         rospy.loginfo('LaunchWidget master_uri={}'.format(master_uri))
00088         self._delegate = NodeDelegate(master_uri,
00089                                       self._rospack)
00090         self._treeview.setModel(self._datamodel)
00091         self._treeview.setItemDelegate(self._delegate)
00092 
00093         # NodeController used in controller class for launch operation.
00094         self._node_controllers = []
00095 
00096         self._pushbutton_load_params.clicked.connect(self._parent.load_params)
00097         self._pushbutton_start_all.clicked.connect(self._parent.start_all)
00098         self._pushbutton_stop_all.clicked.connect(self._parent.stop_all)
00099         # Bind package selection with .launch file selection.
00100         self._combobox_pkg.currentIndexChanged[str].connect(
00101             self._refresh_launchfiles)
00102         # Bind a launch file selection with launch GUI generation.
00103         self._combobox_launchfile_name.currentIndexChanged[str].connect(
00104             self._load_launchfile_slot)
00105         self._update_pkgs_contain_launchfiles()
00106 
00107         # Used for removing previous nodes
00108         self._num_nodes_previous = 0
00109 
00110     def _load_launchfile_slot(self, launchfile_name):
00111         # Not yet sure why, but everytime combobox.currentIndexChanged occurs,
00112         # this method gets called twice with launchfile_name=='' in 1st call.
00113         if launchfile_name is None or launchfile_name == '':
00114             return
00115 
00116         _config = None
00117 
00118         rospy.logdebug('_load_launchfile_slot launchfile_name={}'.format(
00119             launchfile_name))
00120 
00121         try:
00122             _config = self._create_launchconfig(launchfile_name,
00123                                                 self._port_roscore)
00124             # TODO: folder_name_launchfile should be able to specify arbitrarily
00125             # _create_launchconfig takes 3rd arg for it.
00126 
00127         except IndexError as e:
00128             msg = 'IndexError={} launchfile={}'.format(e.message,
00129                                                        launchfile_name)
00130             rospy.logerr(msg)
00131             self.sig_sysmsg.emit(msg)
00132             return
00133         except RLException as e:
00134             msg = 'RLException={} launchfile={}'.format(e.message,
00135                                                         launchfile_name)
00136             rospy.logerr(msg)
00137             self.sig_sysmsg.emit(msg)
00138             return
00139 
00140         self._create_widgets_for_launchfile(_config)
00141 
00142     def _create_launchconfig(self, launchfile_name, port_roscore=11311,
00143                              folder_name_launchfile='launch'):
00144         '''
00145         @rtype: ROSLaunchConfig
00146         @raises RLException: raised by roslaunch.config.load_config_default.
00147         '''
00148 
00149         pkg_name = self._combobox_pkg.currentText()
00150 
00151         try:
00152             launchfile = os.path.join(self._rospack.get_path(pkg_name),
00153                                       folder_name_launchfile, launchfile_name)
00154         except IndexError as e:
00155             raise RLException('IndexError: {}'.format(e.message))
00156 
00157         try:
00158             launch_config = roslaunch.config.load_config_default([launchfile],
00159                                                                  port_roscore)
00160         except rospkg.common.ResourceNotFound as e:
00161             raise RLException('ResourceNotFound: {}'.format(e.message))
00162         except RLException as e:
00163             raise e
00164 
00165         return launch_config
00166 
00167     def _create_widgets_for_launchfile(self, config):
00168         self._config = config
00169 
00170         # Delete old nodes' GUIs.
00171         self._node_controllers = []
00172 
00173         # These lines seem to remove indexWidgets previously set on treeview.
00174         # Per suggestion in API doc, we are not using reset(). Instead,
00175         # using 2 methods below without any operation in between, which
00176         # I suspect might be inproper.
00177         # http://qt-project.org/doc/qt-4.8/qabstractitemmodel.html#reset
00178         self._datamodel.beginResetModel()
00179         self._datamodel.endResetModel()
00180 
00181         # Need to store the num of nodes outside of the loop -- this will
00182         # be used for removing excessive previous node rows.
00183         order_xmlelement = 0
00184         # Loop per xml element
00185         for order_xmlelement, node in enumerate(self._config.nodes):
00186             proxy = NodeProxy(self._run_id, self._config.master.uri, node)
00187 
00188             # TODO: consider using QIcon.fromTheme()
00189             status_label = StatusIndicator()
00190 
00191             qindex_nodewidget = self._datamodel.index(order_xmlelement,
00192                                                       0, QModelIndex())
00193             node_widget = self._delegate.create_node_widget(qindex_nodewidget,
00194                                                             proxy.config,
00195                                                             status_label)
00196 
00197             # TODO: Ideally find a way so that we don't need this block.
00198             # BEGIN If these lines are missing, widget won't be shown either.
00199             std_item = QStandardItem(
00200                 # node_widget.get_node_name()
00201             )
00202             self._datamodel.setItem(order_xmlelement, 0, std_item)
00203             # END If these lines are missing, widget won't be shown either.
00204 
00205             self._treeview.setIndexWidget(qindex_nodewidget, node_widget)
00206 
00207             node_controller = NodeController(proxy, node_widget)
00208             self._node_controllers.append(node_controller)
00209 
00210             node_widget.connect_start_stop_button(
00211                 node_controller.start_stop_slot)
00212             rospy.logdebug('loop #%d proxy.config.namespace=%s ' +
00213                            'proxy.config.name=%s',
00214                            order_xmlelement, proxy.config.namespace,
00215                            proxy.config.name)
00216 
00217         self._num_nodes_previous = order_xmlelement
00218 
00219         self._parent.set_node_controllers(self._node_controllers)
00220 
00221     def _update_pkgs_contain_launchfiles(self):
00222         '''
00223         Inspired by rqt_msg.MessageWidget._update_pkgs_contain_launchfiles
00224         '''
00225         packages = sorted([pkg_tuple[0]
00226                            for pkg_tuple
00227                            in RqtRoscommUtil.iterate_packages('launch')])
00228         self._package_list = packages
00229         rospy.logdebug('pkgs={}'.format(self._package_list))
00230         self._combobox_pkg.clear()
00231         self._combobox_pkg.addItems(self._package_list)
00232         self._combobox_pkg.setCurrentIndex(0)
00233 
00234     def _refresh_launchfiles(self, package=None):
00235         '''
00236         Inspired by rqt_msg.MessageWidget._refresh_msgs
00237         '''
00238         if package is None or len(package) == 0:
00239             return
00240         self._launchfile_instances = []  # Launch[]
00241         # TODO: RqtRoscommUtil.list_files's 2nd arg 'subdir' should NOT be
00242         # hardcoded later.
00243         _launch_instance_list = RqtRoscommUtil.list_files(package,
00244                                                           'launch')
00245 
00246         rospy.logdebug(
00247             '_refresh_launches package={} instance_list={}'.format(package, _launch_instance_list))
00248 
00249         self._launchfile_instances = [x.split('/')[1]
00250                                       for x in _launch_instance_list]
00251 
00252         self._combobox_launchfile_name.clear()
00253         self._combobox_launchfile_name.addItems(self._launchfile_instances)
00254 
00255     def load_parameters(self):
00256         '''Loads all global parameters into roscore.'''
00257         run_id = self._run_id if self._run_id is not None \
00258             else roslaunch.rlutil.get_or_generate_uuid(None, True)
00259         runner = roslaunch.ROSLaunchRunner(run_id, self._config)
00260         runner._load_parameters()
00261 
00262         msg = 'Loaded %d parameters to parameter server.' \
00263               % len(self._config.params)
00264         self.sig_sysmsg.emit(msg)
00265         rospy.logdebug(msg)
00266 
00267     def save_settings(self, plugin_settings, instance_settings):
00268         # instance_settings.set_value('splitter', self._splitter.saveState())
00269         pass
00270 
00271     def restore_settings(self, plugin_settings, instance_settings):
00272         # if instance_settings.contains('splitter'):
00273         #     self._splitter.restoreState(instance_settings.value('splitter'))
00274         # else:
00275         #     self._splitter.setSizes([100, 100, 200])
00276         pass
00277 
00278 
00279 if __name__ == '__main__':
00280     # main should be used only for debug purpose.
00281     # This launches this QWidget as a standalone rqt gui.
00282     from rqt_gui.main import Main
00283 
00284     main = Main()
00285     sys.exit(main.main(sys.argv, standalone='rqt_launch'))


rqt_launch
Author(s): Isaac Saito, Stuart Glaser
autogenerated on Thu Jun 6 2019 21:28:15