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 QDialog, QStandardItem, \
00041                                     QStandardItemModel
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     '''#TODO: comment
00058     '''
00059 
00060     # To be connected to PluginContainerWidget
00061     sig_sysmsg = Signal(str)
00062 
00063     def __init__(self, parent):
00064         '''
00065         @type parent: LaunchMain
00066         '''
00067         super(LaunchWidget, self).__init__()
00068         self._parent = parent
00069 
00070         self._config = None
00071 
00072         #TODO: should be configurable from gui
00073         self._port_roscore = 11311
00074 
00075         self._run_id = None
00076 
00077         self._rospack = rospkg.RosPack()
00078         ui_file = os.path.join(self._rospack.get_path('rqt_launch'),
00079                                'resource', 'launch_widget.ui')
00080         loadUi(ui_file, self)
00081 
00082         # row=0 allows any number of rows to be added.
00083         self._datamodel = QStandardItemModel(0, 1)
00084 
00085         master_uri = rosenv.get_master_uri()
00086         rospy.loginfo('LaunchWidget master_uri={}'.format(master_uri))
00087         self._delegate = NodeDelegate(master_uri,
00088                                       self._rospack)
00089         self._treeview.setModel(self._datamodel)
00090         self._treeview.setItemDelegate(self._delegate)
00091 
00092         # NodeController used in controller class for launch operation.
00093         self._node_controllers = []
00094 
00095         self._pushbutton_start_all.clicked.connect(self._parent.start_all)
00096         self._pushbutton_stop_all.clicked.connect(self._parent.stop_all)
00097         # Bind package selection with .launch file selection.
00098         self._combobox_pkg.currentIndexChanged[str].connect(
00099                                                  self._refresh_launchfiles)
00100         # Bind a launch file selection with launch GUI generation.
00101         self._combobox_launchfile_name.currentIndexChanged[str].connect(
00102                                                  self._load_launchfile_slot)
00103         self._update_pkgs_contain_launchfiles()
00104 
00105         # Used for removing previous nodes
00106         self._num_nodes_previous = 0
00107 
00108     def _load_launchfile_slot(self, launchfile_name):
00109         # Not yet sure why, but everytime combobox.currentIndexChanged occurs,
00110         # this method gets called twice with launchfile_name=='' in 1st call.
00111         if launchfile_name == None or launchfile_name == '':
00112             return
00113 
00114         _config = None
00115 
00116         rospy.logdebug('_load_launchfile_slot launchfile_name={}'.format(
00117                                                            launchfile_name))
00118 
00119         try:
00120             _config = self._create_launchconfig(launchfile_name,
00121                                                 self._port_roscore)
00122             #TODO: folder_name_launchfile should be able to specify arbitrarily
00123             # _create_launchconfig takes 3rd arg for it.
00124 
00125         except IndexError as e:
00126             msg = 'IndexError={} launchfile={}'.format(e.message,
00127                                                        launchfile_name)
00128             rospy.logerr(msg)
00129             self.sig_sysmsg.emit(msg)
00130             return
00131         except RLException as e:
00132             msg = 'RLException={} launchfile={}'.format(e.message,
00133                                                         launchfile_name)
00134             rospy.logerr(msg)
00135             self.sig_sysmsg.emit(msg)
00136             return
00137 
00138         self._create_widgets_for_launchfile(_config)
00139 
00140     def _create_launchconfig(self, launchfile_name, port_roscore=11311,
00141                              folder_name_launchfile='launch'):
00142         '''
00143         @rtype: ROSLaunchConfig
00144         @raises RLException: raised by roslaunch.config.load_config_default.
00145         '''
00146 
00147         pkg_name = self._combobox_pkg.currentText()
00148 
00149         try:
00150             launchfile = os.path.join(self._rospack.get_path(pkg_name),
00151                                       folder_name_launchfile, launchfile_name)
00152         except IndexError as e:
00153             raise RLException('IndexError: {}'.format(e.message))
00154 
00155         try:
00156             launch_config = roslaunch.config.load_config_default([launchfile],
00157                                                                  port_roscore)
00158         except rospkg.common.ResourceNotFound as e:
00159             raise RLException('ResourceNotFound: {}'.format(e.message))
00160         except RLException as e:
00161             raise e
00162 
00163         return launch_config
00164 
00165     def _create_widgets_for_launchfile(self, config):
00166         self._config = config
00167 
00168         # Delete old nodes' GUIs.
00169         self._node_controllers = []
00170 
00171         # These lines seem to remove indexWidgets previously set on treeview.
00172         # Per suggestion in API doc, we are not using reset(). Instead,
00173         # using 2 methods below without any operation in between, which
00174         # I suspect might be inproper.
00175         # http://qt-project.org/doc/qt-4.8/qabstractitemmodel.html#reset
00176         self._datamodel.beginResetModel()
00177         self._datamodel.endResetModel()
00178 
00179         # Need to store the num of nodes outside of the loop -- this will
00180         # be used for removing excessive previous node rows.
00181         order_xmlelement = 0
00182         # Loop per xml element
00183         for order_xmlelement, node in enumerate(self._config.nodes):
00184             proxy = NodeProxy(self._run_id, self._config.master.uri, node)
00185 
00186             # TODO: consider using QIcon.fromTheme()
00187             status_label = StatusIndicator()
00188 
00189             qindex_nodewidget = self._datamodel.index(order_xmlelement,
00190                                                        0, QModelIndex())
00191             node_widget = self._delegate.create_node_widget(qindex_nodewidget,
00192                                                             proxy.config,
00193                                                             status_label)
00194 
00195             #TODO: Ideally find a way so that we don't need this block.
00196             #BEGIN If these lines are missing, widget won't be shown either.
00197             std_item = QStandardItem(
00198                                      #node_widget.get_node_name()
00199                                      )
00200             self._datamodel.setItem(order_xmlelement, 0, std_item)
00201             #END If these lines are missing, widget won't be shown either.
00202 
00203             self._treeview.setIndexWidget(qindex_nodewidget, node_widget)
00204 
00205             node_controller = NodeController(proxy, node_widget)
00206             self._node_controllers.append(node_controller)
00207 
00208             node_widget.connect_start_stop_button( \
00209                                        node_controller.start_stop_slot)
00210             rospy.logdebug('loop #%d proxy.config.namespace=%s ' +
00211                           'proxy.config.name=%s',
00212                           order_xmlelement, proxy.config.namespace,
00213                           proxy.config.name)
00214 
00215         self._num_nodes_previous = order_xmlelement
00216 
00217         self._parent.set_node_controllers(self._node_controllers)
00218 
00219     def _update_pkgs_contain_launchfiles(self):
00220         '''
00221         Inspired by rqt_msg.MessageWidget._update_pkgs_contain_launchfiles
00222         '''
00223         packages = sorted([pkg_tuple[0]
00224                            for pkg_tuple
00225                            in RqtRoscommUtil.iterate_packages('launch')])
00226         self._package_list = packages
00227         rospy.logdebug('pkgs={}'.format(self._package_list))
00228         self._combobox_pkg.clear()
00229         self._combobox_pkg.addItems(self._package_list)
00230         self._combobox_pkg.setCurrentIndex(0)
00231 
00232     def _refresh_launchfiles(self, package=None):
00233         '''
00234         Inspired by rqt_msg.MessageWidget._refresh_msgs
00235         '''
00236         if package is None or len(package) == 0:
00237             return
00238         self._launchfile_instances = []  # Launch[]
00239         #TODO: RqtRoscommUtil.list_files's 2nd arg 'subdir' should NOT be
00240         # hardcoded later.
00241         _launch_instance_list = RqtRoscommUtil.list_files(package,
00242                                                          'launch')
00243 
00244         rospy.logdebug('_refresh_launches package={} instance_list={}'.format(
00245                                                        package,
00246                                                        _launch_instance_list))
00247 
00248         self._launchfile_instances = [x.split('/')[1]
00249                                       for x in _launch_instance_list]
00250 
00251         self._combobox_launchfile_name.clear()
00252         self._combobox_launchfile_name.addItems(self._launchfile_instances)
00253 
00254     def save_settings(self, plugin_settings, instance_settings):
00255         # instance_settings.set_value('splitter', self._splitter.saveState())
00256         pass
00257 
00258     def restore_settings(self, plugin_settings, instance_settings):
00259 #        if instance_settings.contains('splitter'):
00260 #            self._splitter.restoreState(instance_settings.value('splitter'))
00261 #        else:
00262 #            self._splitter.setSizes([100, 100, 200])
00263         pass
00264 
00265 
00266 if __name__ == '__main__':
00267     # main should be used only for debug purpose.
00268     # This launches this QWidget as a standalone rqt gui.
00269     from rqt_gui.main import Main
00270 
00271     main = Main()
00272     sys.exit(main.main(sys.argv, standalone='rqt_launch'))


rqt_launch
Author(s): Isaac Saito, Stuart Glaser
autogenerated on Wed Sep 16 2015 06:58:21