util.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 import os
00034 
00035 import rospy
00036 
00037 from python_qt_binding.QtGui import QIcon, QImage, QMessageBox, QPainter, QPixmap
00038 from python_qt_binding.QtSvg import QSvgRenderer
00039 
00040 
00041 def dashinfo(msg, obj, title='Info'):
00042     """
00043     Logs a message with ``rospy.loginfo`` and displays a ``QMessageBox`` to the user
00044 
00045     :param msg: Message to display.
00046     :type msg: str
00047     :param obj: Parent object for the ``QMessageBox``
00048     :type obj: QObject
00049     :param title: An optional title for the `QMessageBox``
00050     :type title: str
00051     """
00052     rospy.loginfo(msg)
00053 
00054     box = QMessageBox()
00055     box.setText(msg)
00056     box.setWindowTitle(title)
00057     box.show()
00058 
00059     obj._message_box = box
00060 
00061 
00062 def dashwarn(msg, obj, title='Warning'):
00063     """
00064     Logs a message with ``rospy.logwarn`` and displays a ``QMessageBox`` to the user
00065 
00066     :param msg: Message to display.
00067     :type msg: str
00068     :param obj: Parent object for the ``QMessageBox``
00069     :type obj: QObject
00070     :param title: An optional title for the `QMessageBox``
00071     :type title: str
00072     """
00073     rospy.logwarn(msg)
00074 
00075     box = QMessageBox()
00076     box.setText(msg)
00077     box.setWindowTitle(title)
00078     box.show()
00079 
00080     obj._message_box = box
00081 
00082 
00083 def dasherr(msg, obj, title='Error'):
00084     """
00085     Logs a message with ``rospy.logerr`` and displays a ``QMessageBox`` to the user
00086 
00087     :param msg: Message to display.
00088     :type msg: str
00089     :param obj: Parent object for the ``QMessageBox``
00090     :type obj: QObject
00091     :param title: An optional title for the `QMessageBox``
00092     :type title: str
00093     """
00094     rospy.logerr(msg)
00095 
00096     box = QMessageBox()
00097     box.setText(msg)
00098     box.setWindowTitle(title)
00099     box.show()
00100 
00101     obj._message_box = box
00102 
00103 
00104 class IconHelper(object):
00105     """
00106     Helper class to easily access images and build QIcons out of lists of file names
00107     """
00108     def __init__(self, paths=None, name="IconHelper"):
00109         self._image_paths = paths if paths else []
00110         self._name = name
00111 
00112     def add_image_path(self, path):
00113         """
00114         Paths added will be searched for images by the _find_image function
00115         Paths will be searched in revearse order by add time
00116         The last path to be searched is always rqt_robot_dashboard/images
00117         Subdirectories are not recursively searched
00118 
00119         :param path: The path to add to the image paths list
00120         :type path: str
00121         """
00122         self._image_paths = [path] + self._image_paths
00123 
00124     def make_icon(self, image_list, mode=QIcon.Normal, state=QIcon.On):
00125         """
00126         Helper function to create QIcons from lists of image files
00127         Warning: svg files interleaved with other files will not render correctly
00128 
00129         :param image_list: list of image paths to layer into an icon.
00130         :type image: list of str
00131         :param mode: The mode of the QIcon to be created.
00132         :type mode: int
00133         :param state: the state of the QIcon to be created.
00134         :type state: int
00135         """
00136         if type(image_list) is not list:
00137             image_list = [image_list]
00138         if len(image_list) <= 0:
00139             raise TypeError('The list of images is empty.')
00140 
00141         num_svg = 0
00142         for item in image_list:
00143             if item[-4:].lower() == '.svg':
00144                 num_svg = num_svg + 1
00145 
00146         if num_svg != len(image_list):
00147             # Legacy support for non-svg images
00148             icon_pixmap = QPixmap()
00149             icon_pixmap.load(image_list[0])
00150             painter = QPainter(icon_pixmap)
00151             for item in image_list[1:]:
00152                 painter.drawPixmap(0, 0, QPixmap(item))
00153             icon = QIcon()
00154             icon.addPixmap(icon_pixmap, mode, state)
00155             painter.end()
00156             return icon
00157         else:
00158             #  rendering SVG files into a QImage
00159             renderer = QSvgRenderer(image_list[0])
00160             icon_image = QImage(renderer.defaultSize(), QImage.Format_ARGB32)
00161             icon_image.fill(0)
00162             painter = QPainter(icon_image)
00163             renderer.render(painter)
00164             if len(image_list) > 1:
00165                 for item in image_list[1:]:
00166                     renderer.load(item)
00167                     renderer.render(painter)
00168             painter.end()
00169             #  Convert QImage into a pixmap to create the icon
00170             icon_pixmap = QPixmap()
00171             icon_pixmap.convertFromImage(icon_image)
00172             icon = QIcon(icon_pixmap)
00173             return icon
00174 
00175     def find_image(self, path):
00176         """
00177         Convenience function to help with finding images.
00178         Path can either be specified as absolute paths or relative to any path in ``_image_paths``
00179 
00180         :param path: The path or name of the image.
00181         :type path: str
00182         """
00183         if os.path.exists(path):
00184             return path
00185         for image_path in self._image_paths:
00186             if os.path.exists(os.path.join(image_path, path)):
00187                 return os.path.join(image_path, path)
00188             elif '.' in path and os.path.exists(os.path.join(image_path, 'nonsvg', path)):
00189                 return os.path.join(image_path, 'nonsvg', path)
00190         return os.path.join(self._image_paths[-1], 'ic-missing-icon.svg')
00191 
00192     def build_icon(self, image_name_list, mode=QIcon.Normal, state=QIcon.On):
00193         """
00194         Convenience function to create an icon from a list of file names
00195 
00196         :param image_name_list: List of file image names to make into an icon
00197         :type image_name_list: list of str
00198         :param mode: The mode of the QIcon to be created.
00199         :type mode: int
00200         :param state: the state of the QIcon to be created.
00201         :type state: int
00202         """
00203         found_list = []
00204         for name in image_name_list:
00205             found_list.append(self.find_image(name))
00206         return self.make_icon(found_list, mode, state)
00207 
00208     def set_icon_lists(self, icons, clicked_icons=None, suppress_overlays=False):
00209         """
00210         Sets up the icon lists for the button states.
00211         There must be one index in icons for each state.
00212         
00213         :raises IndexError: if ``icons`` is not a list of lists of strings
00214         
00215         :param icons: A list of lists of strings to create icons for the states of this button.\
00216         If only one is supplied then ok, warn, error, stale icons will be created with overlays
00217         :type icons: list
00218         :param clicked_icons: A list of clicked state icons. len must equal icons
00219         :type clicked_icons: list
00220         :param suppress_overlays: if false and there is only one icon path supplied
00221         :type suppress_overlays: bool
00222         """
00223         if clicked_icons is not None and len(icons) != len(clicked_icons):
00224             rospy.logerr("%s: icons and clicked states are unequal" % self._name)
00225             icons = clicked_icons = ['ic-missing-icon.svg']
00226         if not (type(icons) is list and type(icons[0]) is list and type(icons[0][0] is str)):
00227             raise(IndexError("icons must be a list of lists of strings"))
00228         if len(icons) <= 0:
00229             rospy.logerr("%s: Icons not supplied" % self._name)
00230             icons = clicked_icons = ['ic-missing-icon.svg']
00231         if len(icons) == 1 and suppress_overlays == False:
00232             if icons[0][0][-4].lower() == '.svg':
00233                 icons.append(icons[0] + ['ol-warn-badge.svg'])
00234                 icons.append(icons[0] + ['ol-err-badge.svg'])
00235                 icons.append(icons[0] + ['ol-stale-badge.svg'])
00236             else:
00237                 icons.append(icons[0] + ['warn-overlay.png'])
00238                 icons.append(icons[0] + ['err-overlay.png'])
00239                 icons.append(icons[0] + ['stale-overlay.png'])
00240         if clicked_icons is None:
00241             clicked_icons = []
00242             for name in icons:
00243                 clicked_icons.append(name + ['ol-click.svg'])
00244         icons_conv = []
00245         for icon in icons:
00246             icons_conv.append(self.build_icon(icon))
00247         clicked_icons_conv = []
00248         for icon in clicked_icons:
00249             clicked_icons_conv.append(self.build_icon(icon))
00250         return (icons_conv, clicked_icons_conv)


rqt_robot_dashboard
Author(s): Ze'ev Klapow
autogenerated on Fri Aug 28 2015 12:50:54