biotac.py
Go to the documentation of this file.
00001 # Copyright (c) 2013, Shadow Robot Company, SynTouch LLC
00002 # All rights reserved.
00003 #
00004 # Redistribution and use in source and binary forms, with or without
00005 # modification, are permitted provided that the following conditions
00006 # are met:
00007 #
00008 #   * Redistributions of source code must retain the above copyright
00009 #     notice, this list of conditions and the following disclaimer.
00010 #   * Redistributions in binary form must reproduce the above
00011 #     copyright notice, this list of conditions and the following
00012 #     disclaimer in the documentation and/or other materials provided
00013 #     with the distribution.
00014 #   * Neither the name of the TU Darmstadt nor the names of its
00015 #     contributors may be used to endorse or promote products derived
00016 #     from this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 # POSSIBILITY OF SUCH DAMAGE.
00030 
00031 
00032 import rospy
00033 import rospkg
00034 import os
00035 
00036 from qt_gui.plugin import Plugin
00037 from python_qt_binding import loadUi
00038 
00039 from QtGui import QMessageBox, QWidget, QIcon, QColor, QPainter, QFont
00040 from QtCore import QRectF, QTimer, SIGNAL, SLOT
00041 from sr_robot_msgs.msg import Biotac, BiotacAll
00042 from sr_utilities.hand_finder import HandFinder
00043 
00044 
00045 class SrGuiBiotac(Plugin):
00046     _nb_electrodes_biotac = 19
00047     _nb_electrodes_biotac_sp = 24
00048 
00049     def define_electrodes(self):
00050         self.sensing_electrodes_v1_x = \
00051             rospy.get_param(
00052                 "sr_gui_biotac/sensing_electrodes_x_locations",
00053                 [6.45, 3.65, 3.65, 6.45, 3.65, 6.45, 0.00, 1.95, -1.95,
00054                  0.00, -6.45, - 3.65, -3.65, -6.45, -3.65, -6.45, 0.00,
00055                  0.00, 0.00])  # Physical electrode locations on the sensor
00056         self.sensing_electrodes_v1_y = \
00057             rospy.get_param(
00058                 "sr_gui_biotac/sensing_electrodes_y_locations",
00059                 [7.58, 11.28, 14.78, 16.58, 19.08, 21.98, 4.38, 6.38, 6.38,
00060                  8.38, 7.58, 11.28, 14.78, 16.58, 19.08, 21.98, 11.38,
00061                  18.38, 22.18])
00062 
00063         self.excitation_electrodes_v1_x = \
00064             rospy.get_param(
00065                 "sr_gui_biotac/excitation_electrodes_x_locations",
00066                 [6.45, 3.75, -3.75, -6.45])
00067         self.excitation_electrodes_v1_y = \
00068             rospy.get_param(
00069                 "sr_gui_biotac/excitation_electrodes_y_locations",
00070                 [12.48, 24.48, 24.48, 12.48])
00071 
00072         self.sensing_electrodes_v2_x = \
00073             rospy.get_param(
00074                 "sr_gui_biotac/sensing_electrodes_x_locations",
00075                 [5.00, 3.65, 6.45, 4.40, 2.70, 6.45, 4.40, 1.50, 4.00, 4.50,
00076                  -5.00, - 3.65, -6.45, -4.40, -2.70, -6.45, -4.40, -1.50, -4.00, -4.50,
00077                  0.00, 1.95, -1.95, 0.00])  # Physical electrode locations on the sensor
00078         self.sensing_electrodes_v2_y = \
00079             rospy.get_param(
00080                 "sr_gui_biotac/sensing_electrodes_y_locations",
00081                 [4.38, 6.38, 14.78, 15.50, 18.50, 19.08, 20.00, 21.00, 23.00, 25.00,
00082                  4.38, 6.38, 14.78, 15.50, 18.50, 19.08, 20.00, 21.00, 23.00, 25.00,
00083                  7.38, 11.50, 11.50, 15.20])
00084 
00085         self.excitation_electrodes_v2_x = \
00086             rospy.get_param(
00087                 "sr_gui_biotac/excitation_electrodes_x_locations",
00088                 [5.30, 6.00, -5.30, -6.00])
00089         self.excitation_electrodes_v2_y = \
00090             rospy.get_param(
00091                 "sr_gui_biotac/excitation_electrodes_y_locations",
00092                 [9.00, 22.00, 9.00, 22.00])
00093 
00094     def assign_electrodes(self, nb_electrodes):
00095         if nb_electrodes == self._nb_electrodes_biotac:
00096             self.sensing_electrodes_x = self.sensing_electrodes_v1_x
00097             self.sensing_electrodes_y = self.sensing_electrodes_v1_y
00098             self.excitation_electrodes_x = self.excitation_electrodes_v1_x
00099             self.excitation_electrodes_y = self.excitation_electrodes_v1_y
00100             self.factor = rospy.get_param(
00101                 "sr_gui_biotac/display_location_scale_factor",
00102                 17.5)  # Sets the multiplier to go from physical electrode
00103         # location on the sensor in mm to display location in pixels
00104         elif nb_electrodes == self._nb_electrodes_biotac_sp:
00105             self.sensing_electrodes_x = self.sensing_electrodes_v2_x
00106             self.sensing_electrodes_y = self.sensing_electrodes_v2_y
00107             self.excitation_electrodes_x = self.excitation_electrodes_v2_x
00108             self.excitation_electrodes_y = self.excitation_electrodes_v2_y
00109             self.factor = 25.0
00110         else:
00111             rospy.logerr("Number of electrodes %d not matching known biotac models. expected: %d or %d",
00112                          nb_electrodes, self._nb_electrodes_biotac, self._nb_electrodes_biotac_sp)
00113             return
00114 
00115         for n in range(len(self.sensing_electrodes_x)):
00116             self.sensing_electrodes_x[n] = (
00117                 self.sensing_electrodes_x[n] * self.factor +
00118                 self.x_display_offset[0])
00119             self.sensing_electrodes_y[n] = (
00120                 self.sensing_electrodes_y[n] * self.factor +
00121                 self.y_display_offset[0])
00122 
00123         for n in range(len(self.excitation_electrodes_x)):
00124             self.excitation_electrodes_x[n] = (
00125                 self.excitation_electrodes_x[n] * self.factor +
00126                 self.x_display_offset[0])
00127             self.excitation_electrodes_y[n] = (
00128                 self.excitation_electrodes_y[n] * self.factor +
00129                 self.y_display_offset[0])
00130 
00131     def tactile_cb(self, msg):
00132         if len(msg.tactiles[0].electrodes) != self._nb_electrodes:
00133             self._nb_electrodes = len(msg.tactiles[0].electrodes)
00134             self.assign_electrodes(self._nb_electrodes)
00135         self.latest_data = msg
00136 
00137     def get_electrode_colour_from_value(self, value):
00138         r = 0.0
00139         g = 0.0
00140         b = 255.0
00141 
00142         value = float(value)
00143 
00144         threshold = (0.0, 1000.0, 2000.0, 3000.0, 4095.0)
00145 
00146         if value <= threshold[0]:
00147             pass
00148 
00149         elif value < threshold[1]:
00150 
00151             r = 255
00152             g = 255 * ((value - threshold[0]) / (threshold[1] - threshold[0]))
00153             b = 0
00154 
00155         elif value < threshold[2]:
00156 
00157             r = 255 * ((threshold[2] - value) / (threshold[2] - threshold[1]))
00158             g = 255
00159             b = 0
00160 
00161         elif value < threshold[3]:
00162 
00163             r = 0
00164             g = 255
00165             b = 255 * ((value - threshold[2]) / (threshold[3] - threshold[2]))
00166 
00167         elif value < threshold[4]:
00168 
00169             r = 0
00170             g = 255 * ((threshold[4] - value) / (threshold[4] - threshold[3]))
00171             b = 255
00172 
00173         return QColor(r, g, b)
00174 
00175     def biotac_id_from_dropdown(self):
00176         name = self._widget.btSelect.currentText()
00177         fingers = ["FF", "MF", "RF", "LF", "TH"]
00178         return fingers.index(name)
00179 
00180     def draw_electrode(self, painter, elipse_x, elipse_y, text_x, text_y,
00181                        colour, text):
00182 
00183         rect = QRectF(elipse_x, elipse_y, self.RECTANGLE_WIDTH,
00184                       self.RECTANGLE_HEIGHT)
00185 
00186         painter.setBrush(colour)
00187         painter.drawEllipse(rect)
00188 
00189         rect.setX(text_x)
00190         rect.setY(text_y)
00191 
00192         painter.drawText(rect, text)
00193 
00194     def paintEvent(self, paintEvent):
00195         painter = QPainter(self._widget.scrollAreaWidgetContents)
00196         which_tactile = self.biotac_id_from_dropdown()
00197 
00198         painter.setFont(QFont("Arial", self.label_font_size[0]))
00199 
00200         if len(self.sensing_electrodes_x) == len(self.latest_data.tactiles[which_tactile].electrodes):
00201             for n in range(len(self.sensing_electrodes_x)):
00202                 value = self.latest_data.tactiles[which_tactile].electrodes[n]
00203                 eval("self._widget.lcdE%02d.display(%d)" % (n + 1, value))
00204                 colour = self.get_electrode_colour_from_value(value)
00205 
00206                 elipse_x = self.sensing_electrodes_x[n]
00207                 elipse_y = self.sensing_electrodes_y[n]
00208 
00209                 if n < 9:
00210                     text_x = elipse_x + self.x_display_offset[1]
00211                     text_y = elipse_y + self.y_display_offset[1]
00212 
00213                 else:
00214                     text_x = elipse_x + self.x_display_offset[2]
00215                     text_y = elipse_y + self.y_display_offset[2]
00216 
00217                 self.draw_electrode(painter, elipse_x, elipse_y, text_x, text_y,
00218                                     colour, str(n + 1))
00219 
00220         painter.setFont(QFont("Arial", self.label_font_size[1]))
00221 
00222         for n in range(len(self.excitation_electrodes_x)):
00223             elipse_x = self.excitation_electrodes_x[n]
00224             elipse_y = self.excitation_electrodes_y[n]
00225 
00226             colour = QColor(127, 127, 127)
00227 
00228             text_x = elipse_x + self.x_display_offset[3]
00229             text_y = elipse_y + self.y_display_offset[3]
00230 
00231             self.draw_electrode(painter, elipse_x, elipse_y, text_x, text_y,
00232                                 colour, "X" + str(n + 1))
00233 
00234         self._widget.update()
00235 
00236     def subscribe_to_topic(self, prefix):
00237         if prefix:
00238             rospy.Subscriber(prefix + "tactile", BiotacAll, self.tactile_cb)
00239 
00240     def load_params(self):
00241         self.RECTANGLE_WIDTH = rospy.get_param(
00242             "sr_gui_biotac/electrode_display_width",
00243             45)  # Display sizes for electrodes in pixels
00244         self.RECTANGLE_HEIGHT = rospy.get_param(
00245             "sr_gui_biotac/electrode_display_height", 45)
00246 
00247         self.factor = rospy.get_param(
00248             "sr_gui_biotac/display_location_scale_factor",
00249             17.5)  # Sets the multiplier to go from physical electrode
00250         # location on the sensor in mm to display location in pixels
00251         self.x_display_offset = rospy.get_param(
00252             "sr_gui_biotac/x_display_offset", [200, 12.5, 4.5,
00253                                                3.5])  # Pixel offsets for
00254         # displaying electrodes. offset[0] is applied to each electrode.
00255         # 1,2 and 3 are the label offsets for displaying electrode number.
00256         self.y_display_offset = rospy.get_param(
00257             "sr_gui_biotac/y_display_offset", [-50, 4.0, 4.0, 4.0])
00258         self.label_font_size = rospy.get_param(
00259             "sr_gui_biotac/electrode_label_font_sizes", [24,
00260                                                          22])  # Font sizes
00261         # for labels on sensing + excitation electrodes
00262 
00263         if self._hand_parameters.mapping:
00264             self.default_topic = (
00265                 self._hand_parameters.mapping.values()[0] + '/')
00266         else:
00267             self.default_topic = ""
00268 
00269     def __init__(self, context):
00270 
00271         super(SrGuiBiotac, self).__init__(context)
00272         self.setObjectName('SrGuiBiotac')
00273         self._hand_finder = HandFinder()
00274         self._hand_parameters = self._hand_finder.get_hand_parameters()
00275         self.load_params()
00276 
00277         self._publisher = None
00278         self._widget = QWidget()
00279 
00280         self.latest_data = BiotacAll()
00281 
00282         self.define_electrodes()
00283         self._nb_electrodes = self._nb_electrodes_biotac
00284         self.assign_electrodes(self._nb_electrodes)
00285 
00286         ui_file = os.path.join(rospkg.RosPack().get_path('sr_gui_biotac'),
00287                                'uis', 'SrGuiBiotac.ui')
00288         loadUi(ui_file, self._widget)
00289         self._widget.setObjectName('SrBiotacUi')
00290 
00291         self.timer = QTimer(self._widget)
00292         self._widget.connect(self.timer, SIGNAL("timeout()"),
00293                              self._widget.scrollAreaWidgetContents.update)
00294         self._widget.scrollAreaWidgetContents.paintEvent = self.paintEvent
00295 
00296         self.subscribe_to_topic(self.default_topic)
00297 
00298         for hand in self._hand_parameters.mapping:
00299             self._widget.select_prefix.addItem(
00300                 self._hand_parameters.mapping[hand])
00301         if not self._hand_parameters.mapping:
00302             rospy.logerr("No hand detected")
00303             QMessageBox.warning(
00304                 self._widget, "warning", "No hand is detected")
00305         else:
00306             self._widget.select_prefix.setCurrentIndex(0)
00307 
00308         self._widget.connect(self._widget.select_prefix,
00309                              SIGNAL("activated(QString)"),
00310                              self.subscribe_to_topic)
00311 
00312         self.timer.start(50)
00313 
00314         context.add_widget(self._widget)


sr_gui_biotac
Author(s): Dan Greenwald
autogenerated on Thu Jun 6 2019 21:13:47