00001 """
00002 Copyright (c) 2011, Dirk Thomas, TU Darmstadt
00003 All rights reserved.
00004
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions
00007 are met:
00008
00009 * Redistributions of source code must retain the above copyright
00010 notice, this list of conditions and the following disclaimer.
00011 * Redistributions in binary form must reproduce the above
00012 copyright notice, this list of conditions and the following
00013 disclaimer in the documentation and/or other materials provided
00014 with the distribution.
00015 * Neither the name of the TU Darmstadt nor the names of its
00016 contributors may be used to endorse or promote products derived
00017 from this software without specific prior written permission.
00018
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00020 "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00021 LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00022 FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00023 COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00024 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00025 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00026 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00027 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00028 LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00029 ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00030 POSSIBILITY OF SUCH DAMAGE.
00031
00032 Note: This is modified version by Cogniteam
00033 """
00034
00035 from python_qt_binding.QtCore import Qt, QPointF
00036 from python_qt_binding.QtGui import QBrush, QGraphicsSimpleTextItem, QPen, QColor, QPainterPath, QGraphicsPolygonItem, \
00037 QPolygonF, QPainterPath, QGraphicsPathItem
00038
00039 from .graph_item import GraphItem
00040
00041
00042 class EdgeItem(GraphItem):
00043
00044 EDGE_PEN_WIDTH = 0.5
00045
00046 def __init__(self, spline, label, label_center, from_node, to_node, parent=None, **kwargs):
00047 super(EdgeItem, self).__init__(parent, **kwargs)
00048
00049 self._edge_pen_width = kwargs.get('edge_pen_width', self.EDGE_PEN_WIDTH)
00050
00051 self.from_node = from_node
00052 self.from_node.add_outgoing_edge(self)
00053
00054 self.to_node = to_node
00055 self.to_node.add_incoming_edge(self)
00056
00057 self._brush = QBrush(self._color)
00058
00059 self._label_pen = QPen()
00060 self._label_pen.setColor(self._color)
00061 self._label_pen.setJoinStyle(Qt.RoundJoin)
00062 self._label_pen.setWidthF(self._label_pen_width)
00063
00064 self._edge_pen = QPen()
00065 self._edge_pen.setColor(self._color)
00066 self._edge_pen.setWidthF(self._edge_pen_width)
00067
00068 self._sibling_edges = set()
00069
00070 self._label = None
00071 if label is not None:
00072 self._label = QGraphicsSimpleTextItem(label)
00073
00074 font = self._label.font()
00075 font.setPointSize(8)
00076 self._label.setFont(font)
00077
00078 label_rect = self._label.boundingRect()
00079 label_rect.moveCenter(label_center)
00080 self._label.setPos(label_rect.x(), label_rect.y())
00081
00082
00083 coordinates = spline.split(' ')
00084
00085 end_point = None
00086 if coordinates[0].startswith('e,'):
00087 parts = coordinates.pop(0)[2:].split(',')
00088 end_point = QPointF(float(parts[0]), -float(parts[1]))
00089
00090 if coordinates[0].startswith('s,'):
00091 parts = coordinates.pop(0).split(',')
00092
00093
00094 parts = coordinates.pop(0).split(',')
00095 point = QPointF(float(parts[0]), -float(parts[1]))
00096 path = QPainterPath(point)
00097
00098 while len(coordinates) > 2:
00099
00100 parts = coordinates.pop(0).split(',')
00101 point1 = QPointF(float(parts[0]), -float(parts[1]))
00102 parts = coordinates.pop(0).split(',')
00103 point2 = QPointF(float(parts[0]), -float(parts[1]))
00104 parts = coordinates.pop(0).split(',')
00105 point3 = QPointF(float(parts[0]), -float(parts[1]))
00106 path.cubicTo(point1, point2, point3)
00107
00108 self._arrow = None
00109 if end_point is not None:
00110
00111 self._arrow = QGraphicsPolygonItem()
00112 polygon = QPolygonF()
00113 polygon.append(point3)
00114 offset = QPointF(end_point - point3)
00115 corner1 = QPointF(-offset.y(), offset.x()) * 0.35
00116 corner2 = QPointF(offset.y(), -offset.x()) * 0.35
00117 polygon.append(point3 + corner1)
00118 polygon.append(end_point)
00119 polygon.append(point3 + corner2)
00120 self._arrow.setPolygon(polygon)
00121
00122 self._path = QGraphicsPathItem()
00123 self._path.setPath(path)
00124 self.addToGroup(self._path)
00125
00126 self._brush.setColor(self._color)
00127 self._edge_pen.setColor(self._color)
00128 self._label_pen.setColor(self._color)
00129
00130 self._path.setPen(self._edge_pen)
00131 if self._arrow is not None:
00132 self._arrow.setBrush(self._brush)
00133 self._arrow.setPen(self._edge_pen)
00134 if self._label is not None:
00135 self._label.setBrush(self._brush)
00136 self._label.setPen(self._label_pen)
00137
00138 def add_to_scene(self, scene):
00139 scene.addItem(self)
00140 if self._label is not None:
00141 scene.addItem(self._label)
00142 if self._arrow is not None:
00143 scene.addItem(self._arrow)
00144
00145 def setToolTip(self, tool_tip):
00146 super(EdgeItem, self).setToolTip(tool_tip)
00147 if self._label is not None:
00148 self._label.setToolTip(tool_tip)
00149 if self._arrow is not None:
00150 self._arrow.setToolTip(tool_tip)
00151
00152 def add_sibling_edge(self, edge):
00153 self._sibling_edges.add(edge)
00154
00155 def set_color(self, color=None):
00156 if color is None:
00157 color = self._color
00158
00159 self._brush.setColor(color)
00160 self._edge_pen.setColor(color)
00161 self._label_pen.setColor(color)
00162
00163 self._path.setPen(self._edge_pen)
00164 if self._arrow is not None:
00165 self._arrow.setBrush(self._brush)
00166 self._arrow.setPen(self._edge_pen)
00167 if self._label is not None:
00168 self._label.setBrush(self._brush)
00169 self._label.setPen(self._label_pen)