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 __future__ import division
00036
00037 from python_qt_binding.QtCore import QPointF, QRectF, Qt
00038 from python_qt_binding.QtGui import QGraphicsView, QTransform
00039
00040
00041 class InteractiveGraphicsView(QGraphicsView):
00042
00043 def __init__(self, parent=None):
00044 super(InteractiveGraphicsView, self).__init__(parent)
00045 self.setObjectName('InteractiveGraphicsView')
00046
00047 self._last_pan_point = None
00048 self._last_scene_center = None
00049
00050 def mousePressEvent(self, mouse_event):
00051 self._last_pan_point = mouse_event.pos()
00052 self._last_scene_center = self._map_to_scene_f(QRectF(self.frameRect()).center())
00053 self.setCursor(Qt.ClosedHandCursor)
00054 QGraphicsView.mousePressEvent(self, mouse_event)
00055
00056 def mouseReleaseEvent(self, mouse_event):
00057 self.setCursor(Qt.OpenHandCursor)
00058 self._last_pan_point = None
00059
00060 def mouseMoveEvent(self, mouse_event):
00061 if self._last_pan_point is not None:
00062 delta_scene = self.mapToScene(mouse_event.pos()) - self.mapToScene(self._last_pan_point)
00063 if not delta_scene.isNull():
00064 self.centerOn(self._last_scene_center - delta_scene)
00065 self._last_scene_center -= delta_scene
00066 self._last_pan_point = mouse_event.pos()
00067 QGraphicsView.mouseMoveEvent(self, mouse_event)
00068
00069 def wheelEvent(self, wheel_event):
00070 if wheel_event.modifiers() == Qt.NoModifier:
00071 delta = wheel_event.delta()
00072 delta = max(min(delta, 480), -480)
00073 mouse_before_scale_in_scene = self.mapToScene(wheel_event.pos())
00074
00075 scale_factor = 1 + (0.2 * (delta / 120.0))
00076 scaling = QTransform(scale_factor, 0, 0, scale_factor, 0, 0)
00077 self.setTransform(self.transform() * scaling)
00078
00079 mouse_after_scale_in_scene = self.mapToScene(wheel_event.pos())
00080 center_in_scene = self.mapToScene(self.frameRect().center())
00081 self.centerOn(center_in_scene + mouse_before_scale_in_scene - mouse_after_scale_in_scene)
00082
00083 wheel_event.accept()
00084 else:
00085 QGraphicsView.wheelEvent(self, wheel_event)
00086
00087 def _map_to_scene_f(self, pointf):
00088 point = pointf.toPoint()
00089 if pointf.x() == point.x() and pointf.y() == point.y():
00090
00091 return self.mapToScene(point)
00092 elif pointf.x() == point.x():
00093
00094 pointA = self.mapToScene((pointf + QPointF(0, -0.5)).toPoint())
00095 pointB = self.mapToScene((pointf + QPointF(0, 0.5)).toPoint())
00096 return (pointA + pointB) / 2.0
00097 elif pointf.y() == point.y():
00098
00099 pointA = self.mapToScene((pointf + QPointF(-0.5, 0)).toPoint())
00100 pointB = self.mapToScene((pointf + QPointF(0.5, 0)).toPoint())
00101 return (pointA + pointB) / 2.0
00102 else:
00103
00104 pointA = self.mapToScene((pointf + QPointF(-0.5, -0.5)).toPoint())
00105 pointB = self.mapToScene((pointf + QPointF(-0.5, 0.5)).toPoint())
00106 pointC = self.mapToScene((pointf + QPointF(0.5, -0.5)).toPoint())
00107 pointD = self.mapToScene((pointf + QPointF(0.5, 0.5)).toPoint())
00108 return (pointA + pointB + pointC + pointD) / 4.0