icon_tool_button.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 from python_qt_binding.QtCore import Signal
00036 from python_qt_binding.QtGui import QToolButton
00037 import rospy
00038 
00039 from .util import IconHelper
00040 
00041 
00042 class IconToolButton(QToolButton):
00043     """
00044     This is the base class for all widgets.
00045     It provides state and icon switching support as well as convenience functions for creating icons.
00046 
00047     :raises IndexError: if ``icons`` is not a list of lists of strings
00048 
00049     :param name: name of the object
00050     :type name: str
00051     :param icons: A list of lists of strings to create icons for the states of this button.
00052     If only one is supplied then ok, warn, error, stale icons will be created with overlays
00053     :type icons: list
00054     :param clicked_icons: A list of clicked state icons. len must equal icons
00055     :type clicked_icons: list
00056     :param suppress_overlays: if false and there is only one icon path supplied
00057     :type suppress_overlays: bool
00058     :param icon_paths: list of lists of package and subdirectory in the form
00059     ['package name', 'subdirectory'] example ['rqt_pr2_dashboard', 'images/svg']
00060     :type icon_paths: list of lists of strings
00061     """
00062     state_changed = Signal(int)
00063 
00064     def __init__(self, name, icons, clicked_icons=None, suppress_overlays=False, icon_paths=None):
00065         super(IconToolButton, self).__init__()
00066 
00067         self.name = name
00068         self.setObjectName(self.name)
00069 
00070         self.state_changed.connect(self._update_state)
00071         self.pressed.connect(self._pressed)
00072         self.released.connect(self._released)
00073 
00074         import rospkg
00075         icon_paths = (icon_paths if icon_paths else []) + [['rqt_robot_dashboard', 'images']]
00076         paths = []
00077         for path in icon_paths:
00078             paths.append(os.path.join(rospkg.RosPack().get_path(path[0]), path[1]))
00079         self.icon_helper = IconHelper(paths)
00080 
00081         self.setStyleSheet('QToolButton {border: none;}')
00082 
00083         self.__state = 0
00084         self.set_icon_lists(icons, clicked_icons, suppress_overlays)
00085 
00086     def update_state(self, state):
00087         """
00088         Set the state of this button.
00089         This will also update the icon for the button based on the ``self._icons`` list
00090 
00091         :raises IndexError: If state is not a proper index to ``self._icons``
00092 
00093         :param state: The state to set.
00094         :type state: int
00095         """
00096         if 0 <= state and state < len(self._icons):
00097             self.__state = state
00098             self.state_changed.emit(self.__state)
00099         else:
00100             raise IndexError("%s update_state received invalid state: %s" % (self.name, state))
00101 
00102     def set_icon_lists(self, icons, clicked_icons=None, suppress_overlays=False):
00103         """
00104         Sets up the icon lists for the button states.
00105         There must be one index in icons for each state.
00106 
00107         :raises IndexError: if ``icons`` is not a list of lists of strings
00108 
00109         :param icons: A list of lists of strings to create icons for the states of this button.
00110         If only one is supplied then ok, warn, error, stale icons will be created with overlays
00111         :type icons: list
00112         :param clicked_icons: A list of clicked state icons. len must equal icons
00113         :type clicked_icons: list
00114         :param suppress_overlays: if false and there is only one icon path supplied
00115         :type suppress_overlays: bool
00116 
00117         """
00118         if clicked_icons is not None and len(icons) != len(clicked_icons):
00119             rospy.logerr("%s: icons and clicked states are unequal" % self.name)
00120             icons = clicked_icons = ['ic-missing-icon.svg']
00121         if not (type(icons) is list and type(icons[0]) is list and type(icons[0][0] is str)):
00122             raise(IndexError("icons must be a list of lists of strings"))
00123         if len(icons) <= 0:
00124             rospy.logerr("%s: Icons not supplied" % self.name)
00125             icons = clicked_icons = ['ic-missing-icon.svg']
00126         if len(icons) == 1 and suppress_overlays == False:
00127             if icons[0][0][-4].lower() == '.svg':
00128                 icons.append(icons[0] + ['ol-warn-badge.svg'])
00129                 icons.append(icons[0] + ['ol-err-badge.svg'])
00130                 icons.append(icons[0] + ['ol-stale-badge.svg'])
00131             else:
00132                 icons.append(icons[0] + ['warn-overlay.png'])
00133                 icons.append(icons[0] + ['err-overlay.png'])
00134                 icons.append(icons[0] + ['stale-overlay.png'])
00135         if clicked_icons is None:
00136             clicked_icons = []
00137             for name in icons:
00138                 clicked_icons.append(name + ['ol-click.svg'])
00139         self._icons = []
00140         for icon in icons:
00141             self._icons.append(self.icon_helper.build_icon(icon))
00142         self._clicked_icons = []
00143         for icon in clicked_icons:
00144             self._clicked_icons.append(self.icon_helper.build_icon(icon))
00145 
00146     def _update_state(self, state):
00147         if self.isDown():
00148             self.setIcon(self._clicked_icons[self.__state])
00149         else:
00150             self.setIcon(self._icons[self.__state])
00151 
00152     def _pressed(self):
00153         self.setIcon(self._clicked_icons[self.__state])
00154 
00155     def _released(self):
00156         self.setIcon(self._icons[self.__state])


rqt_robot_dashboard
Author(s): Ze'ev Klapow
autogenerated on Fri Jan 3 2014 11:56:25