qwt_data_plot.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2011, Dorian Scholz, TU Darmstadt
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 the TU Darmstadt 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 HOLDER 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 # -*- coding: utf-8 -*-
00034 from __future__ import division
00035 import math
00036 import sys
00037 
00038 from python_qt_binding.QtCore import QEvent, QSize, QPointF, Qt, SIGNAL, Signal, Slot, qWarning
00039 from python_qt_binding.QtGui import QColor, QPen, QBrush, QVector2D
00040 import Qwt
00041 
00042 from numpy import arange, zeros, concatenate
00043 
00044 
00045 # create real QwtDataPlot class
00046 class QwtDataPlot(Qwt.QwtPlot):
00047     mouseCoordinatesChanged = Signal(QPointF)
00048     _num_value_saved = 1000
00049     _num_values_ploted = 1000
00050 
00051     limits_changed = Signal()
00052 
00053     def __init__(self, *args):
00054         super(QwtDataPlot, self).__init__(*args)
00055         self.setCanvasBackground(Qt.white)
00056         self.insertLegend(Qwt.QwtLegend(), Qwt.QwtPlot.BottomLegend)
00057 
00058         self._curves = {}
00059 
00060         # TODO: rejigger these internal data structures so that they're easier
00061         # to work with, and easier to use with set_xlim and set_ylim
00062         #  this may also entail rejiggering the _time_axis so that it's
00063         #  actually time axis data, or just isn't required any more
00064         # new data structure
00065         self._x_limits = [0.0, 10.0]
00066         self._y_limits = [0.0, 10.0]
00067 
00068         # old data structures
00069         self._last_canvas_x = 0
00070         self._last_canvas_y = 0
00071         self._pressed_canvas_y = 0
00072         self._pressed_canvas_x = 0
00073         self._last_click_coordinates = None
00074 
00075         marker_axis_y = Qwt.QwtPlotMarker()
00076         marker_axis_y.setLabelAlignment(Qt.AlignRight | Qt.AlignTop)
00077         marker_axis_y.setLineStyle(Qwt.QwtPlotMarker.HLine)
00078         marker_axis_y.setYValue(0.0)
00079         marker_axis_y.attach(self)
00080 
00081         self._picker = Qwt.QwtPlotPicker(
00082             Qwt.QwtPlot.xBottom, Qwt.QwtPlot.yLeft, Qwt.QwtPicker.PolygonSelection,
00083             Qwt.QwtPlotPicker.PolygonRubberBand, Qwt.QwtPicker.AlwaysOn, self.canvas()
00084         )
00085         self._picker.setRubberBandPen(QPen(Qt.blue))
00086         self._picker.setTrackerPen(QPen(Qt.blue))
00087 
00088         # Initialize data
00089         self.rescale()
00090         #self.move_canvas(0, 0)
00091         self.canvas().setMouseTracking(True)
00092         self.canvas().installEventFilter(self)
00093 
00094     def eventFilter(self, _, event):
00095         if event.type() == QEvent.MouseButtonRelease:
00096             x = self.invTransform(Qwt.QwtPlot.xBottom, event.pos().x())
00097             y = self.invTransform(Qwt.QwtPlot.yLeft, event.pos().y())
00098             self._last_click_coordinates = QPointF(x, y)
00099             self.limits_changed.emit()
00100         elif event.type() == QEvent.MouseMove:
00101             x = self.invTransform(Qwt.QwtPlot.xBottom, event.pos().x())
00102             y = self.invTransform(Qwt.QwtPlot.yLeft, event.pos().y())
00103             coords = QPointF(x, y)
00104             if self._picker.isActive() and self._last_click_coordinates is not None:
00105                 toolTip = 'origin x: %.5f, y: %.5f' % (self._last_click_coordinates.x(), self._last_click_coordinates.y())
00106                 delta = coords - self._last_click_coordinates
00107                 toolTip += '\ndelta x: %.5f, y: %.5f\nlength: %.5f' % (delta.x(), delta.y(), QVector2D(delta).length())
00108             else:
00109                 toolTip = 'buttons\nleft: measure\nmiddle: move\nright: zoom x/y\nwheel: zoom y'
00110             self.setToolTip(toolTip)
00111             self.mouseCoordinatesChanged.emit(coords)
00112         return False
00113 
00114     def log(self, level, message):
00115         self.emit(SIGNAL('logMessage'), level, message)
00116 
00117     def resizeEvent(self, event):
00118         Qwt.QwtPlot.resizeEvent(self, event)
00119         self.rescale()
00120 
00121     def add_curve(self, curve_id, curve_name, curve_color=QColor(Qt.blue), markers_on=False):
00122         curve_id = str(curve_id)
00123         if curve_id in self._curves:
00124             return
00125         curve_object = Qwt.QwtPlotCurve(curve_name)
00126         curve_object.attach(self)
00127         curve_object.setPen(curve_color)
00128         if markers_on:
00129             curve_object.setSymbol(Qwt.QwtSymbol(Qwt.QwtSymbol.Ellipse, QBrush(curve_color), QPen(Qt.black), QSize(4,4)))
00130         self._curves[curve_id] = curve_object
00131 
00132     def remove_curve(self, curve_id):
00133         curve_id = str(curve_id)
00134         if curve_id in self._curves:
00135             self._curves[curve_id].hide()
00136             self._curves[curve_id].attach(None)
00137             del self._curves[curve_id]
00138 
00139     def set_values(self, curve_id, data_x, data_y):
00140         curve = self._curves[curve_id]
00141         curve.setData(data_x, data_y)
00142 
00143     def redraw(self):
00144         self.replot()
00145 
00146     # ----------------------------------------------
00147     # begin qwtplot internal methods
00148     # ----------------------------------------------
00149     def rescale(self):
00150         self.setAxisScale(Qwt.QwtPlot.yLeft,
00151                           self._y_limits[0],
00152                           self._y_limits[1])
00153         self.setAxisScale(Qwt.QwtPlot.xBottom,
00154                           self._x_limits[0],
00155                           self._x_limits[1])
00156 
00157         self._canvas_display_height = self._y_limits[1] - self._y_limits[0]
00158         self._canvas_display_width  = self._x_limits[1] - self._x_limits[0]
00159         self.redraw()
00160 
00161     def rescale_axis_x(self, delta__x):
00162         """
00163         add delta_x to the length of the x axis
00164         """
00165         x_width = self._x_limits[1] - self._x_limits[0]
00166         x_width += delta__x
00167         self._x_limits[1] = x_width + self._x_limits[0]
00168         self.rescale()
00169 
00170     def scale_axis_y(self, max_value):
00171         """
00172         set the y axis height to max_value, about the current center
00173         """
00174         canvas_display_height = max_value
00175         canvas_offset_y = (self._y_limits[1] + self._y_limits[0])/2.0
00176         y_lower_limit = canvas_offset_y - (canvas_display_height / 2)
00177         y_upper_limit = canvas_offset_y + (canvas_display_height / 2)
00178         self._y_limits = [y_lower_limit, y_upper_limit]
00179         self.rescale()
00180 
00181     def move_canvas(self, delta_x, delta_y):
00182         """
00183         move the canvas by delta_x and delta_y in SCREEN COORDINATES
00184         """
00185         canvas_offset_x = delta_x * self._canvas_display_width / self.canvas().width()
00186         canvas_offset_y = delta_y * self._canvas_display_height / self.canvas().height()
00187         self._x_limits = [ l + canvas_offset_x for l in self._x_limits]
00188         self._y_limits = [ l + canvas_offset_y for l in self._y_limits]
00189         self.rescale()
00190 
00191     def mousePressEvent(self, event):
00192         self._last_canvas_x = event.x() - self.canvas().x()
00193         self._last_canvas_y = event.y() - self.canvas().y()
00194         self._pressed_canvas_y = event.y() - self.canvas().y()
00195 
00196     def mouseMoveEvent(self, event):
00197         canvas_x = event.x() - self.canvas().x()
00198         canvas_y = event.y() - self.canvas().y()
00199         if event.buttons() & Qt.MiddleButton:  # middle button moves the canvas
00200             delta_x = self._last_canvas_x - canvas_x
00201             delta_y = canvas_y - self._last_canvas_y
00202             self.move_canvas(delta_x, delta_y)
00203         elif event.buttons() & Qt.RightButton:   # right button zooms
00204             zoom_factor = max(-0.6, min(0.6, (self._last_canvas_y - canvas_y) / 20.0 / 2.0))
00205             delta_y = (self.canvas().height() / 2.0) - self._pressed_canvas_y
00206             self.move_canvas(0, zoom_factor * delta_y * 1.0225)
00207             self.scale_axis_y(max(0.005, self._canvas_display_height - (zoom_factor * self._canvas_display_height)))
00208             self.rescale_axis_x(self._last_canvas_x - canvas_x)
00209         self._last_canvas_x = canvas_x
00210         self._last_canvas_y = canvas_y
00211 
00212     def wheelEvent(self, event):  # mouse wheel zooms the y-axis
00213         # y position of pointer in graph coordinates
00214         canvas_y = event.y() - self.canvas().y()
00215 
00216         zoom_factor = max(-0.6, min(0.6, (event.delta() / 120) / 6.0))
00217         delta_y = (self.canvas().height() / 2.0) - canvas_y
00218         self.move_canvas(0, zoom_factor * delta_y * 1.0225)
00219 
00220         self.scale_axis_y(max(0.0005, self._canvas_display_height - zoom_factor * self._canvas_display_height))
00221         self.limits_changed.emit()
00222 
00223 
00224     def vline(self, x, color):
00225         qWarning("QwtDataPlot.vline is not implemented yet")
00226 
00227     def set_xlim(self, limits):
00228         self.setAxisScale(Qwt.QwtPlot.xBottom, limits[0], limits[1])
00229         self._x_limits = limits
00230 
00231     def set_ylim(self, limits):
00232         self.setAxisScale(Qwt.QwtPlot.yLeft, limits[0], limits[1])
00233         self._y_limits = limits
00234 
00235     def get_xlim(self):
00236         return self._x_limits
00237 
00238     def get_ylim(self):
00239         return self._y_limits
00240 
00241 
00242 if __name__ == '__main__':
00243     from python_qt_binding.QtGui import QApplication
00244 
00245     app = QApplication(sys.argv)
00246     plot = QwtDataPlot()
00247     plot.resize(700, 500)
00248     plot.show()
00249     plot.add_curve(0, '(x/500)^2')
00250     plot.add_curve(1, 'sin(x / 20) * 500')
00251     for i in range(plot._num_value_saved):
00252         plot.update_value(0, (i / 500.0) * (i / 5.0))
00253         plot.update_value(1, math.sin(i / 20.0) * 500)
00254 
00255     sys.exit(app.exec_())


rqt_plot
Author(s): Dorian Scholz
autogenerated on Wed Sep 16 2015 06:58:13