reconfigure_widget.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2009, 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: Ze'ev Klapow
00034 
00035 import sys
00036 
00037 import QtGui
00038 from QtGui import QWidget, QPushButton, QComboBox, QScrollArea, QTreeWidget, QTreeWidgetItem
00039 from QtCore import QTimer
00040 
00041 import dynamic_reconfigure.client
00042 import rosservice
00043 import rospy
00044 
00045 from .editors import *
00046 from .groups import *
00047 from .updater import Updater
00048 
00049 class ReconfigureWidget(QWidget):
00050     def __init__(self):
00051         super(ReconfigureWidget, self).__init__()
00052         self.client = None
00053         self.stretch = None
00054 
00055         self.hbox = QtGui.QHBoxLayout()
00056         self.selector = ReconfigureSelector(self)
00057         self.hbox.addWidget(self.selector.tree)
00058 
00059         self.destroyed.connect(self.close)
00060 
00061         self.setLayout(self.hbox)
00062 
00063     def show(self, node):
00064         self.close()
00065 
00066         reconf = None
00067         
00068         try:
00069             reconf = dynamic_reconfigure.client.Client(str(node), timeout=5.0)
00070         except rospy.exceptions.ROSException:
00071             print("Could not connect to %s"%node) 
00072             return
00073         finally:
00074             self.close()
00075 
00076         self.client = ClientWidget(reconf)
00077 
00078         self.scroll = QScrollArea()
00079         # Buffer min width so no horizontal scroll bar appears
00080         self.scroll.setMinimumWidth(self.client.minimumWidth()+20)
00081 
00082         self.scroll.setWidget(self.client)
00083         self.scroll.setWidgetResizable(True)
00084 
00085         self.hbox.insertWidget(1, self.scroll, 1)
00086         self.hbox.removeItem(self.hbox.itemAt(2))
00087         self.stretch = None
00088 
00089     def close(self):
00090         if self.client is not None:
00091             # Clear out the old widget
00092             self.client.close()
00093             self.client = None
00094 
00095             self.scroll.deleteLater()
00096 
00097     def clear(self):
00098         if not self.stretch:
00099             self.stretch = self.hbox.addStretch(1)
00100 
00101 class ReconfigureSelector(QWidget):
00102     def __init__(self, parent):
00103         super(ReconfigureSelector, self).__init__()
00104 
00105         self.parent = parent
00106         self.last_nodes = None
00107         self.current_node = ''
00108 
00109         self.tree = QTreeWidget()
00110         self.update_tree()
00111 
00112         self.tree.itemClicked.connect(self.selected)
00113         self.tree.setSelectionMode(QtGui.QAbstractItemView.SingleSelection)
00114 
00115         self.tree.setHeaderLabel("Available Nodes")
00116 
00117         self.timer = QTimer()
00118         self.timer.timeout.connect(self.update_tree)
00119         self.timer.start(100)
00120 
00121     def update_tree(self):
00122         try:
00123             nodes = dynamic_reconfigure.find_reconfigure_services()
00124         except rosservice.ROSServiceIOException:
00125             print("Reconfigure GUI cannot connect to master.")
00126         else:
00127             if not nodes == self.last_nodes:
00128                 self.tree.clear()
00129                 for n in nodes:
00130                     item = QTreeWidgetItem()
00131                     item.setText(0, n)
00132                     self.tree.addTopLevelItem(item)
00133             elif len(nodes) == 0:
00134                 self.tree.clear()
00135                 self.parent.close()
00136                 self.parent.clear()
00137 
00138             self.last_nodes = nodes
00139 
00140     def selected(self, node, col):
00141         print("Selected %s"%node.text(0))
00142         if not node.text(0) == self.current_node:
00143             self.parent.show(node.text(0))
00144             self.current_node = node.text(0)
00145 
00146 class ClientWidget(Group):
00147     def __init__(self, reconf):
00148         super(ClientWidget, self).__init__(Updater(reconf), reconf.get_group_descriptions())
00149 
00150         self.setMinimumWidth(550)
00151 
00152         self.reconf = reconf
00153 
00154         self.updater.start()
00155         self.reconf.config_callback = self.config_callback
00156 
00157     def config_callback(self, config):
00158         if config is not None:
00159             # TODO: should use config.keys but this method doesnt exist
00160             names = [name for name, v in config.items()]
00161 
00162             for widget in self.widgets:
00163                 if isinstance(widget, Editor):
00164                     if widget.name in names:
00165                         widget.update_value(config[widget.name])
00166                 elif isinstance(widget, Group):
00167                     cfg = find_cfg(config, widget.name)
00168                     widget.update_group(cfg)
00169                 
00170     def close(self):
00171         self.reconf.close()
00172         self.updater.stop()
00173 
00174         for w in self.widgets:
00175             w.close()
00176 
00177         self.deleteLater()
00178 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


reconfigure_gui
Author(s): Ze'ev Klapow
autogenerated on Mon Aug 19 2013 11:00:48