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


rqt_robot_dashboard
Author(s): Ze'ev Klapow
autogenerated on Sat Jun 8 2019 20:02:45