From 6963097588817aede950eca2343d228655d67988 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 11:31:04 -0700 Subject: [PATCH 01/53] commit --- .../flightgear/Aircraft/EasyStar/easystar.xml | 4 +- src/comm/QGCFlightGearLink.cc | 101 ++++++++++++--- src/comm/QGCFlightGearLink.h | 15 +-- src/qgcunittest/FlightGearTest.cc | 85 +++++++++++++ src/qgcunittest/FlightGearTest.h | 58 +++++++++ src/ui/QGCHilConfiguration.ui | 4 +- src/ui/QGCHilFlightGearConfiguration.cc | 119 +++++++++++++++--- src/ui/QGCHilFlightGearConfiguration.h | 23 +++- src/ui/QGCHilFlightGearConfiguration.ui | 2 +- 9 files changed, 361 insertions(+), 50 deletions(-) create mode 100644 src/qgcunittest/FlightGearTest.cc create mode 100644 src/qgcunittest/FlightGearTest.h diff --git a/files/flightgear/Aircraft/EasyStar/easystar.xml b/files/flightgear/Aircraft/EasyStar/easystar.xml index 3477038fef..742c6cb631 100644 --- a/files/flightgear/Aircraft/EasyStar/easystar.xml +++ b/files/flightgear/Aircraft/EasyStar/easystar.xml @@ -91,7 +91,7 @@ <damping_coeff_rebound unit="LBS/FT/SEC"> 4.0 </damping_coeff_rebound> <max_steer unit="DEG">0</max_steer> <brake_group>NONE</brake_group> - <retractable>FIXED</retractable> + <retractable>0</retractable> </contact> <contact type="BOGEY" name="NOSE"> <location unit="M"> @@ -107,7 +107,7 @@ <damping_coeff_rebound unit="LBS/FT/SEC"> 4.0 </damping_coeff_rebound> <max_steer unit="DEG">0</max_steer> <brake_group>NONE</brake_group> - <retractable>FIXED</retractable> + <retractable>0</retractable> </contact> <contact type="STRUCTURE" name="TAIL"> diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index d0164958a6..ac1539c921 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -40,11 +40,14 @@ This file is part of the QGROUNDCONTROL project #include <QHostInfo> #include "MainWindow.h" +// FlightGear process start and connection is quite fragile. Uncomment the define below to get higher level of debug output +// for tracking down problems. +#define DEBUG_FLIGHTGEAR_CONNECT + QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) : socket(NULL), process(NULL), - terraSync(NULL), - flightGearVersion(0), + flightGearVersion(3), startupArguments(startupArguments), _sensorHilEnabled(true), barometerOffsetkPa(0.0f) @@ -58,7 +61,7 @@ QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments this->connectState = false; this->currentPort = 49000+mav->getUASID(); this->mav = mav; - this->name = tr("FlightGear Link (port:%1)").arg(port); + this->name = tr("FlightGear 3.0+ Link (port:%1)").arg(port); setRemoteHost(remoteHost); } @@ -74,6 +77,7 @@ QGCFlightGearLink::~QGCFlightGearLink() * @brief Runs the thread * **/ + void QGCFlightGearLink::run() { qDebug() << "STARTING FLIGHTGEAR LINK"; @@ -305,23 +309,23 @@ void QGCFlightGearLink::processError(QProcess::ProcessError err) switch(err) { case QProcess::FailedToStart: - MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Failed to Start"), tr("Please check if the path and command is correct")); + MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct")); break; case QProcess::Crashed: - MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear")); + MainWindow::instance()->showCriticalMessage(tr("FlightGear Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear")); break; case QProcess::Timedout: - MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Start Timed Out"), tr("Please check if the path and command is correct")); + MainWindow::instance()->showCriticalMessage(tr("FlightGear Start Timed Out"), tr("Please check if the path and command is correct")); break; case QProcess::WriteError: - MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear/TerraSync"), tr("Please check if the path and command is correct")); + MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct")); break; case QProcess::ReadError: - MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear/TerraSync"), tr("Please check if the path and command is correct")); + MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct")); break; case QProcess::UnknownError: default: - MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Error"), tr("Please check if the path and command is correct.")); + MainWindow::instance()->showCriticalMessage(tr("FlightGear Error"), tr("Please check if the path and command is correct.")); break; } } @@ -633,12 +637,6 @@ bool QGCFlightGearLink::disconnectSimulation() delete process; process = NULL; } - if (terraSync) - { - terraSync->close(); - delete terraSync; - terraSync = NULL; - } if (socket) { socket->close(); @@ -653,6 +651,79 @@ bool QGCFlightGearLink::disconnectSimulation() return !connectState; } +/// @brief Splits a space seperated set of command line arguments into a QStringList. +/// Quoted strings are allowed and handled correctly. +/// @param uiArgs Arguments to parse +/// @param argList Returned argument list +/// @return Returns false if the argument list has mistmatced quotes within in. + +bool QGCFlightGearLink::parseUIArguments(QString uiArgs, QStringList& argList) +{ + + // This is not as easy as it seams since some options can be quoted to preserve spaces within things like + // directories. There is likely some crazed regular expression which can do this. But after trying that + // route I gave up and instead here is the code which does it the hard way. Another thing to be aware of + // is that the QStringList passed to QProces::start is similar to what you would get in argv after the + // command line is processed. This means that quoted strings have the quotes removed before making it to argv. + + bool inQuotedString = false; + bool previousSpace = false; + QString currentArg; + for (int i=0; i<uiArgs.size(); i++) { + const QChar chr = uiArgs[i]; + + if (chr == ' ') { + if (inQuotedString) { + // Space is inside quoted string leave it in + currentArg += chr; + continue; + } else { + if (previousSpace) { + // Disregard multiple spaces + continue; + } else { + // We have a space that is finishing an argument + previousSpace = true; + if (inQuotedString) { + MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Mismatched quotes in specified command line options")); + return false; + } + if (!currentArg.isEmpty()) { + argList += currentArg; + currentArg.clear(); + } + } + } + } else if (chr == '\"') { + // Flip the state of being in a quoted string. Note that we specifically do not add the + // quote to the string. This replicates standards command line parsing behaviour. + if (chr == '\"') { + inQuotedString = !inQuotedString; + } + previousSpace = false; + } else { + // Flip the state of being in a quoted string + if (chr == '\"') { + inQuotedString = !inQuotedString; + } + previousSpace = false; + currentArg += chr; + } + } + // We should never end parsing on an unterminated quote + if (inQuotedString) { + return false; + } + + // Finish up last arg + if (!currentArg.isEmpty()) { + argList += currentArg; + currentArg.clear(); + } + + return true; +} + /** * @brief Connect the connection. * diff --git a/src/comm/QGCFlightGearLink.h b/src/comm/QGCFlightGearLink.h index 603286b93d..3409d312c9 100644 --- a/src/comm/QGCFlightGearLink.h +++ b/src/comm/QGCFlightGearLink.h @@ -87,6 +87,8 @@ public: void sensorHilEnabled(bool sensorHilEnabled) { _sensorHilEnabled = sensorHilEnabled; } + + static bool parseUIArguments(QString uiArgs, QStringList& argList); void run(); @@ -130,8 +132,6 @@ public slots: bool connectSimulation(); bool disconnectSimulation(); - void printTerraSyncOutput(); - void printTerraSyncError(); void printFgfsOutput(); void printFgfsError(); void setStartupArguments(QString startupArguments); @@ -147,19 +147,8 @@ protected: QUdpSocket* socket; bool connectState; - quint64 bitsSentTotal; - quint64 bitsSentCurrent; - quint64 bitsSentMax; - quint64 bitsReceivedTotal; - quint64 bitsReceivedCurrent; - quint64 bitsReceivedMax; - quint64 connectionStartTime; - QMutex statisticsMutex; - QMutex dataMutex; - QTimer refreshTimer; UASInterface* mav; QProcess* process; - QProcess* terraSync; unsigned int flightGearVersion; QString startupArguments; bool _sensorHilEnabled; diff --git a/src/qgcunittest/FlightGearTest.cc b/src/qgcunittest/FlightGearTest.cc new file mode 100644 index 0000000000..28b970501c --- /dev/null +++ b/src/qgcunittest/FlightGearTest.cc @@ -0,0 +1,85 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. + + ======================================================================*/ + +#include "FlightGearTest.h" +#include "QGCFlightGearLink.h" + +/// @file +/// @brief FlightGearUnitTest HIL Simulation class +/// +/// @author Don Gagne <don@thegagnes.com> + +FlightGearUnitTest::FlightGearUnitTest(void) +{ + +} + +// Called before every test +void FlightGearUnitTest::init(void) +{ + // Nothing here yet +} + +// Called after every test +void FlightGearUnitTest::cleanup(void) +{ + // Nothing here yet +} + +/// @brief The QGCFlightGearLink::parseUIArguments method is fairly involved so we have a unit +// test for it. +void FlightGearUnitTest::_parseUIArguments_test(void) +{ + typedef struct { + const char* args; + const char* expectedListAsChar; + bool expectedReturn; + } ParseUIArgumentsTestCase_t; + + static const ParseUIArgumentsTestCase_t rgTestCases[] = { + { "foo", "foo", true }, + { "foo bar", "foo|bar", true }, + { "--foo --bar", "--foo|--bar", true }, + { "foo=bar", "foo=bar", true }, + { "foo=bar bar=baz", "foo=bar|bar=baz", true }, + { "foo=\"bar\"", "foo=bar", true }, + { "foo=\"bar\" bar=\"baz\"", "foo=bar|bar=baz", true }, + { "foo=\"b ar\"", "foo=b ar", true }, + { "foo=\"b ar\" bar=\"b az\"", "foo=b ar|bar=b az", true }, + { "foo\"", NULL, false }, + }; + + for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) { + const ParseUIArgumentsTestCase_t* testCase = &rgTestCases[i]; + QStringList returnedArgList; + bool actualReturn = QGCFlightGearLink::parseUIArguments(testCase->args, returnedArgList); + QCOMPARE(actualReturn, testCase->expectedReturn); + if (actualReturn) { + QStringList expectedArgList = QString(testCase->expectedListAsChar).split("|"); + if (returnedArgList != expectedArgList) { + qDebug() << "About to fail: Returned" << returnedArgList << "Expected" << expectedArgList; + } + QVERIFY(returnedArgList == expectedArgList); + } + } +} diff --git a/src/qgcunittest/FlightGearTest.h b/src/qgcunittest/FlightGearTest.h new file mode 100644 index 0000000000..898006c693 --- /dev/null +++ b/src/qgcunittest/FlightGearTest.h @@ -0,0 +1,58 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. + + ======================================================================*/ + +#ifndef TCPLINKTEST_H +#define TCPLINKTEST_H + +#include <QObject> +#include <QtTest> +#include <QApplication> + +#include "AutoTest.h" +#include "TCPLink.h" +#include "MultiSignalSpy.h" + +/// @file +/// @brief FlightGear HIL Simulation unit tests +/// +/// @author Don Gagne <don@thegagnes.com> + +class FlightGearUnitTest : public QObject +{ + Q_OBJECT + +public: + FlightGearUnitTest(void); + +private slots: + void init(void); + void cleanup(void); + + void _parseUIArguments_test(void); + +private: +}; + +DECLARE_TEST(FlightGearUnitTest) + +#endif diff --git a/src/ui/QGCHilConfiguration.ui b/src/ui/QGCHilConfiguration.ui index 1db3ec1b62..8da9ad667b 100644 --- a/src/ui/QGCHilConfiguration.ui +++ b/src/ui/QGCHilConfiguration.ui @@ -39,7 +39,7 @@ </item> <item> <property name="text"> - <string>Flightgear</string> + <string>FlightGear 3.0+</string> </property> </item> <item> @@ -69,7 +69,7 @@ <item row="2" column="0" colspan="2"> <widget class="QLabel" name="statusLabel"> <property name="text"> - <string>No simulator active..</string> + <string></string> </property> </widget> </item> diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc index 67f4eb21d8..f1c5efea37 100644 --- a/src/ui/QGCHilFlightGearConfiguration.cc +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -1,51 +1,127 @@ #include "QGCHilFlightGearConfiguration.h" -#include "ui_QGCHilFlightGearConfiguration.h" #include "MainWindow.h" -QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav,QWidget *parent) : +// Various settings groups and keys +const char* QGCHilFlightGearConfiguration::_settingsGroup = "QGC_HILCONFIG_FLIGHTGEAR"; +const char* QGCHilFlightGearConfiguration::_mavSettingsSubGroupFixedWing = "FIXED_WING"; +const char* QGCHilFlightGearConfiguration::_mavSettingsSubGroupQuadRotor = "QUADROTOR"; +const char* QGCHilFlightGearConfiguration::_aircraftKey = "AIRCRAFT"; +const char* QGCHilFlightGearConfiguration::_optionsKey = "OPTIONS"; +const char* QGCHilFlightGearConfiguration::_barometerOffsetKey = "BARO_OFFSET"; +const char* QGCHilFlightGearConfiguration::_sensorHilKey = "SENSOR_HIL"; + +// Default set of optional command line parameters. If FlightGear won't run HIL without it it should go into +// the QGCFlightGearLink code instead. +const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync --atlas=socket,out,1,localhost,5505,udp"; + +QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent) : QWidget(parent), - mav(mav), - ui(new Ui::QGCHilFlightGearConfiguration) -{ - ui->setupUi(this); + _mav(mav), + _mavSettingsSubGroup(NULL), + _resetOptionsAction(tr("Reset to default options"), this) - QStringList items = QStringList(); - if (mav->getSystemType() == MAV_TYPE_FIXED_WING) +{ + Q_ASSERT(_mav); + + _ui.setupUi(this); + + QStringList items; + if (_mav->getSystemType() == MAV_TYPE_FIXED_WING) { items << "EasyStar"; items << "Rascal110-JSBSim"; items << "c172p"; items << "YardStik"; items << "Malolo1"; + _mavSettingsSubGroup = _mavSettingsSubGroupFixedWing; } - else if (mav->getSystemType() == MAV_TYPE_QUADROTOR) + else if (_mav->getSystemType() == MAV_TYPE_QUADROTOR) { items << "arducopter"; + _mavSettingsSubGroup = _mavSettingsSubGroupQuadRotor; } else { + // FIXME: Should disable all input, won't work. Show error message in the status label thing. items << "<aircraft>"; } - ui->aircraftComboBox->addItems(items); + _ui.aircraftComboBox->addItems(items); + + QSettings settings; + settings.beginGroup(_settingsGroup); + settings.beginGroup(_mavSettingsSubGroup); + QString aircraft = settings.value(_aircraftKey).toString(); + QString options = settings.value(_optionsKey).toString(); + QString baroOffset = settings.value(_barometerOffsetKey).toString(); + bool sensorHil = settings.value(_sensorHilKey, QVariant(true)).toBool(); + settings.endGroup(); + settings.endGroup(); + + if (!aircraft.isEmpty()) { + int index = _ui.aircraftComboBox->findText(aircraft); + if (index != -1) { + _ui.aircraftComboBox->setCurrentIndex(index); + } + } + if (options.isEmpty()) { + options = _defaultOptions; + } + _ui.optionsPlainTextEdit->setPlainText(options); + _ui.barometerOffsetLineEdit->setText(baroOffset); + _ui.sensorHilCheckBox->setChecked(sensorHil); + + // Provide an option on the context menu to reset the option back to default + _ui.optionsPlainTextEdit->setContextMenuPolicy(Qt::CustomContextMenu); + bool success = connect(&_resetOptionsAction, SIGNAL(triggered()), this, SLOT(_setDefaultOptions())); + Q_ASSERT(success); + success = connect(_ui.optionsPlainTextEdit, SIGNAL(customContextMenuRequested(const QPoint&)), this, SLOT(_showContextMenu(const QPoint &))); + Q_ASSERT(success); } QGCHilFlightGearConfiguration::~QGCHilFlightGearConfiguration() { - delete ui; + QString aircraft = _ui.aircraftComboBox->currentText(); + QString options = _ui.optionsPlainTextEdit->toPlainText(); + QString baroOffset = _ui.barometerOffsetLineEdit->text(); + bool sensorHil = _ui.sensorHilCheckBox->isChecked(); + + QSettings settings; + settings.beginGroup(_settingsGroup); + settings.beginGroup(_mavSettingsSubGroup); + + if (aircraft.isEmpty()) { + settings.remove(_aircraftKey); + } else { + settings.setValue(_aircraftKey, aircraft); + } + + if (options.isEmpty() || options == _defaultOptions) { + settings.remove(_optionsKey); + } else { + settings.setValue(_optionsKey, options); + } + + // Double QVariant is to convert from string to float. It will change to 0.0 if invalid. + settings.setValue(_barometerOffsetKey, QVariant(QVariant(baroOffset).toFloat())); + + settings.setValue(_sensorHilKey, QVariant(sensorHil)); + + settings.endGroup(); + settings.endGroup(); } void QGCHilFlightGearConfiguration::on_startButton_clicked() { //XXX check validity of inputs - QString options = ui->optionsPlainTextEdit->toPlainText(); - options.append(" --aircraft=" + ui->aircraftComboBox->currentText()); - mav->enableHilFlightGear(true, options, ui->sensorHilCheckBox->isChecked(), this); + QString options = _ui.optionsPlainTextEdit->toPlainText(); + options.append(" --aircraft=" + _ui.aircraftComboBox->currentText()); + _mav->enableHilFlightGear(true, options, _ui.sensorHilCheckBox->isChecked(), this); } void QGCHilFlightGearConfiguration::on_stopButton_clicked() { - mav->stopHil(); + _mav->stopHil(); } void QGCHilFlightGearConfiguration::on_barometerOffsetLineEdit_textChanged(const QString& baroOffset) @@ -53,3 +129,16 @@ void QGCHilFlightGearConfiguration::on_barometerOffsetLineEdit_textChanged(const emit barometerOffsetChanged(baroOffset.toFloat()); } +void QGCHilFlightGearConfiguration::_showContextMenu(const QPoint &pt) +{ + QMenu* menu = _ui.optionsPlainTextEdit->createStandardContextMenu(); + menu->addAction(&_resetOptionsAction); + menu->exec(_ui.optionsPlainTextEdit->mapToGlobal(pt)); + delete menu; +} + +void QGCHilFlightGearConfiguration::_setDefaultOptions(void) +{ + _ui.optionsPlainTextEdit->setPlainText(_defaultOptions); +} + diff --git a/src/ui/QGCHilFlightGearConfiguration.h b/src/ui/QGCHilFlightGearConfiguration.h index 7e0e489013..0b72996c6b 100644 --- a/src/ui/QGCHilFlightGearConfiguration.h +++ b/src/ui/QGCHilFlightGearConfiguration.h @@ -7,6 +7,8 @@ #include "QGCFlightGearLink.h" #include "UAS.h" +#include "ui_QGCHilFlightGearConfiguration.h" + namespace Ui { class QGCHilFlightGearConfiguration; } @@ -20,16 +22,33 @@ public: ~QGCHilFlightGearConfiguration(); protected: - UAS* mav; private slots: void on_startButton_clicked(); void on_stopButton_clicked(); void on_barometerOffsetLineEdit_textChanged(const QString& baroOffset); + void _setDefaultOptions(void); + void _showContextMenu(const QPoint& pt); private: - Ui::QGCHilFlightGearConfiguration *ui; + Ui::QGCHilFlightGearConfiguration _ui; + UAS* _mav; /// mav associated with this ui + + static const char* _settingsGroup; /// Top level settings group + const char* _mavSettingsSubGroup; /// We maintain a settings sub group per mav type + + static const char* _mavSettingsSubGroupFixedWing; /// Subgroup if mav type is MAV_TYPE_FIXED_WING + static const char* _mavSettingsSubGroupQuadRotor; /// Subgroup is mav type is MAV_TYPE_QUADROTOR + static const char* _aircraftKey; /// Settings key for aircraft selection + static const char* _optionsKey; /// Settings key for FlightGear cmd line options + static const char* _barometerOffsetKey; /// Settings key for barometer offset + static const char* _sensorHilKey; /// Settings key for Sensor Hil checkbox + + static const char* _defaultOptions; /// Default set of FlightGEar command line options + + QAction _resetOptionsAction; /// Context menu item to reset options to default + signals: void barometerOffsetChanged(float barometerOffsetkPa); }; diff --git a/src/ui/QGCHilFlightGearConfiguration.ui b/src/ui/QGCHilFlightGearConfiguration.ui index c91f992ac7..96bb40fcaf 100644 --- a/src/ui/QGCHilFlightGearConfiguration.ui +++ b/src/ui/QGCHilFlightGearConfiguration.ui @@ -68,7 +68,7 @@ </sizepolicy> </property> <property name="plainText"> - <string>--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-sound --disable-random-objects --disable-ai-models --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --prop:/engines/engine/running=true</string> + <string></string> </property> </widget> </item> -- GitLab From 0f90f07977c9da6e8ae84da823ae7d8a178f1cb9 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 12:51:31 -0700 Subject: [PATCH 02/53] commit --- qgroundcontrol.pro | 6 +- src/comm/QGCFlightGearLink.cc | 610 +++++++++++++++++++++------------- src/comm/QGCFlightGearLink.h | 9 +- 3 files changed, 394 insertions(+), 231 deletions(-) diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 6475dc52f6..328653986a 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -187,7 +187,8 @@ DebugBuild { src/qgcunittest/MockUAS.h \ src/qgcunittest/MockQGCUASParamManager.h \ src/qgcunittest/MultiSignalSpy.h \ - src/qgcunittest/FlightModeConfigTest.h + src/qgcunittest/FlightModeConfigTest.h \ + src/qgcunittest/FlightGearTest.h SOURCES += \ src/qgcunittest/UASUnitTest.cc \ @@ -195,7 +196,8 @@ DebugBuild { src/qgcunittest/MockUAS.cc \ src/qgcunittest/MockQGCUASParamManager.cc \ src/qgcunittest/MultiSignalSpy.cc \ - src/qgcunittest/FlightModeConfigTest.cc + src/qgcunittest/FlightModeConfigTest.cc \ + src/qgcunittest/FlightGearTest.cc } # diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index ac1539c921..b8198a5eef 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -73,226 +73,86 @@ QGCFlightGearLink::~QGCFlightGearLink() } } -/** - * @brief Runs the thread - * - **/ - +/// @brief Runs the simulation thread. We do setup work here which needs to happen in the seperate thread. void QGCFlightGearLink::run() { - qDebug() << "STARTING FLIGHTGEAR LINK"; - - if (!mav) return; + Q_ASSERT(mav); + Q_ASSERT(!_fgProcessName.isEmpty()); + + // We communicate with FlightGear over a UDP socket socket = new QUdpSocket(this); + Q_CHECK_PTR(socket); socket->moveToThread(this); - connectState = socket->bind(host, port); - + // FIXME: How do we deal with a failed bind. Signal? + socket->bind(host, port); QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); - - process = new QProcess(this); - process->moveToThread(this); - terraSync = new QProcess(this); - terraSync->moveToThread(this); - - connect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); - connect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float))); - connect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int))); - connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); - + + + // Connect to the various HIL signals that we use to then send information across the UDP protocol to FlightGear. + connect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), + this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); + connect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), + mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float))); + connect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), + mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int))); + connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), + mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); + + // FIXME: Does this need to be called from the new thread + + // FIXME: Why the need for dynamic cast. Missing virtual in interface? + // Wait until we know we can actually start FlightGear? UAS* uas = dynamic_cast<UAS*>(mav); if (uas) { uas->startHil(); } - - //connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(sendUAVUpdate())); + + // Start a new process to run FlightGear in + process = new QProcess(this); + Q_CHECK_PTR(process); + process->moveToThread(this); + // Catch process error - QObject::connect( process, SIGNAL(error(QProcess::ProcessError)), - this, SLOT(processError(QProcess::ProcessError))); - QObject::connect( terraSync, SIGNAL(error(QProcess::ProcessError)), - this, SLOT(processError(QProcess::ProcessError))); - // Start Flightgear - QStringList flightGearArguments; - QString processFgfs; - QString processTerraSync; - QString fgRoot; - QString fgScenery; - QString terraSyncScenery; - QString fgAircraft; - -#ifdef Q_OS_MACX - processFgfs = "/Applications/FlightGear.app/Contents/Resources/fgfs"; - processTerraSync = "/Applications/FlightGear.app/Contents/Resources/terrasync"; - //fgRoot = "/Applications/FlightGear.app/Contents/Resources/data"; - fgScenery = "/Applications/FlightGear.app/Contents/Resources/data/Scenery"; - terraSyncScenery = "/Applications/FlightGear.app/Contents/Resources/data/Scenery-TerraSync"; - // /Applications/FlightGear.app/Contents/Resources/data/Scenery: + // FIXME: What happens if you quit FG from app side? Shouldn't that be the norm, instead of exiting process? + connect(process, SIGNAL(error(QProcess::ProcessError)), this, SLOT(processError(QProcess::ProcessError))); +#ifdef DEBUG_FLIGHTGEAR_CONNECT + connect(process, SIGNAL(readyReadStandardOutput()), this, SLOT(printFgfsOutput())); + connect(process, SIGNAL(readyReadStandardError()), this, SLOT(printFgfsError())); #endif - -#ifdef Q_OS_WIN32 - processFgfs = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs"; - //fgRoot = "C:\\Program Files (x86)\\FlightGear\\data"; - fgScenery = "C:\\Program Files (x86)\\FlightGear\\data\\Scenery"; - terraSyncScenery = "C:\\Program Files (x86)\\FlightGear\\data\\Scenery-Terrasync"; -#endif - -#ifdef Q_OS_LINUX - processFgfs = "fgfs"; - //fgRoot = "/usr/share/flightgear"; - QString fgScenery1 = "/usr/share/flightgear/data/Scenery"; - QString fgScenery2 = "/usr/share/games/flightgear/Scenery"; // Ubuntu default location - fgScenery = ""; //Flightgear can also start with fgScenery = "" - if (QDir(fgScenery1).exists()) - fgScenery = fgScenery1; - else if (QDir(fgScenery2).exists()) - fgScenery = fgScenery2; - - - processTerraSync = "nice"; //according to http://wiki.flightgear.org/TerraSync, run with lower priority - terraSyncScenery = QDir::homePath() + "/.terrasync/Scenery"; //according to http://wiki.flightgear.org/TerraSync a separate directory is used -#endif - - fgAircraft = QApplication::applicationDirPath() + "/files/flightgear/Aircraft"; - - // Sanity checks - bool sane = true; -// QFileInfo executable(processFgfs); -// if (!executable.isExecutable()) -// { -// MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("FlightGear was not found at %1").arg(processFgfs)); -// sane = false; -// } - -// QFileInfo root(fgRoot); -// if (!root.isDir()) -// { -// MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("FlightGear data directory was not found at %1").arg(fgRoot)); -// sane = false; -// } - -// QFileInfo scenery(fgScenery); -// if (!scenery.isDir()) -// { -// MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("FlightGear scenery directory was not found at %1").arg(fgScenery)); -// sane = false; -// } - -// QFileInfo terraSyncExecutableInfo(processTerraSync); -// if (!terraSyncExecutableInfo.isExecutable()) -// { -// MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("TerraSync was not found at %1").arg(processTerraSync)); -// sane = false; -// } - - - if (!sane) return; - - // --atlas=socket,out,1,localhost,5505,udp - // terrasync -p 5505 -S -d /usr/local/share/TerraSync - - /*Prepare FlightGear Arguments */ - //flightGearArguments << QString("--fg-root=%1").arg(fgRoot); - flightGearArguments << QString("--fg-scenery=%1:%2").arg(fgScenery).arg(terraSyncScenery); //according to http://wiki.flightgear.org/TerraSync a separate directory is used - flightGearArguments << QString("--fg-aircraft=%1").arg(fgAircraft); - if (mav->getSystemType() == MAV_TYPE_QUADROTOR) - { - flightGearArguments << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol-quadrotor").arg(port); - flightGearArguments << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol-quadrotor").arg(currentPort); - } - else - { - flightGearArguments << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol-fixed-wing").arg(port); - flightGearArguments << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol-fixed-wing").arg(currentPort); - } - flightGearArguments << "--atlas=socket,out,1,localhost,5505,udp"; -// flightGearArguments << "--in-air"; -// flightGearArguments << "--roll=0"; -// flightGearArguments << "--pitch=0"; -// flightGearArguments << "--vc=90"; -// flightGearArguments << "--heading=300"; -// flightGearArguments << "--timeofday=noon"; -// flightGearArguments << "--disable-hud-3d"; -// flightGearArguments << "--disable-fullscreen"; -// flightGearArguments << "--geometry=400x300"; -// flightGearArguments << "--disable-anti-alias-hud"; -// flightGearArguments << "--wind=0@0"; -// flightGearArguments << "--turbulence=0.0"; -// flightGearArguments << "--prop:/sim/frame-rate-throttle-hz=30"; -// flightGearArguments << "--control=mouse"; -// flightGearArguments << "--disable-intro-music"; -// flightGearArguments << "--disable-sound"; -// flightGearArguments << "--disable-random-objects"; -// flightGearArguments << "--disable-ai-models"; -// flightGearArguments << "--shading-flat"; -// flightGearArguments << "--fog-disable"; -// flightGearArguments << "--disable-specular-highlight"; -// //flightGearArguments << "--disable-skyblend"; -// flightGearArguments << "--disable-random-objects"; -// flightGearArguments << "--disable-panel"; -// //flightGearArguments << "--disable-horizon-effect"; -// flightGearArguments << "--disable-clouds"; -// flightGearArguments << "--fdm=jsb"; -// flightGearArguments << "--units-meters"; //XXX: check: the protocol xml has already a conversion from feet to m? -// flightGearArguments << "--notrim"; - - flightGearArguments += startupArguments.split(" "); - if (mav->getSystemType() == MAV_TYPE_QUADROTOR) - { - // Start all engines of the quad - flightGearArguments << "--prop:/engines/engine[0]/running=true"; - flightGearArguments << "--prop:/engines/engine[1]/running=true"; - flightGearArguments << "--prop:/engines/engine[2]/running=true"; - flightGearArguments << "--prop:/engines/engine[3]/running=true"; - } - else - { - flightGearArguments << "--prop:/engines/engine/running=true"; + + if (!_fgProcessWorkingDirPath.isEmpty()) { + process->setWorkingDirectory(_fgProcessWorkingDirPath); + qDebug() << "Working directory" << process->workingDirectory(); } - flightGearArguments << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude()); - flightGearArguments << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude()); - //The altitude is not set because an altitude not equal to the ground altitude leads to a non-zero default throttle in flightgear - //Without the altitude-setting the aircraft is positioned on the ground - //flightGearArguments << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude()); - - // Add new argument with this: flightGearArguments << ""; - //flightGearArguments << QString("--aircraft=%2").arg(aircraft); - - /*Prepare TerraSync Arguments */ - QStringList terraSyncArguments; -#ifdef Q_OS_LINUX - terraSyncArguments << "terrasync"; + +#ifdef Q_OS_WIN32 + // On Windows we need to full qualify the location of the excecutable. The call to setWorkingDirectory only + // sets the process context, not the QProcess::start context. For some strange reason this is not the case on + // OSX. + QDir fgProcessFullyQualified(_fgProcessWorkingDirPath); + _fgProcessName = fgProcessFullyQualified.absoluteFilePath(_fgProcessName); #endif - terraSyncArguments << "-p"; - terraSyncArguments << "5505"; - terraSyncArguments << "-S"; - terraSyncArguments << "-d"; - terraSyncArguments << terraSyncScenery; //according to http://wiki.flightgear.org/TerraSync a separate directory is used - -#ifdef Q_OS_LINUX - /* Setting environment */ - QProcessEnvironment env = QProcessEnvironment::systemEnvironment(); - process->setProcessEnvironment(env); - terraSync->setProcessEnvironment(env); + + // FIXME: Need to clean up this debug arg list stuff + QStringList debugArgList; + debugArgList << "--log-level=debug"; + //debugArgList += "--fg-scenery=" + fgSceneryPath + ""; + //debugArgList += "--fg-root=" + fgRootPath + ""; + + debugArgList += "--fg-root=\"c:\\Flight Gear\\data\""; + debugArgList += "--fg-scenery=\"c:\\Flight Gear\\data\\Scenery;c:\\Flight Gear\\scenery;C:\\Flight Gear\\terrasync\""; +#ifdef DEBUG_FLIGHTGEAR_CONNECT + qDebug() << "Starting FlightGear" << _fgProcessWorkingDirPath << _fgProcessName << _fgArgList; + qDebug() << "Debug args" << debugArgList; #endif -// connect (terraSync, SIGNAL(readyReadStandardOutput()), this, SLOT(printTerraSyncOutput())); -// connect (terraSync, SIGNAL(readyReadStandardError()), this, SLOT(printTerraSyncError())); - terraSync->start(processTerraSync, terraSyncArguments); -// qDebug() << "STARTING: " << processTerraSync << terraSyncArguments; - - process->start(processFgfs, flightGearArguments); -// connect (process, SIGNAL(readyReadStandardOutput()), this, SLOT(printFgfsOutput())); -// connect (process, SIGNAL(readyReadStandardError()), this, SLOT(printFgfsError())); - - - + + process->start(_fgProcessName, /*debugArgList*/ _fgArgList); + emit simulationConnected(connectState); if (connectState) { emit simulationConnected(); - connectionStartTime = QGC::groundTimeUsecs()/1000; } - qDebug() << "STARTING SIM"; - -// qDebug() << "STARTING: " << processFgfs << flightGearArguments; exec(); } @@ -731,34 +591,334 @@ bool QGCFlightGearLink::parseUIArguments(QString uiArgs, QStringList& argList) **/ bool QGCFlightGearLink::connectSimulation() { - + // We setup all the information we need to start FlightGear here such that if something goes + // wrong we can return false out of here. All of this happens on the main UI thread. Once we + // have that information setup we start the thread which will call run, which will in turn + // start the various FG processes on the seperate thread. + + // FixMe: Does returning false out of here leave in inconsistent state? + + qDebug() << "STARTING FLIGHTGEAR LINK"; + + // FIXME: !mav is failure isn't it? + if (!mav) { + return false; + } + + // FIXME: Pull previous information from settings + + QString fgAppName; + QString fgRootPath; // FlightGear root data directory as specified by --fg-root + bool fgRootDirOverride = false; // true: User has specified --fg-root from ui options + QString fgSceneryPath; // FlightGear scenery path as specified by --fg-scenery + bool fgSceneryDirOverride = false; // true: User has specified --fg-scenery from ui options + QDir fgAppDir; // Location of main FlightGear application + +#if defined Q_OS_MACX + // Mac installs will default to the /Applications folder 99% of the time. Anything other than + // that is pretty non-standard so we don't try to get fancy beyond hardcoding that path. + fgAppDir.setPath("/Applications"); + fgAppName = "FlightGear.app"; + _fgProcessName = "./fgfs.sh"; + _fgProcessWorkingDirPath = "/Applications/FlightGear.app/Contents/Resources/"; + fgRootPath = "/Applications/FlightGear.app/Contents/Resources/data/"; +#elif defined Q_OS_WIN32 + fgProcessName = "fgfs.exe"; + //fgProcessWorkingDir = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32"; + + // Windows installs are not as easy to determine. Default installation is to + // C:\Program Files\FlightGear, but that can be easily changed. That also doesn't + // tell us whether the user is running 32 or 64 bit which will both be installed there. + // The preferences for the fgrun app will tell us which version they are using + // and where it is. That is stored in the $APPDATA\fliggear.org\fgrun.prefs file. This + // looks to be a more stable location and way to determine app location so we use that. + fgAppName = "fgfs.exe"; + const char* appdataEnv = "APPDATA"; + if (!qgetenv(appdataEnv).isEmpty()) { + QString fgrunPrefsFile = QDir(qgetenv(appdataEnv).constData()).absoluteFilePath("flightgear.org/fgrun.prefs"); + qDebug() << fgrunPrefsFile; + QFile file(fgrunPrefsFile); + if (file.open(QIODevice::ReadOnly | QIODevice::Text)) { + QTextStream in(&file); + QString lookahead; // lookahead for continuation lines + while (!in.atEnd() || !lookahead.isEmpty()) { + QString line; + QRegExp regExp; + + // Prefs file has strange format where a line prepended with "+" is a continuation of the previous line. + // So do a lookahead to determine if we have a continuation or not. + + if (!lookahead.isEmpty()) { + line = lookahead; + lookahead.clear(); + } else { + line = in.readLine(); + } + + if (!in.atEnd()) { + lookahead = in.readLine(); + regExp.setPattern("^\\+(.*)"); + if (regExp.indexIn(lookahead) == 0) { + Q_ASSERT(regExp.captureCount() == 1); + line += regExp.cap(1); + lookahead.clear(); + } + } + + regExp.setPattern("^fg_exe:(.*)"); + if (regExp.indexIn(line) == 0 && regExp.captureCount() == 1) { + QString fgExeLocationFullQualified = regExp.cap(1); + qDebug() << fgExeLocationFullQualified; + regExp.setPattern("(.*)\\\\fgfs.exe"); + if (regExp.indexIn(fgExeLocationFullQualified) == 0 && regExp.captureCount() == 1) { + fgAppDir.setPath(regExp.cap(1)); + fgProcessWorkingDirPath = fgAppDir.absolutePath(); + qDebug() << "fg_exe" << fgAppDir.absolutePath(); + } + continue; + } + + regExp.setPattern("^fg_root:(.*)"); + if (regExp.indexIn(line) == 0 && regExp.captureCount() == 1) { + fgRootPath = QDir(regExp.cap(1)).absolutePath(); + qDebug() << "fg_root" << fgRootPath; + continue; + } + + regExp.setPattern("^fg_scenery:(.*)"); + if (regExp.indexIn(line) == 0 && regExp.captureCount() == 1) { + // Scenery can contain multiple paths seperated by ';' so don't do QDir::absolutePath on it + fgSceneryPath = regExp.cap(1); + qDebug() << "fg_scenery" << fgSceneryPath; + continue; + } + } + } + } +#elif defined Q_OS_LINUX + // Linux installs to a location on the path so we don't need a directory to run the executable + fgAppName = "fgfs"; + fgProcessName = "fgfs"; + fgRootPath = "/usr/share/games/flightgear/"; // Default Ubuntu location as best guess +#else +#error Unknown OS build flavor +#endif + + // Validate the FlightGear application directory location. Linux runs from path so we don't validate on that OS. +#ifndef Q_OS_LINUX + Q_ASSERT(!fgAppName.isEmpty()); + QString fgAppFullyQualified = fgAppDir.absoluteFilePath(fgAppName); + while (!QFileInfo(fgAppFullyQualified).exists()) { + QMessageBox msgBox(QMessageBox::Critical, + tr("FlightGear application not found"), + tr("FlightGear application not found at: %1").arg(fgAppFullyQualified), + QMessageBox::Cancel, + MainWindow::instance()); + msgBox.setWindowModality(Qt::ApplicationModal); + msgBox.addButton(tr("I'll specify directory"), QMessageBox::ActionRole); + if (msgBox.exec() == QMessageBox::Cancel) { + return false; + } + + // Let the user pick the right directory + fgAppDir.setPath(QFileDialog::getExistingDirectory(MainWindow::instance(), tr("Please select directory of FlightGear application : ") + fgAppName)); + fgAppFullyQualified = fgAppDir.absoluteFilePath(fgAppName); + } +#endif + + // Split the space seperated command line arguments coming in from the ui into a QStringList since + // that is what QProcess::start needs. + QStringList uiArgList; + bool mismatchedQuotes = parseUIArguments(startupArguments, uiArgList); + if (!mismatchedQuotes) { + MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Mismatched quotes in specified command line options")); + return false; + } + + // Add the user specified arguments to our argument list +#ifdef DEBUG_FLIGHTGEAR_CONNECT + qDebug() << "Split arguments" << uiArgList; +#endif + _fgArgList += uiArgList; + + // Add --fg-root command line arg. If --fg-root is specified from the ui we use that instead. + // We need to know what --fg-root is set to because we are going to use it to validate + // communication protocols. + if (startupArguments.contains("--fg-root=", Qt::CaseInsensitive)) { + // FIXME: Won't handle missing quotes + const char* regExpStr = "--fg-root=(.*)"; + int index = _fgArgList.indexOf(QRegExp(regExpStr, Qt::CaseInsensitive)); + Q_ASSERT(index != -1); + QString rootArg(_fgArgList[index]); + QRegExp regExp(regExpStr); + index = regExp.indexIn(rootArg); + Q_ASSERT(index != -1); + fgRootPath = regExp.cap(1); + qDebug() << "--fg-root override" << fgRootPath; + fgRootDirOverride = true; + } else { + _fgArgList += "--fg-root=" + fgRootPath; + } + + // Add --fg-scenery command line arg. If --fg-scenery is specified from the ui we use that instead. + // On Windows --fg-scenery is required on the command line otherwise FlightGear won't boot. + // FIXME: Use single routine for both overrides + if (startupArguments.contains("--fg-scenery=", Qt::CaseInsensitive)) { + // FIXME: Won't handle missing quotes + const char* regExpStr = "--fg-scenery=(.*)"; + int index = _fgArgList.indexOf(QRegExp(regExpStr, Qt::CaseInsensitive)); + Q_ASSERT(index != -1); + QString rootArg(_fgArgList[index]); + QRegExp regExp(regExpStr); + index = regExp.indexIn(rootArg); + Q_ASSERT(index != -1); + Q_ASSERT(regExp.captureCount() == 1); + fgSceneryPath = regExp.cap(1); + qDebug() << "--fg-scenery override" << fgSceneryPath; + fgSceneryDirOverride = true; + } else if (!fgSceneryPath.isEmpty()) { + _fgArgList += "--fg-scenery=" + fgSceneryPath; + } + +#ifdef Q_OS_WIN32 + // Windows won't start without an --fg-scenery set. We don't validate the directory in the path since + // it can be multiple paths. + if (fgSceneryPath.isEmpty()) { + QString errMsg; + if (fgSceneryDirOverride) { + errMsg = tr("--fg-scenery directory specified from ui option not found: %1").arg(fgSceneryPath); + } else { + errMsg = tr("Unable to automatically determine --fg-scenery directory location. You will need to specify --fg-scenery=directory as an additional command line parameter from ui."); + } + MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), errMsg); + return false; + } +#endif + + // Check that we have a good fgRootDir set before we use it to check communication protocol files. + if (fgRootPath.isEmpty() || !QFileInfo(fgRootPath).isDir()) { + QString errMsg; + if (fgRootDirOverride) { + errMsg = tr("--fg-root directory specified from ui option not found: %1").arg(fgRootPath); + } else if (fgRootPath.isEmpty()) { + errMsg = tr("Unable to automatically determine --fg-root directory location. You will need to specify --fg-root=<directory> as an additional command line parameter from ui."); + } else { + errMsg = tr("Unable to automatically determine --fg-root directory location. Attempted directory '%1', which does not exist. You will need to specify --fg-root=<directory> as an additional command line parameter from ui.").arg(fgRootPath); + } + MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), errMsg); + return false; + } + + // Setup and verify directory which contains QGC provided aircraft files + QString qgcAircraftDir(QApplication::applicationDirPath() + "/files/flightgear/Aircraft"); + if (!QFileInfo(qgcAircraftDir).isDir()) { + MainWindow::instance()->showCriticalMessage(tr("Incorrect QGroundControl installation"), tr("Aircraft directory is missing: '%1'.").arg(qgcAircraftDir)); + return false; + } + _fgArgList += "--fg-aircraft=" + qgcAircraftDir; + + // Setup protocol we will be using to communicate with FlightGear + QString fgProtocol(mav->getSystemType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); + QString fgProtocolArg("--generic=socket,%1,50,127.0.0.1,%2,udp,%3"); + _fgArgList << fgProtocolArg.arg("out").arg(port).arg(fgProtocol); + _fgArgList << fgProtocolArg.arg("in").arg(currentPort).arg(fgProtocol); + + // Verify directory where FlightGear stores communicaton protocols. + QDir fgProtocolDir(fgRootPath); + if (!fgProtocolDir.cd("Protocol")) { + MainWindow::instance()->showCriticalMessage(tr("Incorrect FlightGear setup"), tr("Protocol directory is missing: '%1'. Command line parameter for --fg-root may be set incorrectly.").arg(fgProtocolDir.path())); + return false; + } + + // Verify directory which contains QGC provided FlightGear communication protocol files + QDir qgcProtocolDir(QApplication::applicationDirPath() + "/files/flightgear/Protocol/"); + if (!qgcProtocolDir.isReadable()) { + MainWindow::instance()->showCriticalMessage(tr("Incorrect QGroundControl installation"), tr("Protocol directory is missing (%1).").arg(qgcProtocolDir.path())); + return false; + } + + // Communication protocol must be in FlightGear protocol directory. There does not appear to be any way + // around this by specifying something on the FlightGear command line. FG code does direct append + // of protocol xml file to $FG_ROOT and $FG_ROOT only allows a single directory to be specified. + QString fgProtocolXmlFile = fgProtocol + ".xml"; + QString fgProtocolFileFullyQualified = fgProtocolDir.absoluteFilePath(fgProtocolXmlFile); + if (!QFileInfo(fgProtocolFileFullyQualified).exists()) { + QMessageBox msgBox(QMessageBox::Critical, + tr("FlightGear Failed to Start"), + tr("FlightGear Failed to Start. QGroundControl protocol (%1) not installed to FlightGear Protocol directory (%2)").arg(fgProtocolXmlFile).arg(fgProtocolDir.path()), + QMessageBox::Cancel, + MainWindow::instance()); + msgBox.setWindowModality(Qt::ApplicationModal); + msgBox.addButton(tr("Fix it for me"), QMessageBox::ActionRole); + if (msgBox.exec() == QMessageBox::Cancel) { + return false; + } + + // Make sure we can find the communication protocol file in QGC install before we attempt to copy to FlightGear + QString qgcProtocolFileFullyQualified = qgcProtocolDir.absoluteFilePath(fgProtocolXmlFile); + if (!QFileInfo(qgcProtocolFileFullyQualified).exists()) { + MainWindow::instance()->showCriticalMessage(tr("Incorrect QGroundControl installation"), tr("FlightGear protocol file missing: %1").arg(qgcProtocolFileFullyQualified)); + return false; + } + + // Now that we made it this far, we should be able to try to copy the protocol file to FlightGear. + bool succeeded = QFile::copy(qgcProtocolFileFullyQualified, fgProtocolFileFullyQualified); + if (!succeeded) { + MainWindow::instance()->showCriticalMessage(tr("Copy failed"), tr("Copy from (%1) to (%2) failed, possibly due to permissions issue. You will need to perform manually.").arg(qgcProtocolFileFullyQualified).arg(fgProtocolFileFullyQualified)); + +#ifdef Q_OS_WIN32 + QString copyCmd = QString("copy \"%1\" \"%2\"").arg(qgcProtocolFileFullyQualified).arg(fgProtocolFileFullyQualified); + copyCmd.replace("/", "\\"); +#else + QString copyCmd = QString("sudo cp %1 %2").arg(qgcProtocolFileFullyQualified).arg(fgProtocolFileFullyQualified); +#endif + + QMessageBox msgBox(QMessageBox::Critical, + tr("Copy failed"), +#ifdef Q_OS_WIN32 + tr("Try pasting the following command into a Command Prompt which was started with Run as Administrator: ") + copyCmd, +#else + tr("Try pasting the following command into a shell: ") + copyCmd, +#endif + QMessageBox::Cancel, + MainWindow::instance()); + msgBox.setWindowModality(Qt::ApplicationModal); + msgBox.addButton(tr("Copy to Clipboard"), QMessageBox::ActionRole); + if (msgBox.exec() != QMessageBox::Cancel) { + QApplication::clipboard()->setText(copyCmd); + } + return false; + } + } + + // Start the engines to save a startup step + if (mav->getSystemType() == MAV_TYPE_QUADROTOR) { + // Start all engines of the quad + _fgArgList << "--prop:/engines/engine[0]/running=true"; + _fgArgList << "--prop:/engines/engine[1]/running=true"; + _fgArgList << "--prop:/engines/engine[2]/running=true"; + _fgArgList << "--prop:/engines/engine[3]/running=true"; + } else { + _fgArgList << "--prop:/engines/engine/running=true"; + } + + // We start out at our home position + _fgArgList << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude()); + _fgArgList << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude()); + // The altitude is not set because an altitude not equal to the ground altitude leads to a non-zero default throttle in flightgear + // Without the altitude-setting the aircraft is positioned on the ground + //_fgArgList << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude()); + +#ifdef DEBUG_FLIGHTGEAR_CONNECT + // This tell FlightGear to output highest debug level of log output. Handy for debuggin failures by looking at the FG + // log files. + _fgArgList << "--log-level=debug"; +#endif + start(HighPriority); return true; } -void QGCFlightGearLink::printTerraSyncOutput() -{ - qDebug() << "TerraSync stdout:"; - QByteArray byteArray = terraSync->readAllStandardOutput(); - QStringList strLines = QString(byteArray).split("\n"); - - foreach (QString line, strLines){ - qDebug() << line; - } -} - -void QGCFlightGearLink::printTerraSyncError() -{ - qDebug() << "TerraSync stderr:"; - - QByteArray byteArray = terraSync->readAllStandardError(); - QStringList strLines = QString(byteArray).split("\n"); - - foreach (QString line, strLines){ - qDebug() << line; - } -} - void QGCFlightGearLink::printFgfsOutput() { qDebug() << "fgfs stdout:"; diff --git a/src/comm/QGCFlightGearLink.h b/src/comm/QGCFlightGearLink.h index 3409d312c9..6f16a2f5d8 100644 --- a/src/comm/QGCFlightGearLink.h +++ b/src/comm/QGCFlightGearLink.h @@ -155,10 +155,11 @@ protected: float barometerOffsetkPa; void setName(QString name); - -signals: - - + +private: + QString _fgProcessName; ///< FlightGear process to start + QString _fgProcessWorkingDirPath; ///< Working directory to start FG process in, empty for none + QStringList _fgArgList; ///< Arguments passed to FlightGear process }; #endif // QGCFLIGHTGEARLINK_H -- GitLab From fbfb093177d98c9f1f20411b5e41117bc70b1342 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 13:07:45 -0700 Subject: [PATCH 03/53] commit --- src/comm/QGCFlightGearLink.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index b8198a5eef..48cc019227 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -623,7 +623,7 @@ bool QGCFlightGearLink::connectSimulation() _fgProcessWorkingDirPath = "/Applications/FlightGear.app/Contents/Resources/"; fgRootPath = "/Applications/FlightGear.app/Contents/Resources/data/"; #elif defined Q_OS_WIN32 - fgProcessName = "fgfs.exe"; + _fgProcessName = "fgfs.exe"; //fgProcessWorkingDir = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32"; // Windows installs are not as easy to determine. Default installation is to @@ -672,7 +672,7 @@ bool QGCFlightGearLink::connectSimulation() regExp.setPattern("(.*)\\\\fgfs.exe"); if (regExp.indexIn(fgExeLocationFullQualified) == 0 && regExp.captureCount() == 1) { fgAppDir.setPath(regExp.cap(1)); - fgProcessWorkingDirPath = fgAppDir.absolutePath(); + _fgProcessWorkingDirPath = fgAppDir.absolutePath(); qDebug() << "fg_exe" << fgAppDir.absolutePath(); } continue; -- GitLab From 07e1d07a07b067eb6c50f4b39f871253455dac6b Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 17:00:49 -0700 Subject: [PATCH 04/53] commit --- src/comm/QGCFlightGearLink.cc | 27 +++++++++---------------- src/ui/QGCHilFlightGearConfiguration.cc | 2 +- 2 files changed, 11 insertions(+), 18 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 48cc019227..640cc5bdd4 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -98,16 +98,6 @@ void QGCFlightGearLink::run() connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); - // FIXME: Does this need to be called from the new thread - - // FIXME: Why the need for dynamic cast. Missing virtual in interface? - // Wait until we know we can actually start FlightGear? - UAS* uas = dynamic_cast<UAS*>(mav); - if (uas) - { - uas->startHil(); - } - // Start a new process to run FlightGear in process = new QProcess(this); Q_CHECK_PTR(process); @@ -148,11 +138,10 @@ void QGCFlightGearLink::run() #endif process->start(_fgProcessName, /*debugArgList*/ _fgArgList); + connectState = true; emit simulationConnected(connectState); - if (connectState) { - emit simulationConnected(); - } + emit simulationConnected(); exec(); } @@ -257,13 +246,13 @@ void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float p QString state("%1\t%2\t%3\t%4\t%5\n"); state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle); writeBytes(state.toAscii().constData(), state.length()); -// qDebug() << "updated controls" << rollAilerons << pitchElevator << yawRudder << throttle; + //qDebug() << "Updated controls" << rollAilerons << pitchElevator << yawRudder << throttle; + //qDebug() << "Updated controls" << state; } else { qDebug() << "HIL: Got NaN values from the hardware: isnan output: roll: " << isnan(rollAilerons) << ", pitch: " << isnan(pitchElevator) << ", yaw: " << isnan(yawRudder) << ", throttle: " << isnan(throttle); } - //qDebug() << "Updated controls" << state; } void QGCFlightGearLink::writeBytes(const char* data, qint64 size) @@ -313,7 +302,7 @@ void QGCFlightGearLink::readBytes() // Print string QString state(b); -// qDebug() << "FG LINK GOT:" << state; + //qDebug() << "FG LINK GOT:" << state; QStringList values = state.split("\t"); @@ -508,6 +497,10 @@ bool QGCFlightGearLink::disconnectSimulation() emit simulationDisconnected(); emit simulationConnected(false); + + // Exit the thread + quit(); + return !connectState; } @@ -819,7 +812,7 @@ bool QGCFlightGearLink::connectSimulation() // Setup protocol we will be using to communicate with FlightGear QString fgProtocol(mav->getSystemType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); - QString fgProtocolArg("--generic=socket,%1,50,127.0.0.1,%2,udp,%3"); + QString fgProtocolArg("--generic=socket,%1,300,127.0.0.1,%2,udp,%3"); _fgArgList << fgProtocolArg.arg("out").arg(port).arg(fgProtocol); _fgArgList << fgProtocolArg.arg("in").arg(currentPort).arg(fgProtocol); diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc index f1c5efea37..44630ff6cf 100644 --- a/src/ui/QGCHilFlightGearConfiguration.cc +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -13,7 +13,7 @@ const char* QGCHilFlightGearConfiguration::_sensorHilKey = "SEN // Default set of optional command line parameters. If FlightGear won't run HIL without it it should go into // the QGCFlightGearLink code instead. -const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync --atlas=socket,out,1,localhost,5505,udp"; +const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent) : QWidget(parent), -- GitLab From bac63010ea487c2c50b363ab1004213a520ade93 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 17:13:45 -0700 Subject: [PATCH 05/53] commit --- src/comm/QGCFlightGearLink.cc | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 640cc5bdd4..e48c1d143f 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -691,7 +691,7 @@ bool QGCFlightGearLink::connectSimulation() #elif defined Q_OS_LINUX // Linux installs to a location on the path so we don't need a directory to run the executable fgAppName = "fgfs"; - fgProcessName = "fgfs"; + _fgProcessName = "fgfs"; fgRootPath = "/usr/share/games/flightgear/"; // Default Ubuntu location as best guess #else #error Unknown OS build flavor @@ -786,6 +786,8 @@ bool QGCFlightGearLink::connectSimulation() MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), errMsg); return false; } +#else + Q_UNUSED(fgSceneryDirOverride); #endif // Check that we have a good fgRootDir set before we use it to check communication protocol files. -- GitLab From c8e57f74563033d018123b67b69eb62129552dd0 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 18:37:43 -0700 Subject: [PATCH 06/53] commit --- src/comm/QGCFlightGearLink.cc | 15 +++++++++------ src/comm/QGCFlightGearLink.h | 3 +++ 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index e48c1d143f..198cf8dea0 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -63,6 +63,9 @@ QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments this->mav = mav; this->name = tr("FlightGear 3.0+ Link (port:%1)").arg(port); setRemoteHost(remoteHost); + + // We need a mechanism so show error message from our FGLink thread on the UI thread. This signal connection will do that for us. + connect(this, SIGNAL(showCriticalMessageFromThread(const QString&, const QString&)), MainWindow::instance(), SLOT(showCriticalMessage(const QString&, const QString&))); } QGCFlightGearLink::~QGCFlightGearLink() @@ -158,23 +161,23 @@ void QGCFlightGearLink::processError(QProcess::ProcessError err) switch(err) { case QProcess::FailedToStart: - MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct")); + emit showCriticalMessageFromThread(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct")); break; case QProcess::Crashed: - MainWindow::instance()->showCriticalMessage(tr("FlightGear Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear")); + emit showCriticalMessageFromThread(tr("FlightGear Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear")); break; case QProcess::Timedout: - MainWindow::instance()->showCriticalMessage(tr("FlightGear Start Timed Out"), tr("Please check if the path and command is correct")); + emit showCriticalMessageFromThread(tr("FlightGear Start Timed Out"), tr("Please check if the path and command is correct")); break; case QProcess::WriteError: - MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct")); + emit showCriticalMessageFromThread(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct")); break; case QProcess::ReadError: - MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct")); + emit showCriticalMessageFromThread(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct")); break; case QProcess::UnknownError: default: - MainWindow::instance()->showCriticalMessage(tr("FlightGear Error"), tr("Please check if the path and command is correct.")); + emit showCriticalMessageFromThread(tr("FlightGear Error"), tr("Please check if the path and command is correct.")); break; } } diff --git a/src/comm/QGCFlightGearLink.h b/src/comm/QGCFlightGearLink.h index 6f16a2f5d8..02dc11b94c 100644 --- a/src/comm/QGCFlightGearLink.h +++ b/src/comm/QGCFlightGearLink.h @@ -91,6 +91,9 @@ public: static bool parseUIArguments(QString uiArgs, QStringList& argList); void run(); + +signals: + void showCriticalMessageFromThread(const QString& title, const QString& message); public slots: // void setAddress(QString address); -- GitLab From 976747b083d03b4da7cb47cb968c6251946778f0 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 18:52:36 -0700 Subject: [PATCH 07/53] commit --- src/comm/QGCFlightGearLink.cc | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 198cf8dea0..715648e228 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -127,20 +127,11 @@ void QGCFlightGearLink::run() _fgProcessName = fgProcessFullyQualified.absoluteFilePath(_fgProcessName); #endif - // FIXME: Need to clean up this debug arg list stuff - QStringList debugArgList; - debugArgList << "--log-level=debug"; - //debugArgList += "--fg-scenery=" + fgSceneryPath + ""; - //debugArgList += "--fg-root=" + fgRootPath + ""; - - debugArgList += "--fg-root=\"c:\\Flight Gear\\data\""; - debugArgList += "--fg-scenery=\"c:\\Flight Gear\\data\\Scenery;c:\\Flight Gear\\scenery;C:\\Flight Gear\\terrasync\""; #ifdef DEBUG_FLIGHTGEAR_CONNECT qDebug() << "Starting FlightGear" << _fgProcessWorkingDirPath << _fgProcessName << _fgArgList; - qDebug() << "Debug args" << debugArgList; #endif - process->start(_fgProcessName, /*debugArgList*/ _fgArgList); + process->start(_fgProcessName, _fgArgList); connectState = true; emit simulationConnected(connectState); -- GitLab From 60f3d724ac253913c6c65bc33412cd84d7be7319 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 20:23:43 -0700 Subject: [PATCH 08/53] commit --- src/comm/QGCFlightGearLink.cc | 6 +++--- src/ui/QGCHilFlightGearConfiguration.cc | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 715648e228..15066acb5c 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -42,7 +42,7 @@ This file is part of the QGROUNDCONTROL project // FlightGear process start and connection is quite fragile. Uncomment the define below to get higher level of debug output // for tracking down problems. -#define DEBUG_FLIGHTGEAR_CONNECT +//#define DEBUG_FLIGHTGEAR_CONNECT QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) : socket(NULL), @@ -152,7 +152,7 @@ void QGCFlightGearLink::processError(QProcess::ProcessError err) switch(err) { case QProcess::FailedToStart: - emit showCriticalMessageFromThread(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct")); + emit showCriticalMessageFromThread(tr("FlightGear Failed to Start"), process->errorString()); break; case QProcess::Crashed: emit showCriticalMessageFromThread(tr("FlightGear Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear")); @@ -808,7 +808,7 @@ bool QGCFlightGearLink::connectSimulation() // Setup protocol we will be using to communicate with FlightGear QString fgProtocol(mav->getSystemType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); - QString fgProtocolArg("--generic=socket,%1,300,127.0.0.1,%2,udp,%3"); + QString fgProtocolArg("--generic=socket,%1,50,127.0.0.1,%2,udp,%3"); _fgArgList << fgProtocolArg.arg("out").arg(port).arg(fgProtocol); _fgArgList << fgProtocolArg.arg("in").arg(currentPort).arg(fgProtocol); diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc index 44630ff6cf..732a794e0f 100644 --- a/src/ui/QGCHilFlightGearConfiguration.cc +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -13,7 +13,7 @@ const char* QGCHilFlightGearConfiguration::_sensorHilKey = "SEN // Default set of optional command line parameters. If FlightGear won't run HIL without it it should go into // the QGCFlightGearLink code instead. -const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; +const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent) : QWidget(parent), -- GitLab From bbffbb828aa185c4fe8b15b1dc8e862b80ab31b8 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 21:33:04 -0700 Subject: [PATCH 09/53] commit --- src/ui/QGCHilFlightGearConfiguration.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc index 732a794e0f..8106c8be81 100644 --- a/src/ui/QGCHilFlightGearConfiguration.cc +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -13,7 +13,7 @@ const char* QGCHilFlightGearConfiguration::_sensorHilKey = "SEN // Default set of optional command line parameters. If FlightGear won't run HIL without it it should go into // the QGCFlightGearLink code instead. -const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; +const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent) : QWidget(parent), -- GitLab From 1378b1b094e28d100e13951a41cc403dae5ca855 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 29 May 2014 22:18:37 -0700 Subject: [PATCH 10/53] Thomas changes --- src/comm/QGCFlightGearLink.cc | 2 +- src/ui/QGCHilFlightGearConfiguration.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 15066acb5c..52e240f0c1 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -808,7 +808,7 @@ bool QGCFlightGearLink::connectSimulation() // Setup protocol we will be using to communicate with FlightGear QString fgProtocol(mav->getSystemType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); - QString fgProtocolArg("--generic=socket,%1,50,127.0.0.1,%2,udp,%3"); + QString fgProtocolArg("--generic=socket,%1,300,127.0.0.1,%2,udp,%3"); _fgArgList << fgProtocolArg.arg("out").arg(port).arg(fgProtocol); _fgArgList << fgProtocolArg.arg("in").arg(currentPort).arg(fgProtocol); diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc index 8106c8be81..0488fbbd08 100644 --- a/src/ui/QGCHilFlightGearConfiguration.cc +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -13,7 +13,7 @@ const char* QGCHilFlightGearConfiguration::_sensorHilKey = "SEN // Default set of optional command line parameters. If FlightGear won't run HIL without it it should go into // the QGCFlightGearLink code instead. -const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; +const char* QGCHilFlightGearConfiguration::_defaultOptions = "--roll=0 --pitch=0 --vc=0 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --control=mouse --disable-sound --disable-random-objects --disable-ai-traffic --shading-flat --fog-disable --disable-specular-highlight --disable-panel --disable-clouds --fdm=jsb --units-meters --enable-terrasync"; QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent) : QWidget(parent), -- GitLab From c8c3290ed6c7e61c367a8a7c32683a0d3e0292a2 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Wed, 4 Jun 2014 20:47:40 -0700 Subject: [PATCH 11/53] commit --- src/comm/QGCFlightGearLink.cc | 237 ++++++++++++++++++---------------- src/comm/QGCFlightGearLink.h | 19 +-- 2 files changed, 134 insertions(+), 122 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 52e240f0c1..04cefb63a1 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -40,17 +40,17 @@ This file is part of the QGROUNDCONTROL project #include <QHostInfo> #include "MainWindow.h" -// FlightGear process start and connection is quite fragile. Uncomment the define below to get higher level of debug output +// FlightGear _fgProcess start and connection is quite fragile. Uncomment the define below to get higher level of debug output // for tracking down problems. //#define DEBUG_FLIGHTGEAR_CONNECT QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) : - socket(NULL), - process(NULL), flightGearVersion(3), startupArguments(startupArguments), _sensorHilEnabled(true), - barometerOffsetkPa(0.0f) + barometerOffsetkPa(0.0f), + _udpCommSocket(NULL), + _fgProcess(NULL) { // We're doing it wrong - because the Qt folks got the API wrong: // http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/ @@ -70,7 +70,7 @@ QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments QGCFlightGearLink::~QGCFlightGearLink() { //do not disconnect unless it is connected. - //disconnectSimulation will delete the memory that was allocated for proces, terraSync and socket + //disconnectSimulation will delete the memory that was allocated for proces, terraSync and _udpCommSocket if(connectState){ disconnectSimulation(); } @@ -82,13 +82,12 @@ void QGCFlightGearLink::run() Q_ASSERT(mav); Q_ASSERT(!_fgProcessName.isEmpty()); - // We communicate with FlightGear over a UDP socket - socket = new QUdpSocket(this); - Q_CHECK_PTR(socket); - socket->moveToThread(this); - // FIXME: How do we deal with a failed bind. Signal? - socket->bind(host, port); - QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); + // We communicate with FlightGear over a UDP _udpCommSocket + _udpCommSocket = new QUdpSocket(this); + Q_CHECK_PTR(_udpCommSocket); + _udpCommSocket->moveToThread(this); + _udpCommSocket->bind(host, port); + QObject::connect(_udpCommSocket, SIGNAL(readyRead()), this, SLOT(readBytes())); // Connect to the various HIL signals that we use to then send information across the UDP protocol to FlightGear. @@ -101,27 +100,25 @@ void QGCFlightGearLink::run() connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); - // Start a new process to run FlightGear in - process = new QProcess(this); - Q_CHECK_PTR(process); - process->moveToThread(this); + // Start a new QProcess to run FlightGear in + _fgProcess = new QProcess(this); + Q_CHECK_PTR(_fgProcess); + _fgProcess->moveToThread(this); - // Catch process error - // FIXME: What happens if you quit FG from app side? Shouldn't that be the norm, instead of exiting process? - connect(process, SIGNAL(error(QProcess::ProcessError)), this, SLOT(processError(QProcess::ProcessError))); + connect(_fgProcess, SIGNAL(error(QProcess::ProcessError)), this, SLOT(processError(QProcess::ProcessError))); #ifdef DEBUG_FLIGHTGEAR_CONNECT - connect(process, SIGNAL(readyReadStandardOutput()), this, SLOT(printFgfsOutput())); - connect(process, SIGNAL(readyReadStandardError()), this, SLOT(printFgfsError())); + connect(_fgProcess, SIGNAL(readyReadStandardOutput()), this, SLOT(_printFgfsOutput())); + connect(_fgProcess, SIGNAL(readyReadStandardError()), this, SLOT(_printFgfsError())); #endif if (!_fgProcessWorkingDirPath.isEmpty()) { - process->setWorkingDirectory(_fgProcessWorkingDirPath); - qDebug() << "Working directory" << process->workingDirectory(); + _fgProcess->setWorkingDirectory(_fgProcessWorkingDirPath); + qDebug() << "Working directory" << _fgProcess->workingDirectory(); } #ifdef Q_OS_WIN32 // On Windows we need to full qualify the location of the excecutable. The call to setWorkingDirectory only - // sets the process context, not the QProcess::start context. For some strange reason this is not the case on + // sets the QProcess context, not the QProcess::start context. For some strange reason this is not the case on // OSX. QDir fgProcessFullyQualified(_fgProcessWorkingDirPath); _fgProcessName = fgProcessFullyQualified.absoluteFilePath(_fgProcessName); @@ -131,7 +128,7 @@ void QGCFlightGearLink::run() qDebug() << "Starting FlightGear" << _fgProcessWorkingDirPath << _fgProcessName << _fgArgList; #endif - process->start(_fgProcessName, _fgArgList); + _fgProcess->start(_fgProcessName, _fgArgList); connectState = true; emit simulationConnected(connectState); @@ -152,7 +149,7 @@ void QGCFlightGearLink::processError(QProcess::ProcessError err) switch(err) { case QProcess::FailedToStart: - emit showCriticalMessageFromThread(tr("FlightGear Failed to Start"), process->errorString()); + emit showCriticalMessageFromThread(tr("FlightGear Failed to Start"), _fgProcess->errorString()); break; case QProcess::Crashed: emit showCriticalMessageFromThread(tr("FlightGear Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear")); @@ -272,7 +269,7 @@ void QGCFlightGearLink::writeBytes(const char* data, qint64 size) qDebug() << bytes; qDebug() << "ASCII:" << ascii; #endif - if (connectState && socket) socket->writeDatagram(data, size, currentHost, currentPort); + if (connectState && _udpCommSocket) _udpCommSocket->writeDatagram(data, size, currentHost, currentPort); } /** @@ -288,9 +285,9 @@ void QGCFlightGearLink::readBytes() QHostAddress sender; quint16 senderPort; - unsigned int s = socket->pendingDatagramSize(); + unsigned int s = _udpCommSocket->pendingDatagramSize(); if (s > maxLength) std::cerr << __FILE__ << __LINE__ << " UDP datagram overflow, allowed to read less bytes than datagram size" << std::endl; - socket->readDatagram(data, maxLength, &sender, &senderPort); + _udpCommSocket->readDatagram(data, maxLength, &sender, &senderPort); QByteArray b(data, s); @@ -457,7 +454,7 @@ void QGCFlightGearLink::readBytes() **/ qint64 QGCFlightGearLink::bytesAvailable() { - return socket->pendingDatagramSize(); + return _udpCommSocket->pendingDatagramSize(); } /** @@ -467,24 +464,24 @@ qint64 QGCFlightGearLink::bytesAvailable() **/ bool QGCFlightGearLink::disconnectSimulation() { - disconnect(process, SIGNAL(error(QProcess::ProcessError)), + disconnect(_fgProcess, SIGNAL(error(QProcess::ProcessError)), this, SLOT(processError(QProcess::ProcessError))); disconnect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); disconnect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float))); disconnect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int))); disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); - if (process) + if (_fgProcess) { - process->close(); - delete process; - process = NULL; + _fgProcess->close(); + delete _fgProcess; + _fgProcess = NULL; } - if (socket) + if (_udpCommSocket) { - socket->close(); - delete socket; - socket = NULL; + _udpCommSocket->close(); + delete _udpCommSocket; + _udpCommSocket = NULL; } connectState = false; @@ -500,12 +497,13 @@ bool QGCFlightGearLink::disconnectSimulation() /// @brief Splits a space seperated set of command line arguments into a QStringList. /// Quoted strings are allowed and handled correctly. -/// @param uiArgs Arguments to parse -/// @param argList Returned argument list +/// @param uiArgs Arguments to parse +/// @param argList Returned argument list /// @return Returns false if the argument list has mistmatced quotes within in. bool QGCFlightGearLink::parseUIArguments(QString uiArgs, QStringList& argList) { + // FYI: The only reason this routine is public is so that we can reference it from a unit test. // This is not as easy as it seams since some options can be quoted to preserve spaces within things like // directories. There is likely some crazed regular expression which can do this. But after trying that @@ -571,6 +569,26 @@ bool QGCFlightGearLink::parseUIArguments(QString uiArgs, QStringList& argList) return true; } +/// @brief Locates the specified argument in the argument list, returning the value for it. +/// @param uiArgList Argument list to search through +/// @param argLabel Argument label to search for +/// @param argValue Returned argument value if found +/// @return Returns true if argument found and argValue returned +bool QGCFlightGearLink::_findUIArgument(const QStringList& uiArgList, const QString& argLabel, QString& argValue) +{ + QString regExpStr = argLabel + "=(.*)"; + int index = uiArgList.indexOf(QRegExp(regExpStr, Qt::CaseInsensitive)); + if (index != -1) { + QRegExp regExp(regExpStr); + index = regExp.indexIn(uiArgList[index]); + Q_ASSERT(index != -1); + argValue = regExp.cap(1); + return true; + } else { + return false; + } +} + /** * @brief Connect the connection. * @@ -583,23 +601,17 @@ bool QGCFlightGearLink::connectSimulation() // have that information setup we start the thread which will call run, which will in turn // start the various FG processes on the seperate thread. - // FixMe: Does returning false out of here leave in inconsistent state? - - qDebug() << "STARTING FLIGHTGEAR LINK"; - - // FIXME: !mav is failure isn't it? if (!mav) { return false; } - // FIXME: Pull previous information from settings - - QString fgAppName; - QString fgRootPath; // FlightGear root data directory as specified by --fg-root - bool fgRootDirOverride = false; // true: User has specified --fg-root from ui options - QString fgSceneryPath; // FlightGear scenery path as specified by --fg-scenery - bool fgSceneryDirOverride = false; // true: User has specified --fg-scenery from ui options - QDir fgAppDir; // Location of main FlightGear application + QString fgAppName; + QString fgRootPath; // FlightGear root data directory as specified by --fg-root + QStringList fgRootPathProposedList; // Directories we will attempt to search for --fg-root + bool fgRootDirOverride = false; // true: User has specified --fg-root from ui options + QString fgSceneryPath; // FlightGear scenery path as specified by --fg-scenery + bool fgSceneryDirOverride = false; // true: User has specified --fg-scenery from ui options + QDir fgAppDir; // Location of main FlightGear application #if defined Q_OS_MACX // Mac installs will default to the /Applications folder 99% of the time. Anything other than @@ -608,10 +620,9 @@ bool QGCFlightGearLink::connectSimulation() fgAppName = "FlightGear.app"; _fgProcessName = "./fgfs.sh"; _fgProcessWorkingDirPath = "/Applications/FlightGear.app/Contents/Resources/"; - fgRootPath = "/Applications/FlightGear.app/Contents/Resources/data/"; + fgRootPathProposedList += "/Applications/FlightGear.app/Contents/Resources/data/"; #elif defined Q_OS_WIN32 _fgProcessName = "fgfs.exe"; - //fgProcessWorkingDir = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32"; // Windows installs are not as easy to determine. Default installation is to // C:\Program Files\FlightGear, but that can be easily changed. That also doesn't @@ -667,8 +678,8 @@ bool QGCFlightGearLink::connectSimulation() regExp.setPattern("^fg_root:(.*)"); if (regExp.indexIn(line) == 0 && regExp.captureCount() == 1) { - fgRootPath = QDir(regExp.cap(1)).absolutePath(); - qDebug() << "fg_root" << fgRootPath; + fgRootPathProposedList += QDir(regExp.cap(1)).absolutePath(); + qDebug() << "fg_root" << fgRootPathProposedList[0]; continue; } @@ -686,7 +697,8 @@ bool QGCFlightGearLink::connectSimulation() // Linux installs to a location on the path so we don't need a directory to run the executable fgAppName = "fgfs"; _fgProcessName = "fgfs"; - fgRootPath = "/usr/share/games/flightgear/"; // Default Ubuntu location as best guess + fgRootPathProposedList += "/usr/share/flightgear/data/"; // Default Archlinux location + fgRootPathProposedList += "/usr/share/games/flightgear/"; // Default Ubuntu location #else #error Unknown OS build flavor #endif @@ -708,7 +720,11 @@ bool QGCFlightGearLink::connectSimulation() } // Let the user pick the right directory - fgAppDir.setPath(QFileDialog::getExistingDirectory(MainWindow::instance(), tr("Please select directory of FlightGear application : ") + fgAppName)); + QString dirPath = QFileDialog::getExistingDirectory(MainWindow::instance(), tr("Please select directory of FlightGear application : ") + fgAppName); + if (dirPath.isEmpty()) { + return false; + } + fgAppDir.setPath(dirPath); fgAppFullyQualified = fgAppDir.absoluteFilePath(fgAppName); } #endif @@ -718,7 +734,7 @@ bool QGCFlightGearLink::connectSimulation() QStringList uiArgList; bool mismatchedQuotes = parseUIArguments(startupArguments, uiArgList); if (!mismatchedQuotes) { - MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Mismatched quotes in specified command line options")); + MainWindow::instance()->showCriticalMessage(tr("FlightGear settings"), tr("Mismatched quotes in specified command line options")); return false; } @@ -728,41 +744,50 @@ bool QGCFlightGearLink::connectSimulation() #endif _fgArgList += uiArgList; - // Add --fg-root command line arg. If --fg-root is specified from the ui we use that instead. - // We need to know what --fg-root is set to because we are going to use it to validate - // communication protocols. - if (startupArguments.contains("--fg-root=", Qt::CaseInsensitive)) { - // FIXME: Won't handle missing quotes - const char* regExpStr = "--fg-root=(.*)"; - int index = _fgArgList.indexOf(QRegExp(regExpStr, Qt::CaseInsensitive)); - Q_ASSERT(index != -1); - QString rootArg(_fgArgList[index]); - QRegExp regExp(regExpStr); - index = regExp.indexIn(rootArg); - Q_ASSERT(index != -1); - fgRootPath = regExp.cap(1); - qDebug() << "--fg-root override" << fgRootPath; - fgRootDirOverride = true; - } else { - _fgArgList += "--fg-root=" + fgRootPath; - } + // If we have an --fg-root coming in from the ui options that overrides any internal searching of + // proposed locations. + QString argValue; + fgRootDirOverride = _findUIArgument(_fgArgList, "--fg-root", argValue); + if (fgRootDirOverride) { + fgRootPathProposedList.clear(); + fgRootPathProposedList += argValue; + qDebug() << "--fg-root override" << argValue; + } + + // See if we can find an --fg-root directory from the proposed list. + Q_ASSERT(fgRootPath.isEmpty()); + for (int i=0; i<fgRootPathProposedList.count(); i++) { + fgRootPath = fgRootPathProposedList[i]; + if (QFileInfo(fgRootPath).isDir()) { + // We found it + break; + } else { + fgRootPath.clear(); + } + } + // Alert the user if we couldn't find an --fg-root + if (fgRootPath.isEmpty()) { + QString errMsg; + if (fgRootDirOverride) { + errMsg = tr("--fg-root directory specified from ui option not found: %1").arg(fgRootPath); + } else if (fgRootPath.isEmpty()) { + errMsg = tr("Unable to automatically determine --fg-root directory location. You will need to specify --fg-root=<directory> as an additional command line parameter from ui."); + } + MainWindow::instance()->showCriticalMessage(tr("FlightGear settings"), errMsg); + return false; + } + + if (!fgRootDirOverride) { + _fgArgList += "--fg-root=" + fgRootPath; + } + // Add --fg-scenery command line arg. If --fg-scenery is specified from the ui we use that instead. // On Windows --fg-scenery is required on the command line otherwise FlightGear won't boot. - // FIXME: Use single routine for both overrides - if (startupArguments.contains("--fg-scenery=", Qt::CaseInsensitive)) { - // FIXME: Won't handle missing quotes - const char* regExpStr = "--fg-scenery=(.*)"; - int index = _fgArgList.indexOf(QRegExp(regExpStr, Qt::CaseInsensitive)); - Q_ASSERT(index != -1); - QString rootArg(_fgArgList[index]); - QRegExp regExp(regExpStr); - index = regExp.indexIn(rootArg); - Q_ASSERT(index != -1); - Q_ASSERT(regExp.captureCount() == 1); - fgSceneryPath = regExp.cap(1); - qDebug() << "--fg-scenery override" << fgSceneryPath; - fgSceneryDirOverride = true; + fgSceneryDirOverride = _findUIArgument(_fgArgList, "--fg-scenery", argValue); + if (fgSceneryDirOverride) { + fgSceneryPath = argValue; + qDebug() << "--fg-scenery override" << argValue; } else if (!fgSceneryPath.isEmpty()) { _fgArgList += "--fg-scenery=" + fgSceneryPath; } @@ -777,27 +802,13 @@ bool QGCFlightGearLink::connectSimulation() } else { errMsg = tr("Unable to automatically determine --fg-scenery directory location. You will need to specify --fg-scenery=directory as an additional command line parameter from ui."); } - MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), errMsg); + MainWindow::instance()->showCriticalMessage(tr("FlightGear settings"), errMsg); return false; } #else Q_UNUSED(fgSceneryDirOverride); #endif - // Check that we have a good fgRootDir set before we use it to check communication protocol files. - if (fgRootPath.isEmpty() || !QFileInfo(fgRootPath).isDir()) { - QString errMsg; - if (fgRootDirOverride) { - errMsg = tr("--fg-root directory specified from ui option not found: %1").arg(fgRootPath); - } else if (fgRootPath.isEmpty()) { - errMsg = tr("Unable to automatically determine --fg-root directory location. You will need to specify --fg-root=<directory> as an additional command line parameter from ui."); - } else { - errMsg = tr("Unable to automatically determine --fg-root directory location. Attempted directory '%1', which does not exist. You will need to specify --fg-root=<directory> as an additional command line parameter from ui.").arg(fgRootPath); - } - MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), errMsg); - return false; - } - // Setup and verify directory which contains QGC provided aircraft files QString qgcAircraftDir(QApplication::applicationDirPath() + "/files/flightgear/Aircraft"); if (!QFileInfo(qgcAircraftDir).isDir()) { @@ -808,7 +819,7 @@ bool QGCFlightGearLink::connectSimulation() // Setup protocol we will be using to communicate with FlightGear QString fgProtocol(mav->getSystemType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); - QString fgProtocolArg("--generic=socket,%1,300,127.0.0.1,%2,udp,%3"); + QString fgProtocolArg("--generic=_udpCommSocket,%1,300,127.0.0.1,%2,udp,%3"); _fgArgList << fgProtocolArg.arg("out").arg(port).arg(fgProtocol); _fgArgList << fgProtocolArg.arg("in").arg(currentPort).arg(fgProtocol); @@ -908,10 +919,10 @@ bool QGCFlightGearLink::connectSimulation() return true; } -void QGCFlightGearLink::printFgfsOutput() +void QGCFlightGearLink::_printFgfsOutput(void) { qDebug() << "fgfs stdout:"; - QByteArray byteArray = process->readAllStandardOutput(); + QByteArray byteArray = _fgProcess->readAllStandardOutput(); QStringList strLines = QString(byteArray).split("\n"); foreach (QString line, strLines){ @@ -919,11 +930,11 @@ void QGCFlightGearLink::printFgfsOutput() } } -void QGCFlightGearLink::printFgfsError() +void QGCFlightGearLink::_printFgfsError(void) { qDebug() << "fgfs stderr:"; - QByteArray byteArray = process->readAllStandardError(); + QByteArray byteArray = _fgProcess->readAllStandardError(); QStringList strLines = QString(byteArray).split("\n"); foreach (QString line, strLines){ diff --git a/src/comm/QGCFlightGearLink.h b/src/comm/QGCFlightGearLink.h index 02dc11b94c..a86de73266 100644 --- a/src/comm/QGCFlightGearLink.h +++ b/src/comm/QGCFlightGearLink.h @@ -47,7 +47,6 @@ This file is part of the QGROUNDCONTROL project class QGCFlightGearLink : public QGCHilLink { Q_OBJECT - //Q_INTERFACES(QGCFlightGearLinkInterface:LinkInterface) public: QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005); @@ -103,10 +102,6 @@ public slots: /** @brief Send new control states to the simulation */ void updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode); void updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8); -// /** @brief Remove a host from broadcasting messages to */ -// void removeHost(const QString& host); - // void readPendingDatagrams(); - void processError(QProcess::ProcessError err); /** @brief Set the simulator version as text string */ void setVersion(const QString& version) { @@ -135,10 +130,9 @@ public slots: bool connectSimulation(); bool disconnectSimulation(); - void printFgfsOutput(); - void printFgfsError(); void setStartupArguments(QString startupArguments); void setBarometerOffset(float barometerOffsetkPa); + void processError(QProcess::ProcessError err); protected: QString name; @@ -147,11 +141,9 @@ protected: quint16 currentPort; quint16 port; int id; - QUdpSocket* socket; bool connectState; UASInterface* mav; - QProcess* process; unsigned int flightGearVersion; QString startupArguments; bool _sensorHilEnabled; @@ -159,10 +151,19 @@ protected: void setName(QString name); +private slots: + void _printFgfsOutput(void); + void _printFgfsError(void); + private: + static bool _findUIArgument(const QStringList& uiArgList, const QString& argLabel, QString& argValue); + QString _fgProcessName; ///< FlightGear process to start QString _fgProcessWorkingDirPath; ///< Working directory to start FG process in, empty for none QStringList _fgArgList; ///< Arguments passed to FlightGear process + + QUdpSocket* _udpCommSocket; ///< UDP communication sockect between FG and QGC + QProcess* _fgProcess; ///< FlightGear process }; #endif // QGCFLIGHTGEARLINK_H -- GitLab From dda783ff065c205d23bc63a864c82bb3cc00a851 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Fri, 6 Jun 2014 13:39:11 -0400 Subject: [PATCH 12/53] commit --- src/comm/QGCFlightGearLink.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 04cefb63a1..80e3208f21 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -574,6 +574,7 @@ bool QGCFlightGearLink::parseUIArguments(QString uiArgs, QStringList& argList) /// @param argLabel Argument label to search for /// @param argValue Returned argument value if found /// @return Returns true if argument found and argValue returned + bool QGCFlightGearLink::_findUIArgument(const QStringList& uiArgList, const QString& argLabel, QString& argValue) { QString regExpStr = argLabel + "=(.*)"; @@ -703,8 +704,8 @@ bool QGCFlightGearLink::connectSimulation() #error Unknown OS build flavor #endif - // Validate the FlightGear application directory location. Linux runs from path so we don't validate on that OS. #ifndef Q_OS_LINUX + // Validate the FlightGear application directory location. Linux runs from path so we don't validate on that OS. Q_ASSERT(!fgAppName.isEmpty()); QString fgAppFullyQualified = fgAppDir.absoluteFilePath(fgAppName); while (!QFileInfo(fgAppFullyQualified).exists()) { @@ -744,7 +745,7 @@ bool QGCFlightGearLink::connectSimulation() #endif _fgArgList += uiArgList; - // If we have an --fg-root coming in from the ui options that overrides any internal searching of + // If we have an --fg-root coming in from the ui options, that setting overrides any internal searching of // proposed locations. QString argValue; fgRootDirOverride = _findUIArgument(_fgArgList, "--fg-root", argValue); -- GitLab From 1cad7af3aaf09107c3fc8a21d6328f8e71248af7 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Wed, 11 Jun 2014 11:57:18 -0700 Subject: [PATCH 13/53] Removed mavlinkgen application as it has been unused and deprecated for many months. --- .gitignore | 1 - QGCExternalLibs.pri | 28 - README.md | 3 - src/apps/mavlinkgen/MAVLinkGen.cc | 88 -- src/apps/mavlinkgen/MAVLinkGen.h | 60 -- src/apps/mavlinkgen/README | 29 - .../deploy/mac_create_dmg_mavlinkgen.sh | 7 - .../deploy/mavlinkgen_installer.nsi | 35 - .../mavlinkgen/generator/MAVLinkXMLParser.cc | 754 ------------------ .../mavlinkgen/generator/MAVLinkXMLParser.h | 66 -- .../generator/MAVLinkXMLParserV10.cc | 148 ---- .../generator/MAVLinkXMLParserV10.h | 84 -- .../images/categories/applications-system.svg | 247 ------ .../mavlinkgen/images/status/folder-open.svg | 482 ----------- src/apps/mavlinkgen/license.txt | 195 ----- src/apps/mavlinkgen/main.cc | 46 -- src/apps/mavlinkgen/mavlinkgen.pri | 44 - src/apps/mavlinkgen/mavlinkgen.pro | 22 - src/apps/mavlinkgen/mavlinkgen.qrc | 6 - src/apps/mavlinkgen/msinttypes/inttypes.h | 305 ------- src/apps/mavlinkgen/msinttypes/stdint.h | 247 ------ src/apps/mavlinkgen/template/checksum.h | 139 ---- .../mavlinkgen/template/documentation.dox | 41 - .../mavlinkgen/template/mavlink_checksum.h | 183 ----- src/apps/mavlinkgen/template/mavlink_data.h | 21 - .../mavlinkgen/template/mavlink_options.h | 135 ---- .../mavlinkgen/template/mavlink_protocol.h | 423 ---------- src/apps/mavlinkgen/template/mavlink_types.h | 120 --- src/apps/mavlinkgen/template/protocol.h | 439 ---------- src/apps/mavlinkgen/ui/DomItem.cc | 47 -- src/apps/mavlinkgen/ui/DomItem.h | 24 - src/apps/mavlinkgen/ui/DomModel.cc | 195 ----- src/apps/mavlinkgen/ui/DomModel.h | 34 - src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.cc | 480 ----------- src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.h | 106 --- .../mavlinkgen/ui/XMLCommProtocolWidget.cc | 194 ----- .../mavlinkgen/ui/XMLCommProtocolWidget.h | 89 --- .../mavlinkgen/ui/XMLCommProtocolWidget.ui | 175 ---- 38 files changed, 5742 deletions(-) delete mode 100644 src/apps/mavlinkgen/MAVLinkGen.cc delete mode 100644 src/apps/mavlinkgen/MAVLinkGen.h delete mode 100644 src/apps/mavlinkgen/README delete mode 100644 src/apps/mavlinkgen/deploy/mac_create_dmg_mavlinkgen.sh delete mode 100644 src/apps/mavlinkgen/deploy/mavlinkgen_installer.nsi delete mode 100644 src/apps/mavlinkgen/generator/MAVLinkXMLParser.cc delete mode 100644 src/apps/mavlinkgen/generator/MAVLinkXMLParser.h delete mode 100644 src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.cc delete mode 100644 src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.h delete mode 100644 src/apps/mavlinkgen/images/categories/applications-system.svg delete mode 100644 src/apps/mavlinkgen/images/status/folder-open.svg delete mode 100644 src/apps/mavlinkgen/license.txt delete mode 100644 src/apps/mavlinkgen/main.cc delete mode 100644 src/apps/mavlinkgen/mavlinkgen.pri delete mode 100644 src/apps/mavlinkgen/mavlinkgen.pro delete mode 100644 src/apps/mavlinkgen/mavlinkgen.qrc delete mode 100644 src/apps/mavlinkgen/msinttypes/inttypes.h delete mode 100644 src/apps/mavlinkgen/msinttypes/stdint.h delete mode 100644 src/apps/mavlinkgen/template/checksum.h delete mode 100644 src/apps/mavlinkgen/template/documentation.dox delete mode 100644 src/apps/mavlinkgen/template/mavlink_checksum.h delete mode 100644 src/apps/mavlinkgen/template/mavlink_data.h delete mode 100644 src/apps/mavlinkgen/template/mavlink_options.h delete mode 100644 src/apps/mavlinkgen/template/mavlink_protocol.h delete mode 100644 src/apps/mavlinkgen/template/mavlink_types.h delete mode 100644 src/apps/mavlinkgen/template/protocol.h delete mode 100644 src/apps/mavlinkgen/ui/DomItem.cc delete mode 100644 src/apps/mavlinkgen/ui/DomItem.h delete mode 100644 src/apps/mavlinkgen/ui/DomModel.cc delete mode 100644 src/apps/mavlinkgen/ui/DomModel.h delete mode 100644 src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.cc delete mode 100644 src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.h delete mode 100644 src/apps/mavlinkgen/ui/XMLCommProtocolWidget.cc delete mode 100644 src/apps/mavlinkgen/ui/XMLCommProtocolWidget.h delete mode 100644 src/apps/mavlinkgen/ui/XMLCommProtocolWidget.ui diff --git a/.gitignore b/.gitignore index ee259ce1c0..4f1e63458e 100644 --- a/.gitignore +++ b/.gitignore @@ -21,7 +21,6 @@ tmp debug release /qgroundcontrol -mavlinkgen-build-desktop qgroundcontrol.xcodeproj/** doc/html doc/doxy.log diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index eaea69384b..ce80c1a782 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -123,34 +123,6 @@ INCLUDEPATH += $$MAVLINKPATH INCLUDEPATH += $$MAVLINKPATH/common } -# -# [DEPRECATED] MAVLink generator UI. Provides a GUI interface for generating MAVLink dialects. -# Replaced by mavgenerator.py within the MAVLink project. -# -contains(DEFINES, ENABLE_MAVGEN) { - warning("Including support for MAVLink generator GUI (manual override from command line, CAUTION: deprecated)") -} else:infile(user_config.pri, DEFINES, ENABLE_MAVGEN) { - DEFINES += ENABLE_MAVGEN # infile doesn't automatically include everything in the specified file - warning("Including support for MAVLink generator GUI (manual override from user_config.pri, CAUTION: deprecated)") -} - -contains(DEFINES, ENABLE_MAVGEN) { - # Rename the macro to be consistent with other QGC feature existance macros. - DEFINES -= ENABLE_MAVGEN - DEFINES += QGC_MAVGEN_ENABLED - DEPENDPATH += \ - src/apps/mavlinkgen - - INCLUDEPATH += \ - src/apps/mavlinkgen \ - src/apps/mavlinkgen/ui \ - src/apps/mavlinkgen/generator - - include(src/apps/mavlinkgen/mavlinkgen.pri) -} else { - message("Skipping support for MAVLink generator GUI (deprecated, see README)") -} - # # [OPTIONAL] OpenSceneGraph # Allow the user to override OpenSceneGraph compilation through a DISABLE_OPEN_SCENE_GRAPH diff --git a/README.md b/README.md index 5771904be0..07043d7fc7 100644 --- a/README.md +++ b/README.md @@ -37,9 +37,6 @@ The QUpgrade module relies on `libudev` on Linux platforms, so be sure to instal ### Specifying MAVLink dialects The MAVLink dialect compiled by default by QGC is for the ardupilotmega. This will happen if no other dialects are specified. Setting the `MAVLINK_CONF` variable sets the dialects, with more than one specified in a space-separated list. Note that doing this may result in compilation errors as certain dialects may conflict with each other! -### MAVLink dialect generator -An add-on is available for QGC that provides a UI for generating MAVLink dialects from within QGC. This feature has been deprecated since identical functionality now exists within the MAVLink project itself. Enable this functionality by specifying the `DEFINES` variable `ENABLE_MAVGEN`. - ### Opal-RT's RT-LAB simulator Integration with Opal-RT's RT-LAB simulator can be enabled on Windows by installing RT-LAB 7.2.4. This allows vehicles to be simulated in RT-LAB and communicate directly with QGC on the same computer as if the UAS was actually deployed. This support is enabled by default once the requisite RT-LAB software is installed. Disabling this can be done by adding `DISABLE_RTLAB` to the `DEFINES` variable. diff --git a/src/apps/mavlinkgen/MAVLinkGen.cc b/src/apps/mavlinkgen/MAVLinkGen.cc deleted file mode 100644 index 3d6e8f2307..0000000000 --- a/src/apps/mavlinkgen/MAVLinkGen.cc +++ /dev/null @@ -1,88 +0,0 @@ -/*===================================================================== - -PIXHAWK Micro Air Vehicle Flying Robotics Toolkit - -(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch> - -This file is part of the PIXHAWK project - - PIXHAWK is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - PIXHAWK is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Implementation of class MAVLinkGen - * - * @author Lorenz Meier <mavteam@student.ethz.ch> - * - */ - - -#include <QFile> -#include <QFlags> -#include <QThread> -#include <QSplashScreen> -#include <QPixmap> -#include <QDesktopWidget> -#include <QPainter> -#include <QStyleFactory> -#include <QAction> -#include <QSettings> -#include <QFontDatabase> -#include <QMainWindow> - -#include "MAVLinkGen.h" -#include "XMLCommProtocolWidget.h" - - -/** - * @brief Constructor for the main application. - * - * This constructor initializes and starts the whole application. It takes standard - * command-line parameters - * - * @param argc The number of command-line parameters - * @param argv The string array of parameters - **/ - -MAVLinkGen::MAVLinkGen(int &argc, char* argv[]) : QApplication(argc, argv) -{ - this->setApplicationName("MAVLink Generator"); - this->setApplicationVersion("v. 1.0.0 (Beta)"); - this->setOrganizationName(QLatin1String("MAVLink Consortium")); - this->setOrganizationDomain("http://qgroundcontrol.org/mavlink"); - - QSettings::setDefaultFormat(QSettings::IniFormat); - // Exit main application when last window is closed - connect(this, SIGNAL(lastWindowClosed()), this, SLOT(quit())); - - // Create main window - window = new QMainWindow(); - window->setCentralWidget(new XMLCommProtocolWidget(window)); - window->setWindowTitle(applicationName() + " " + applicationVersion()); - window->resize(qMax(950, static_cast<int>(QApplication::desktop()->width()*0.7f)), qMax(600, static_cast<int>(QApplication::desktop()->height()*0.8f))); - window->show(); -} - -/** - * @brief Destructor - * - **/ -MAVLinkGen::~MAVLinkGen() -{ - window->hide(); - delete window; -} - diff --git a/src/apps/mavlinkgen/MAVLinkGen.h b/src/apps/mavlinkgen/MAVLinkGen.h deleted file mode 100644 index 674346d75f..0000000000 --- a/src/apps/mavlinkgen/MAVLinkGen.h +++ /dev/null @@ -1,60 +0,0 @@ -/*===================================================================== - -PIXHAWK Micro Air Vehicle Flying Robotics Toolkit - -(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch> - -This file is part of the PIXHAWK project - - PIXHAWK is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - PIXHAWK is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Definition of class MAVLinkGen - * - * @author Lorenz Meier <mavteam@student.ethz.ch> - * - */ - - -#ifndef MAVLINKGEN_H -#define MAVLINKGEN_H - -#include <QApplication> -#include <QMainWindow> - -/** - * @brief The main application and management class. - * - * This class is started by the main method and provides - * the central management unit of the groundstation application. - * - **/ -class MAVLinkGen : public QApplication -{ - Q_OBJECT - -public: - MAVLinkGen(int &argc, char* argv[]); - ~MAVLinkGen(); - -protected: - QMainWindow* window; - -private: -}; - -#endif /* MAVLINKGEN_H */ diff --git a/src/apps/mavlinkgen/README b/src/apps/mavlinkgen/README deleted file mode 100644 index a0e3724103..0000000000 --- a/src/apps/mavlinkgen/README +++ /dev/null @@ -1,29 +0,0 @@ -Code Generator for the MAVLink Micro Air Vehicle Message Marshalling Library - -This is a code generator for the library for lightweight communication between -Micro Air Vehicles and/or ground control stations. -It serializes C-structs for serial channels and can be used with -any type of radio modem. - -********** -* NEWS * -********** - -MAVLink has been ported to Python and Java. MAVLinkGen will soon support the output of Python and Java code as well. - - - -For help, please visit the mailing list: http://groups.google.com/group/mavlink - -MAVLink is licensed under the terms of the Lesser General Public License of the Free Software Foundation (LGPL). - -MAVLink's reference implementation is done in the QGroundControl operator control unit. MAVLink is however not tied in any way to QGroundControl nor does it depend on it. Many other groundstations (APM Planner, HK GCS, Copter-GCS) support it and might be better suited for your application than QGC - check them out. - -Project: -http://qgroundcontrol.org/mavlink - -Files: -http://github.com/pixhawk/mavlinkgen -http://github.com/pixhawk/mavlink - -(c) 2009-2011 Lorenz Meier <mail@qgroundcontrol.org> \ No newline at end of file diff --git a/src/apps/mavlinkgen/deploy/mac_create_dmg_mavlinkgen.sh b/src/apps/mavlinkgen/deploy/mac_create_dmg_mavlinkgen.sh deleted file mode 100644 index 8f2cb27805..0000000000 --- a/src/apps/mavlinkgen/deploy/mac_create_dmg_mavlinkgen.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/sh -cp -r ../../mavlinkgen-build-desktop/mavlinkgen.app . - -echo -e '\n\nStarting to create disk image. This may take a while..\n' -macdeployqt mavlinkgen.app -dmg -rm -rf mavlinkgen.app -echo -e '\n\n MAVLinkGen .DMG file is now ready for publishing\n' diff --git a/src/apps/mavlinkgen/deploy/mavlinkgen_installer.nsi b/src/apps/mavlinkgen/deploy/mavlinkgen_installer.nsi deleted file mode 100644 index 346cb3994c..0000000000 --- a/src/apps/mavlinkgen/deploy/mavlinkgen_installer.nsi +++ /dev/null @@ -1,35 +0,0 @@ -Name "MAVLink Generator" - -OutFile "mavlinkgen-installer-win32.exe" - -InstallDir $PROGRAMFILES\mavlinkgen - -Page license -Page directory -Page components -Page instfiles -UninstPage uninstConfirm -UninstPage instfiles - -LicenseData ..\license.txt - -Section "" - - SetOutPath $INSTDIR - File ..\release\*.* - WriteUninstaller $INSTDIR\mavlinkgen_uninstall.exe -SectionEnd - -Section "Uninstall" - Delete $INSTDIR\mavlinkgen_uninstall.exe - Delete $INSTDIR\*.* - RMDir $INSTDIR - Delete "$SMPROGRAMS\mavlinkgen\*.*" - RMDir "$SMPROGRAMS\mavlinkgen\" -SectionEnd - -Section "create Start Menu Shortcuts" - CreateDirectory "$SMPROGRAMS\MAVLink" - CreateShortCut "$SMPROGRAMS\MAVLink\Uninstall.lnk" "$INSTDIR\mavlinkgen_uninstall.exe" "" "$INSTDIR\mavlinkgen_uninstall.exe" 0 - CreateShortCut "$SMPROGRAMS\MAVLink\MAVLinkGen.lnk" "$INSTDIR\mavlinkgen.exe" "" "$INSTDIR\mavlinkgen.exe" 0 -SectionEnd \ No newline at end of file diff --git a/src/apps/mavlinkgen/generator/MAVLinkXMLParser.cc b/src/apps/mavlinkgen/generator/MAVLinkXMLParser.cc deleted file mode 100644 index 66769ae158..0000000000 --- a/src/apps/mavlinkgen/generator/MAVLinkXMLParser.cc +++ /dev/null @@ -1,754 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Implementation of class MAVLinkXMLParser - * @author Lorenz Meier <mail@qgroundcontrol.org> - */ - -#include <QFile> -#include <QDir> -#include <QPair> -#include <QList> -#include <QMap> -#include <QDateTime> -#include <QLocale> -#include "MAVLinkXMLParser.h" - -#include <QDebug> - -MAVLinkXMLParser::MAVLinkXMLParser(QDomDocument* document, QString outputDirectory, QObject* parent) : QObject(parent), - doc(document), - outputDirName(outputDirectory), - fileName("") -{ -} - -MAVLinkXMLParser::MAVLinkXMLParser(QString document, QString outputDirectory, QObject* parent) : QObject(parent) -{ - doc = new QDomDocument(); - QFile file(document); - if (file.open(QIODevice::ReadOnly | QIODevice::Text)) - { - const QString instanceText(QString::fromUtf8(file.readAll())); - doc->setContent(instanceText); - } - fileName = document; - outputDirName = outputDirectory; -} - -MAVLinkXMLParser::~MAVLinkXMLParser() -{ -} - -/** - * Generate C-code (C-89 compliant) out of the XML protocol specs. - */ -bool MAVLinkXMLParser::generate() -{ - // Process result - bool success = true; - - // Only generate if output dir is correctly set - if (outputDirName == "") - { - emit parseState(tr("<font color=\"red\">ERROR: No output directory given.\nAbort.</font>")); - return false; - } - - QString topLevelOutputDirName = outputDirName; - - // print out the element names of all elements that are direct children - // of the outermost element. - QDomElement docElem = doc->documentElement(); - QDomNode n = docElem;//.firstChild(); - QDomNode p = docElem; - - // Sanity check variables - QList<int>* usedMessageIDs = new QList<int>(); - QMap<QString, QString>* usedMessageNames = new QMap<QString, QString>(); - QMap<QString, QString>* usedEnumNames = new QMap<QString, QString>(); - - QList< QPair<QString, QString> > cFiles; - QString lcmStructDefs = ""; - - QString pureFileName; - QString pureIncludeFileName; - - QFileInfo fInfo(this->fileName); - pureFileName = fInfo.baseName().split(".", QString::SkipEmptyParts).first(); - - // XML parsed and converted to C code. Now generating the files - outputDirName += QDir::separator() + pureFileName; - QDateTime now = QDateTime::currentDateTime().toUTC(); - QLocale loc(QLocale::English); - QString dateFormat = "dddd, MMMM d yyyy, hh:mm UTC"; - QString date = loc.toString(now, dateFormat); - QString includeLine = "#include \"%1\"\n"; - QString mainHeaderName = pureFileName + ".h"; - QString messagesDirName = ".";//"generated"; - QDir dir(outputDirName + "/" + messagesDirName); - - int mavlinkVersion = 0; - - // we need to gather the message lengths across multiple includes, - // which we can do via detecting recursion - static unsigned message_lengths[256]; - static int highest_message_id; - static int recursion_level; - - if (recursion_level == 0){ - highest_message_id = 0; - memset(message_lengths, 0, sizeof(message_lengths)); - } - - - // Start main header - QString mainHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://qgroundcontrol.org/mavlink/\n *\t Generated on %1\n */\n#ifndef " + pureFileName.toUpper() + "_H\n#define " + pureFileName.toUpper() + "_H\n\n").arg(date); // The main header includes all messages - // Mark all code as C code - mainHeader += "#ifdef __cplusplus\nextern \"C\" {\n#endif\n\n"; - mainHeader += "\n#include \"../protocol.h\"\n"; - mainHeader += "\n#define MAVLINK_ENABLED_" + pureFileName.toUpper() + "\n\n"; - - QString enums; - - - // Run through root children - while(!n.isNull()) - { - // Each child is a message - QDomElement e = n.toElement(); // try to convert the node to an element. - if(!e.isNull()) - { - if (e.tagName() == "mavlink") - { - p = n; - n = n.firstChild(); - while (!n.isNull()) - { - e = n.toElement(); - if (!e.isNull()) - { - // Handle all include tags - if (e.tagName() == "include") - { - QString incFileName = e.text(); - // Load file - //QDomDocument includeDoc = QDomDocument(); - - // Prepend file path if it is a relative path and - // make it relative to opened file - QFileInfo fInfo(incFileName); - - QString incFilePath; - if (fInfo.isRelative()) - { - QFileInfo rInfo(this->fileName); - incFilePath = rInfo.absoluteDir().canonicalPath() + "/" + incFileName; - pureIncludeFileName = fInfo.baseName().split(".", QString::SkipEmptyParts).first(); - } - - QFile file(incFilePath); - if (file.open(QIODevice::ReadOnly | QIODevice::Text)) - { - emit parseState(QString("<font color=\"green\">Included messages from file: %1</font>").arg(incFileName)); - // NEW MODE: CREATE INDIVIDUAL FOLDERS - // Create new output directory, parse included XML and generate C-code - MAVLinkXMLParser includeParser(incFilePath, topLevelOutputDirName, this); - connect(&includeParser, SIGNAL(parseState(QString)), this, SIGNAL(parseState(QString))); - // Generate and write - recursion_level++; - // Abort if inclusion fails - if (!includeParser.generate()) return false; - recursion_level--; - mainHeader += "\n#include \"../" + pureIncludeFileName + "/" + pureIncludeFileName + ".h\"\n"; - - - // OLD MODE: MERGE BOTH FILES - // const QString instanceText(QString::fromUtf8(file.readAll())); - // includeDoc.setContent(instanceText); - // // Get all messages - // QDomNode in = includeDoc.documentElement().firstChild(); - // QDomElement ie = in.toElement(); - // if (!ie.isNull()) - // { - // if (ie.tagName() == "messages" || ie.tagName() == "include") - // { - // QDomNode ref = n.parentNode().insertAfter(in, n); - // if (ref.isNull()) - // { - // emit parseState(QString("<font color=\"red\">ERROR: Inclusion failed: XML syntax error in file %1. Wrong/misspelled XML?\nAbort.</font>").arg(fileName)); - // return false; - // } - // } - // } - - emit parseState(QString("<font color=\"green\">End of inclusion from file: %1</font>").arg(incFileName)); - } - else - { - // Include file could not be opened - emit parseState(QString("<font color=\"red\">ERROR: Failed including file: %1, file is not readable. Wrong/misspelled filename?\nAbort.</font>").arg(fileName)); - return false; - } - - } - // Handle all enum tags - else if (e.tagName() == "version") - { - //QString fieldType = e.attribute("type", ""); - //QString fieldName = e.attribute("name", ""); - QString fieldText = e.text(); - - // Check if version has been previously set - if (mavlinkVersion != 0) - { - emit parseState(QString("<font color=\"red\">ERROR: Protocol version tag set twice, please use it only once. First version was %1, second version is %2.\nAbort.</font>").arg(mavlinkVersion).arg(fieldText)); - return false; - } - - bool ok; - int version = fieldText.toInt(&ok); - if (ok && (version > 0) && (version < 256)) - { - // Set MAVLink version - mavlinkVersion = version; - } - else - { - emit parseState(QString("<font color=\"red\">ERROR: Reading version string failed: %1, string is not an integer number between 1 and 255.\nAbort.</font>").arg(fieldText)); - return false; - } - } - // Handle all enum tags - else if (e.tagName() == "enums") - { - // One down into the enums list - p = n; - n = n.firstChild(); - while (!n.isNull()) - { - e = n.toElement(); - - QString currEnum; - QString currEnumEnd; - // Comment - QString comment; - - if(!e.isNull() && e.tagName() == "enum") - { - // Get enum name - QString enumName = e.attribute("name", "").toLower(); - if (enumName.size() == 0) - { - emit parseState(tr("<font color=\"red\">ERROR: Missing required name=\"\" attribute for tag %2 near line %1\nAbort.</font>").arg(QString::number(e.lineNumber()), e.tagName())); - return false; - } - else - { - // Sanity check: Accept only enum names not used previously - if (usedEnumNames->contains(enumName)) - { - emit parseState(tr("<font color=\"red\">ERROR: Enum name %1 used twice, second occurence near line %2 of file %3\nAbort.</font>").arg(enumName, QString::number(e.lineNumber()), fileName)); - return false; - } - else - { - usedEnumNames->insert(enumName, QString::number(e.lineNumber())); - } - - // Everything sane, starting with enum content - currEnum = "enum " + enumName.toUpper() + "\n{\n"; - currEnumEnd = QString("\t%1_ENUM_END\n};\n\n").arg(enumName.toUpper()); - - int nextEnumValue = 0; - - // Get the enum fields - QDomNode f = e.firstChild(); - while (!f.isNull()) - { - QDomElement e2 = f.toElement(); - if (!e2.isNull() && e2.tagName() == "entry") - { - QString fieldValue = e2.attribute("value", ""); - - // If value was given, use it, if not, use the enum iterator - // value. The iterator value gets reset by manual values - - QString fieldName = e2.attribute("name", ""); - if (fieldValue.length() == 0) - { - fieldValue = QString::number(nextEnumValue); - nextEnumValue++; - } - else - { - bool ok; - nextEnumValue = fieldValue.toInt(&ok) + 1; - if (!ok) - { - emit parseState(tr("<font color=\"red\">ERROR: Enum entry %1 has not a valid number (%2) in the value field.\nAbort.</font>").arg(fieldName, fieldValue)); - return false; - } - } - - // Add comment of field if there is one - QString fieldComment; - if (e2.text().length() > 0) - { - QString sep(" | "); - QDomNode pp = e2.firstChild(); - while (!pp.isNull()) - { - QDomElement pp2 = pp.toElement(); - if (pp2.isText() || pp2.isCDATASection()) - { - fieldComment += pp2.nodeValue() + sep; - } - else if (pp2.isElement()) - { - fieldComment += pp2.text() + sep; - } - pp = pp.nextSibling(); - } - fieldComment = fieldComment.replace("\n", " "); - fieldComment = " /* " + fieldComment.simplified() + " */"; - } - currEnum += "\t" + fieldName.toUpper() + "=" + fieldValue + "," + fieldComment + "\n"; - } - else if(!e2.isNull() && e2.tagName() == "description") - { - comment = " " + e2.text().replace("\n", " ") + comment; - } - f = f.nextSibling(); - } - } - // Add the last parsed enum - // Remove the last comma, as the last value has none - // ENUM END MARKER IS LAST ENTRY, COMMA REMOVAL NOT NEEDED - //int commaPosition = currEnum.lastIndexOf(","); - //currEnum.remove(commaPosition, 1); - - enums += "/** @brief " + comment + " */\n" + currEnum + currEnumEnd; - } // Element is non-zero and element name is <enum> - n = n.nextSibling(); - } // While through <enums> - // One up, back into the <mavlink> structure - n = p; - } - - // Handle all message tags - else if (e.tagName() == "messages") - { - p = n; - n = n.firstChild(); - while (!n.isNull()) - { - e = n.toElement(); - if(!e.isNull()) - { - //if (e.isNull()) continue; - // Get message name - QString messageName = e.attribute("name", "").toLower(); - if (messageName.size() == 0) - { - emit parseState(tr("<font color=\"red\">ERROR: Missing required name=\"\" attribute for tag %2 near line %1\nAbort.</font>").arg(QString::number(e.lineNumber()), e.tagName())); - return false; - } - else - { - // Get message id - bool ok; - int messageId = e.attribute("id", "-1").toInt(&ok, 10); - emit parseState(tr("Compiling message <strong>%1 \t(#%3)</strong> \tnear line %2").arg(messageName, QString::number(n.lineNumber()), QString::number(messageId))); - - // Sanity check: Accept only message IDs not used previously - if (usedMessageIDs->contains(messageId)) - { - emit parseState(tr("<font color=\"red\">ERROR: Message ID %1 used twice, second occurence near line %2 of file %3\nAbort.</font>").arg(QString::number(messageId), QString::number(e.lineNumber()), fileName)); - return false; - } - else - { - usedMessageIDs->append(messageId); - } - - // Sanity check: Accept only message names not used previously - if (usedMessageNames->contains(messageName)) - { - emit parseState(tr("<font color=\"red\">ERROR: Message name %1 used twice, second occurence near line %2 of file %3\nAbort.</font>").arg(messageName, QString::number(e.lineNumber()), fileName)); - return false; - } - else - { - usedMessageNames->insert(messageName, QString::number(e.lineNumber())); - } - - QString channelType("mavlink_channel_t"); - QString messageType("mavlink_message_t"); - - // Build up function call - QString commentContainer("/**\n * @brief Pack a %1 message\n * @param system_id ID of this system\n * @param component_id ID of this component (e.g. 200 for IMU)\n * @param msg The MAVLink message to compress the data into\n *\n%2 * @return length of the message in bytes (excluding serial stream start sign)\n */\n"); - QString commentPackChanContainer("/**\n * @brief Pack a %1 message\n * @param system_id ID of this system\n * @param component_id ID of this component (e.g. 200 for IMU)\n * @param chan The MAVLink channel this message was sent over\n * @param msg The MAVLink message to compress the data into\n%2 * @return length of the message in bytes (excluding serial stream start sign)\n */\n"); - QString commentSendContainer("/**\n * @brief Send a %1 message\n * @param chan MAVLink channel to send the message\n *\n%2 */\n"); - QString commentEncodeContainer("/**\n * @brief Encode a %1 struct into a message\n *\n * @param system_id ID of this system\n * @param component_id ID of this component (e.g. 200 for IMU)\n * @param msg The MAVLink message to compress the data into\n * @param %1 C-struct to read the message contents from\n */\n"); - QString commentDecodeContainer("/**\n * @brief Decode a %1 message into a struct\n *\n * @param msg The message to decode\n * @param %1 C-struct to decode the message contents into\n */\n"); - QString commentEntry(" * @param %1 %2\n"); - QString idDefine = QString("#define MAVLINK_MSG_ID_%1 %2").arg(messageName.toUpper(), QString::number(messageId)); - QString arrayDefines; - QString cStructName = QString("mavlink_%1_t").arg(messageName); - QString cStruct("typedef struct __%1 \n{\n%2\n} %1;"); - QString cStructLines; - QString encode("static inline uint16_t mavlink_msg_%1_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const %2* %1)\n{\n\treturn mavlink_msg_%1_pack(%3);\n}\n"); - - QString decode("static inline void mavlink_msg_%1_decode(const mavlink_message_t* msg, %2* %1)\n{\n%3}\n"); - QString pack("static inline uint16_t mavlink_msg_%1_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg%2)\n{\n\tuint16_t i = 0;\n\tmsg->msgid = MAVLINK_MSG_ID_%3;\n\n%4\n\treturn mavlink_finalize_message(msg, system_id, component_id, i);\n}\n\n"); - QString packChan("static inline uint16_t mavlink_msg_%1_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg%2)\n{\n\tuint16_t i = 0;\n\tmsg->msgid = MAVLINK_MSG_ID_%3;\n\n%4\n\treturn mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);\n}\n\n"); - QString compactSend("#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS\n\nstatic inline void mavlink_msg_%3_send(%1 chan%5)\n{\n\t%2 msg;\n\tmavlink_msg_%3_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif"); - //QString compactStructSend = "#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS\n\nstatic inline void mavlink_msg_%3_struct_send(%1 chan%5)\n{\n\t%2 msg;\n\tmavlink_msg_%3_encode(mavlink_system.sysid, mavlink_system.compid, &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif"; - QString unpacking; - QString prepends; - QString packParameters; - QString packArguments("system_id, component_id, msg"); - QString packLines; - QString decodeLines; - QString sendArguments; - QString commentLines; - unsigned message_length = 0; - - - // Get the message fields - QDomNode f = e.firstChild(); - while (!f.isNull()) - { - QDomElement e2 = f.toElement(); - if (!e2.isNull() && e2.tagName() == "field") - { - QString fieldType = e2.attribute("type", ""); - QString fieldName = e2.attribute("name", ""); - QString fieldText = e2.text(); - - QString unpackingCode; - QString unpackingComment = QString("/**\n * @brief Get field %1 from %2 message\n *\n * @return %3\n */\n").arg(fieldName, messageName, fieldText); - - // Send arguments do not work for the version field - if (!fieldType.contains("uint8_t_mavlink_version")) - { - // Send arguments are the same for integral types and arrays - sendArguments += ", " + fieldName; - commentLines += commentEntry.arg(fieldName, fieldText.replace("\n", " ")); - } - - // MAVLink version field - // this is a special field always containing the version define - if (fieldType.contains("uint8_t_mavlink_version")) - { - // Add field to C structure - cStructLines += QString("\t%1 %2; ///< %3\n").arg("uint8_t", fieldName, fieldText); - // Add pack line to message_xx_pack function - packLines += QString("\ti += put_uint8_t_by_index(%1, i, msg->payload); // %2\n").arg(mavlinkVersion).arg(fieldText); - // Add decode function for this type - decodeLines += QString("\t%1->%2 = mavlink_msg_%1_get_%2(msg);\n").arg(messageName, fieldName); - } - - // Array handling is different from simple types - else if (fieldType.startsWith("array")) - { - int arrayLength = QString(fieldType.split("[").at(1).split("]").first()).toInt(); - QString arrayType = fieldType.split("[").first(); - packParameters += QString(", const ") + QString("int8_t*") + " " + fieldName; - packArguments += ", " + messageName + "->" + fieldName; - - // Add field to C structure - cStructLines += QString("\t%1 %2[%3]; ///< %4\n").arg("int8_t", fieldName, QString::number(arrayLength), fieldText); - // Add pack line to message_xx_pack function - packLines += QString("\ti += put_%1_by_index(%2, %3, i, msg->payload); // %4\n").arg(arrayType, fieldName, QString::number(arrayLength), fieldText); - // Add decode function for this type - decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName); - arrayDefines += QString("#define MAVLINK_MSG_%1_FIELD_%2_LEN %3\n").arg(messageName.toUpper(), fieldName.toUpper(), QString::number(arrayLength)); - } - else if (fieldType.startsWith("string")) - { - int arrayLength = QString(fieldType.split("[").at(1).split("]").first()).toInt(); - QString arrayType = fieldType.split("[").first(); - packParameters += QString(", const ") + QString("char*") + " " + fieldName; - packArguments += ", " + messageName + "->" + fieldName; - - // Add field to C structure - cStructLines += QString("\t%1 %2[%3]; ///< %4\n").arg("char", fieldName, QString::number(arrayLength), fieldText); - // Add pack line to message_xx_pack function - packLines += QString("\ti += put_%1_by_index(%2, %3, i, msg->payload); // %4\n").arg(arrayType, fieldName, QString::number(arrayLength), e2.text()); - // Add decode function for this type - decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName); - arrayDefines += QString("#define MAVLINK_MSG_%1_FIELD_%2_LEN %3\n").arg(messageName.toUpper(), fieldName.toUpper(), QString::number(arrayLength)); - } - // Expand array handling to all valid mavlink data types - else if(fieldType.contains('[') && fieldType.contains(']')) - { - int arrayLength = QString(fieldType.split("[").at(1).split("]").first()).toInt(); - QString arrayType = fieldType.split("[").first(); - packParameters += QString(", const ") + arrayType + "* " + fieldName; - packArguments += ", " + messageName + "->" + fieldName; - - // Add field to C structure - cStructLines += QString("\t%1 %2[%3]; ///< %4\n").arg(arrayType, fieldName, QString::number(arrayLength), fieldText); - // Add pack line to message_xx_pack function - packLines += QString("\ti += put_array_by_index((const int8_t*)%1, sizeof(%2)*%3, i, msg->payload); // %4\n").arg(fieldName, arrayType, QString::number(arrayLength), fieldText); - // Add decode function for this type - decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName); - arrayDefines += QString("#define MAVLINK_MSG_%1_FIELD_%2_LEN %3\n").arg(messageName.toUpper(), fieldName.toUpper(), QString::number(arrayLength)); - - unpackingCode = QString("\n\tmemcpy(r_data, msg->payload%1, sizeof(%2)*%3);\n\treturn sizeof(%2)*%3;").arg(prepends, arrayType, QString::number(arrayLength)); - - unpacking += unpackingComment + QString("static inline uint16_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg, %3* r_data)\n{\n%4\n}\n\n").arg(messageName, fieldName, arrayType, unpackingCode); - // decodeLines += ""; - prepends += QString("+sizeof(%1)*%2").arg(arrayType, QString::number(arrayLength)); - - } - else - // Handle simple types like integers and floats - { - packParameters += ", " + fieldType + " " + fieldName; - packArguments += ", " + messageName + "->" + fieldName; - - // Add field to C structure - cStructLines += QString("\t%1 %2; ///< %3\n").arg(fieldType, fieldName, fieldText); - // Add pack line to message_xx_pack function - packLines += QString("\ti += put_%1_by_index(%2, i, msg->payload); // %3\n").arg(fieldType, fieldName, e2.text()); - // Add decode function for this type - decodeLines += QString("\t%1->%2 = mavlink_msg_%1_get_%2(msg);\n").arg(messageName, fieldName); - } - - - // message length calculation - unsigned element_multiplier = 1; - unsigned element_length = 0; - const struct - { - const char *prefix; - unsigned length; - } length_map[] = { - { "array", 1 }, - { "char", 1 }, - { "uint8", 1 }, - { "int8", 1 }, - { "uint16", 2 }, - { "int16", 2 }, - { "uint32", 4 }, - { "int32", 4 }, - { "uint64", 8 }, - { "int64", 8 }, - { "float", 4 }, - { "double", 8 }, - }; - if (fieldType.contains("[")) - { - element_multiplier = fieldType.split("[").at(1).split("]").first().toInt(); - } - for (unsigned i=0; i<sizeof(length_map)/sizeof(length_map[0]); i++) - { - if (fieldType.startsWith(length_map[i].prefix)) { - element_length = length_map[i].length * element_multiplier; - break; - } - } - if (element_length == 0) { - emit parseState(tr("<font color=\"red\">ERROR: Unable to calculate length for %2 near line %1\nAbort.</font>").arg(QString::number(e.lineNumber()), fieldType)); - } - message_length += element_length; - - // - // QString unpackingCode; - - if (fieldType == "uint8_t_mavlink_version") - { - unpackingCode = QString("\treturn (%1)(msg->payload%2)[0];").arg("uint8_t", prepends); - } - else if (fieldType == "uint8_t" || fieldType == "int8_t") - { - unpackingCode = QString("\treturn (%1)(msg->payload%2)[0];").arg(fieldType, prepends); - } - else if (fieldType == "uint16_t" || fieldType == "int16_t") - { - unpackingCode = QString("\tgeneric_16bit r;\n\tr.b[1] = (msg->payload%1)[0];\n\tr.b[0] = (msg->payload%1)[1];\n\treturn (%2)r.s;").arg(prepends).arg(fieldType); - } - else if (fieldType == "uint32_t" || fieldType == "int32_t") - { - unpackingCode = QString("\tgeneric_32bit r;\n\tr.b[3] = (msg->payload%1)[0];\n\tr.b[2] = (msg->payload%1)[1];\n\tr.b[1] = (msg->payload%1)[2];\n\tr.b[0] = (msg->payload%1)[3];\n\treturn (%2)r.i;").arg(prepends).arg(fieldType); - } - else if (fieldType == "float") - { - unpackingCode = QString("\tgeneric_32bit r;\n\tr.b[3] = (msg->payload%1)[0];\n\tr.b[2] = (msg->payload%1)[1];\n\tr.b[1] = (msg->payload%1)[2];\n\tr.b[0] = (msg->payload%1)[3];\n\treturn (%2)r.f;").arg(prepends).arg(fieldType); - } - else if (fieldType == "uint64_t" || fieldType == "int64_t") - { - unpackingCode = QString("\tgeneric_64bit r;\n\tr.b[7] = (msg->payload%1)[0];\n\tr.b[6] = (msg->payload%1)[1];\n\tr.b[5] = (msg->payload%1)[2];\n\tr.b[4] = (msg->payload%1)[3];\n\tr.b[3] = (msg->payload%1)[4];\n\tr.b[2] = (msg->payload%1)[5];\n\tr.b[1] = (msg->payload%1)[6];\n\tr.b[0] = (msg->payload%1)[7];\n\treturn (%2)r.ll;").arg(prepends).arg(fieldType); - } - else if (fieldType.startsWith("array")) - { - // fieldtype formatis string[n] where n is the number of bytes, extract n from field type string - unpackingCode = QString("\n\tmemcpy(r_data, msg->payload%1, %2);\n\treturn %2;").arg(prepends, fieldType.split("[").at(1).split("]").first()); - } - else if (fieldType.startsWith("string")) - { - // fieldtype formatis string[n] where n is the number of bytes, extract n from field type string - unpackingCode = QString("\n\tstrcpy(r_data, msg->payload%1, %2);\n\treturn %2;").arg(prepends, fieldType.split("[").at(1).split("]").first()); - } - - - // Generate the message decoding function - if (fieldType.contains("uint8_t_mavlink_version")) - { - unpacking += unpackingComment + QString("static inline %1 mavlink_msg_%2_get_%3(const mavlink_message_t* msg)\n{\n%4\n}\n\n").arg("uint8_t", messageName, fieldName, unpackingCode); - decodeLines += ""; - prepends += "+sizeof(uint8_t)"; - } - // Array handling is different from simple types - else if (fieldType.startsWith("array")) - { - unpacking += unpackingComment + QString("static inline uint16_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg, int8_t* r_data)\n{\n%4\n}\n\n").arg(messageName, fieldName, unpackingCode); - decodeLines += ""; - QString arrayLength = QString(fieldType.split("[").at(1).split("]").first()); - prepends += "+" + arrayLength; - } - else if (fieldType.startsWith("string")) - { - unpacking += unpackingComment + QString("static inline uint16_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg, char* r_data)\n{\n%4\n}\n\n").arg(messageName, fieldName, unpackingCode); - decodeLines += ""; - QString arrayLength = QString(fieldType.split("[").at(1).split("]").first()); - prepends += "+" + arrayLength; - } - else if(fieldType.contains('[') && fieldType.contains(']')) - { - // prevent this case from being caught in the following else - } - else - { - unpacking += unpackingComment + QString("static inline %1 mavlink_msg_%2_get_%3(const mavlink_message_t* msg)\n{\n%4\n}\n\n").arg(fieldType, messageName, fieldName, unpackingCode); - decodeLines += ""; - prepends += "+sizeof(" + e2.attribute("type", "void") + ")"; - } - } - f = f.nextSibling(); - } - - if (messageId > highest_message_id) - { - highest_message_id = messageId; - } - message_lengths[messageId] = message_length; - - cStruct = cStruct.arg(cStructName, cStructLines); - lcmStructDefs.append("\n").append(cStruct).append("\n"); - pack = pack.arg(messageName, packParameters, messageName.toUpper(), packLines); - packChan = packChan.arg(messageName, packParameters, messageName.toUpper(), packLines); - encode = encode.arg(messageName).arg(cStructName).arg(packArguments); - decode = decode.arg(messageName).arg(cStructName).arg(decodeLines); - compactSend = compactSend.arg(channelType, messageType, messageName, sendArguments, packParameters); - QString cFile = "// MESSAGE " + messageName.toUpper() + " PACKING\n\n" + idDefine + "\n\n" + cStruct + "\n\n" + arrayDefines + "\n\n" + commentContainer.arg(messageName.toLower(), commentLines) + pack + commentPackChanContainer.arg(messageName.toLower(), commentLines) + packChan + commentEncodeContainer.arg(messageName.toLower()) + encode + "\n" + commentSendContainer.arg(messageName.toLower(), commentLines) + compactSend + "\n" + "// MESSAGE " + messageName.toUpper() + " UNPACKING\n\n" + unpacking + commentDecodeContainer.arg(messageName.toLower()) + decode; - cFiles.append(qMakePair(QString("mavlink_msg_%1.h").arg(messageName), cFile)); - } // Check if tag = message - } // Check if e = NULL - n = n.nextSibling(); - } // While through <message> - n = p; - - } // Check if tag = messages - } // Check if e = NULL - n = n.nextSibling(); - } // While through include and messages - // One up - current node = parent - n = p; - - } // Check if tag = mavlink - } // Check if e = NULL - n = n.nextSibling(); - } // While through root children - - // Add version to main header - - mainHeader += "// MAVLINK VERSION\n\n"; - mainHeader += QString("#ifndef MAVLINK_VERSION\n#define MAVLINK_VERSION %1\n#endif\n\n").arg(mavlinkVersion); - mainHeader += QString("#if (MAVLINK_VERSION == 0)\n#undef MAVLINK_VERSION\n#define MAVLINK_VERSION %1\n#endif\n\n").arg(mavlinkVersion); - - // Add enums to main header - - mainHeader += "// ENUM DEFINITIONS\n\n"; - mainHeader += enums; - mainHeader += "\n"; - - mainHeader += "// MESSAGE DEFINITIONS\n\n"; - // Create directory if it doesn't exist, report result in success - if (!dir.exists()) success = success && dir.mkpath(outputDirName + "/" + messagesDirName); - for (int i = 0; i < cFiles.size(); i++) - { - QFile rawFile(dir.filePath(cFiles.at(i).first)); - bool ok = rawFile.open(QIODevice::WriteOnly | QIODevice::Text); - success = success && ok; - rawFile.write(cFiles.at(i).second.toLatin1()); - rawFile.close(); - mainHeader += includeLine.arg(messagesDirName + "/" + cFiles.at(i).first); - } - - mainHeader += "\n\n// MESSAGE LENGTHS\n\n"; - mainHeader += "#undef MAVLINK_MESSAGE_LENGTHS\n"; - mainHeader += "#define MAVLINK_MESSAGE_LENGTHS { "; - for (int i=0; i<highest_message_id; i++) - { - mainHeader += QString::number(message_lengths[i]); - if (i < highest_message_id-1) mainHeader += ", "; - } - mainHeader += " }\n\n"; - - mainHeader += "#ifdef __cplusplus\n}\n#endif\n"; - mainHeader += "#endif"; - // Newline to make compiler happy - mainHeader += "\n"; - - // Write main header - QFile rawHeader(outputDirName + "/" + mainHeaderName); - bool ok = rawHeader.open(QIODevice::WriteOnly | QIODevice::Text); - success = success && ok; - rawHeader.write(mainHeader.toLatin1()); - rawHeader.close(); - - // Write alias mavlink header - QFile mavlinkHeader(outputDirName + "/mavlink.h"); - ok = mavlinkHeader.open(QIODevice::WriteOnly | QIODevice::Text); - success = success && ok; - QString mHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://pixhawk.ethz.ch/software/mavlink\n *\t Generated on %1\n */\n#ifndef MAVLINK_H\n#define MAVLINK_H\n\n").arg(date); // The main header includes all messages - // Mark all code as C code - mHeader += "#include \"" + mainHeaderName + "\"\n\n"; - mHeader += "#endif\n"; - mavlinkHeader.write(mHeader.toLatin1()); - mavlinkHeader.close(); - - // Write C structs / lcm definitions - // QFile lcmStructs(outputDirName + "/mavlink.lcm"); - // ok = lcmStructs.open(QIODevice::WriteOnly | QIODevice::Text); - // success = success && ok; - // lcmStructs.write(lcmStructDefs.toLatin1()); - - return success; -} diff --git a/src/apps/mavlinkgen/generator/MAVLinkXMLParser.h b/src/apps/mavlinkgen/generator/MAVLinkXMLParser.h deleted file mode 100644 index c4ede024ea..0000000000 --- a/src/apps/mavlinkgen/generator/MAVLinkXMLParser.h +++ /dev/null @@ -1,66 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Definition of class MAVLinkXMLParser - * @author Lorenz Meier <mail@qgroundcontrol.org> - */ - -#ifndef MAVLINKXMLPARSER_H -#define MAVLINKXMLPARSER_H - -#include <QObject> -#include <QDomDocument> -#include <QString> - -/** - * @brief MAVLink micro air vehicle protocol generator - * - * MAVLink is a generic communication protocol for micro air vehicles. - * for more information, please see the official website. - * @ref http://pixhawk.ethz.ch/software/mavlink/ - **/ -class MAVLinkXMLParser : public QObject -{ - Q_OBJECT -public: - MAVLinkXMLParser(QDomDocument* document, QString outputDirectory, QObject* parent=0); - MAVLinkXMLParser(QString document, QString outputDirectory, QObject* parent=0); - ~MAVLinkXMLParser(); - -public slots: - /** @brief Parse XML and generate C files */ - bool generate(); - -signals: - /** @brief Status message on the parsing */ - void parseState(QString message); - -protected: - QDomDocument* doc; - QString outputDirName; - QString fileName; -}; - -#endif // MAVLINKXMLPARSER_H diff --git a/src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.cc b/src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.cc deleted file mode 100644 index 199be7a40d..0000000000 --- a/src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.cc +++ /dev/null @@ -1,148 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Implementation of class MAVLinkXMLParserV10 - * @author Lorenz Meier <mail@qgroundcontrol.org> - */ - -#include <QFile> -#include <QDir> -#include <QPair> -#include <QList> -#include <QMap> -#include <QDateTime> -#include <QLocale> -#include <QApplication> - -#include "MAVLinkXMLParserV10.h" - -#include <QDebug> - -MAVLinkXMLParserV10::MAVLinkXMLParserV10(QDomDocument* document, QString outputDirectory, QObject* parent) : QObject(parent), -doc(document), -outputDirName(outputDirectory), -fileName("") -{ -} - -MAVLinkXMLParserV10::MAVLinkXMLParserV10(QString document, QString outputDirectory, QObject* parent) : QObject(parent) -{ - doc = new QDomDocument(); - QFile file(document); - if (file.open(QIODevice::ReadOnly | QIODevice::Text)) - { - const QString instanceText(QString::fromUtf8(file.readAll())); - doc->setContent(instanceText); - } - fileName = document; - outputDirName = outputDirectory; -} - -MAVLinkXMLParserV10::~MAVLinkXMLParserV10() -{ -} - -void MAVLinkXMLParserV10::processError(QProcess::ProcessError err) -{ - switch(err) - { - case QProcess::FailedToStart: - emit parseState(tr("Generator failed to start. Please check if the path and command is correct.")); - break; - case QProcess::Crashed: - emit parseState("Generator crashed, This is a generator-related problem. Please upgrade MAVLink generator."); - break; - case QProcess::Timedout: - emit parseState(tr("Generator start timed out, please check if the path and command are correct")); - break; - case QProcess::WriteError: - emit parseState(tr("Could not communicate with generator. Please check if the path and command are correct")); - break; - case QProcess::ReadError: - emit parseState(tr("Could not communicate with generator. Please check if the path and command are correct")); - break; - case QProcess::UnknownError: - default: - emit parseState(tr("Generator error. Please check if the path and command is correct.")); - break; - } -} - -/** - * Generate C-code (C-89 compliant) out of the XML protocol specs. - */ -bool MAVLinkXMLParserV10::generate() -{ - emit parseState(tr("Generator ready.")); -#ifdef Q_OS_WIN - QString generatorCall("files/mavgen.exe"); -#endif -#if (defined Q_OS_MAC) || (defined Q_OS_LINUX) - QString generatorCall("python"); -#endif - QString lang("C"); - QString version("1.0"); - - QStringList arguments; -#if (defined Q_OS_MAC) || (defined Q_OS_LINUX) - // Script is only needed as argument if Python is used, the Py2Exe implicitely knows the script - arguments << QString("%1/libs/mavlink/share/pyshared/pymavlink/generator/mavgen.py").arg(QApplication::applicationDirPath()); -#endif - arguments << QString("--lang=%1").arg(lang); - arguments << QString("--output=%2").arg(outputDirName); - arguments << QString("%3").arg(fileName); - arguments << QString("--wire-protocol=%4").arg(version); - - qDebug() << "Attempted to start" << generatorCall << arguments; - process = new QProcess(this); - process->setProcessChannelMode(QProcess::SeparateChannels); - connect(process, SIGNAL(error(QProcess::ProcessError)), this, SLOT(processError(QProcess::ProcessError))); - connect(process, SIGNAL(readyReadStandardOutput()), this, SLOT(readStdOut())); - connect(process, SIGNAL(readyReadStandardError()), this, SLOT(readStdErr())); - process->start(generatorCall, arguments, QIODevice::ReadWrite); - QString output = QString(process->readAll()); - emit parseState(output); - // Print process status - emit parseState(QString("<font color=\"red\">%1</font>").arg(QString(process->readAllStandardError()))); - emit parseState(QString(process->readAllStandardOutput())); - - process->waitForFinished(20000); - - process->terminate(); - process->kill(); - return true;//result; -} - -void MAVLinkXMLParserV10::readStdOut() -{ - QString out(process->readAllStandardOutput()); - emit parseState(out); -} - -void MAVLinkXMLParserV10::readStdErr() -{ - QString out = QString("<font color=\"red\">%1</font>").arg(QString(process->readAllStandardError())); - emit parseState(out); -} diff --git a/src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.h b/src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.h deleted file mode 100644 index 05b65c68cb..0000000000 --- a/src/apps/mavlinkgen/generator/MAVLinkXMLParserV10.h +++ /dev/null @@ -1,84 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Definition of class MAVLinkXMLParserV10 - * @author Lorenz Meier <mail@qgroundcontrol.org> - */ - -#ifndef MAVLINKXMLPARSERV10_H -#define MAVLINKXMLPARSERV10_H - -#include <QObject> -#include <QDomDocument> -#include <QString> -#include <QProcess> - -#include <inttypes.h> - -/** - * @brief MAVLink micro air vehicle protocol generator - * - * MAVLink is a generic communication protocol for micro air vehicles. - * for more information, please see the official website. - * @ref http://pixhawk.ethz.ch/software/mavlink/ - **/ -class MAVLinkXMLParserV10 : public QObject -{ - Q_OBJECT -public: - MAVLinkXMLParserV10(QDomDocument* document, QString outputDirectory, QObject* parent=0); - MAVLinkXMLParserV10(QString document, QString outputDirectory, QObject* parent=0); - ~MAVLinkXMLParserV10(); - -public slots: - /** @brief Parse XML and generate C files */ - bool generate(); - - /** @brief Handle process errors */ - void processError(QProcess::ProcessError err); - - /** @brief Redirect standard output */ - void readStdOut(); - /** @brief Redirect standard error output */ - void readStdErr(); - -signals: - /** @brief Status message on the parsing */ - void parseState(QString message); - -protected: -// /** @brief Accumulate the X.25 CRC by adding one char at a time. */ -// void crcAccumulate(uint8_t data, uint16_t *crcAccum); - -// /** @brief Initialize the buffer for the X.25 CRC */ -// void crcInit(uint16_t* crcAccum); - - QDomDocument* doc; - QString outputDirName; - QString fileName; - QProcess* process; -}; - -#endif // MAVLINKXMLPARSERV10_H diff --git a/src/apps/mavlinkgen/images/categories/applications-system.svg b/src/apps/mavlinkgen/images/categories/applications-system.svg deleted file mode 100644 index 9d767742df..0000000000 --- a/src/apps/mavlinkgen/images/categories/applications-system.svg +++ /dev/null @@ -1,247 +0,0 @@ -<?xml version="1.0" encoding="UTF-8" standalone="no"?> -<!-- Created with Inkscape (http://www.inkscape.org/) --> -<svg - xmlns:dc="http://purl.org/dc/elements/1.1/" - xmlns:cc="http://creativecommons.org/ns#" - xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#" - xmlns:svg="http://www.w3.org/2000/svg" - xmlns="http://www.w3.org/2000/svg" - xmlns:xlink="http://www.w3.org/1999/xlink" - xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd" - xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape" - width="48.000000px" - height="48.000000px" - id="svg53383" - sodipodi:version="0.32" - inkscape:version="0.46" - sodipodi:docbase="/home/jimmac/src/cvs/tango-icon-theme/scalable/categories" - sodipodi:docname="applications-system.svg" - inkscape:output_extension="org.inkscape.output.svg.inkscape"> - <defs - id="defs3"> - <inkscape:perspective - sodipodi:type="inkscape:persp3d" - inkscape:vp_x="0 : 24 : 1" - inkscape:vp_y="0 : 1000 : 0" - inkscape:vp_z="48 : 24 : 1" - inkscape:persp3d-origin="24 : 16 : 1" - id="perspective31" /> - <linearGradient - id="linearGradient3264"> - <stop - style="stop-color:#c9c9c9;stop-opacity:1;" - offset="0" - id="stop3266" /> - <stop - id="stop3276" - offset="0.25" - style="stop-color:#f8f8f8;stop-opacity:1;" /> - <stop - id="stop3272" - offset="0.5" - style="stop-color:#e2e2e2;stop-opacity:1;" /> - <stop - style="stop-color:#b0b0b0;stop-opacity:1;" - offset="0.75" - id="stop3274" /> - <stop - style="stop-color:#c9c9c9;stop-opacity:1;" - offset="1" - id="stop3268" /> - </linearGradient> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient3264" - id="linearGradient3281" - gradientUnits="userSpaceOnUse" - x1="14.462892" - y1="12.284524" - x2="34.534348" - y2="39.684914" - gradientTransform="matrix(1.241935,0,0,1.241935,-5.027508,-7.208988)" /> - <linearGradient - id="linearGradient2300"> - <stop - id="stop2302" - offset="0.0000000" - style="stop-color:#000000;stop-opacity:0.32673267;" /> - <stop - id="stop2304" - offset="1" - style="stop-color:#000000;stop-opacity:0;" /> - </linearGradient> - <linearGradient - id="aigrd1" - gradientUnits="userSpaceOnUse" - x1="99.7773" - y1="15.4238" - x2="153.0005" - y2="248.6311"> - <stop - offset="0" - style="stop-color:#184375" - id="stop53300" /> - <stop - offset="1" - style="stop-color:#C8BDDC" - id="stop53302" /> - </linearGradient> - <linearGradient - inkscape:collect="always" - xlink:href="#aigrd1" - id="linearGradient53551" - gradientUnits="userSpaceOnUse" - x1="99.7773" - y1="15.4238" - x2="153.0005" - y2="248.6311" - gradientTransform="matrix(0.200685,0.000000,0.000000,0.200685,-0.585758,-1.050787)" /> - <radialGradient - gradientUnits="userSpaceOnUse" - r="11.689870" - fy="72.568001" - fx="14.287618" - cy="68.872971" - cx="14.287618" - gradientTransform="matrix(1.399258,-2.234445e-7,8.196178e-8,0.513264,4.365074,4.839285)" - id="radialGradient2308" - xlink:href="#linearGradient2300" - inkscape:collect="always" /> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient3264" - id="linearGradient3760" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(1.241935,0,0,1.241935,-5.027508,-7.208988)" - x1="14.462892" - y1="12.284524" - x2="34.534348" - y2="39.684914" /> - <linearGradient - inkscape:collect="always" - xlink:href="#aigrd1" - id="linearGradient3773" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(0.200685,0,0,0.200685,-54.33576,-1.050787)" - x1="99.7773" - y1="15.4238" - x2="153.0005" - y2="248.6311" /> - </defs> - <sodipodi:namedview - inkscape:showpageshadow="false" - id="base" - pagecolor="#ffffff" - bordercolor="#666666" - borderopacity="0.11764706" - inkscape:pageopacity="0.0" - inkscape:pageshadow="2" - inkscape:zoom="5.6568542" - inkscape:cx="43.652227" - inkscape:cy="21.164787" - inkscape:current-layer="layer1" - showgrid="false" - inkscape:grid-bbox="true" - inkscape:document-units="px" - inkscape:window-width="872" - inkscape:window-height="697" - inkscape:window-x="562" - inkscape:window-y="151" /> - <metadata - id="metadata4"> - <rdf:RDF> - <cc:Work - rdf:about=""> - <dc:format>image/svg+xml</dc:format> - <dc:type - rdf:resource="http://purl.org/dc/dcmitype/StillImage" /> - <dc:title>System Applications</dc:title> - <dc:creator> - <cc:Agent> - <dc:title>Jakub Steiner</dc:title> - </cc:Agent> - </dc:creator> - <dc:source>http://jimmac.musichall.cz/</dc:source> - <dc:subject> - <rdf:Bag> - <rdf:li>system</rdf:li> - <rdf:li>applications</rdf:li> - <rdf:li>group</rdf:li> - <rdf:li>category</rdf:li> - <rdf:li>admin</rdf:li> - <rdf:li>root</rdf:li> - </rdf:Bag> - </dc:subject> - <cc:license - rdf:resource="http://creativecommons.org/licenses/publicdomain/" /> - </cc:Work> - <cc:License - rdf:about="http://creativecommons.org/licenses/publicdomain/"> - <cc:permits - rdf:resource="http://creativecommons.org/ns#Reproduction" /> - <cc:permits - rdf:resource="http://creativecommons.org/ns#Distribution" /> - <cc:permits - rdf:resource="http://creativecommons.org/ns#DerivativeWorks" /> - </cc:License> - </rdf:RDF> - </metadata> - <g - inkscape:label="shadow" - id="layer2" - inkscape:groupmode="layer"> - <path - transform="matrix(1.186380,0.000000,0.000000,1.186380,-4.539687,-7.794678)" - d="M 44.285715 38.714287 A 19.928572 9.8372450 0 1 1 4.4285717,38.714287 A 19.928572 9.8372450 0 1 1 44.285715 38.714287 z" - sodipodi:ry="9.8372450" - sodipodi:rx="19.928572" - sodipodi:cy="38.714287" - sodipodi:cx="24.357143" - id="path1538" - style="color:#000000;fill:url(#radialGradient2308);fill-opacity:1.0000000;fill-rule:evenodd;stroke:none;stroke-width:0.50000042;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4.0000000;stroke-dashoffset:0.0000000;stroke-opacity:1.0000000;marker:none;marker-start:none;marker-mid:none;marker-end:none;visibility:visible;display:inline;overflow:visible" - sodipodi:type="arc" /> - </g> - <g - id="layer1" - inkscape:label="Layer 1" - inkscape:groupmode="layer"> - <path - inkscape:r_cy="true" - inkscape:r_cx="true" - style="opacity:1;color:#000000;fill:url(#linearGradient3773);fill-opacity:1;fill-rule:nonzero;stroke:#3f4561;stroke-width:1;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 22.699525,0.94746963 C 22.22635,0.97984519 21.766437,1.0531317 21.301673,1.1063165 L 21.269903,1.1063165 L 20.157975,7.1742671 C 18.345621,7.5870046 16.640562,8.2874574 15.106644,9.2392765 L 10.118853,5.6493371 C 8.770521,6.6961412 7.543552,7.9170049 6.465374,9.2392765 L 9.928236,14.290607 C 8.876814,15.89739 8.086153,17.732094 7.640841,19.659632 C 7.640765,19.668743 7.640779,19.689813 7.640841,19.691401 L 1.60466,20.644482 C 1.494303,21.545851 1.445813,22.477386 1.445813,23.408418 C 1.445813,24.170171 1.466846,24.921747 1.541121,25.664043 L 7.577303,26.744202 C 8.0066,28.840363 8.822112,30.797987 9.960006,32.526228 L 6.370066,37.450482 C 7.398201,38.726866 8.585171,39.888962 9.864698,40.913343 L 14.947798,37.418712 C 16.724273,38.551956 18.707343,39.346604 20.856901,39.737877 L 21.809983,45.742288 C 22.487237,45.803935 23.181758,45.805827 23.874992,45.805827 C 24.853677,45.805826 25.788512,45.768738 26.734236,45.64698 L 27.877933,39.515491 C 29.91886,39.007587 31.836112,38.126493 33.501113,36.942172 L 38.393596,40.500342 C 39.662366,39.420897 40.822583,38.180154 41.824689,36.846863 L 38.266519,31.700225 C 39.230125,30.036028 39.897817,28.199859 40.23622,26.235892 L 46.240632,25.282811 C 46.29329,24.656221 46.30417,24.048546 46.30417,23.408418 C 46.30417,22.296018 46.174875,21.205317 46.018246,20.136172 L 39.918526,19.024244 C 39.440518,17.259164 38.656214,15.612364 37.662901,14.13176 L 41.25284,9.2075071 C 40.140075,7.8466524 38.870718,6.5895264 37.472284,5.5222596 L 32.293876,9.0804296 C 30.805549,8.200202 29.203897,7.5248159 27.464931,7.1424978 L 26.51185,1.1063165 C 25.644369,1.0042729 24.769749,0.94746963 23.874992,0.94746963 C 23.633166,0.94746964 23.384286,0.93986063 23.144296,0.94746963 C 23.027301,0.95117908 22.911525,0.94066346 22.794833,0.94746963 C 22.763228,0.94931296 22.73107,0.94531125 22.699525,0.94746963 z M 23.525529,16.387386 C 23.641592,16.381497 23.757473,16.387386 23.874992,16.387386 C 27.635598,16.387386 30.705408,19.457196 30.705408,23.217802 C 30.705409,26.978407 27.635597,30.016448 23.874992,30.016448 C 20.114387,30.016449 17.076346,26.978407 17.076346,23.217802 C 17.076347,19.574716 19.927558,16.569963 23.525529,16.387386 z " - id="path3243" /> - <path - inkscape:r_cy="true" - inkscape:r_cx="true" - sodipodi:type="arc" - style="opacity:0.64772728;color:#000000;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#ffffff;stroke-width:1.62180054;stroke-linecap:butt;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - id="path3283" - sodipodi:cx="23.511301" - sodipodi:cy="23.781593" - sodipodi:rx="12.727922" - sodipodi:ry="12.727922" - d="M 36.239223 23.781593 A 12.727922 12.727922 0 1 1 10.783379,23.781593 A 12.727922 12.727922 0 1 1 36.239223 23.781593 z" - transform="matrix(0.616598,0,0,0.616598,9.38202,8.539674)" /> - <path - inkscape:r_cy="true" - inkscape:r_cx="true" - id="path3285" - d="M 21.995808,2.1484671 L 21.103024,8.0235243 C 19.404254,8.4103946 16.279442,9.5936035 14.841657,10.485771 L 10.091975,6.9406268 C 8.828145,7.9218257 8.741474,7.9883656 7.730867,9.2277688 L 11.165063,14.320988 C 10.179537,15.827071 8.995796,18.510982 8.570778,20.42893 C 8.570778,20.42893 2.552988,21.443355 2.552988,21.443355 C 2.449547,22.288234 2.49926,24.096528 2.56888,24.792303 L 8.317097,25.82782 C 8.71949,27.79261 10.225324,30.955232 11.291904,32.575161 L 7.656902,37.377719 C 8.620601,38.57411 8.813474,38.683589 10.01281,39.64377 L 14.873441,36.082733 C 16.538581,37.144954 19.84373,38.437109 21.858571,38.80386 L 22.656299,44.604952 C 23.291109,44.662736 25.044829,44.824827 25.931283,44.710701 L 26.824066,38.671821 C 28.737084,38.195749 32.042539,36.838896 33.603191,35.728798 L 38.458624,39.236958 C 39.647878,38.225166 39.658533,38.072709 40.597835,36.822978 L 36.999815,31.708667 C 37.90303,30.148767 39.070902,27.098068 39.388097,25.257187 L 45.279046,24.279744 C 45.328399,23.692424 45.330802,22.054578 45.18399,21.052439 L 39.182092,20.016922 C 38.73404,18.362463 37.196418,15.381153 36.265359,13.993342 L 40.080075,9.1907857 C 39.037052,7.915218 38.64924,7.7402002 37.338448,6.7398212 L 32.313994,10.337839 C 30.918941,9.5127782 28.137095,8.2550417 26.507114,7.8966842 L 25.619528,2.1484671 C 24.806414,2.0528187 22.460488,2.0952921 21.995808,2.1484671 z " - style="opacity:0.34659089;color:#000000;fill:none;fill-opacity:1;fill-rule:nonzero;stroke:#ffffff;stroke-width:0.99999923;stroke-linecap:butt;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - sodipodi:nodetypes="ccccccccccccccccccccccccccccccccc" /> - <path - style="opacity:0.5;color:#000000;fill:#ffffff;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 10.102903,6.2970655 C 8.7545689,7.3438694 8.1656464,7.9719226 7.0874684,9.2941942 L 10.489927,14.259153 C 9.4385072,15.857755 8.3316275,18.426114 8.1423859,19.987706 C 8.1423859,19.987706 2.0798859,21.0319 2.0798859,21.0319 C 2.0109129,21.595256 1.90625,22.884803 1.90625,22.884803 L 2.0830267,24.447303 C 2.5107567,24.535638 2.9231817,24.617818 3.3642767,24.666053 L 3.8642767,23.134803 C 4.2083177,23.163279 4.5439297,23.197303 4.8955267,23.197303 C 5.2467347,23.197303 5.6139847,23.163473 5.9580267,23.134803 L 6.4267767,24.666053 C 6.8680647,24.617818 7.3115487,24.535638 7.7392767,24.447303 L 7.7392767,22.884803 C 8.4250337,22.72518 9.0712777,22.497045 9.7080267,22.228553 L 10.645527,23.509803 C 11.047878,23.327709 11.421123,23.133984 11.801777,22.916053 L 11.301777,21.416053 C 11.89901,21.053803 12.463529,20.620706 12.989277,20.166053 L 14.270527,21.103553 C 14.596162,20.806973 14.91164,20.491691 15.208027,20.166053 L 14.270527,18.916053 C 14.725373,18.390305 15.127027,17.826171 15.489277,17.228553 L 16.989277,17.697303 C 17.207208,17.316456 17.432571,16.943209 17.614277,16.541053 L 16.333027,15.603553 C 16.601517,14.966804 16.798016,14.320561 16.958027,13.634803 L 18.551777,13.634803 C 18.640112,13.207076 18.691236,12.763591 18.739277,12.322303 L 17.239277,11.853553 C 17.268139,11.509705 17.301777,11.142456 17.301777,10.791053 C 17.301776,10.43965 17.267753,10.104039 17.239277,9.7598034 L 18.739277,9.2910534 C 18.69373,8.8711662 18.633686,8.4490548 18.551777,8.0410534 C 17.404349,8.4403544 15.999117,9.1941729 14.983265,9.8245243 L 10.102903,6.2970655 z " - id="path3767" - inkscape:r_cx="true" - inkscape:r_cy="true" - sodipodi:nodetypes="cccccccccsccccccccccccccccccccsccccc" /> - <path - style="opacity:0.5;color:#000000;fill:#ffffff;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:1;stroke-linecap:butt;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 37.236641,17.217754 C 36.85286,17.39913 36.490003,17.603509 36.123236,17.813295 L 36.692886,19.548136 C 35.995792,19.970436 35.338156,20.467825 34.725008,20.998151 L 33.249099,19.910639 C 32.869013,20.256538 32.507327,20.618223 32.161588,20.998151 L 33.249099,22.474059 C 32.718773,23.087371 32.221547,23.745002 31.799084,24.441937 L 31.255328,24.260685 C 31.207646,24.960968 31.018949,25.62217 30.737466,26.228563 L 30.841038,26.306242 C 30.527881,27.048922 30.27649,27.83664 30.090137,28.636624 L 28.614229,28.636624 C 28.477946,28.722076 28.343676,28.821684 28.199938,28.895555 C 28.121568,29.310822 28.065026,29.712881 28.018687,30.138426 L 29.77942,30.708074 C 29.746033,31.10935 29.727633,31.515269 29.727633,31.925052 C 29.727631,32.334993 29.746034,32.740753 29.77942,33.142029 L 28.018687,33.711677 C 28.074705,34.226432 28.148678,34.740347 28.251725,35.239372 L 30.090137,35.213479 C 30.218255,35.763466 30.393202,36.320918 30.582107,36.844746 C 31.327023,36.557466 32.05594,36.214561 32.731236,35.809021 C 32.319649,34.59298 32.083908,33.279913 32.083908,31.925052 C 32.083909,26.727119 35.376289,22.288397 39.981313,20.583861 L 38.893802,20.402608 C 38.671014,19.579946 38.382478,18.774017 38.013435,18.020441 C 38.002581,17.998277 37.99851,17.96486 37.987542,17.942761 L 37.935756,17.890975 L 37.236641,17.217754 z " - id="path3770" - inkscape:r_cx="true" - inkscape:r_cy="true" /> - </g> -</svg> diff --git a/src/apps/mavlinkgen/images/status/folder-open.svg b/src/apps/mavlinkgen/images/status/folder-open.svg deleted file mode 100644 index 237f6f2540..0000000000 --- a/src/apps/mavlinkgen/images/status/folder-open.svg +++ /dev/null @@ -1,482 +0,0 @@ -<?xml version="1.0" encoding="UTF-8" standalone="no"?> -<!-- Created with Inkscape (http://www.inkscape.org/) --> -<svg - xmlns:dc="http://purl.org/dc/elements/1.1/" - xmlns:cc="http://creativecommons.org/ns#" - xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#" - xmlns:svg="http://www.w3.org/2000/svg" - xmlns="http://www.w3.org/2000/svg" - xmlns:xlink="http://www.w3.org/1999/xlink" - xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd" - xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape" - width="48.000000px" - height="48.000000px" - id="svg97" - sodipodi:version="0.32" - inkscape:version="0.46" - sodipodi:docbase="/home/jimmac/src/cvs/tango-icon-theme/scalable/status" - sodipodi:docname="folder-open.svg" - inkscape:export-filename="/home/jimmac/ximian_art/icons/nautilus/snowdunes/gnome-fs-directory-accept.png" - inkscape:export-xdpi="90.000000" - inkscape:export-ydpi="90.000000" - inkscape:output_extension="org.inkscape.output.svg.inkscape"> - <defs - id="defs3"> - <inkscape:perspective - sodipodi:type="inkscape:persp3d" - inkscape:vp_x="0 : 24 : 1" - inkscape:vp_y="0 : 1000 : 0" - inkscape:vp_z="48 : 24 : 1" - inkscape:persp3d-origin="24 : 16 : 1" - id="perspective75" /> - <radialGradient - inkscape:collect="always" - xlink:href="#linearGradient5060" - id="radialGradient6719" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(-2.774389,0,0,1.969706,112.7623,-872.8854)" - cx="605.71429" - cy="486.64789" - fx="605.71429" - fy="486.64789" - r="117.14286" /> - <linearGradient - inkscape:collect="always" - id="linearGradient5060"> - <stop - style="stop-color:black;stop-opacity:1;" - offset="0" - id="stop5062" /> - <stop - style="stop-color:black;stop-opacity:0;" - offset="1" - id="stop5064" /> - </linearGradient> - <radialGradient - inkscape:collect="always" - xlink:href="#linearGradient5060" - id="radialGradient6717" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(2.774389,0,0,1.969706,-1891.633,-872.8854)" - cx="605.71429" - cy="486.64789" - fx="605.71429" - fy="486.64789" - r="117.14286" /> - <linearGradient - id="linearGradient5048"> - <stop - style="stop-color:black;stop-opacity:0;" - offset="0" - id="stop5050" /> - <stop - id="stop5056" - offset="0.5" - style="stop-color:black;stop-opacity:1;" /> - <stop - style="stop-color:black;stop-opacity:0;" - offset="1" - id="stop5052" /> - </linearGradient> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient5048" - id="linearGradient6715" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(2.774389,0,0,1.969706,-1892.179,-872.8854)" - x1="302.85715" - y1="366.64789" - x2="302.85715" - y2="609.50507" /> - <linearGradient - inkscape:collect="always" - id="linearGradient13842"> - <stop - style="stop-color:#000000;stop-opacity:1;" - offset="0" - id="stop13844" /> - <stop - style="stop-color:#000000;stop-opacity:0;" - offset="1" - id="stop13846" /> - </linearGradient> - <linearGradient - id="linearGradient9766"> - <stop - style="stop-color:#6194cb;stop-opacity:1;" - offset="0" - id="stop9768" /> - <stop - style="stop-color:#729fcf;stop-opacity:1;" - offset="1" - id="stop9770" /> - </linearGradient> - <linearGradient - inkscape:collect="always" - id="linearGradient9806"> - <stop - style="stop-color:#000000;stop-opacity:1;" - offset="0" - id="stop9808" /> - <stop - style="stop-color:#000000;stop-opacity:0;" - offset="1" - id="stop9810" /> - </linearGradient> - <radialGradient - inkscape:collect="always" - xlink:href="#linearGradient9806" - id="radialGradient9812" - cx="24.35099" - cy="41.591846" - fx="24.35099" - fy="41.591846" - r="19.136078" - gradientTransform="matrix(1.000000,0.000000,0.000000,0.242494,1.565588e-16,31.50606)" - gradientUnits="userSpaceOnUse" /> - <linearGradient - id="linearGradient148"> - <stop - style="stop-color:#ffffff;stop-opacity:0.13402061;" - offset="0.0000000" - id="stop149" /> - <stop - style="stop-color:#ffffff;stop-opacity:0.051546391;" - offset="1.0000000" - id="stop150" /> - </linearGradient> - <linearGradient - id="linearGradient335"> - <stop - style="stop-color:#ffffff;stop-opacity:1.0000000;" - offset="0.0000000" - id="stop336" /> - <stop - style="stop-color:#ffffff;stop-opacity:0.0000000;" - offset="1.0000000" - id="stop337" /> - </linearGradient> - <linearGradient - id="linearGradient1789"> - <stop - style="stop-color:#a0a0a0;stop-opacity:1;" - offset="0" - id="stop1790" /> - <stop - style="stop-color:#a8a8a8;stop-opacity:1;" - offset="1" - id="stop1791" /> - </linearGradient> - <linearGradient - id="linearGradient137"> - <stop - style="stop-color:#ffffff;stop-opacity:0.70059878;" - offset="0.0000000" - id="stop138" /> - <stop - style="stop-color:#ffffff;stop-opacity:0.0000000;" - offset="1.0000000" - id="stop139" /> - </linearGradient> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient335" - id="linearGradient155" - gradientUnits="userSpaceOnUse" - gradientTransform="scale(1.421537,0.703464)" - x1="19.116116" - y1="28.946041" - x2="19.426924" - y2="51.912693" /> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient148" - id="linearGradient156" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(1.535299,0,0,0.651339,3.451418,2.448)" - x1="14.899379" - y1="27.059643" - x2="22.715446" - y2="41.836895" /> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient137" - id="linearGradient158" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(1.462696,0,6.907908e-2,0.683669,-8.7075e-19,0)" - x1="5.2657914" - y1="18.725863" - x2="8.2122240" - y2="52.625851" /> - <radialGradient - inkscape:collect="always" - xlink:href="#linearGradient1789" - id="radialGradient159" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(1.015635,0,0.103105,1.000512,-6.73857e-18,-8.369458e-2)" - cx="26.106777" - cy="38.195114" - fx="26.106777" - fy="38.195114" - r="32.259769" /> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient9766" - id="linearGradient13162" - gradientUnits="userSpaceOnUse" - gradientTransform="matrix(1,0,0,1.022118,52.05694,-1.323026)" - x1="22.175976" - y1="36.987999" - x2="22.065331" - y2="32.050499" /> - <linearGradient - inkscape:collect="always" - xlink:href="#linearGradient13842" - id="linearGradient13848" - x1="22.25" - y1="37.625" - x2="19.75" - y2="14.875" - gradientUnits="userSpaceOnUse" /> - </defs> - <sodipodi:namedview - id="base" - pagecolor="#ffffff" - bordercolor="#666666" - borderopacity="1.0" - inkscape:pageopacity="0.0" - inkscape:pageshadow="2" - inkscape:zoom="10.54135" - inkscape:cx="8.8898314" - inkscape:cy="26.16018" - inkscape:current-layer="layer3" - showgrid="true" - inkscape:grid-bbox="true" - inkscape:document-units="px" - inkscape:window-width="1027" - inkscape:window-height="818" - inkscape:window-x="271" - inkscape:window-y="30" - inkscape:showpageshadow="false" /> - <metadata - id="metadata4"> - <rdf:RDF> - <cc:Work - rdf:about=""> - <dc:format>image/svg+xml</dc:format> - <dc:type - rdf:resource="http://purl.org/dc/dcmitype/StillImage" /> - <dc:title>Folder Icon Accept</dc:title> - <dc:date>2005-01-31</dc:date> - <dc:creator> - <cc:Agent> - <dc:title>Jakub Steiner</dc:title> - </cc:Agent> - </dc:creator> - <cc:license - rdf:resource="http://creativecommons.org/licenses/publicdomain/" /> - <dc:source>http://jimmac.musichall.cz</dc:source> - <dc:description>Active state - when files are being dragged to.</dc:description> - <dc:publisher> - <cc:Agent> - <dc:title>Novell, Inc.</dc:title> - </cc:Agent> - </dc:publisher> - <dc:contributor> - <cc:Agent> - <dc:title>Garrett LeSage</dc:title> - </cc:Agent> - </dc:contributor> - </cc:Work> - <cc:License - rdf:about="http://creativecommons.org/licenses/publicdomain/"> - <cc:permits - rdf:resource="http://creativecommons.org/ns#Reproduction" /> - <cc:permits - rdf:resource="http://creativecommons.org/ns#Distribution" /> - <cc:permits - rdf:resource="http://creativecommons.org/ns#DerivativeWorks" /> - </cc:License> - </rdf:RDF> - </metadata> - <g - id="layer1" - inkscape:label="Folder" - inkscape:groupmode="layer" /> - <g - inkscape:label="Open" - id="layer3" - inkscape:groupmode="layer"> - <g - style="display:inline" - transform="matrix(2.262383e-2,0,0,2.086758e-2,43.38343,36.36962)" - id="g6707"> - <rect - style="opacity:0.40206185;color:black;fill:url(#linearGradient6715);fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - id="rect6709" - width="1339.6335" - height="478.35718" - x="-1559.2523" - y="-150.69685" /> - <path - style="opacity:0.40206185;color:black;fill:url(#radialGradient6717);fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M -219.61876,-150.68038 C -219.61876,-150.68038 -219.61876,327.65041 -219.61876,327.65041 C -76.744594,328.55086 125.78146,220.48075 125.78138,88.454235 C 125.78138,-43.572302 -33.655436,-150.68036 -219.61876,-150.68038 z " - id="path6711" - sodipodi:nodetypes="cccc" /> - <path - sodipodi:nodetypes="cccc" - id="path6713" - d="M -1559.2523,-150.68038 C -1559.2523,-150.68038 -1559.2523,327.65041 -1559.2523,327.65041 C -1702.1265,328.55086 -1904.6525,220.48075 -1904.6525,88.454235 C -1904.6525,-43.572302 -1745.2157,-150.68036 -1559.2523,-150.68038 z " - style="opacity:0.40206185;color:black;fill:url(#radialGradient6719);fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:1;stroke-linecap:round;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - </g> - <path - sodipodi:nodetypes="ccccccssssccc" - style="color:#000000;fill:url(#radialGradient159);fill-opacity:1;fill-rule:nonzero;stroke:#5a5a5a;stroke-width:0.99487108;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - id="path2375" - d="M 4.6200285,38.651015 C 4.6618365,39.07147 5.1174141,39.491924 5.5311838,39.491924 L 36.667346,39.491924 C 37.081116,39.491924 37.453078,39.07147 37.41127,38.651015 L 34.714653,11.531728 C 34.672845,11.111274 34.217267,10.69082 33.803498,10.69082 L 21.080082,10.69082 C 20.489536,10.69082 19.870999,10.311268 19.677221,9.7304849 L 18.574219,6.4246085 C 18.404967,5.9173308 18.027069,5.6888138 17.259746,5.6888138 L 2.3224188,5.6888138 C 1.9086492,5.6888138 1.5366876,6.109268 1.5784956,6.529722 L 4.6200285,38.651015 z " - transform="matrix(1.004486,0,0,1.005825,-8.234449e-2,-0.221964)" - inkscape:r_cx="true" - inkscape:r_cy="true" /> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000024;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 5.3301525,37.533487 L 35.317907,37.533487" - id="path13160" - sodipodi:nodetypes="cc" /> - <path - sodipodi:nodetypes="cc" - id="path13139" - d="M 5.3301525,35.533487 L 35.317907,35.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000024;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <path - sodipodi:nodetypes="ccccccsscsscccc" - id="path2380" - d="M 6.1717518,38.418674 C 6.2031078,38.729001 6.017127,38.935886 5.6963478,38.832443 L 5.6963478,38.832443 C 5.3755686,38.729001 5.1477798,38.522116 5.1164238,38.211789 L 2.0868572,6.8445942 C 2.0555012,6.534267 2.2434512,6.3468711 2.5537784,6.3468711 L 17.303531,6.2554251 C 17.834815,6.2521313 18.04296,6.308731 18.18333,6.7726371 C 18.18333,6.7726371 19.268704,9.885435 19.429564,10.470742 L 17.873968,7.5537061 C 17.608788,7.0564434 17.275224,7.1399365 16.901178,7.1399365 L 3.7717775,7.1399365 C 3.4614503,7.1399365 3.2754695,7.3468213 3.3068255,7.6571485 L 6.2856462,38.522116 L 6.1717518,38.418674 z " - style="color:#000000;fill:url(#linearGradient158);fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:1.17341149;stroke-linecap:butt;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:block;overflow:visible" - transform="matrix(1.008872,0,0,1.012144,-0.101943,-0.33126)" - inkscape:r_cx="true" - inkscape:r_cy="true" /> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000036;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 3.3386019,17.533487 L 34.488461,17.533487" - id="path13113" - sodipodi:nodetypes="cc" /> - <path - sodipodi:nodetypes="cc" - id="path13115" - d="M 2.7573333,11.533487 L 33.496214,11.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000012;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <g - inkscape:export-ydpi="74.800003" - inkscape:export-xdpi="74.800003" - inkscape:export-filename="/home/jimmac/ximian_art/icons/nautilus/suse93/gnome-fs-directory.png" - transform="matrix(1.034503,0,0.104528,1.035221,-9.922058,2.395183)" - id="g2381" - style="fill:#ffffff;fill-opacity:0.5803109;fill-rule:nonzero;stroke:#000000;stroke-miterlimit:4;display:block" - inkscape:r_cx="true" - inkscape:r_cy="true"> - <path - sodipodi:nodetypes="cscscs" - id="path2382" - d="M 41.785743,9.0363862 C 41.795369,8.5618034 41.800932,8.3118806 41.36235,8.312183 L 28.80653,8.3208402 C 28.50653,8.3208402 28.481916,8.1776341 28.80653,8.3208402 C 29.131144,8.4640463 30.053628,8.9791114 30.989227,9.0218349 C 30.989227,9.0218349 41.785704,9.0382983 41.785743,9.0363862 z " - style="stroke:none" - inkscape:r_cx="true" - inkscape:r_cy="true" /> - </g> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000024;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 5.1594716,33.533487 L 35.147226,33.533487" - id="path13121" - sodipodi:nodetypes="cc" /> - <path - sodipodi:nodetypes="cc" - id="path13119" - d="M 4.8658086,31.533487 L 34.974533,31.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000036;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000036;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 4.6336367,29.533487 L 34.802847,29.533487" - id="path13135" - sodipodi:nodetypes="cc" /> - <path - sodipodi:nodetypes="cc" - id="path13137" - d="M 4.4629557,27.533487 L 34.632166,27.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000036;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 4.2556718,25.533487 L 34.460793,25.533487" - id="path13143" - sodipodi:nodetypes="cc" /> - <path - sodipodi:nodetypes="cc" - id="path13133" - d="M 4.0235198,23.533487 L 34.289101,23.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000024;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000024;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 3.8528389,21.533487 L 34.11842,21.533487" - id="path13117" - sodipodi:nodetypes="cc" /> - <path - sodipodi:nodetypes="cc" - id="path13125" - d="M 3.6514189,19.533487 L 33.947215,19.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000012;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <path - style="opacity:0.39204545;color:#000000;fill:url(#linearGradient13848);fill-opacity:1.0;fill-rule:nonzero;stroke:none;stroke-width:1;stroke-linecap:butt;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:block;overflow:visible" - d="M 34.375,14.125 L 37,38.75 L 6,38.875 C 6,38.875 4.125,14.125 4.125,14.125 C 4.125,14.125 34.5,14.125 34.375,14.125 z " - id="path13840" - sodipodi:nodetypes="cccsc" /> - <path - inkscape:export-ydpi="74.800003" - inkscape:export-xdpi="74.800003" - inkscape:export-filename="/home/jimmac/ximian_art/icons/nautilus/suse93/gnome-fs-directory.png" - sodipodi:nodetypes="cccsscccscc" - id="path2401" - d="M 5.7785654,39.065997 C 5.8820074,39.277466 6.0888914,39.488925 6.3992173,39.488925 L 39.70767,39.488925 C 39.914562,39.488925 40.228834,39.36262 40.415844,39.224574 C 40.946246,38.833039 41.070704,38.612189 41.308626,38.251107 C 43.756752,34.535647 47.113767,18.974214 47.113767,18.974214 C 47.217209,18.762754 47.010326,18.551294 46.7,18.551294 L 11.776358,18.551294 C 11.466032,18.551294 10.120393,34.658624 6.9133592,37.838317 L 5.6751235,39.065997 L 5.7785654,39.065997 z " - style="opacity:1;color:#000000;fill:url(#linearGradient13162);fill-opacity:1;fill-rule:nonzero;stroke:#3465a4;stroke-width:1.00416672;stroke-linecap:butt;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:block;overflow:visible" - transform="matrix(0.988773,0,0,1.002979,-0.111407,-0.106563)" - inkscape:r_cx="true" - inkscape:r_cy="true" /> - <path - id="path323" - d="M 13.134476,20.138641 C 12.361729,25.129398 11.633175,29.147884 10.418486,33.652505 C 12.804971,32.945398 17.534602,30.448 27.534602,30.448 C 37.534602,30.448 44.258175,21.199301 45.186253,20.094447 L 13.134476,20.138641 z " - style="fill:url(#linearGradient156);fill-opacity:1;fill-rule:evenodd;stroke:none;stroke-width:1px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" - sodipodi:nodetypes="ccccc" - transform="matrix(0.988773,0,0,1.002979,-0.111407,-0.106563)" - inkscape:r_cx="true" - inkscape:r_cy="true" /> - <path - style="opacity:0.52272728;color:#000000;fill:none;fill-opacity:1;fill-rule:evenodd;stroke:url(#linearGradient155);stroke-width:1.00416696px;stroke-linecap:round;stroke-linejoin:miter;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 45.820083,19.6875 L 12.661612,19.6875 C 12.661612,19.6875 10.513864,35.707107 7.9393398,37.928078 C 16.060417,37.928078 39.510511,37.879442 39.53033,37.879442 C 41.281989,37.879442 44.437971,25.243248 45.820083,19.6875 z " - id="path324" - sodipodi:nodetypes="cccsc" - transform="matrix(0.988773,0,0,1.002979,-0.111407,-0.106563)" - inkscape:r_cx="true" - inkscape:r_cy="true" /> - <path - sodipodi:nodetypes="cc" - id="path13123" - d="M 3.1628954,15.533487 L 33.993452,15.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:0.99999994;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000036;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 2.9642313,13.533487 L 33.990735,13.533487" - id="path13127" - sodipodi:nodetypes="cc" /> - <path - sodipodi:nodetypes="cc" - id="path13145" - d="M 2.3052333,7.533487 L 17.088967,7.533487" - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:0.99999982;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" /> - <path - style="opacity:0.11363633;color:#000000;fill:#729fcf;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:1.00000024;stroke-linecap:round;stroke-linejoin:round;marker:none;marker-start:none;marker-mid:none;marker-end:none;stroke-miterlimit:4;stroke-dasharray:none;stroke-dashoffset:0;stroke-opacity:1;visibility:visible;display:inline;overflow:visible" - d="M 2.5242572,9.5334871 L 17.805073,9.5334871" - id="path13147" - sodipodi:nodetypes="cc" /> - </g> - <g - inkscape:groupmode="layer" - id="layer2" - inkscape:label="pattern" /> -</svg> diff --git a/src/apps/mavlinkgen/license.txt b/src/apps/mavlinkgen/license.txt deleted file mode 100644 index f90060e638..0000000000 --- a/src/apps/mavlinkgen/license.txt +++ /dev/null @@ -1,195 +0,0 @@ -This software is published under GNU GENERAL PUBLIC LICENSE 3 - -TERMS AND CONDITIONS -0. Definitions. - -“This License” refers to version 3 of the GNU General Public License. - -“Copyright” also means copyright-like laws that apply to other kinds of works, such as semiconductor masks. - -“The Program” refers to any copyrightable work licensed under this License. Each licensee is addressed as “you”. “Licensees” and “recipients” may be individuals or organizations. - -To “modify” a work means to copy from or adapt all or part of the work in a fashion requiring copyright permission, other than the making of an exact copy. The resulting work is called a “modified version” of the earlier work or a work “based on” the earlier work. - -A “covered work” means either the unmodified Program or a work based on the Program. - -To “propagate” a work means to do anything with it that, without permission, would make you directly or secondarily liable for infringement under applicable copyright law, except executing it on a computer or modifying a private copy. Propagation includes copying, distribution (with or without modification), making available to the public, and in some countries other activities as well. - -To “convey” a work means any kind of propagation that enables other parties to make or receive copies. Mere interaction with a user through a computer network, with no transfer of a copy, is not conveying. - -An interactive user interface displays “Appropriate Legal Notices” to the extent that it includes a convenient and prominently visible feature that (1) displays an appropriate copyright notice, and (2) tells the user that there is no warranty for the work (except to the extent that warranties are provided), that licensees may convey the work under this License, and how to view a copy of this License. If the interface presents a list of user commands or options, such as a menu, a prominent item in the list meets this criterion. - - -1. Source Code. - -The “source code” for a work means the preferred form of the work for making modifications to it. “Object code” means any non-source form of a work. - -A “Standard Interface” means an interface that either is an official standard defined by a recognized standards body, or, in the case of interfaces specified for a particular programming language, one that is widely used among developers working in that language. - -The “System Libraries” of an executable work include anything, other than the work as a whole, that (a) is included in the normal form of packaging a Major Component, but which is not part of that Major Component, and (b) serves only to enable use of the work with that Major Component, or to implement a Standard Interface for which an implementation is available to the public in source code form. A “Major Component”, in this context, means a major essential component (kernel, window system, and so on) of the specific operating system (if any) on which the executable work runs, or a compiler used to produce the work, or an object code interpreter used to run it. - -The “Corresponding Source” for a work in object code form means all the source code needed to generate, install, and (for an executable work) run the object code and to modify the work, including scripts to control those activities. However, it does not include the work's System Libraries, or general-purpose tools or generally available free programs which are used unmodified in performing those activities but which are not part of the work. For example, Corresponding Source includes interface definition files associated with source files for the work, and the source code for shared libraries and dynamically linked subprograms that the work is specifically designed to require, such as by intimate data communication or control flow between those subprograms and other parts of the work. - -The Corresponding Source need not include anything that users can regenerate automatically from other parts of the Corresponding Source. - -The Corresponding Source for a work in source code form is that same work. - - -2. Basic Permissions. - -All rights granted under this License are granted for the term of copyright on the Program, and are irrevocable provided the stated conditions are met. This License explicitly affirms your unlimited permission to run the unmodified Program. The output from running a covered work is covered by this License only if the output, given its content, constitutes a covered work. This License acknowledges your rights of fair use or other equivalent, as provided by copyright law. - -You may make, run and propagate covered works that you do not convey, without conditions so long as your license otherwise remains in force. You may convey covered works to others for the sole purpose of having them make modifications exclusively for you, or provide you with facilities for running those works, provided that you comply with the terms of this License in conveying all material for which you do not control copyright. Those thus making or running the covered works for you must do so exclusively on your behalf, under your direction and control, on terms that prohibit them from making any copies of your copyrighted material outside their relationship with you. - -Conveying under any other circumstances is permitted solely under the conditions stated below. Sublicensing is not allowed; section 10 makes it unnecessary. - - -3. Protecting Users' Legal Rights From Anti-Circumvention Law. - -No covered work shall be deemed part of an effective technological measure under any applicable law fulfilling obligations under article 11 of the WIPO copyright treaty adopted on 20 December 1996, or similar laws prohibiting or restricting circumvention of such measures. - -When you convey a covered work, you waive any legal power to forbid circumvention of technological measures to the extent such circumvention is effected by exercising rights under this License with respect to the covered work, and you disclaim any intention to limit operation or modification of the work as a means of enforcing, against the work's users, your or third parties' legal rights to forbid circumvention of technological measures. - - -4. Conveying Verbatim Copies. - -You may convey verbatim copies of the Program's source code as you receive it, in any medium, provided that you conspicuously and appropriately publish on each copy an appropriate copyright notice; keep intact all notices stating that this License and any non-permissive terms added in accord with section 7 apply to the code; keep intact all notices of the absence of any warranty; and give all recipients a copy of this License along with the Program. - -You may charge any price or no price for each copy that you convey, and you may offer support or warranty protection for a fee. - - -5. Conveying Modified Source Versions. - -You may convey a work based on the Program, or the modifications to produce it from the Program, in the form of source code under the terms of section 4, provided that you also meet all of these conditions: - - * a) The work must carry prominent notices stating that you modified it, and giving a relevant date. - * b) The work must carry prominent notices stating that it is released under this License and any conditions added under section 7. This requirement modifies the requirement in section 4 to “keep intact all notices”. - * c) You must license the entire work, as a whole, under this License to anyone who comes into possession of a copy. This License will therefore apply, along with any applicable section 7 additional terms, to the whole of the work, and all its parts, regardless of how they are packaged. This License gives no permission to license the work in any other way, but it does not invalidate such permission if you have separately received it. - * d) If the work has interactive user interfaces, each must display Appropriate Legal Notices; however, if the Program has interactive interfaces that do not display Appropriate Legal Notices, your work need not make them do so. - -A compilation of a covered work with other separate and independent works, which are not by their nature extensions of the covered work, and which are not combined with it such as to form a larger program, in or on a volume of a storage or distribution medium, is called an “aggregate” if the compilation and its resulting copyright are not used to limit the access or legal rights of the compilation's users beyond what the individual works permit. Inclusion of a covered work in an aggregate does not cause this License to apply to the other parts of the aggregate. - - -6. Conveying Non-Source Forms. - -You may convey a covered work in object code form under the terms of sections 4 and 5, provided that you also convey the machine-readable Corresponding Source under the terms of this License, in one of these ways: - - * a) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by the Corresponding Source fixed on a durable physical medium customarily used for software interchange. - * b) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by a written offer, valid for at least three years and valid for as long as you offer spare parts or customer support for that product model, to give anyone who possesses the object code either (1) a copy of the Corresponding Source for all the software in the product that is covered by this License, on a durable physical medium customarily used for software interchange, for a price no more than your reasonable cost of physically performing this conveying of source, or (2) access to copy the Corresponding Source from a network server at no charge. - * c) Convey individual copies of the object code with a copy of the written offer to provide the Corresponding Source. This alternative is allowed only occasionally and noncommercially, and only if you received the object code with such an offer, in accord with subsection 6b. - * d) Convey the object code by offering access from a designated place (gratis or for a charge), and offer equivalent access to the Corresponding Source in the same way through the same place at no further charge. You need not require recipients to copy the Corresponding Source along with the object code. If the place to copy the object code is a network server, the Corresponding Source may be on a different server (operated by you or a third party) that supports equivalent copying facilities, provided you maintain clear directions next to the object code saying where to find the Corresponding Source. Regardless of what server hosts the Corresponding Source, you remain obligated to ensure that it is available for as long as needed to satisfy these requirements. - * e) Convey the object code using peer-to-peer transmission, provided you inform other peers where the object code and Corresponding Source of the work are being offered to the general public at no charge under subsection 6d. - -A separable portion of the object code, whose source code is excluded from the Corresponding Source as a System Library, need not be included in conveying the object code work. - -A “User Product” is either (1) a “consumer product”, which means any tangible personal property which is normally used for personal, family, or household purposes, or (2) anything designed or sold for incorporation into a dwelling. In determining whether a product is a consumer product, doubtful cases shall be resolved in favor of coverage. For a particular product received by a particular user, “normally used” refers to a typical or common use of that class of product, regardless of the status of the particular user or of the way in which the particular user actually uses, or expects or is expected to use, the product. A product is a consumer product regardless of whether the product has substantial commercial, industrial or non-consumer uses, unless such uses represent the only significant mode of use of the product. - -“Installation Information” for a User Product means any methods, procedures, authorization keys, or other information required to install and execute modified versions of a covered work in that User Product from a modified version of its Corresponding Source. The information must suffice to ensure that the continued functioning of the modified object code is in no case prevented or interfered with solely because modification has been made. - -If you convey an object code work under this section in, or with, or specifically for use in, a User Product, and the conveying occurs as part of a transaction in which the right of possession and use of the User Product is transferred to the recipient in perpetuity or for a fixed term (regardless of how the transaction is characterized), the Corresponding Source conveyed under this section must be accompanied by the Installation Information. But this requirement does not apply if neither you nor any third party retains the ability to install modified object code on the User Product (for example, the work has been installed in ROM). - -The requirement to provide Installation Information does not include a requirement to continue to provide support service, warranty, or updates for a work that has been modified or installed by the recipient, or for the User Product in which it has been modified or installed. Access to a network may be denied when the modification itself materially and adversely affects the operation of the network or violates the rules and protocols for communication across the network. - -Corresponding Source conveyed, and Installation Information provided, in accord with this section must be in a format that is publicly documented (and with an implementation available to the public in source code form), and must require no special password or key for unpacking, reading or copying. - - -7. Additional Terms. - -“Additional permissions” are terms that supplement the terms of this License by making exceptions from one or more of its conditions. Additional permissions that are applicable to the entire Program shall be treated as though they were included in this License, to the extent that they are valid under applicable law. If additional permissions apply only to part of the Program, that part may be used separately under those permissions, but the entire Program remains governed by this License without regard to the additional permissions. - -When you convey a copy of a covered work, you may at your option remove any additional permissions from that copy, or from any part of it. (Additional permissions may be written to require their own removal in certain cases when you modify the work.) You may place additional permissions on material, added by you to a covered work, for which you have or can give appropriate copyright permission. - -Notwithstanding any other provision of this License, for material you add to a covered work, you may (if authorized by the copyright holders of that material) supplement the terms of this License with terms: - - * a) Disclaiming warranty or limiting liability differently from the terms of sections 15 and 16 of this License; or - * b) Requiring preservation of specified reasonable legal notices or author attributions in that material or in the Appropriate Legal Notices displayed by works containing it; or - * c) Prohibiting misrepresentation of the origin of that material, or requiring that modified versions of such material be marked in reasonable ways as different from the original version; or - * d) Limiting the use for publicity purposes of names of licensors or authors of the material; or - * e) Declining to grant rights under trademark law for use of some trade names, trademarks, or service marks; or - * f) Requiring indemnification of licensors and authors of that material by anyone who conveys the material (or modified versions of it) with contractual assumptions of liability to the recipient, for any liability that these contractual assumptions directly impose on those licensors and authors. - -All other non-permissive additional terms are considered “further restrictions” within the meaning of section 10. If the Program as you received it, or any part of it, contains a notice stating that it is governed by this License along with a term that is a further restriction, you may remove that term. If a license document contains a further restriction but permits relicensing or conveying under this License, you may add to a covered work material governed by the terms of that license document, provided that the further restriction does not survive such relicensing or conveying. - -If you add terms to a covered work in accord with this section, you must place, in the relevant source files, a statement of the additional terms that apply to those files, or a notice indicating where to find the applicable terms. - -Additional terms, permissive or non-permissive, may be stated in the form of a separately written license, or stated as exceptions; the above requirements apply either way. - - -8. Termination. - -You may not propagate or modify a covered work except as expressly provided under this License. Any attempt otherwise to propagate or modify it is void, and will automatically terminate your rights under this License (including any patent licenses granted under the third paragraph of section 11). - -However, if you cease all violation of this License, then your license from a particular copyright holder is reinstated (a) provisionally, unless and until the copyright holder explicitly and finally terminates your license, and (b) permanently, if the copyright holder fails to notify you of the violation by some reasonable means prior to 60 days after the cessation. - -Moreover, your license from a particular copyright holder is reinstated permanently if the copyright holder notifies you of the violation by some reasonable means, this is the first time you have received notice of violation of this License (for any work) from that copyright holder, and you cure the violation prior to 30 days after your receipt of the notice. - -Termination of your rights under this section does not terminate the licenses of parties who have received copies or rights from you under this License. If your rights have been terminated and not permanently reinstated, you do not qualify to receive new licenses for the same material under section 10. - - -9. Acceptance Not Required for Having Copies. - -You are not required to accept this License in order to receive or run a copy of the Program. Ancillary propagation of a covered work occurring solely as a consequence of using peer-to-peer transmission to receive a copy likewise does not require acceptance. However, nothing other than this License grants you permission to propagate or modify any covered work. These actions infringe copyright if you do not accept this License. Therefore, by modifying or propagating a covered work, you indicate your acceptance of this License to do so. - - -10. Automatic Licensing of Downstream Recipients. - -Each time you convey a covered work, the recipient automatically receives a license from the original licensors, to run, modify and propagate that work, subject to this License. You are not responsible for enforcing compliance by third parties with this License. - -An “entity transaction” is a transaction transferring control of an organization, or substantially all assets of one, or subdividing an organization, or merging organizations. If propagation of a covered work results from an entity transaction, each party to that transaction who receives a copy of the work also receives whatever licenses to the work the party's predecessor in interest had or could give under the previous paragraph, plus a right to possession of the Corresponding Source of the work from the predecessor in interest, if the predecessor has it or can get it with reasonable efforts. - -You may not impose any further restrictions on the exercise of the rights granted or affirmed under this License. For example, you may not impose a license fee, royalty, or other charge for exercise of rights granted under this License, and you may not initiate litigation (including a cross-claim or counterclaim in a lawsuit) alleging that any patent claim is infringed by making, using, selling, offering for sale, or importing the Program or any portion of it. - - -11. Patents. - -A “contributor” is a copyright holder who authorizes use under this License of the Program or a work on which the Program is based. The work thus licensed is called the contributor's “contributor version”. - -A contributor's “essential patent claims” are all patent claims owned or controlled by the contributor, whether already acquired or hereafter acquired, that would be infringed by some manner, permitted by this License, of making, using, or selling its contributor version, but do not include claims that would be infringed only as a consequence of further modification of the contributor version. For purposes of this definition, “control” includes the right to grant patent sublicenses in a manner consistent with the requirements of this License. - -Each contributor grants you a non-exclusive, worldwide, royalty-free patent license under the contributor's essential patent claims, to make, use, sell, offer for sale, import and otherwise run, modify and propagate the contents of its contributor version. - -In the following three paragraphs, a “patent license” is any express agreement or commitment, however denominated, not to enforce a patent (such as an express permission to practice a patent or covenant not to sue for patent infringement). To “grant” such a patent license to a party means to make such an agreement or commitment not to enforce a patent against the party. - -If you convey a covered work, knowingly relying on a patent license, and the Corresponding Source of the work is not available for anyone to copy, free of charge and under the terms of this License, through a publicly available network server or other readily accessible means, then you must either (1) cause the Corresponding Source to be so available, or (2) arrange to deprive yourself of the benefit of the patent license for this particular work, or (3) arrange, in a manner consistent with the requirements of this License, to extend the patent license to downstream recipients. “Knowingly relying” means you have actual knowledge that, but for the patent license, your conveying the covered work in a country, or your recipient's use of the covered work in a country, would infringe one or more identifiable patents in that country that you have reason to believe are valid. - -If, pursuant to or in connection with a single transaction or arrangement, you convey, or propagate by procuring conveyance of, a covered work, and grant a patent license to some of the parties receiving the covered work authorizing them to use, propagate, modify or convey a specific copy of the covered work, then the patent license you grant is automatically extended to all recipients of the covered work and works based on it. - -A patent license is “discriminatory” if it does not include within the scope of its coverage, prohibits the exercise of, or is conditioned on the non-exercise of one or more of the rights that are specifically granted under this License. You may not convey a covered work if you are a party to an arrangement with a third party that is in the business of distributing software, under which you make payment to the third party based on the extent of your activity of conveying the work, and under which the third party grants, to any of the parties who would receive the covered work from you, a discriminatory patent license (a) in connection with copies of the covered work conveyed by you (or copies made from those copies), or (b) primarily for and in connection with specific products or compilations that contain the covered work, unless you entered into that arrangement, or that patent license was granted, prior to 28 March 2007. - -Nothing in this License shall be construed as excluding or limiting any implied license or other defenses to infringement that may otherwise be available to you under applicable patent law. - - -12. No Surrender of Others' Freedom. - -If conditions are imposed on you (whether by court order, agreement or otherwise) that contradict the conditions of this License, they do not excuse you from the conditions of this License. If you cannot convey a covered work so as to satisfy simultaneously your obligations under this License and any other pertinent obligations, then as a consequence you may not convey it at all. For example, if you agree to terms that obligate you to collect a royalty for further conveying from those to whom you convey the Program, the only way you could satisfy both those terms and this License would be to refrain entirely from conveying the Program. - - -13. Use with the GNU Affero General Public License. - -Notwithstanding any other provision of this License, you have permission to link or combine any covered work with a work licensed under version 3 of the GNU Affero General Public License into a single combined work, and to convey the resulting work. The terms of this License will continue to apply to the part which is the covered work, but the special requirements of the GNU Affero General Public License, section 13, concerning interaction through a network will apply to the combination as such. - - -14. Revised Versions of this License. - -The Free Software Foundation may publish revised and/or new versions of the GNU General Public License from time to time. Such new versions will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. - -Each version is given a distinguishing version number. If the Program specifies that a certain numbered version of the GNU General Public License “or any later version” applies to it, you have the option of following the terms and conditions either of that numbered version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of the GNU General Public License, you may choose any version ever published by the Free Software Foundation. - -If the Program specifies that a proxy can decide which future versions of the GNU General Public License can be used, that proxy's public statement of acceptance of a version permanently authorizes you to choose that version for the Program. - -Later license versions may give you additional or different permissions. However, no additional obligations are imposed on any author or copyright holder as a result of your choosing to follow a later version. - - -15. Disclaimer of Warranty. - -THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM “AS IS” WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - -16. Limitation of Liability. - -IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. - - -17. Interpretation of Sections 15 and 16. - -If the disclaimer of warranty and limitation of liability provided above cannot be given local legal effect according to their terms, reviewing courts shall apply local law that most closely approximates an absolute waiver of all civil liability in connection with the Program, unless a warranty or assumption of liability accompanies a copy of the Program in return for a fee. diff --git a/src/apps/mavlinkgen/main.cc b/src/apps/mavlinkgen/main.cc deleted file mode 100644 index 4a57b36902..0000000000 --- a/src/apps/mavlinkgen/main.cc +++ /dev/null @@ -1,46 +0,0 @@ -/*===================================================================== - -PIXHAWK Micro Air Vehicle Flying Robotics Toolkit - -(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch> - -This file is part of the PIXHAWK project - - PIXHAWK is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - PIXHAWK is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Main executable - * @author Lorenz Meier <mavteam@student.ethz.ch> - * - */ - -#include <QtGui/QApplication> -#include "MAVLinkGen.h" - -/** - * @brief Starts the application - * - * @param argc Number of commandline arguments - * @param argv Commandline arguments - * @return exit code, 0 for normal exit and !=0 for error cases - */ -int main(int argc, char *argv[]) -{ - - MAVLinkGen gen(argc, argv); - return gen.exec(); -} diff --git a/src/apps/mavlinkgen/mavlinkgen.pri b/src/apps/mavlinkgen/mavlinkgen.pri deleted file mode 100644 index a5ef920b55..0000000000 --- a/src/apps/mavlinkgen/mavlinkgen.pri +++ /dev/null @@ -1,44 +0,0 @@ -# Third-party includes. -# if you include this file with the commands below into -# your Qt project, you can enable your application -# to generate MAVLink code easily. - -###### EXAMPLE BEGIN - -## Include MAVLink generator -#DEPENDPATH += \ -# src/apps/mavlinkgen -# -#INCLUDEPATH += \ -# src/apps/mavlinkgen -# src/apps/mavlinkgen/ui \ -# src/apps/mavlinkgen/generator -# -#include(src/apps/mavlinkgen/mavlinkgen.pri) - -###### EXAMPLE END - - - -INCLUDEPATH += .\ - ui \ - generator - -FORMS += ui/XMLCommProtocolWidget.ui - -HEADERS += \ - ui/XMLCommProtocolWidget.h \ - generator/MAVLinkXMLParser.h \ - generator/MAVLinkXMLParserV10.h \ - ui/DomItem.h \ - ui/DomModel.h \ - ui/QGCMAVLinkTextEdit.h -SOURCES += \ - ui/XMLCommProtocolWidget.cc \ - ui/DomItem.cc \ - ui/DomModel.cc \ - generator/MAVLinkXMLParser.cc \ - generator/MAVLinkXMLParserV10.cc \ - ui/QGCMAVLinkTextEdit.cc - -RESOURCES += mavlinkgen.qrc diff --git a/src/apps/mavlinkgen/mavlinkgen.pro b/src/apps/mavlinkgen/mavlinkgen.pro deleted file mode 100644 index 2786956043..0000000000 --- a/src/apps/mavlinkgen/mavlinkgen.pro +++ /dev/null @@ -1,22 +0,0 @@ -# MAVLink code generator -# generates code in several languages for MAVLink encoding/decoding - -QT += svg xml - -TEMPLATE = app -TARGET = mavlinkgen - -LANGUAGE = C++ - -# Widget files (can be included in third-party Qt applications) -include(mavlinkgen.pri) - -# Standalone files -HEADERS += MAVLinkGen.h -win32-msvc2008|win32-msvc2010 { -HEADERS += msinttypes/inttypes.h \ - msinttypes/stdint.h -INCLUDEPATH += msinttypes -} -SOURCES += main.cc \ - MAVLinkGen.cc diff --git a/src/apps/mavlinkgen/mavlinkgen.qrc b/src/apps/mavlinkgen/mavlinkgen.qrc deleted file mode 100644 index 9db933d565..0000000000 --- a/src/apps/mavlinkgen/mavlinkgen.qrc +++ /dev/null @@ -1,6 +0,0 @@ -<RCC> - <qresource prefix="/"> - <file>images/categories/applications-system.svg</file> - <file>images/status/folder-open.svg</file> - </qresource> -</RCC> diff --git a/src/apps/mavlinkgen/msinttypes/inttypes.h b/src/apps/mavlinkgen/msinttypes/inttypes.h deleted file mode 100644 index 4b3828a216..0000000000 --- a/src/apps/mavlinkgen/msinttypes/inttypes.h +++ /dev/null @@ -1,305 +0,0 @@ -// ISO C9x compliant inttypes.h for Microsoft Visual Studio -// Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124 -// -// Copyright (c) 2006 Alexander Chemeris -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// 1. Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// 2. Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// 3. The name of the author may be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED -// WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF -// MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO -// EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, -// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; -// OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -// WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR -// OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF -// ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -// -/////////////////////////////////////////////////////////////////////////////// - -#ifndef _MSC_VER // [ -#error "Use this header only with Microsoft Visual C++ compilers!" -#endif // _MSC_VER ] - -#ifndef _MSC_INTTYPES_H_ // [ -#define _MSC_INTTYPES_H_ - -#if _MSC_VER > 1000 -#pragma once -#endif - -#include "stdint.h" - -// 7.8 Format conversion of integer types - -typedef struct { - intmax_t quot; - intmax_t rem; -} imaxdiv_t; - -// 7.8.1 Macros for format specifiers - -#if !defined(__cplusplus) || defined(__STDC_FORMAT_MACROS) // [ See footnote 185 at page 198 - -// The fprintf macros for signed integers are: -#define PRId8 "d" -#define PRIi8 "i" -#define PRIdLEAST8 "d" -#define PRIiLEAST8 "i" -#define PRIdFAST8 "d" -#define PRIiFAST8 "i" - -#define PRId16 "hd" -#define PRIi16 "hi" -#define PRIdLEAST16 "hd" -#define PRIiLEAST16 "hi" -#define PRIdFAST16 "hd" -#define PRIiFAST16 "hi" - -#define PRId32 "I32d" -#define PRIi32 "I32i" -#define PRIdLEAST32 "I32d" -#define PRIiLEAST32 "I32i" -#define PRIdFAST32 "I32d" -#define PRIiFAST32 "I32i" - -#define PRId64 "I64d" -#define PRIi64 "I64i" -#define PRIdLEAST64 "I64d" -#define PRIiLEAST64 "I64i" -#define PRIdFAST64 "I64d" -#define PRIiFAST64 "I64i" - -#define PRIdMAX "I64d" -#define PRIiMAX "I64i" - -#define PRIdPTR "Id" -#define PRIiPTR "Ii" - -// The fprintf macros for unsigned integers are: -#define PRIo8 "o" -#define PRIu8 "u" -#define PRIx8 "x" -#define PRIX8 "X" -#define PRIoLEAST8 "o" -#define PRIuLEAST8 "u" -#define PRIxLEAST8 "x" -#define PRIXLEAST8 "X" -#define PRIoFAST8 "o" -#define PRIuFAST8 "u" -#define PRIxFAST8 "x" -#define PRIXFAST8 "X" - -#define PRIo16 "ho" -#define PRIu16 "hu" -#define PRIx16 "hx" -#define PRIX16 "hX" -#define PRIoLEAST16 "ho" -#define PRIuLEAST16 "hu" -#define PRIxLEAST16 "hx" -#define PRIXLEAST16 "hX" -#define PRIoFAST16 "ho" -#define PRIuFAST16 "hu" -#define PRIxFAST16 "hx" -#define PRIXFAST16 "hX" - -#define PRIo32 "I32o" -#define PRIu32 "I32u" -#define PRIx32 "I32x" -#define PRIX32 "I32X" -#define PRIoLEAST32 "I32o" -#define PRIuLEAST32 "I32u" -#define PRIxLEAST32 "I32x" -#define PRIXLEAST32 "I32X" -#define PRIoFAST32 "I32o" -#define PRIuFAST32 "I32u" -#define PRIxFAST32 "I32x" -#define PRIXFAST32 "I32X" - -#define PRIo64 "I64o" -#define PRIu64 "I64u" -#define PRIx64 "I64x" -#define PRIX64 "I64X" -#define PRIoLEAST64 "I64o" -#define PRIuLEAST64 "I64u" -#define PRIxLEAST64 "I64x" -#define PRIXLEAST64 "I64X" -#define PRIoFAST64 "I64o" -#define PRIuFAST64 "I64u" -#define PRIxFAST64 "I64x" -#define PRIXFAST64 "I64X" - -#define PRIoMAX "I64o" -#define PRIuMAX "I64u" -#define PRIxMAX "I64x" -#define PRIXMAX "I64X" - -#define PRIoPTR "Io" -#define PRIuPTR "Iu" -#define PRIxPTR "Ix" -#define PRIXPTR "IX" - -// The fscanf macros for signed integers are: -#define SCNd8 "d" -#define SCNi8 "i" -#define SCNdLEAST8 "d" -#define SCNiLEAST8 "i" -#define SCNdFAST8 "d" -#define SCNiFAST8 "i" - -#define SCNd16 "hd" -#define SCNi16 "hi" -#define SCNdLEAST16 "hd" -#define SCNiLEAST16 "hi" -#define SCNdFAST16 "hd" -#define SCNiFAST16 "hi" - -#define SCNd32 "ld" -#define SCNi32 "li" -#define SCNdLEAST32 "ld" -#define SCNiLEAST32 "li" -#define SCNdFAST32 "ld" -#define SCNiFAST32 "li" - -#define SCNd64 "I64d" -#define SCNi64 "I64i" -#define SCNdLEAST64 "I64d" -#define SCNiLEAST64 "I64i" -#define SCNdFAST64 "I64d" -#define SCNiFAST64 "I64i" - -#define SCNdMAX "I64d" -#define SCNiMAX "I64i" - -#ifdef _WIN64 // [ -# define SCNdPTR "I64d" -# define SCNiPTR "I64i" -#else // _WIN64 ][ -# define SCNdPTR "ld" -# define SCNiPTR "li" -#endif // _WIN64 ] - -// The fscanf macros for unsigned integers are: -#define SCNo8 "o" -#define SCNu8 "u" -#define SCNx8 "x" -#define SCNX8 "X" -#define SCNoLEAST8 "o" -#define SCNuLEAST8 "u" -#define SCNxLEAST8 "x" -#define SCNXLEAST8 "X" -#define SCNoFAST8 "o" -#define SCNuFAST8 "u" -#define SCNxFAST8 "x" -#define SCNXFAST8 "X" - -#define SCNo16 "ho" -#define SCNu16 "hu" -#define SCNx16 "hx" -#define SCNX16 "hX" -#define SCNoLEAST16 "ho" -#define SCNuLEAST16 "hu" -#define SCNxLEAST16 "hx" -#define SCNXLEAST16 "hX" -#define SCNoFAST16 "ho" -#define SCNuFAST16 "hu" -#define SCNxFAST16 "hx" -#define SCNXFAST16 "hX" - -#define SCNo32 "lo" -#define SCNu32 "lu" -#define SCNx32 "lx" -#define SCNX32 "lX" -#define SCNoLEAST32 "lo" -#define SCNuLEAST32 "lu" -#define SCNxLEAST32 "lx" -#define SCNXLEAST32 "lX" -#define SCNoFAST32 "lo" -#define SCNuFAST32 "lu" -#define SCNxFAST32 "lx" -#define SCNXFAST32 "lX" - -#define SCNo64 "I64o" -#define SCNu64 "I64u" -#define SCNx64 "I64x" -#define SCNX64 "I64X" -#define SCNoLEAST64 "I64o" -#define SCNuLEAST64 "I64u" -#define SCNxLEAST64 "I64x" -#define SCNXLEAST64 "I64X" -#define SCNoFAST64 "I64o" -#define SCNuFAST64 "I64u" -#define SCNxFAST64 "I64x" -#define SCNXFAST64 "I64X" - -#define SCNoMAX "I64o" -#define SCNuMAX "I64u" -#define SCNxMAX "I64x" -#define SCNXMAX "I64X" - -#ifdef _WIN64 // [ -# define SCNoPTR "I64o" -# define SCNuPTR "I64u" -# define SCNxPTR "I64x" -# define SCNXPTR "I64X" -#else // _WIN64 ][ -# define SCNoPTR "lo" -# define SCNuPTR "lu" -# define SCNxPTR "lx" -# define SCNXPTR "lX" -#endif // _WIN64 ] - -#endif // __STDC_FORMAT_MACROS ] - -// 7.8.2 Functions for greatest-width integer types - -// 7.8.2.1 The imaxabs function -#define imaxabs _abs64 - -// 7.8.2.2 The imaxdiv function - -// This is modified version of div() function from Microsoft's div.c found -// in %MSVC.NET%\crt\src\div.c -#ifdef STATIC_IMAXDIV // [ -static -#else // STATIC_IMAXDIV ][ -_inline -#endif // STATIC_IMAXDIV ] -imaxdiv_t __cdecl imaxdiv(intmax_t numer, intmax_t denom) -{ - imaxdiv_t result; - - result.quot = numer / denom; - result.rem = numer % denom; - - if (numer < 0 && result.rem > 0) { - // did division wrong; must fix up - ++result.quot; - result.rem -= denom; - } - - return result; -} - -// 7.8.2.3 The strtoimax and strtoumax functions -#define strtoimax _strtoi64 -#define strtoumax _strtoui64 - -// 7.8.2.4 The wcstoimax and wcstoumax functions -#define wcstoimax _wcstoi64 -#define wcstoumax _wcstoui64 - - -#endif // _MSC_INTTYPES_H_ ] diff --git a/src/apps/mavlinkgen/msinttypes/stdint.h b/src/apps/mavlinkgen/msinttypes/stdint.h deleted file mode 100644 index d02608a597..0000000000 --- a/src/apps/mavlinkgen/msinttypes/stdint.h +++ /dev/null @@ -1,247 +0,0 @@ -// ISO C9x compliant stdint.h for Microsoft Visual Studio -// Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124 -// -// Copyright (c) 2006-2008 Alexander Chemeris -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// 1. Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// 2. Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// 3. The name of the author may be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED -// WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF -// MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO -// EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, -// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; -// OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -// WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR -// OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF -// ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -// -/////////////////////////////////////////////////////////////////////////////// - -#ifndef _MSC_VER // [ -#error "Use this header only with Microsoft Visual C++ compilers!" -#endif // _MSC_VER ] - -#ifndef _MSC_STDINT_H_ // [ -#define _MSC_STDINT_H_ - -#if _MSC_VER > 1000 -#pragma once -#endif - -#include <limits.h> - -// For Visual Studio 6 in C++ mode and for many Visual Studio versions when -// compiling for ARM we should wrap <wchar.h> include with 'extern "C++" {}' -// or compiler give many errors like this: -// error C2733: second C linkage of overloaded function 'wmemchr' not allowed -#ifdef __cplusplus -extern "C" { -#endif -# include <wchar.h> -#ifdef __cplusplus -} -#endif - -// Define _W64 macros to mark types changing their size, like intptr_t. -#ifndef _W64 -# if !defined(__midl) && (defined(_X86_) || defined(_M_IX86)) && _MSC_VER >= 1300 -# define _W64 __w64 -# else -# define _W64 -# endif -#endif - - -// 7.18.1 Integer types - -// 7.18.1.1 Exact-width integer types - -// Visual Studio 6 and Embedded Visual C++ 4 doesn't -// realize that, e.g. char has the same size as __int8 -// so we give up on __intX for them. -#if (_MSC_VER < 1300) - typedef signed char int8_t; - typedef signed short int16_t; - typedef signed int int32_t; - typedef unsigned char uint8_t; - typedef unsigned short uint16_t; - typedef unsigned int uint32_t; -#else - typedef signed __int8 int8_t; - typedef signed __int16 int16_t; - typedef signed __int32 int32_t; - typedef unsigned __int8 uint8_t; - typedef unsigned __int16 uint16_t; - typedef unsigned __int32 uint32_t; -#endif -typedef signed __int64 int64_t; -typedef unsigned __int64 uint64_t; - - -// 7.18.1.2 Minimum-width integer types -typedef int8_t int_least8_t; -typedef int16_t int_least16_t; -typedef int32_t int_least32_t; -typedef int64_t int_least64_t; -typedef uint8_t uint_least8_t; -typedef uint16_t uint_least16_t; -typedef uint32_t uint_least32_t; -typedef uint64_t uint_least64_t; - -// 7.18.1.3 Fastest minimum-width integer types -typedef int8_t int_fast8_t; -typedef int16_t int_fast16_t; -typedef int32_t int_fast32_t; -typedef int64_t int_fast64_t; -typedef uint8_t uint_fast8_t; -typedef uint16_t uint_fast16_t; -typedef uint32_t uint_fast32_t; -typedef uint64_t uint_fast64_t; - -// 7.18.1.4 Integer types capable of holding object pointers -#ifdef _WIN64 // [ - typedef signed __int64 intptr_t; - typedef unsigned __int64 uintptr_t; -#else // _WIN64 ][ - typedef _W64 signed int intptr_t; - typedef _W64 unsigned int uintptr_t; -#endif // _WIN64 ] - -// 7.18.1.5 Greatest-width integer types -typedef int64_t intmax_t; -typedef uint64_t uintmax_t; - - -// 7.18.2 Limits of specified-width integer types - -#if !defined(__cplusplus) || defined(__STDC_LIMIT_MACROS) // [ See footnote 220 at page 257 and footnote 221 at page 259 - -// 7.18.2.1 Limits of exact-width integer types -#define INT8_MIN ((int8_t)_I8_MIN) -#define INT8_MAX _I8_MAX -#define INT16_MIN ((int16_t)_I16_MIN) -#define INT16_MAX _I16_MAX -#define INT32_MIN ((int32_t)_I32_MIN) -#define INT32_MAX _I32_MAX -#define INT64_MIN ((int64_t)_I64_MIN) -#define INT64_MAX _I64_MAX -#define UINT8_MAX _UI8_MAX -#define UINT16_MAX _UI16_MAX -#define UINT32_MAX _UI32_MAX -#define UINT64_MAX _UI64_MAX - -// 7.18.2.2 Limits of minimum-width integer types -#define INT_LEAST8_MIN INT8_MIN -#define INT_LEAST8_MAX INT8_MAX -#define INT_LEAST16_MIN INT16_MIN -#define INT_LEAST16_MAX INT16_MAX -#define INT_LEAST32_MIN INT32_MIN -#define INT_LEAST32_MAX INT32_MAX -#define INT_LEAST64_MIN INT64_MIN -#define INT_LEAST64_MAX INT64_MAX -#define UINT_LEAST8_MAX UINT8_MAX -#define UINT_LEAST16_MAX UINT16_MAX -#define UINT_LEAST32_MAX UINT32_MAX -#define UINT_LEAST64_MAX UINT64_MAX - -// 7.18.2.3 Limits of fastest minimum-width integer types -#define INT_FAST8_MIN INT8_MIN -#define INT_FAST8_MAX INT8_MAX -#define INT_FAST16_MIN INT16_MIN -#define INT_FAST16_MAX INT16_MAX -#define INT_FAST32_MIN INT32_MIN -#define INT_FAST32_MAX INT32_MAX -#define INT_FAST64_MIN INT64_MIN -#define INT_FAST64_MAX INT64_MAX -#define UINT_FAST8_MAX UINT8_MAX -#define UINT_FAST16_MAX UINT16_MAX -#define UINT_FAST32_MAX UINT32_MAX -#define UINT_FAST64_MAX UINT64_MAX - -// 7.18.2.4 Limits of integer types capable of holding object pointers -#ifdef _WIN64 // [ -# define INTPTR_MIN INT64_MIN -# define INTPTR_MAX INT64_MAX -# define UINTPTR_MAX UINT64_MAX -#else // _WIN64 ][ -# define INTPTR_MIN INT32_MIN -# define INTPTR_MAX INT32_MAX -# define UINTPTR_MAX UINT32_MAX -#endif // _WIN64 ] - -// 7.18.2.5 Limits of greatest-width integer types -#define INTMAX_MIN INT64_MIN -#define INTMAX_MAX INT64_MAX -#define UINTMAX_MAX UINT64_MAX - -// 7.18.3 Limits of other integer types - -#ifdef _WIN64 // [ -# define PTRDIFF_MIN _I64_MIN -# define PTRDIFF_MAX _I64_MAX -#else // _WIN64 ][ -# define PTRDIFF_MIN _I32_MIN -# define PTRDIFF_MAX _I32_MAX -#endif // _WIN64 ] - -#define SIG_ATOMIC_MIN INT_MIN -#define SIG_ATOMIC_MAX INT_MAX - -#ifndef SIZE_MAX // [ -# ifdef _WIN64 // [ -# define SIZE_MAX _UI64_MAX -# else // _WIN64 ][ -# define SIZE_MAX _UI32_MAX -# endif // _WIN64 ] -#endif // SIZE_MAX ] - -// WCHAR_MIN and WCHAR_MAX are also defined in <wchar.h> -#ifndef WCHAR_MIN // [ -# define WCHAR_MIN 0 -#endif // WCHAR_MIN ] -#ifndef WCHAR_MAX // [ -# define WCHAR_MAX _UI16_MAX -#endif // WCHAR_MAX ] - -#define WINT_MIN 0 -#define WINT_MAX _UI16_MAX - -#endif // __STDC_LIMIT_MACROS ] - - -// 7.18.4 Limits of other integer types - -#if !defined(__cplusplus) || defined(__STDC_CONSTANT_MACROS) // [ See footnote 224 at page 260 - -// 7.18.4.1 Macros for minimum-width integer constants - -#define INT8_C(val) val##i8 -#define INT16_C(val) val##i16 -#define INT32_C(val) val##i32 -#define INT64_C(val) val##i64 - -#define UINT8_C(val) val##ui8 -#define UINT16_C(val) val##ui16 -#define UINT32_C(val) val##ui32 -#define UINT64_C(val) val##ui64 - -// 7.18.4.2 Macros for greatest-width integer constants -#define INTMAX_C INT64_C -#define UINTMAX_C UINT64_C - -#endif // __STDC_CONSTANT_MACROS ] - - -#endif // _MSC_STDINT_H_ ] diff --git a/src/apps/mavlinkgen/template/checksum.h b/src/apps/mavlinkgen/template/checksum.h deleted file mode 100644 index 07bab9102a..0000000000 --- a/src/apps/mavlinkgen/template/checksum.h +++ /dev/null @@ -1,139 +0,0 @@ -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef _CHECKSUM_H_ -#define _CHECKSUM_H_ - -#include "inttypes.h" - - -/** - * - * CALCULATE THE CHECKSUM - * - */ - -#define X25_INIT_CRC 0xffff -#define X25_VALIDATE_CRC 0xf0b8 - -/** - * @brief Accumulate the X.25 CRC by adding one char at a time. - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new char to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) -{ - /*Accumulate one byte of data into the CRC*/ - uint8_t tmp; - - tmp=data ^ (uint8_t)(*crcAccum &0xff); - tmp^= (tmp<<4); - *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -// *crcAccum += data; // super simple to test -} - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(uint8_t* pBuffer, int length) -{ - - // For a "message" of length bytes contained in the unsigned char array - // pointed to by pBuffer, calculate the CRC - // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed - - uint16_t crcTmp; - //uint16_t tmp; - uint8_t* pTmp; - int i; - - pTmp=pBuffer; - - - /* init crcTmp */ - crc_init(&crcTmp); - - for (i = 0; i < length; i++){ - crc_accumulate(*pTmp++, &crcTmp); - } - - /* This is currently not needed, as only the checksum over payload should be computed - tmp = crcTmp; - crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp); - crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp); - *checkConst = tmp; - */ - return(crcTmp); -} - - -/** - * @brief Calculates the X.25 checksum on a msg buffer - * - * @param pMSG buffer containing the msg to hash - * @param length number of bytes to hash - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate_msg(mavlink_message_t* pMSG, int length) -{ - - // For a "message" of length bytes contained in the unsigned char array - // pointed to by pBuffer, calculate the CRC - // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed - - uint16_t crcTmp; - //uint16_t tmp; - uint8_t* pTmp; - int i; - - pTmp=&pMSG->len; - - /* init crcTmp */ - crc_init(&crcTmp); - - for (i = 0; i < 5; i++){ - crc_accumulate(*pTmp++, &crcTmp); - } - - pTmp=&pMSG->payload[0]; - for (; i < length; i++){ - crc_accumulate(*pTmp++, &crcTmp); - } - - /* This is currently not needed, as only the checksum over payload should be computed - tmp = crcTmp; - crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp); - crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp); - *checkConst = tmp; - */ - return(crcTmp); -} - - - - -#endif /* _CHECKSUM_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/src/apps/mavlinkgen/template/documentation.dox b/src/apps/mavlinkgen/template/documentation.dox deleted file mode 100644 index 49de0050e4..0000000000 --- a/src/apps/mavlinkgen/template/documentation.dox +++ /dev/null @@ -1,41 +0,0 @@ -/** - * @file - * @brief MAVLink communication protocol - * - * @author Lorenz Meier <mavteam@student.ethz.ch> - * - */ - - -/** - * @mainpage MAVLink API Documentation - * - * @section intro_sec Introduction - * - * This <a href="http://en.wikipedia.org/wiki/API" target="_blank">API</a> documentation covers the MAVLink - * protocol developed <a href="http://pixhawk.ethz.ch" target="_blank">PIXHAWK</a> project. - * In case you have generated this documentation locally, the most recent version (generated on every commit) - * is also publicly available on the internet. - * - * @sa http://pixhawk.ethz.ch/api/qgroundcontrol/ - Groundstation code base - * @sa http://pixhawk.ethz.ch/api/mavlink - (this) MAVLink communication protocol - * @sa http://pixhawk.ethz.ch/api/imu_autopilot/ - Flight board (ARM MCU) code base - * @sa http://pixhawk.ethz.ch/api/ai_vision - Computer Vision / AI API docs - * - * @section further_sec Further Information - * - * How to run our software and a general overview of the software architecture is documented in the project - * wiki pages. - * - * @sa http://pixhawk.ethz.ch/software/mavlink/ - MAVLink main documentation - * - * See the <a href="http://pixhawk.ethz.ch" target="_blank">PIXHAWK website</a> for more information. - * - * @section usage_sec Doxygen Usage - * - * You can exclude files from being parsed into this Doxygen documentation - * by adding them to the EXCLUDE list in the file in embedded/cmake/doc/api/doxy.config.in. - * - * - * - **/ diff --git a/src/apps/mavlinkgen/template/mavlink_checksum.h b/src/apps/mavlinkgen/template/mavlink_checksum.h deleted file mode 100644 index fdcee99d16..0000000000 --- a/src/apps/mavlinkgen/template/mavlink_checksum.h +++ /dev/null @@ -1,183 +0,0 @@ -/** @file - * @brief MAVLink comm protocol checksum routines. - * @see http://qgroundcontrol.org/mavlink/ - * Edited on Monday, August 8 2011 - */ - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef _CHECKSUM_H_ -#define _CHECKSUM_H_ - -#include "inttypes.h" - - -/** - * - * CALCULATE THE CHECKSUM - * - */ - -#define X25_INIT_CRC 0xffff -#define X25_VALIDATE_CRC 0xf0b8 - -/** - * @brief Accumulate the X.25 CRC by adding one char at a time. - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new char to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) -{ - /*Accumulate one byte of data into the CRC*/ - uint8_t tmp; - - tmp=data ^ (uint8_t)(*crcAccum &0xff); - tmp^= (tmp<<4); - *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -// *crcAccum += data; // super simple to test -} - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - -/** - * @brief Initiliaze the buffer for the X.25 CRC to a specified value - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init2(uint16_t* crcAccum, uint16_t crcValue) -{ - *crcAccum = crcValue; -} - - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(uint8_t* pBuffer, int length) -{ - - // For a "message" of length bytes contained in the unsigned char array - // pointed to by pBuffer, calculate the CRC - // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed - - uint16_t crcTmp; - //uint16_t tmp; - uint8_t* pTmp; - int i; - - pTmp=pBuffer; - - - /* init crcTmp */ - crc_init(&crcTmp); - - for (i = 0; i < length; i++){ - crc_accumulate(*pTmp++, &crcTmp); - } - - /* This is currently not needed, as only the checksum over payload should be computed - tmp = crcTmp; - crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp); - crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp); - *checkConst = tmp; - */ - return(crcTmp); -} - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate_mem(uint8_t *pBuffer, uint16_t *crcTmp, int length) -{ - - // For a "message" of length bytes contained in the unsigned char array - // pointed to by pBuffer, calculate the CRC - // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed - - //uint16_t tmp; - //uint8_t* pTmp; - int i; - -// pTmp=pBuffer; - - for (i = 0; i < length; i++){ - crc_accumulate(*pBuffer++, crcTmp); - } - - return(*crcTmp); -} - - -/** - * @brief Calculates the X.25 checksum on a msg buffer - * - * @param pMSG buffer containing the msg to hash - * @param length number of bytes to hash - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate_msg(mavlink_message_t* pMSG, int length) -{ - - // For a "message" of length bytes contained in the unsigned char array - // pointed to by pBuffer, calculate the CRC - // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed - - uint16_t crcTmp; - //uint16_t tmp; - uint8_t* pTmp; - int i; - - pTmp=&pMSG->len; - - /* init crcTmp */ - crc_init(&crcTmp); - - for (i = 0; i < 5; i++){ - crc_accumulate(*pTmp++, &crcTmp); - } - - pTmp=&pMSG->payload[0]; - for (; i < length; i++){ - crc_accumulate(*pTmp++, &crcTmp); - } - - /* This is currently not needed, as only the checksum over payload should be computed - tmp = crcTmp; - crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp); - crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp); - *checkConst = tmp; - */ - return(crcTmp); -} - - - - -#endif /* _CHECKSUM_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/src/apps/mavlinkgen/template/mavlink_data.h b/src/apps/mavlinkgen/template/mavlink_data.h deleted file mode 100644 index 17c88cc2a9..0000000000 --- a/src/apps/mavlinkgen/template/mavlink_data.h +++ /dev/null @@ -1,21 +0,0 @@ -/** @file - * @brief Main MAVLink comm protocol data. - * @see http://qgroundcontrol.org/mavlink/ - * Edited on Monday, August 8 2011 - */ - -#ifndef _ML_DATA_H_ -#define _ML_DATA_H_ - -#include "mavlink_types.h" - -#ifdef MAVLINK_CHECK_LENGTH -const uint8_t MAVLINK_CONST mavlink_msg_lengths[256] = MAVLINK_MESSAGE_LENGTHS; -#endif - -const uint8_t MAVLINK_CONST mavlink_msg_keys[256] = MAVLINK_MESSAGE_KEYS; - -mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; -mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; -mavlink_system_t mavlink_system; -#endif \ No newline at end of file diff --git a/src/apps/mavlinkgen/template/mavlink_options.h b/src/apps/mavlinkgen/template/mavlink_options.h deleted file mode 100644 index 550a85ae55..0000000000 --- a/src/apps/mavlinkgen/template/mavlink_options.h +++ /dev/null @@ -1,135 +0,0 @@ -/** @file - * @brief MAVLink comm protocol option constants. - * @see http://qgroundcontrol.org/mavlink/ - * Edited on Monday, August 8 2011 - */ - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef _ML_OPTIONS_H_ -#define _ML_OPTIONS_H_ - - -/** - * - * Receive message length check option. On receive verify the length field - * as soon as the message ID field is received. Requires a 256 byte const - * table. Comment out the define to leave out the table and code to check it. - * - */ -//#define MAVLINK_CHECK_LENGTH - -/** - * - * Receive message buffer option. This option should be used only when the - * side effects are understood but allows the underlying program access to - * the internal recieve buffer - eliminating the usual double buffering. It - * also REQUIRES changes in the return type of mavlink_parse_char so only - * enable if you make the changes required. Default DISABLED. - * - */ -//#define MAVLINK_STATIC_BUFFER - -/** - * - * Receive message buffers option. This option defines how many msg buffers - * mavlink will define, and thereby how many links it can support. A default - * will be supplied if the symbol is not pre-defined, dependant on the make - * envionment. The default is 16 for a recognised OS envionment and 1 - * otherwise. - * - */ -#if !((defined MAVLINK_COMM_NB) | (MAVLINK_COMM_NB < 1)) -#undef MAVLINK_COMM_NB - #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) | (defined __APPLE__) - #define MAVLINK_COMM_NB 16 - #else - #define MAVLINK_COMM_NB 1 - #endif -#endif - - -/** - * - * Data relization option. This option controls inclusion of the file - * mavlink_data.h in the current compile unit - thus defining mavlink's - * variables. Default is ON (not defined) because typically mavlink.h is only - * included once in a system but if it was used in two files there would - * be duplicate variables at link time. Normal practice would be to define - * this symbol outside of this file as defining it here will cause missing - * symbols at link time. In other words in the first file to include mavlink.h - * do not define this sybol, then define this symbol in all other files before - * including mavlink.h - * - */ -//#define MAVLINK_NO_DATA -#ifdef MAVLINK_NO_DATA - #undef MAVLINK_DATA -#else - #define MAVLINK_DATA -#endif - -/** - * - * Custom data const data relization and access options. - * This define is placed in the form - * const uint8_t MAVLINK_CONST name[] = { ... }; - * for the keys table and (if applicable) lengths table to tell the compiler - * were to put the data. The access option is placed in the form - * variable = MAVLINK_CONST_READ( name[i] ); - * in order to allow custom read function's or accessors. - * By default MAVLINK_CONST is defined as nothing and MAVLINK_CONST_READ as - * MAVLINK_CONST_READ( a ) a - * These symbols are only defined if not already defined allowing this file - * to remain unchanged while the actual definitions are maintained in external - * files. - * - */ -#ifndef MAVLINK_CONST -#define MAVLINK_CONST -#endif -#ifndef MAVLINK_CONST_READ -#define MAVLINK_CONST_READ( a ) a -#endif - - -/** - * - * Convience functions. These are all in one send functions that are very - * easy to use. Just define the symbol MAVLINK_USE_CONVENIENCE_FUNCTIONS. - * These functions also support a buffer check, to ensure there is enough - * space in your comm buffer that the function would not block - it could - * also be used as the basis of a MUTEX. This is implemented in the send - * function as a macro with two arguments, first the comm chan number and - * the message length in the form - * MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_LEN ) - * followed by the function code and then - * MAVLINK_BUFFER_CHECK_START - * Note that there are no terminators on these statements to allow for - * code nesting or other constructs. Default value for both is empty. - * A sugested implementation is shown below and the symbols will be defined - * only if they are not allready. - * - * if ( serial_space( chan ) > len ) { // serial_space returns available space - * ..... code that creates message - * } - * - * #define MAVLINK_BUFFER_CHECK_START( c, l ) if ( serial_space( c ) > l ) { - * #define MAVLINK_BUFFER_CHECK_END } - * - */ -//#define MAVLINK_USE_CONVENIENCE_FUNCTIONS -#ifndef MAVLINK_BUFFER_CHECK_START -#define MAVLINK_BUFFER_CHECK_START( c, l ) ; -#endif -#ifndef MAVLINK_BUFFER_CHECK_END -#define MAVLINK_BUFFER_CHECK_END ; -#endif - -#endif /* _ML_OPTIONS_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/src/apps/mavlinkgen/template/mavlink_protocol.h b/src/apps/mavlinkgen/template/mavlink_protocol.h deleted file mode 100644 index 8cf62f115d..0000000000 --- a/src/apps/mavlinkgen/template/mavlink_protocol.h +++ /dev/null @@ -1,423 +0,0 @@ -/** @file - * @brief Main MAVLink comm protocol routines. - * @see http://qgroundcontrol.org/mavlink/ - * Edited on Monday, August 8 2011 - */ - -#ifndef _MAVLINK_PROTOCOL_H_ -#define _MAVLINK_PROTOCOL_H_ - -#include "mavlink_types.h" - -#include "mavlink_checksum.h" - -#ifdef MAVLINK_CHECK_LENGTH -extern const uint8_t MAVLINK_CONST mavlink_msg_lengths[256]; -#endif - -extern const uint8_t MAVLINK_CONST mavlink_msg_keys[256]; - -extern mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; -extern mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; -extern mavlink_system_t mavlink_system; - - -/** - * @brief Initialize the communication stack - * - * This function has to be called before using commParseBuffer() to initialize the different status registers. - * - * @return Will initialize the different buffers and status registers. - */ -static void mavlink_parse_state_initialize(mavlink_status_t* initStatus) -{ - if ((initStatus->parse_state <= MAVLINK_PARSE_STATE_UNINIT) || (initStatus->parse_state > MAVLINK_PARSE_STATE_GOT_CRC1)) - { - initStatus->ck_a = 0; - initStatus->ck_b = 0; - initStatus->msg_received = 0; - initStatus->buffer_overrun = 0; - initStatus->parse_error = 0; - initStatus->parse_state = MAVLINK_PARSE_STATE_UNINIT; - initStatus->packet_idx = 0; - initStatus->packet_rx_drop_count = 0; - initStatus->packet_rx_success_count = 0; - initStatus->current_rx_seq = 0; - initStatus->current_tx_seq = 0; - } -} - -static inline mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ - - return &m_mavlink_status[chan]; -} - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. - * - * @warning This function implicitely assumes the message is sent over channel zero. - * if the message is sent over a different channel it will reach the receiver - * without error, BUT the sequence number might be wrong due to the wrong - * channel sequence counter. This will result is wrongly reported excessive - * packet loss. Please use @see mavlink_{pack|encode}_headerless and then - * @see mavlink_finalize_message_chan before sending for a correct channel - * assignment. Please note that the mavlink_msg_xxx_pack and encode functions - * assign channel zero as default and thus induce possible loss counter errors.\ - * They have been left to ensure code compatibility. - * - * @see mavlink_finalize_message_chan - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length, usually just the counter incremented while packing the message - */ -static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint16_t length) -{ - // This code part is the same for all messages; - uint8_t key; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq; - mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1; - msg->ck = crc_calculate_msg(msg, length + MAVLINK_CORE_HEADER_LEN); - key = MAVLINK_CONST_READ( mavlink_msg_keys[msg->msgid] ); - crc_accumulate( key, &msg->ck ); /// include key in X25 checksum - - return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES; -} - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length, usually just the counter incremented while packing the message - */ -static inline uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint16_t length) -{ - // This code part is the same for all messages; - uint8_t key; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; - mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; - msg->ck = crc_calculate_msg(msg, length + MAVLINK_CORE_HEADER_LEN); - key = MAVLINK_CONST_READ( mavlink_msg_keys[msg->msgid] ); - crc_accumulate( key, &msg->ck ); /// include key in X25 checksum - - return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES; -} - -/** - * @brief Pack a message to send it over a serial byte stream - */ -static inline uint16_t mavlink_msg_to_send_buffer(uint8_t* buffer, const mavlink_message_t* msg) -{ - *(buffer+0) = MAVLINK_STX; ///< Start transmit -// memcpy((buffer+1), msg, msg->len + MAVLINK_CORE_HEADER_LEN); ///< Core header plus payload - memcpy((buffer+1), &msg->len, MAVLINK_CORE_HEADER_LEN); ///< Core header - memcpy((buffer+1+MAVLINK_CORE_HEADER_LEN), &msg->payload[0], msg->len); ///< payload - *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 1) = msg->ck_a; - *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 2) = msg->ck_b; - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; -// return 0; -} - -/** - * @brief Get the required buffer size for this message - */ -static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) -{ - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - -union checksum_ { - uint16_t s; - uint8_t c[2]; -}; - -static inline void mavlink_start_checksum(mavlink_message_t* msg) -{ - crc_init(&msg->ck); -} - -static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - crc_accumulate(c, &msg->ck); -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. Checksum and other failures will be silently - * ignored. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to barse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @return 0 if no message could be decoded, 1 else - * - * A typical use scenario of this function call is: - * - * @code - * #include <inttypes.h> // For fixed-width uint8_t type - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -#ifdef MAVLINK_STATIC_BUFFER -static inline mavlink_message_t* mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -#else -static inline int16_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -#endif -{ - // Initializes only once, values keep unchanged after first initialization - mavlink_parse_state_initialize(mavlink_get_channel_status(chan)); - - mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message - mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status - int bufferIndex = 0; - - status->msg_received = 0; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received) - { - status->buffer_overrun++; - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); -#ifdef MAVLINK_CHECK_LENGTH - if (rxmsg->len != MAVLINK_CONST_READ( mavlink_msg_lengths[c] ) ) - { - status->parse_state = MAVLINK_PARSE_STATE_IDLE; // abort, not going to understand it anyway - break; - } else ; -#endif - if (rxmsg->len == 0) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID: - rxmsg->payload[status->packet_idx++] = c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - mavlink_update_checksum(rxmsg, - MAVLINK_CONST_READ( mavlink_msg_keys[rxmsg->msgid] )); - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: - if (c != rxmsg->ck_a) - { - // Check first checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - mavlink_start_checksum(rxmsg); - } - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - } - break; - - case MAVLINK_PARSE_STATE_GOT_CRC1: - if (c != rxmsg->ck_b) - {// Check second checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - mavlink_start_checksum(rxmsg); - } - } - else - { - // Successfully got message - status->msg_received = 1; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if ( r_message != NULL ) - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - else ; - } - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == 1) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - status->parse_error = 0; -#ifdef MAVLINK_STATIC_BUFFER - if (status->msg_received == 1) - { - if ( r_message != NULL ) - return r_message; - else return rxmsg; - } else return NULL; -#else - if (status->msg_received == 1) - return 1; - else return 0; -#endif -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define a similar function - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - - -static inline void mavlink_send_msg(mavlink_channel_t chan, mavlink_message_t* msg) -{ - // ARM7 MCU board implementation - // Create pointer on message struct - // Send STX - comm_send_ch(chan, MAVLINK_STX); - comm_send_ch(chan, msg->len); - comm_send_ch(chan, msg->seq); - comm_send_ch(chan, msg->sysid); - comm_send_ch(chan, msg->compid); - comm_send_ch(chan, msg->msgid); - for(uint16_t i = 0; i < msg->len; i++) - { - comm_send_ch(chan, msg->payload[i]); - } - comm_send_ch(chan, msg->ck_a); - comm_send_ch(chan, msg->ck_b); -} - -static inline void mavlink_send_mem(mavlink_channel_t chan, (uint8_t *)mem, uint8_t num) -{ - // ARM7 MCU board implementation - // Create pointer on message struct - // Send STX - for(uint16_t i = 0; i < num; i++) - { - comm_send_ch( chan, mem[i] ); - } -} - */ -static inline void mavlink_send_uart(mavlink_channel_t chan, mavlink_message_t* msg); -static inline void mavlink_send_mem(mavlink_channel_t chan, uint8_t *mem, uint16_t num); -#define mavlink_send_msg( a, b ) mavlink_send_uart( a, b ) -#endif - -#endif /* _MAVLINK_PROTOCOL_H_ */ diff --git a/src/apps/mavlinkgen/template/mavlink_types.h b/src/apps/mavlinkgen/template/mavlink_types.h deleted file mode 100644 index 77b2e24096..0000000000 --- a/src/apps/mavlinkgen/template/mavlink_types.h +++ /dev/null @@ -1,120 +0,0 @@ -/** @file - * @brief MAVLink comm protocol enumerations / structures / constants. - * @see http://qgroundcontrol.org/mavlink/ - * Edited on Monday, August 8 2011 - */ - -#ifndef MAVLINK_TYPES_H_ -#define MAVLINK_TYPES_H_ - -#include "inttypes.h" - -#define MAVLINK_STX 0xD5 ///< Packet start sign -#define MAVLINK_STX_LEN 1 ///< Length of start sign -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length - -#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + MAVLINK_STX_LEN) ///< Length of all header bytes, including core and checksum -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) -#define MAVLINK_NUM_NON_STX_PAYLOAD_BYTES (MAVLINK_NUM_NON_PAYLOAD_BYTES - MAVLINK_STX_LEN) - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length -//#define MAVLINK_MAX_DATA_LEN MAVLINK_MAX_PACKET_LEN - MAVLINK_STX_LEN - -typedef struct __mavlink_system -{ - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t type; ///< Unused, can be used by user to store the system's type - uint8_t state; ///< Unused, can be used by user to store the system's state - uint8_t mode; ///< Unused, can be used by user to store the system's mode - uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode -} mavlink_system_t; - -typedef struct __mavlink_message -{ - union - { - uint16_t ck; ///< Checksum word - struct - { - uint8_t ck_a; ///< Checksum low byte - uint8_t ck_b; ///< Checksum high byte - }; - }; - uint8_t STX; ///< start of packet marker - uint8_t len; ///< Length of payload - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint8_t msgid; ///< ID of message in payload - uint8_t payload[MAVLINK_MAX_PAYLOAD_LEN]; ///< Payload data, ALIGNMENT IMPORTANT ON MCU -} mavlink_message_t; - -typedef struct __mavlink_header -{ - union - { - uint16_t ck; ///< Checksum word - struct - { - uint8_t ck_a; ///< Checksum low byte - uint8_t ck_b; ///< Checksum high byte - }; - }; - uint8_t STX; ///< start of packet marker - uint8_t len; ///< Length of payload - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint8_t msgid; ///< ID of message in payload -} mavlink_header_t; - -typedef enum -{ - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3, - MAVLINK_COMM_NB, - MAVLINK_COMM_NB_HIGH = 16 -} mavlink_channel_t; - -typedef enum -{ - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1 -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef struct __mavlink_status -{ - union - { - uint16_t ck; ///< Checksum word - struct - { - uint8_t ck_a; ///< Checksum low byte - uint8_t ck_b; ///< Checksum high byte - }; - }; - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops -} mavlink_status_t; - -#endif /* MAVLINK_TYPES_H_ */ diff --git a/src/apps/mavlinkgen/template/protocol.h b/src/apps/mavlinkgen/template/protocol.h deleted file mode 100644 index a45993e692..0000000000 --- a/src/apps/mavlinkgen/template/protocol.h +++ /dev/null @@ -1,439 +0,0 @@ -#ifndef _MAVLINK_PROTOCOL_H_ -#define _MAVLINK_PROTOCOL_H_ - -#include "string.h" -#include "mavlink_types.h" - -#include "checksum.h" - -/** - * @brief Initialize the communication stack - * - * This function has to be called before using commParseBuffer() to initialize the different status registers. - * - * @return Will initialize the different buffers and status registers. - */ -static void mavlink_parse_state_initialize(mavlink_status_t* initStatus) -{ - if ((initStatus->parse_state <= MAVLINK_PARSE_STATE_UNINIT) || (initStatus->parse_state > MAVLINK_PARSE_STATE_GOT_CRC1)) - { - initStatus->ck_a = 0; - initStatus->ck_b = 0; - initStatus->msg_received = 0; - initStatus->buffer_overrun = 0; - initStatus->parse_error = 0; - initStatus->parse_state = MAVLINK_PARSE_STATE_UNINIT; - initStatus->packet_idx = 0; - initStatus->packet_rx_drop_count = 0; - initStatus->packet_rx_success_count = 0; - initStatus->current_rx_seq = 0; - initStatus->current_tx_seq = 0; - } -} - -static inline mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH]; -#else - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; -#endif - - return &m_mavlink_status[chan]; -} - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. - * - * @warning This function implicitely assumes the message is sent over channel zero. - * if the message is sent over a different channel it will reach the receiver - * without error, BUT the sequence number might be wrong due to the wrong - * channel sequence counter. This will result is wrongly reported excessive - * packet loss. Please use @see mavlink_{pack|encode}_headerless and then - * @see mavlink_finalize_message_chan before sending for a correct channel - * assignment. Please note that the mavlink_msg_xxx_pack and encode functions - * assign channel zero as default and thus induce possible loss counter errors.\ - * They have been left to ensure code compatibility. - * - * @see mavlink_finalize_message_chan - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length, usually just the counter incremented while packing the message - */ -static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint16_t length) -{ - // This code part is the same for all messages; - uint16_t checksum; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq; - mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1; -// checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN); - checksum = crc_calculate_msg(msg, length + MAVLINK_CORE_HEADER_LEN); - msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte - msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte - - return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES; -} - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length, usually just the counter incremented while packing the message - */ -static inline uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint16_t length) -{ - // This code part is the same for all messages; - uint16_t checksum; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; - mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; -// checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN); - checksum = crc_calculate_msg(msg, length + MAVLINK_CORE_HEADER_LEN); - msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte - msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte - - return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES; -} - -/** - * @brief Pack a message to send it over a serial byte stream - */ -static inline uint16_t mavlink_msg_to_send_buffer(uint8_t* buffer, const mavlink_message_t* msg) -{ - *(buffer+0) = MAVLINK_STX; ///< Start transmit -// memcpy((buffer+1), msg, msg->len + MAVLINK_CORE_HEADER_LEN); ///< Core header plus payload - memcpy((buffer+1), &msg->len, MAVLINK_CORE_HEADER_LEN); ///< Core header - memcpy((buffer+1+MAVLINK_CORE_HEADER_LEN), &msg->payload[0], msg->len); ///< payload - *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 1) = msg->ck_a; - *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 2) = msg->ck_b; - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; -// return 0; -} - -/** - * @brief Get the required buffer size for this message - */ -static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) -{ - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - -union checksum_ { - uint16_t s; - uint8_t c[2]; -}; - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -static inline void mavlink_start_checksum(mavlink_message_t* msg) -{ - union checksum_ ck; - crc_init(&(ck.s)); - msg->ck_a = ck.c[0]; - msg->ck_b = ck.c[1]; -} - -static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - union checksum_ ck; - ck.c[0] = msg->ck_a; - ck.c[1] = msg->ck_b; - crc_accumulate(c, &(ck.s)); - msg->ck_a = ck.c[0]; - msg->ck_b = ck.c[1]; -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. Checksum and other failures will be silently - * ignored. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to barse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @return 0 if no message could be decoded, 1 else - * - * A typical use scenario of this function call is: - * - * @code - * #include <inttypes.h> // For fixed-width uint8_t type - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH]; -#elif defined(NB_MAVLINK_COMM) - static mavlink_message_t m_mavlink_message[NB_MAVLINK_COMM]; -#else - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; -#endif - // Initializes only once, values keep unchanged after first initialization - mavlink_parse_state_initialize(mavlink_get_channel_status(chan)); - - mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message - mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status - int bufferIndex = 0; - - status->msg_received = 0; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received) - { - status->buffer_overrun++; - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); -#ifdef MAVLINK_CHECK_LENGTH - if (rxmsg->len != mavlink_msg_lengths[c] ) - status->parse_state = MAVLINK_PARSE_STATE_IDLE; // abort, not going to understand it anyway - else ; -#endif - if (rxmsg->len == 0) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID: - rxmsg->payload[status->packet_idx++] = c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: - if (c != rxmsg->ck_a) - { - // Check first checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - mavlink_start_checksum(rxmsg); - } - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - } - break; - - case MAVLINK_PARSE_STATE_GOT_CRC1: - if (c != rxmsg->ck_b) - {// Check second checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - mavlink_start_checksum(rxmsg); - } - } - else - { - // Successfully got message - status->msg_received = 1; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if ( r_message != NULL ) - { - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - } - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == 1) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - status->parse_error = 0; - - // For future use - -// if (status->msg_received == 1) -// { -// if ( r_message != NULL ) -// { -// return r_message; -// } -// else -// { -// return rxmsg; -// } -// } -// else -// { -// return NULL; -// } - return status->msg_received; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define a similar function - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - - -static inline void mavlink_send_msg(mavlink_channel_t chan, mavlink_message_t* msg) -{ - // ARM7 MCU board implementation - // Create pointer on message struct - // Send STX - comm_send_ch(chan, MAVLINK_STX); - comm_send_ch(chan, msg->len); - comm_send_ch(chan, msg->seq); - comm_send_ch(chan, msg->sysid); - comm_send_ch(chan, msg->compid); - comm_send_ch(chan, msg->msgid); - for(uint16_t i = 0; i < msg->len; i++) - { - comm_send_ch(chan, msg->payload[i]); - } - comm_send_ch(chan, msg->ck_a); - comm_send_ch(chan, msg->ck_b); -} - -static inline void mavlink_send_mem(mavlink_channel_t chan, (uint8_t *)mem, uint8_t num) -{ - // ARM7 MCU board implementation - // Create pointer on message struct - // Send STX - for(uint16_t i = 0; i < num; i++) - { - comm_send_ch( chan, mem[i] ); - } -} - */ -static inline void mavlink_send_uart(mavlink_channel_t chan, mavlink_message_t* msg); -static inline void mavlink_send_mem(mavlink_channel_t chan, (uint8_t *)mem, uint8_t num); -#define mavlink_send_msg( a, b ) mavlink_send_uart( a, b ) -#endif - -#endif /* _MAVLINK_PROTOCOL_H_ */ diff --git a/src/apps/mavlinkgen/ui/DomItem.cc b/src/apps/mavlinkgen/ui/DomItem.cc deleted file mode 100644 index df2c52bc8b..0000000000 --- a/src/apps/mavlinkgen/ui/DomItem.cc +++ /dev/null @@ -1,47 +0,0 @@ -#include <QtXml> - -#include "DomItem.h" - -DomItem::DomItem(QDomNode &node, int row, DomItem *parent) -{ - domNode = node; - // Record the item's location within its parent. - rowNumber = row; - parentItem = parent; -} - -DomItem::~DomItem() -{ - QHash<int,DomItem*>::iterator it; - for (it = childItems.begin(); it != childItems.end(); ++it) - delete it.value(); -} - -QDomNode DomItem::node() const -{ - return domNode; -} - -DomItem *DomItem::parent() -{ - return parentItem; -} - -DomItem *DomItem::child(int i) -{ - if (childItems.contains(i)) - return childItems[i]; - - if (i >= 0 && i < domNode.childNodes().count()) { - QDomNode childNode = domNode.childNodes().item(i); - DomItem *childItem = new DomItem(childNode, i, this); - childItems[i] = childItem; - return childItem; - } - return 0; -} - -int DomItem::row() -{ - return rowNumber; -} diff --git a/src/apps/mavlinkgen/ui/DomItem.h b/src/apps/mavlinkgen/ui/DomItem.h deleted file mode 100644 index 30432795f2..0000000000 --- a/src/apps/mavlinkgen/ui/DomItem.h +++ /dev/null @@ -1,24 +0,0 @@ -#ifndef DOMITEM_H -#define DOMITEM_H - -#include <QDomNode> -#include <QHash> - -class DomItem -{ -public: - DomItem(QDomNode &node, int row, DomItem *parent = 0); - ~DomItem(); - DomItem *child(int i); - DomItem *parent(); - QDomNode node() const; - int row(); - -private: - QDomNode domNode; - QHash<int,DomItem*> childItems; - DomItem *parentItem; - int rowNumber; -}; - -#endif diff --git a/src/apps/mavlinkgen/ui/DomModel.cc b/src/apps/mavlinkgen/ui/DomModel.cc deleted file mode 100644 index 2271f9a515..0000000000 --- a/src/apps/mavlinkgen/ui/DomModel.cc +++ /dev/null @@ -1,195 +0,0 @@ -#include <QtGui> -#include <QtXml> - -#include "DomItem.h" -#include "DomModel.h" - -DomModel::DomModel(QDomDocument document, QObject *parent) - : QAbstractItemModel(parent), domDocument(document) -{ - rootItem = new DomItem(domDocument, 0); -} - -DomModel::~DomModel() -{ - delete rootItem; -} - -int DomModel::columnCount(const QModelIndex &/*parent*/) const -{ - return 3; -} - -QVariant DomModel::data(const QModelIndex &index, int role) const -{ - if (!index.isValid()) - return QVariant(); - - if (role != Qt::DisplayRole) - return QVariant(); - - DomItem *item = static_cast<DomItem*>(index.internalPointer()); - - QDomNode node = item->node(); - QStringList attributes; - QDomNamedNodeMap attributeMap = node.attributes(); - - switch (index.column()) { - case 0: - { - if (node.nodeName() == "message") - { - for (int i = 0; i < attributeMap.count(); ++i) { - QDomNode attribute = attributeMap.item(i); - if (attribute.nodeName() == "name") return attribute.nodeValue(); - } - } - else if (node.nodeName() == "field") - { - for (int i = 0; i < attributeMap.count(); ++i) { - QDomNode attribute = attributeMap.item(i); - if (attribute.nodeName() == "name") return attribute.nodeValue(); - } - } - else if (node.nodeName() == "enum") - { - for (int i = 0; i < attributeMap.count(); ++i) { - QDomNode attribute = attributeMap.item(i); - if (attribute.nodeName() == "name") return attribute.nodeValue(); - } - } - else if (node.nodeName() == "entry") - { - for (int i = 0; i < attributeMap.count(); ++i) { - QDomNode attribute = attributeMap.item(i); - if (attribute.nodeName() == "name") return attribute.nodeValue(); - } - } - else if (node.nodeName() == "#text") - { - return node.nodeValue().split("\n").join(" "); - } - else - { - return node.nodeName(); - } - } - break; - case 1: - if (node.nodeName() == "description") - { - return node.nodeValue().split("\n").join(" "); - } - else - { - for (int i = 0; i < attributeMap.count(); ++i) { - QDomNode attribute = attributeMap.item(i); - - if (attribute.nodeName() == "id" || attribute.nodeName() == "index" || attribute.nodeName() == "value") - { - return QString("(# %1)").arg(attribute.nodeValue()); - } - else if (attribute.nodeName() == "type") - { - return attribute.nodeValue(); - } - } - } - break; -// case 2: -// { -//// if (node.nodeName() != "description") -//// { -//// for (int i = 0; i < attributeMap.count(); ++i) { -//// QDomNode attribute = attributeMap.item(i); -//// attributes << attribute.nodeName() + "=\"" -//// +attribute.nodeValue() + "\""; -//// } -//// return attributes.join(" "); -//// } -//// else -//// { -//// return node.nodeValue().split("\n").join(" "); -//// } -// } -// break; - } - // Return empty variant if no case applied - return QVariant(); -} - -Qt::ItemFlags DomModel::flags(const QModelIndex &index) const -{ - if (!index.isValid()) - return 0; - - return Qt::ItemIsEnabled | Qt::ItemIsSelectable; -} - -QVariant DomModel::headerData(int section, Qt::Orientation orientation, - int role) const -{ - if (orientation == Qt::Horizontal && role == Qt::DisplayRole) { - switch (section) { - case 0: - return tr("Name "); - case 1: - return tr("Value"); -// case 2: -// return tr("Description"); - default: - return QVariant(); - } - } - - return QVariant(); -} - -QModelIndex DomModel::index(int row, int column, const QModelIndex &parent) - const -{ - if (!hasIndex(row, column, parent)) - return QModelIndex(); - - DomItem *parentItem; - - if (!parent.isValid()) - parentItem = rootItem; - else - parentItem = static_cast<DomItem*>(parent.internalPointer()); - - DomItem *childItem = parentItem->child(row); - if (childItem) - return createIndex(row, column, childItem); - else - return QModelIndex(); -} - -QModelIndex DomModel::parent(const QModelIndex &child) const -{ - if (!child.isValid()) - return QModelIndex(); - - DomItem *childItem = static_cast<DomItem*>(child.internalPointer()); - DomItem *parentItem = childItem->parent(); - - if (!parentItem || parentItem == rootItem) - return QModelIndex(); - - return createIndex(parentItem->row(), 0, parentItem); -} - -int DomModel::rowCount(const QModelIndex &parent) const -{ - if (parent.column() > 0) - return 0; - - DomItem *parentItem; - - if (!parent.isValid()) - parentItem = rootItem; - else - parentItem = static_cast<DomItem*>(parent.internalPointer()); - - return parentItem->node().childNodes().count(); -} diff --git a/src/apps/mavlinkgen/ui/DomModel.h b/src/apps/mavlinkgen/ui/DomModel.h deleted file mode 100644 index ae6bf6a749..0000000000 --- a/src/apps/mavlinkgen/ui/DomModel.h +++ /dev/null @@ -1,34 +0,0 @@ -#ifndef DOMMODEL_H -#define DOMMODEL_H - -#include <QAbstractItemModel> -#include <QDomDocument> -#include <QModelIndex> -#include <QVariant> - -class DomItem; - -class DomModel : public QAbstractItemModel -{ - Q_OBJECT - -public: - DomModel(QDomDocument document, QObject *parent = 0); - ~DomModel(); - - QVariant data(const QModelIndex &index, int role) const; - Qt::ItemFlags flags(const QModelIndex &index) const; - QVariant headerData(int section, Qt::Orientation orientation, - int role = Qt::DisplayRole) const; - QModelIndex index(int row, int column, - const QModelIndex &parent = QModelIndex()) const; - QModelIndex parent(const QModelIndex &child) const; - int rowCount(const QModelIndex &parent = QModelIndex()) const; - int columnCount(const QModelIndex &parent = QModelIndex()) const; - -private: - QDomDocument domDocument; - DomItem *rootItem; -}; - -#endif diff --git a/src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.cc b/src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.cc deleted file mode 100644 index a199a3cb61..0000000000 --- a/src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.cc +++ /dev/null @@ -1,480 +0,0 @@ -#include "QGCMAVLinkTextEdit.h" -#include <QMessageBox> -#include <QMenu> -#include <QEvent> -#include <QPainter> -#include <QScrollBar> -#include <QTextLayout> - -QGCMAVLinkTextEdit::QGCMAVLinkTextEdit(QWidget *parent) -: QTextEdit(parent) -{ - setViewportMargins(50, 0, 0, 0); - highlight = new XmlHighlighter(document()); - setLineWrapMode ( QTextEdit::NoWrap ); - setAcceptRichText ( false ); - connect(verticalScrollBar(), SIGNAL(valueChanged(int)), this, SLOT(update())); - connect(this, SIGNAL(textChanged()), this, SLOT(update())); -} - - -bool QGCMAVLinkTextEdit::Conform() -{ - QString errorStr; - int errorLine, errorColumn; - QDomDocument doc; - return doc.setContent(text(),false, &errorStr, &errorLine, &errorColumn); -} - -QDomDocument QGCMAVLinkTextEdit::xml_document() -{ - QString errorStr; - int errorLine, errorColumn; - QDomDocument doc; - doc.setContent(text(),false, &errorStr, &errorLine, &errorColumn); - return doc; -} - - -void QGCMAVLinkTextEdit::setPlainText( const QString txt ) -{ - QString errorStr; - int errorLine, errorColumn; - QDomDocument doc; - if (!doc.setContent(txt,false, &errorStr, &errorLine, &errorColumn)) { - QTextEdit::setPlainText(txt); - } else { - QTextEdit::setPlainText(doc.toString(5)); - } -} - -bool QGCMAVLinkTextEdit::syntaxcheck() -{ - bool noError = true; - if (text().size() > 0 ) { - QString errorStr; - int errorLine, errorColumn; - QDomDocument doc; - if (!doc.setContent(text(),false, &errorStr, &errorLine, &errorColumn)) { - //////return doc.toString(5); - QMessageBox::critical(0, tr("Found xml error"),tr("Check line %1 column %2 on string \"%3\"!") - .arg(errorLine - 1) - .arg(errorColumn - 1) - .arg(errorStr)); - noError = false; - - // FIXME Mark line - if (errorLine >= 0 ) { - - } - } else { - QMessageBox::information(0, tr("XML valid."),tr("All tags are valid. Document size is %1 characters.").arg(text().size())); - setPlainText(doc.toString(5)); - } - } else { - QMessageBox::information(0, tr("XML not found!"),tr("Null size xml document!")); - noError = false; - } - return noError; -} - -void QGCMAVLinkTextEdit::contextMenuEvent ( QContextMenuEvent * e ) -{ - Q_UNUSED(e); - QMenu *RContext = createOwnStandardContextMenu(); - RContext->exec(QCursor::pos()); - delete RContext; -} - -QMenu *QGCMAVLinkTextEdit::createOwnStandardContextMenu() -{ - QMenu *TContext = createStandardContextMenu(); - TContext->addAction(QIcon(QString::fromUtf8(":/img/zoomin.png")),tr( "Zoom In" ), this , SLOT( zoomIn() ) ); - TContext->addAction(QIcon(QString::fromUtf8(":/img/zoomout.png")),tr( "Zoom Out" ), this , SLOT( zoomOut() ) ); - TContext->addAction(tr("Check xml syntax" ), this , SLOT( syntaxcheck() ) ); - return TContext; -} - -bool QGCMAVLinkTextEdit::event( QEvent *event ) -{ - if (event->type()==QEvent::Paint) { - QPainter p(this); - p.fillRect(0, 0, 50, height(), QColor("#636363")); - QFont workfont(font()); - QPen pen(QColor("#ffffff"),1); - p.setPen(pen); - p.setFont (workfont); - int contentsY = verticalScrollBar()->value(); - qreal pageBottom = contentsY+viewport()->height(); - int m_lineNumber(1); - const QFontMetrics fm=fontMetrics(); - const int ascent = fontMetrics().ascent() +1; - - for (QTextBlock block=document()->begin(); block.isValid(); block=block.next(), m_lineNumber++) { - QTextLayout *layout = block.layout(); - const QRectF boundingRect = layout->boundingRect(); - QPointF position = layout->position(); - if ( position.y() +boundingRect.height() < contentsY ) { - continue; - } - if ( position.y() > pageBottom ) { - break; - } - const QString txt = QString::number(m_lineNumber); - p.drawText(50-fm.width(txt)-2, qRound(position.y())-contentsY+ascent, txt); - - } - p.setPen(QPen(Qt::NoPen)); - } else if ( event->type() == QEvent::KeyPress ) { - QKeyEvent *ke = static_cast<QKeyEvent *>(event); - if ((ke->modifiers() & Qt::ControlModifier) && ke->key() == Qt::Key_Minus) { - QTextEdit::zoomOut(); - return true; - } - if ((ke->modifiers() & Qt::ControlModifier) && ke->key() == Qt::Key_Plus) { - QTextEdit::zoomIn(); - return true; - } - } - return QTextEdit::event(event); -} - - - - - - - - - - - - - - - -static const QColor DEFAULT_SYNTAX_CHAR = Qt::blue; -static const QColor DEFAULT_ELEMENT_NAME = Qt::darkRed; -static const QColor DEFAULT_COMMENT = Qt::darkGreen; -static const QColor DEFAULT_ATTRIBUTE_NAME = Qt::red; -static const QColor DEFAULT_ATTRIBUTE_VALUE = Qt::darkGreen; -static const QColor DEFAULT_ERROR = Qt::darkMagenta; -static const QColor DEFAULT_OTHER = Qt::black; - -// Regular expressions for parsing XML borrowed from: -// http://www.cs.sfu.ca/~cameron/REX.html -static const QString EXPR_COMMENT = "<!--[^-]*-([^-][^-]*-)*->"; -static const QString EXPR_COMMENT_BEGIN = "<!--"; -static const QString EXPR_COMMENT_END = "[^-]*-([^-][^-]*-)*->"; -static const QString EXPR_ATTRIBUTE_VALUE = "\"[^<\"]*\"|'[^<']*'"; -static const QString EXPR_NAME = "([A-Za-z_:]|[^\\x00-\\x7F])([A-Za-z0-9_:.-]|[^\\x00-\\x7F])*"; - -XmlHighlighter::XmlHighlighter(QObject* parent) -: QSyntaxHighlighter(parent) -{ - init(); -} - -XmlHighlighter::XmlHighlighter(QTextDocument* parent) -: QSyntaxHighlighter(parent) -{ - init(); -} - -XmlHighlighter::XmlHighlighter(QTextEdit* parent) -: QSyntaxHighlighter(parent) -{ - init(); -} - -XmlHighlighter::~XmlHighlighter() -{ -} - -void XmlHighlighter::init() -{ - fmtSyntaxChar.setForeground(DEFAULT_SYNTAX_CHAR); - fmtElementName.setForeground(DEFAULT_ELEMENT_NAME); - fmtComment.setForeground(DEFAULT_COMMENT); - fmtAttributeName.setForeground(DEFAULT_ATTRIBUTE_NAME); - fmtAttributeValue.setForeground(DEFAULT_ATTRIBUTE_VALUE); - fmtError.setForeground(DEFAULT_ERROR); - fmtOther.setForeground(DEFAULT_OTHER); -} - -void XmlHighlighter::setHighlightColor(HighlightType type, QColor color, bool foreground) -{ - QTextCharFormat format; - if (foreground) - format.setForeground(color); - else - format.setBackground(color); - setHighlightFormat(type, format); -} - -void XmlHighlighter::setHighlightFormat(HighlightType type, QTextCharFormat format) -{ - switch (type) - { - case SyntaxChar: - fmtSyntaxChar = format; - break; - case ElementName: - fmtElementName = format; - break; - case Comment: - fmtComment = format; - break; - case AttributeName: - fmtAttributeName = format; - break; - case AttributeValue: - fmtAttributeValue = format; - break; - case Error: - fmtError = format; - break; - case Other: - fmtOther = format; - break; - } - rehighlight(); -} - -void XmlHighlighter::highlightBlock(const QString& text) -{ - int i = 0; - int pos = 0; - int brackets = 0; - - state = (previousBlockState() == InElement ? ExpectAttributeOrEndOfElement : NoState); - - if (previousBlockState() == InComment) - { - // search for the end of the comment - QRegExp expression(EXPR_COMMENT_END); - pos = expression.indexIn(text, i); - - if (pos >= 0) - { - // end comment found - const int iLength = expression.matchedLength(); - setFormat(0, iLength - 3, fmtComment); - setFormat(iLength - 3, 3, fmtSyntaxChar); - i += iLength; // skip comment - } - else - { - // in comment - setFormat(0, text.length(), fmtComment); - setCurrentBlockState(InComment); - return; - } - } - - for (; i < text.length(); i++) - { - switch (text.at(i).toAscii()) - { - case '<': - brackets++; - if (brackets == 1) - { - setFormat(i, 1, fmtSyntaxChar); - state = ExpectElementNameOrSlash; - } - else - { - // wrong bracket nesting - setFormat(i, 1, fmtError); - } - break; - - case '>': - brackets--; - if (brackets == 0) - { - setFormat(i, 1, fmtSyntaxChar); - } - else - { - // wrong bracket nesting - setFormat( i, 1, fmtError); - } - state = NoState; - break; - - case '/': - if (state == ExpectElementNameOrSlash) - { - state = ExpectElementName; - setFormat(i, 1, fmtSyntaxChar); - } - else - { - if (state == ExpectAttributeOrEndOfElement) - { - setFormat(i, 1, fmtSyntaxChar); - } - else - { - processDefaultText(i, text); - } - } - break; - - case '=': - if (state == ExpectEqual) - { - state = ExpectAttributeValue; - setFormat(i, 1, fmtOther); - } - else - { - processDefaultText(i, text); - } - break; - - case '\'': - case '\"': - if (state == ExpectAttributeValue) - { - // search attribute value - QRegExp expression(EXPR_ATTRIBUTE_VALUE); - pos = expression.indexIn(text, i); - - if (pos == i) // attribute value found ? - { - const int iLength = expression.matchedLength(); - - setFormat(i, 1, fmtOther); - setFormat(i + 1, iLength - 2, fmtAttributeValue); - setFormat(i + iLength - 1, 1, fmtOther); - - i += iLength - 1; // skip attribute value - state = ExpectAttributeOrEndOfElement; - } - else - { - processDefaultText(i, text); - } - } - else - { - processDefaultText(i, text); - } - break; - - case '!': - if (state == ExpectElementNameOrSlash) - { - // search comment - QRegExp expression(EXPR_COMMENT); - pos = expression.indexIn(text, i - 1); - - if (pos == i - 1) // comment found ? - { - const int iLength = expression.matchedLength(); - - setFormat(pos, 4, fmtSyntaxChar); - setFormat(pos + 4, iLength - 7, fmtComment); - setFormat(iLength - 3, 3, fmtSyntaxChar); - i += iLength - 2; // skip comment - state = NoState; - brackets--; - } - else - { - // Try find multiline comment - QRegExp expression(EXPR_COMMENT_BEGIN); // search comment start - pos = expression.indexIn(text, i - 1); - - //if (pos == i - 1) // comment found ? - if (pos >= i - 1) - { - setFormat(i, 3, fmtSyntaxChar); - setFormat(i + 3, text.length() - i - 3, fmtComment); - setCurrentBlockState(InComment); - return; - } - else - { - processDefaultText(i, text); - } - } - } - else - { - processDefaultText(i, text); - } - - break; - - default: - const int iLength = processDefaultText(i, text); - if (iLength > 0) - i += iLength - 1; - break; - } - } - - if (state == ExpectAttributeOrEndOfElement) - { - setCurrentBlockState(InElement); - } -} - -int XmlHighlighter::processDefaultText(int i, const QString& text) -{ - // length of matched text - int iLength = 0; - - switch(state) - { - case ExpectElementNameOrSlash: - case ExpectElementName: - { - // search element name - QRegExp expression(EXPR_NAME); - const int pos = expression.indexIn(text, i); - - if (pos == i) // found ? - { - iLength = expression.matchedLength(); - - setFormat(pos, iLength, fmtElementName); - state = ExpectAttributeOrEndOfElement; - } - else - { - setFormat(i, 1, fmtOther); - } - } - break; - - case ExpectAttributeOrEndOfElement: - { - // search attribute name - QRegExp expression(EXPR_NAME); - const int pos = expression.indexIn(text, i); - - if (pos == i) // found ? - { - iLength = expression.matchedLength(); - - setFormat(pos, iLength, fmtAttributeName); - state = ExpectEqual; - } - else - { - setFormat(i, 1, fmtOther); - } - } - break; - - default: - setFormat(i, 1, fmtOther); - break; - } - return iLength; -} diff --git a/src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.h b/src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.h deleted file mode 100644 index a29465701d..0000000000 --- a/src/apps/mavlinkgen/ui/QGCMAVLinkTextEdit.h +++ /dev/null @@ -1,106 +0,0 @@ - -// Based on: Syntax highlighting from: -// http://code.google.com/p/fop-miniscribus/ -// (GPL v2) thanks! - -#ifndef QGCMAVLINKTEXTEDIT_H -#define QGCMAVLINKTEXTEDIT_H - -#include <QSyntaxHighlighter> -#include <QTextCharFormat> -#include <QColor> -#include <QDomDocument> -#include <QTextEdit> - -//class QGCMAVLinkTextEdit : public QTextEdit -//{ -//public: -// QGCMAVLinkTextEdit(); -//}; - -class XmlHighlighter : public QSyntaxHighlighter -{ -public: - XmlHighlighter(QObject* parent); - XmlHighlighter(QTextDocument* parent); - XmlHighlighter(QTextEdit* parent); - ~XmlHighlighter(); - - enum HighlightType - { - SyntaxChar, - ElementName, - Comment, - AttributeName, - AttributeValue, - Error, - Other - }; - - void setHighlightColor(HighlightType type, QColor color, bool foreground = true); - void setHighlightFormat(HighlightType type, QTextCharFormat format); - -protected: - void highlightBlock(const QString& rstrText); - int processDefaultText(int i, const QString& rstrText); - -private: - void init(); - - QTextCharFormat fmtSyntaxChar; - QTextCharFormat fmtElementName; - QTextCharFormat fmtComment; - QTextCharFormat fmtAttributeName; - QTextCharFormat fmtAttributeValue; - QTextCharFormat fmtError; - QTextCharFormat fmtOther; - - enum ParsingState - { - NoState = 0, - ExpectElementNameOrSlash, - ExpectElementName, - ExpectAttributeOrEndOfElement, - ExpectEqual, - ExpectAttributeValue - }; - - enum BlockState - { - NoBlock = -1, - InComment, - InElement - }; - - ParsingState state; -}; - - - - - -class QGCMAVLinkTextEdit : public QTextEdit -{ - Q_OBJECT - // -public: - QGCMAVLinkTextEdit( QWidget * parent = 0 ); - bool Conform(); - QDomDocument xml_document(); - inline QString text() const - { - return QTextEdit::toPlainText(); - } - QMenu *createOwnStandardContextMenu(); -protected: - void contextMenuEvent ( QContextMenuEvent * e ); - bool event( QEvent *event ); -private: - XmlHighlighter *highlight; -signals: -public slots: - bool syntaxcheck(); - void setPlainText( const QString txt ); -}; - -#endif // QGCMAVLINKTEXTEDIT_H diff --git a/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.cc b/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.cc deleted file mode 100644 index 8e627fe32e..0000000000 --- a/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.cc +++ /dev/null @@ -1,194 +0,0 @@ -#include <QFileDialog> -#include <QTextBrowser> -#include <QMessageBox> -#include <QSettings> -#include <QDesktopServices> - -#include "XMLCommProtocolWidget.h" -#include "ui_XMLCommProtocolWidget.h" -#include "MAVLinkXMLParser.h" -#include "MAVLinkXMLParserV10.h" - -#include <QDebug> -#include <iostream> - -XMLCommProtocolWidget::XMLCommProtocolWidget(QWidget *parent) : - QWidget(parent), - model(NULL), -m_ui(new Ui::XMLCommProtocolWidget) -{ - m_ui->setupUi(this); - - connect(m_ui->selectFileButton, SIGNAL(clicked()), this, SLOT(selectXMLFile())); - connect(m_ui->selectOutputButton, SIGNAL(clicked()), this, SLOT(selectOutputDirectory())); - connect(m_ui->generateButton, SIGNAL(clicked()), this, SLOT(generate())); - connect(m_ui->saveButton, SIGNAL(clicked()), this, SLOT(save())); - - // Make sure text background is white - m_ui->xmlTextView->setStyleSheet("QGCMAVLinkTextEdit { background-color: #FFFFFF; }"); -} - -void XMLCommProtocolWidget::selectXMLFile() -{ - QSettings settings("MAVLink Consortium", "MAVLink Generator"); - const QString mavlinkXML = "MAVLINK_XML_FILE"; - QString dirPath = settings.value(mavlinkXML, QCoreApplication::applicationDirPath() + "../").toString(); - QFileInfo dir(dirPath); - QFileDialog dialog; - dialog.setDirectory(dir.absoluteDir()); - dialog.setFileMode(QFileDialog::AnyFile); - dialog.setFilter(tr("MAVLink XML (*.xml)")); - dialog.setViewMode(QFileDialog::Detail); - QStringList fileNames; - if (dialog.exec()) - { - fileNames = dialog.selectedFiles(); - } - - if (fileNames.size() > 0) - { - QFile file(fileNames.first()); - m_ui->fileNameLabel->setText(file.fileName()); - - if (file.open(QIODevice::ReadOnly | QIODevice::Text)) - { - const QString instanceText(QString::fromUtf8(file.readAll())); - setXML(instanceText); - // Store filename for next time - settings.setValue(mavlinkXML, QFileInfo(file).absoluteFilePath()); - settings.sync(); - } - else - { - QMessageBox msgBox; - msgBox.setText("Could not read XML file. Permission denied"); - msgBox.exec(); - } - } -} - -void XMLCommProtocolWidget::setXML(const QString& xml) -{ - m_ui->xmlTextView->setText(xml); - QDomDocument doc; - - if (doc.setContent(xml)) - { - m_ui->validXMLLabel->setText(tr("<font color=\"green\">Valid XML file</font>")); - } - else - { - m_ui->validXMLLabel->setText(tr("<font color=\"red\">File is NOT valid XML, please fix in editor</font>")); - } -} - -void XMLCommProtocolWidget::selectOutputDirectory() -{ - QSettings settings("MAVLink Consortium", "MAVLink Generator"); - const QString mavlinkOutputDir = "MAVLINK_OUTPUT_DIR"; - QString dirPath = settings.value(mavlinkOutputDir, QDesktopServices::DesktopLocation).toString(); - QFileDialog dialog; - dialog.setDirectory(dirPath); - dialog.setFileMode(QFileDialog::Directory); - dialog.setViewMode(QFileDialog::Detail); - QStringList fileNames; - if (dialog.exec()) - { - fileNames = dialog.selectedFiles(); - } - - if (fileNames.size() > 0) - { - m_ui->outputDirNameLabel->setText(fileNames.first()); - // Store directory for next time - settings.setValue(mavlinkOutputDir, QFileInfo(fileNames.first()).absoluteFilePath()); - settings.sync(); - //QFile file(fileName); - } -} - -void XMLCommProtocolWidget::generate() -{ - // Check if input file is present - if (!QFileInfo(m_ui->fileNameLabel->text().trimmed()).isFile()) - { - QMessageBox::critical(this, tr("Please select an XML input file first"), tr("You have to select an input XML file before generating C files."), QMessageBox::Ok); - return; - } - - // Check if output dir is selected - if (!QFileInfo(m_ui->outputDirNameLabel->text().trimmed()).isDir()) - { - QMessageBox::critical(this, tr("Please select output directory first"), tr("You have to select an output directory before generating C files."), QMessageBox::Ok); - return; - } - - // First save file - save(); - // Clean log - m_ui->compileLog->clear(); - - // Check XML validity - if (!m_ui->xmlTextView->syntaxcheck()) - { - // Syntax check already gives output - return; - } - - MAVLinkXMLParser* parser = NULL; - MAVLinkXMLParserV10* parserV10 = NULL; - - bool result = false; - - if (m_ui->versionComboBox->currentIndex() == 1) - { - MAVLinkXMLParser* parser = new MAVLinkXMLParser(m_ui->fileNameLabel->text().trimmed(), m_ui->outputDirNameLabel->text().trimmed()); - connect(parser, SIGNAL(parseState(QString)), m_ui->compileLog, SLOT(appendHtml(QString))); - result = parser->generate(); - } - else if (m_ui->versionComboBox->currentIndex() == 0) - { - MAVLinkXMLParserV10* parserV10 = new MAVLinkXMLParserV10(m_ui->fileNameLabel->text().trimmed(), m_ui->outputDirNameLabel->text().trimmed()); - connect(parserV10, SIGNAL(parseState(QString)), m_ui->compileLog, SLOT(appendHtml(QString))); - result = parserV10->generate(); - } - - if (result) - { - QMessageBox msgBox; - msgBox.setText(QString("The C code / headers have been generated in folder\n%1").arg(m_ui->outputDirNameLabel->text().trimmed())); - msgBox.exec(); - } - else - { - QMessageBox::critical(this, tr("C code generation failed, please see the compile log for further information"), QString("The C code / headers could not be written to folder\n%1").arg(m_ui->outputDirNameLabel->text().trimmed()), QMessageBox::Ok); - } - if (parser) delete parser; - if (parserV10) delete parserV10; -} - -void XMLCommProtocolWidget::save() -{ - QFile file(m_ui->fileNameLabel->text().trimmed()); - setXML(m_ui->xmlTextView->document()->toPlainText().toUtf8()); - file.open(QIODevice::WriteOnly | QIODevice::Text); - file.write(m_ui->xmlTextView->document()->toPlainText().toUtf8()); -} - -XMLCommProtocolWidget::~XMLCommProtocolWidget() -{ - if (model) delete model; - delete m_ui; -} - -void XMLCommProtocolWidget::changeEvent(QEvent *e) -{ - QWidget::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - m_ui->retranslateUi(this); - break; - default: - break; - } -} diff --git a/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.h b/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.h deleted file mode 100644 index 0ad3fcc93a..0000000000 --- a/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.h +++ /dev/null @@ -1,89 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. - -======================================================================*/ - -/** - * @file - * @brief Definition of class XMLCommProtocolWidget - * @author Lorenz Meier <mavteam@student.ethz.ch> - * - */ - -#ifndef XMLCOMMPROTOCOLWIDGET_H -#define XMLCOMMPROTOCOLWIDGET_H - -#include <QtGui/QWidget> -#include "DomModel.h" - -namespace Ui -{ -class XMLCommProtocolWidget; -} - -/** - * @brief Tool to generate MAVLink code out of XML protocol definitions - * @see http://doc.trolltech.com/4.6/itemviews-simpledommodel.html for a XML view tutorial - */ -class XMLCommProtocolWidget : public QWidget -{ - Q_OBJECT -public: - XMLCommProtocolWidget(QWidget *parent = 0); - ~XMLCommProtocolWidget(); - -protected slots: - /** @brief Select input XML protocol definition */ - void selectXMLFile(); - /** @brief Select output directory for generated .h files */ - void selectOutputDirectory(); - /** @brief Set the XML this widget currently operates on */ - void setXML(const QString& xml); - /** @brief Parse XML file and generate .h files */ - void generate(); - /** @brief Save the edited file */ - void save(); - -protected: - DomModel* model; - void changeEvent(QEvent *e); - -signals: - void visibilityChanged(bool visible); - -protected: - void showEvent(QShowEvent* event) - { - QWidget::showEvent(event); - emit visibilityChanged(true); - } - - void hideEvent(QHideEvent* event) - { - QWidget::hideEvent(event); - emit visibilityChanged(false); - } - -private: - Ui::XMLCommProtocolWidget *m_ui; -}; - -#endif // XMLCOMMPROTOCOLWIDGET_H diff --git a/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.ui b/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.ui deleted file mode 100644 index 38b68cf472..0000000000 --- a/src/apps/mavlinkgen/ui/XMLCommProtocolWidget.ui +++ /dev/null @@ -1,175 +0,0 @@ -<?xml version="1.0" encoding="UTF-8"?> -<ui version="4.0"> - <class>XMLCommProtocolWidget</class> - <widget class="QWidget" name="XMLCommProtocolWidget"> - <property name="geometry"> - <rect> - <x>0</x> - <y>0</y> - <width>846</width> - <height>480</height> - </rect> - </property> - <property name="windowTitle"> - <string>Form</string> - </property> - <layout class="QGridLayout" name="gridLayout" columnstretch="1,1,1,100"> - <property name="horizontalSpacing"> - <number>8</number> - </property> - <property name="verticalSpacing"> - <number>12</number> - </property> - <property name="margin"> - <number>8</number> - </property> - <item row="0" column="0"> - <widget class="QLabel" name="fileNameLabel"> - <property name="maximumSize"> - <size> - <width>300</width> - <height>16777215</height> - </size> - </property> - <property name="text"> - <string>Select input file</string> - </property> - <property name="scaledContents"> - <bool>true</bool> - </property> - </widget> - </item> - <item row="0" column="2"> - <widget class="QPushButton" name="selectFileButton"> - <property name="text"> - <string>Select input file</string> - </property> - <property name="icon"> - <iconset resource="../../../../qgroundcontrol.qrc"> - <normaloff>:/files/images/status/folder-open.svg</normaloff>:/files/images/status/folder-open.svg</iconset> - </property> - </widget> - </item> - <item row="0" column="3" rowspan="7"> - <widget class="QGCMAVLinkTextEdit" name="xmlTextView"> - <property name="minimumSize"> - <size> - <width>200</width> - <height>100</height> - </size> - </property> - <property name="baseSize"> - <size> - <width>800</width> - <height>600</height> - </size> - </property> - <property name="readOnly"> - <bool>false</bool> - </property> - </widget> - </item> - <item row="1" column="0"> - <widget class="QLabel" name="outputDirNameLabel"> - <property name="maximumSize"> - <size> - <width>400</width> - <height>16777215</height> - </size> - </property> - <property name="text"> - <string>Select output directory</string> - </property> - <property name="scaledContents"> - <bool>true</bool> - </property> - </widget> - </item> - <item row="1" column="2"> - <widget class="QPushButton" name="selectOutputButton"> - <property name="text"> - <string>Select directory</string> - </property> - <property name="icon"> - <iconset resource="../../../../qgroundcontrol.qrc"> - <normaloff>:/files/images/status/folder-open.svg</normaloff>:/files/images/status/folder-open.svg</iconset> - </property> - </widget> - </item> - <item row="4" column="0"> - <widget class="QLabel" name="label"> - <property name="text"> - <string>Compile Output</string> - </property> - </widget> - </item> - <item row="5" column="0" colspan="3"> - <widget class="QPlainTextEdit" name="compileLog"> - <property name="tabStopWidth"> - <number>40</number> - </property> - </widget> - </item> - <item row="6" column="0"> - <widget class="QLabel" name="validXMLLabel"> - <property name="text"> - <string>No file loaded</string> - </property> - </widget> - </item> - <item row="6" column="1"> - <widget class="QPushButton" name="saveButton"> - <property name="text"> - <string>Save file</string> - </property> - </widget> - </item> - <item row="6" column="2"> - <widget class="QPushButton" name="generateButton"> - <property name="text"> - <string>Save and generate</string> - </property> - <property name="icon"> - <iconset resource="../../../../qgroundcontrol.qrc"> - <normaloff>:/files/images/categories/applications-system.svg</normaloff>:/files/images/categories/applications-system.svg</iconset> - </property> - </widget> - </item> - <item row="2" column="0"> - <widget class="QLabel" name="label_2"> - <property name="text"> - <string>Select MAVLink Version</string> - </property> - <property name="alignment"> - <set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set> - </property> - </widget> - </item> - <item row="2" column="2"> - <widget class="QComboBox" name="versionComboBox"> - <item> - <property name="text"> - <string>MAVLink v1.0 (Sept'10+)</string> - </property> - </item> - <item> - <property name="text"> - <string>MAVLink v0.9 (-Aug'10)</string> - </property> - </item> - </widget> - </item> - </layout> - </widget> - <customwidgets> - <customwidget> - <class>QGCMAVLinkTextEdit</class> - <extends>QTextEdit</extends> - <header location="global">QGCMAVLinkTextEdit.h</header> - </customwidget> - </customwidgets> - <resources> - <include location="../../../../qgroundcontrol.qrc"/> - </resources> - <connections/> -</ui> -- GitLab From aea2114386f409ce7bb5ad7f950150268aae4473 Mon Sep 17 00:00:00 2001 From: treymarc <trey.marc@gmail.com> Date: Tue, 29 Apr 2014 13:01:46 +0200 Subject: [PATCH 14/53] Make HUD the center widget in Flight view. Add menu item for map widget. --- src/ui/MainWindow.cc | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 364c9d9263..51e6db429d 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -556,7 +556,7 @@ void MainWindow::buildCommonWidgets() { pilotView = new SubMainWindow(this); pilotView->setObjectName("VIEW_FLIGHT"); - pilotView->setCentralWidget(new QGCMapTool(this)); + pilotView->setCentralWidget(new HUD(640,480,this)); addToCentralStackedWidget(pilotView, VIEW_FLIGHT, "Pilot"); } @@ -658,6 +658,8 @@ void MainWindow::buildCommonWidgets() createDockWidget(engineeringView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea); createDockWidget(simView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea); + createDockWidget(pilotView,new QGCMapTool(this),tr("Map view"),"MAP_VIEW_DOCKWIDGET",VIEW_MISSION,Qt::RightDockWidgetArea); + menuActionHelper->createToolAction(tr("Status Details"), "UAS_STATUS_DETAILS_DOCKWIDGET"); { @@ -819,6 +821,10 @@ void MainWindow::loadDockWidget(const QString& name) { createDockWidget(centerStack->currentWidget(),new UASInfoWidget(this),tr("Status Details"),"UAS_STATUS_DETAILS_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); } + else if (name == "MAP_VIEW_DOCKWIDGET") + { + createDockWidget(centerStack->currentWidget(),new QGCMapTool(this),tr("Map view"),"MAP_VIEW_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); + } else if (name == "COMMUNICATION_DEBUG_CONSOLE_DOCKWIDGET") { //This is now a permanently detached window. -- GitLab From 1ce84ec51b2fd6afd7910150f9c03b07cef4cc42 Mon Sep 17 00:00:00 2001 From: treymarc <trey.marc@gmail.com> Date: Tue, 29 Apr 2014 14:03:38 +0200 Subject: [PATCH 15/53] hud is a tool in VIEW_FLIGHT --- src/ui/MainWindow.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 51e6db429d..558feedaaa 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -679,7 +679,7 @@ void MainWindow::buildCommonWidgets() menuActionHelper->createToolAction(tr("Actuator Status"), "HEAD_DOWN_DISPLAY_2_DOCKWIDGET"); menuActionHelper->createToolAction(tr("Radio Control")); - createDockWidget(engineeringView,new HUD(320,240,this),tr("Video Downlink"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea); + createDockWidget(engineeringView,new HUD(320,240,this),tr("Video Downlink"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); createDockWidget(simView,new PrimaryFlightDisplay(this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea); createDockWidget(pilotView,new PrimaryFlightDisplay(this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); -- GitLab From dd75a986e60e612581ffeb5f46f1da2e505c32e4 Mon Sep 17 00:00:00 2001 From: Koen Kooi <koen@dominion.thruhere.net> Date: Fri, 13 Jun 2014 09:09:43 +0200 Subject: [PATCH 16/53] MainWindow: handle maptool widget destroy event Signed-off-by: Koen Kooi <koen@dominion.thruhere.net> --- src/ui/MainWindow.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 558feedaaa..ab2d78695b 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -658,7 +658,7 @@ void MainWindow::buildCommonWidgets() createDockWidget(engineeringView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_ENGINEER,Qt::RightDockWidgetArea); createDockWidget(simView,new ParameterInterface(this),tr("Onboard Parameters"),"PARAMETER_INTERFACE_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea); - createDockWidget(pilotView,new QGCMapTool(this),tr("Map view"),"MAP_VIEW_DOCKWIDGET",VIEW_MISSION,Qt::RightDockWidgetArea); + menuActionHelper->createToolAction(tr("Map View"), "MAP_VIEW_DOCKWIDGET"); menuActionHelper->createToolAction(tr("Status Details"), "UAS_STATUS_DETAILS_DOCKWIDGET"); -- GitLab From 287d75ac859195bc9b652710497f5cd2e96bf7ff Mon Sep 17 00:00:00 2001 From: Koen Kooi <koen@dominion.thruhere.net> Date: Fri, 13 Jun 2014 09:20:25 +0200 Subject: [PATCH 17/53] MainWindow: make PFD the central widget. Signed-off-by: Koen Kooi <koen@dominion.thruhere.net> --- src/ui/MainWindow.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index ab2d78695b..cb820f24fa 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -556,7 +556,7 @@ void MainWindow::buildCommonWidgets() { pilotView = new SubMainWindow(this); pilotView->setObjectName("VIEW_FLIGHT"); - pilotView->setCentralWidget(new HUD(640,480,this)); + pilotView->setCentralWidget(new PrimaryFlightDisplay(this)); addToCentralStackedWidget(pilotView, VIEW_FLIGHT, "Pilot"); } -- GitLab From 4533eba2a8103ce1b8b293cee4e067681c8a5567 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sat, 14 Jun 2014 12:58:48 -0700 Subject: [PATCH 18/53] Fix typo in FG protocol --- src/comm/QGCFlightGearLink.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 80e3208f21..e44ce57c0e 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -125,7 +125,7 @@ void QGCFlightGearLink::run() #endif #ifdef DEBUG_FLIGHTGEAR_CONNECT - qDebug() << "Starting FlightGear" << _fgProcessWorkingDirPath << _fgProcessName << _fgArgList; + qDebug() << "\nStarting FlightGear" << _fgProcessWorkingDirPath << _fgProcessName << _fgArgList << "\n"; #endif _fgProcess->start(_fgProcessName, _fgArgList); @@ -741,7 +741,7 @@ bool QGCFlightGearLink::connectSimulation() // Add the user specified arguments to our argument list #ifdef DEBUG_FLIGHTGEAR_CONNECT - qDebug() << "Split arguments" << uiArgList; + qDebug() << "\nSplit arguments" << uiArgList << "\n"; #endif _fgArgList += uiArgList; @@ -820,7 +820,7 @@ bool QGCFlightGearLink::connectSimulation() // Setup protocol we will be using to communicate with FlightGear QString fgProtocol(mav->getSystemType() == MAV_TYPE_QUADROTOR ? "qgroundcontrol-quadrotor" : "qgroundcontrol-fixed-wing"); - QString fgProtocolArg("--generic=_udpCommSocket,%1,300,127.0.0.1,%2,udp,%3"); + QString fgProtocolArg("--generic=socket,%1,300,127.0.0.1,%2,udp,%3"); _fgArgList << fgProtocolArg.arg("out").arg(port).arg(fgProtocol); _fgArgList << fgProtocolArg.arg("in").arg(currentPort).arg(fgProtocol); -- GitLab From e3432de0f6e4e921e41785f529ea21f7711db9e2 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sat, 14 Jun 2014 13:10:13 -0700 Subject: [PATCH 19/53] Show copy failed and clipboard in single dialog --- src/comm/QGCFlightGearLink.cc | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index e44ce57c0e..fe6594b751 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -865,8 +865,6 @@ bool QGCFlightGearLink::connectSimulation() // Now that we made it this far, we should be able to try to copy the protocol file to FlightGear. bool succeeded = QFile::copy(qgcProtocolFileFullyQualified, fgProtocolFileFullyQualified); if (!succeeded) { - MainWindow::instance()->showCriticalMessage(tr("Copy failed"), tr("Copy from (%1) to (%2) failed, possibly due to permissions issue. You will need to perform manually.").arg(qgcProtocolFileFullyQualified).arg(fgProtocolFileFullyQualified)); - #ifdef Q_OS_WIN32 QString copyCmd = QString("copy \"%1\" \"%2\"").arg(qgcProtocolFileFullyQualified).arg(fgProtocolFileFullyQualified); copyCmd.replace("/", "\\"); @@ -877,9 +875,9 @@ bool QGCFlightGearLink::connectSimulation() QMessageBox msgBox(QMessageBox::Critical, tr("Copy failed"), #ifdef Q_OS_WIN32 - tr("Try pasting the following command into a Command Prompt which was started with Run as Administrator: ") + copyCmd, + tr("Copy from (%1) to (%2) failed, possibly due to permissions issue. You will need to perform manually. Try pasting the following command into a Command Prompt which was started with Run as Administrator:\n\n").arg(qgcProtocolFileFullyQualified).arg(fgProtocolFileFullyQualified) + copyCmd, #else - tr("Try pasting the following command into a shell: ") + copyCmd, + tr("Copy from (%1) to (%2) failed, possibly due to permissions issue. You will need to perform manually. Try pasting the following command into a shell:\n\n").arg(qgcProtocolFileFullyQualified).arg(fgProtocolFileFullyQualified) + copyCmd, #endif QMessageBox::Cancel, MainWindow::instance()); -- GitLab From a8559d6e3adabddb63386e38676cc0fb38951faf Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sat, 14 Jun 2014 16:49:22 -0700 Subject: [PATCH 20/53] Add back TCPLinkTest after threading change fixes --- qgroundcontrol.pro | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 6475dc52f6..be0b52be8b 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -187,7 +187,8 @@ DebugBuild { src/qgcunittest/MockUAS.h \ src/qgcunittest/MockQGCUASParamManager.h \ src/qgcunittest/MultiSignalSpy.h \ - src/qgcunittest/FlightModeConfigTest.h + src/qgcunittest/FlightModeConfigTest.h \ + src/qgcunittest/TCPLinkTest.h SOURCES += \ src/qgcunittest/UASUnitTest.cc \ @@ -195,7 +196,8 @@ DebugBuild { src/qgcunittest/MockUAS.cc \ src/qgcunittest/MockQGCUASParamManager.cc \ src/qgcunittest/MultiSignalSpy.cc \ - src/qgcunittest/FlightModeConfigTest.cc + src/qgcunittest/FlightModeConfigTest.cc \ + src/qgcunittest/TCPLinkTest.cc } # -- GitLab From 74690d82424d309cad96fcd03b0037e04a343328 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sat, 14 Jun 2014 16:49:38 -0700 Subject: [PATCH 21/53] Updated for threading changes --- src/qgcunittest/TCPLinkTest.cc | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/qgcunittest/TCPLinkTest.cc b/src/qgcunittest/TCPLinkTest.cc index ac57772f27..045c4e51f5 100644 --- a/src/qgcunittest/TCPLinkTest.cc +++ b/src/qgcunittest/TCPLinkTest.cc @@ -111,7 +111,9 @@ void TCPLinkUnitTest::_connectFail_test(void) Q_ASSERT(_multiSpy); Q_ASSERT(_multiSpy->checkNoSignals() == true); - QCOMPARE(_link->connect(), false); + // With the new threading model connect will always succeed. We only get an error signal + // for a failed connected. + QCOMPARE(_link->connect(), true); // Make sure we get a linkError signal with the right link name QCOMPARE(_multiSpy->waitForSignalByIndex(communicationErrorSignalIndex, 1000), true); @@ -119,10 +121,12 @@ void TCPLinkUnitTest::_connectFail_test(void) QList<QVariant> arguments = _multiSpy->getSpyByIndex(communicationErrorSignalIndex)->takeFirst(); QCOMPARE(arguments.at(0).toString(), _link->getName()); _multiSpy->clearSignalByIndex(communicationErrorSignalIndex); + + _link->disconnect(); // Try to connect again to make sure everything was cleaned up correctly from previous failed connection - QCOMPARE(_link->connect(), false); + QCOMPARE(_link->connect(), true); // Make sure we get a linkError signal with the right link name QCOMPARE(_multiSpy->waitForSignalByIndex(communicationErrorSignalIndex, 1000), true); -- GitLab From 780606e804c7abbef2c3438ec34f47960803d795 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sat, 14 Jun 2014 16:50:18 -0700 Subject: [PATCH 22/53] Limit time in processEvents This allows other threads to signal --- src/qgcunittest/MultiSignalSpy.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/qgcunittest/MultiSignalSpy.cc b/src/qgcunittest/MultiSignalSpy.cc index 1699dad439..4cebd83478 100644 --- a/src/qgcunittest/MultiSignalSpy.cc +++ b/src/qgcunittest/MultiSignalSpy.cc @@ -218,7 +218,7 @@ bool MultiSignalSpy::waitForSignalByIndex( Q_ASSERT(spy); while (spy->count() == 0 && !_timeout) { - QCoreApplication::processEvents(QEventLoop::AllEvents | QEventLoop::WaitForMoreEvents); + QCoreApplication::processEvents(QEventLoop::AllEvents | QEventLoop::WaitForMoreEvents, 500); } // Clean up and return status -- GitLab From 7576bdd4b38be6a6edbe223a3db21b9c6394cb52 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Sun, 15 Jun 2014 14:08:56 -0700 Subject: [PATCH 23/53] Refactored the lost packets calculations for MAVLink. Current version was not as clear as it could be. --- src/comm/MAVLinkProtocol.cc | 40 ++++++++++++++----------------------- 1 file changed, 15 insertions(+), 25 deletions(-) diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 450f45c1c4..3ff291b5ab 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -476,41 +476,31 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) totalReceiveCounter[linkId]++; currReceiveCounter[linkId]++; - // Update last message sequence ID - uint8_t expectedIndex; - if (lastIndex[message.sysid][message.compid] == -1) - { - lastIndex[message.sysid][message.compid] = message.seq; - expectedIndex = message.seq; - } - else - { - // NOTE: Using uint8_t here auto-wraps the number around to 0. - expectedIndex = lastIndex[message.sysid][message.compid] + 1; - } + // Determine what the next expected sequence number is, accounting for + // never having seen a message for this system/component pair. + int lastSeq = lastIndex[message.sysid][message.compid]; + int expectedSeq = (lastSeq == -1) ? message.seq : (lastSeq + 1); - // Make some noise if a message was skipped - //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "EXPECTED INDEX:" << expectedIndex << "SEQ" << message.seq; - if (message.seq != expectedIndex) + // And if we didn't encounter that sequence number, record the error + if (message.seq != expectedSeq) { - // Determine how many messages were skipped accounting for 0-wraparound - int16_t lostMessages = message.seq - expectedIndex; + + // Determine how many messages were skipped + int lostMessages = message.seq - expectedSeq; + + // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity if (lostMessages < 0) { - // Usually, this happens in the case of an out-of order packet lostMessages = 0; } - else - { - // Console generates excessive load at high loss rates, needs better GUI visualization - //qDebug() << QString("Lost %1 messages for comp %4: expected sequence ID %2 but received %3.").arg(lostMessages).arg(expectedIndex).arg(message.seq).arg(message.compid); - } + + // And log how many were lost for all time and just this timestep totalLossCounter[linkId] += lostMessages; currLossCounter[linkId] += lostMessages; } - // Update the last sequence ID - lastIndex[message.sysid][message.compid] = message.seq; + // And update the last sequence number for this system/component pair + lastIndex[message.sysid][message.compid] = expectedSeq; // Update on every 32th packet if (totalReceiveCounter[linkId] % 32 == 0) -- GitLab From 8d3e1779dd1a6efa29541ed821e26a503b613673 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Sun, 15 Jun 2014 14:13:39 -0700 Subject: [PATCH 24/53] Replaced expensive modulus operation with bitwise-and. --- src/comm/MAVLinkProtocol.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 3ff291b5ab..66ba6dc3ac 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -503,7 +503,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) lastIndex[message.sysid][message.compid] = expectedSeq; // Update on every 32th packet - if (totalReceiveCounter[linkId] % 32 == 0) + if ((totalReceiveCounter[linkId] & 0x1F) == 0) { // Calculate new loss ratio // Receive loss -- GitLab From be2780d72870213f247b885027152e7b0cf4d889 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sun, 15 Jun 2014 14:45:43 -0700 Subject: [PATCH 25/53] Modify TCPLinkTest for new threading model --- qgroundcontrol.pro | 6 ++- src/comm/TCPLink.cc | 12 +++++ src/comm/TCPLink.h | 7 ++- src/qgcunittest/MultiSignalSpy.cc | 6 ++- src/qgcunittest/TCPLinkTest.cc | 67 ++++++++++++---------------- src/qgcunittest/TCPLinkTest.h | 4 ++ src/qgcunittest/TCPLoopBackServer.cc | 65 +++++++++++++++++++++++++++ src/qgcunittest/TCPLoopBackServer.h | 55 +++++++++++++++++++++++ 8 files changed, 179 insertions(+), 43 deletions(-) create mode 100644 src/qgcunittest/TCPLoopBackServer.cc create mode 100644 src/qgcunittest/TCPLoopBackServer.h diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index be0b52be8b..e8f3512a41 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -188,7 +188,8 @@ DebugBuild { src/qgcunittest/MockQGCUASParamManager.h \ src/qgcunittest/MultiSignalSpy.h \ src/qgcunittest/FlightModeConfigTest.h \ - src/qgcunittest/TCPLinkTest.h + src/qgcunittest/TCPLinkTest.h \ + src/qgcunittest/TCPLoopBackServer.h SOURCES += \ src/qgcunittest/UASUnitTest.cc \ @@ -197,7 +198,8 @@ DebugBuild { src/qgcunittest/MockQGCUASParamManager.cc \ src/qgcunittest/MultiSignalSpy.cc \ src/qgcunittest/FlightModeConfigTest.cc \ - src/qgcunittest/TCPLinkTest.cc + src/qgcunittest/TCPLinkTest.cc \ + src/qgcunittest/TCPLoopBackServer.cc } # diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index 146e7a3930..7eee21cf5b 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -306,3 +306,15 @@ void TCPLink::_resetName(void) _name = QString("TCP Link (host:%1 port:%2)").arg(_hostAddress.toString()).arg(_port); emit nameChanged(_name); } + +void TCPLink::waitForBytesWritten(int msecs) +{ + Q_ASSERT(_socket); + _socket->waitForBytesWritten(msecs); +} + +void TCPLink::waitForReadyRead(int msecs) +{ + Q_ASSERT(_socket); + _socket->waitForReadyRead(msecs); +} diff --git a/src/comm/TCPLink.h b/src/comm/TCPLink.h index b7e7fe72e7..38da51e683 100644 --- a/src/comm/TCPLink.h +++ b/src/comm/TCPLink.h @@ -60,6 +60,8 @@ public: quint16 getPort(void) const { return _port; } QTcpSocket* getSocket(void) { return _socket; } + void signalBytesWritten(void); + // LinkInterface methods virtual int getId(void) const; virtual QString getName(void) const; @@ -80,6 +82,9 @@ public slots: // From LinkInterface virtual void writeBytes(const char* data, qint64 length); + + void waitForBytesWritten(int msecs); + void waitForReadyRead(int msecs); protected slots: void _socketError(QAbstractSocket::SocketError socketError); @@ -90,7 +95,7 @@ protected slots: protected: // From LinkInterface->QThread virtual void run(void); - + private: void _resetName(void); bool _hardwareConnect(void); diff --git a/src/qgcunittest/MultiSignalSpy.cc b/src/qgcunittest/MultiSignalSpy.cc index 4cebd83478..5d8d87c015 100644 --- a/src/qgcunittest/MultiSignalSpy.cc +++ b/src/qgcunittest/MultiSignalSpy.cc @@ -25,6 +25,7 @@ #include <QEventLoop> #include <QCoreApplication> #include <QDebug> +#include <QTest> /// @file /// @brief This class allows you to keep track of signal counts on a set of signals associated with an object. @@ -218,7 +219,10 @@ bool MultiSignalSpy::waitForSignalByIndex( Q_ASSERT(spy); while (spy->count() == 0 && !_timeout) { - QCoreApplication::processEvents(QEventLoop::AllEvents | QEventLoop::WaitForMoreEvents, 500); + QCoreApplication::sendPostedEvents(); + QCoreApplication::processEvents(); + QCoreApplication::flush(); + QTest::qSleep(100); } // Clean up and return status diff --git a/src/qgcunittest/TCPLinkTest.cc b/src/qgcunittest/TCPLinkTest.cc index 045c4e51f5..50471251e7 100644 --- a/src/qgcunittest/TCPLinkTest.cc +++ b/src/qgcunittest/TCPLinkTest.cc @@ -22,7 +22,7 @@ ======================================================================*/ #include "TCPLinkTest.h" -#include <QTcpServer> +#include "TCPLoopBackServer.h" /// @file /// @brief TCPLink class unit test @@ -143,51 +143,46 @@ void TCPLinkUnitTest::_connectSucceed_test(void) Q_ASSERT(_multiSpy->checkNoSignals() == true); // Start the server side - QTcpServer* server = new QTcpServer(this); - QCOMPARE(server->listen(_hostAddress, _port), true); + TCPLoopBackServer* server = new TCPLoopBackServer(_hostAddress, _port); + Q_CHECK_PTR(server); // Connect to the server QCOMPARE(_link->connect(), true); - // Wait for the connection to come through on server side - QCOMPARE(server->waitForNewConnection(1000), true); - QTcpSocket* serverSocket = server->nextPendingConnection(); - Q_ASSERT(serverSocket); - // Make sure we get the two different connected signals QCOMPARE(_multiSpy->waitForSignalByIndex(connectedSignalIndex, 1000), true); QCOMPARE(_multiSpy->checkOnlySignalByMask(connectedSignalMask | connected2SignalMask), true); QList<QVariant> arguments = _multiSpy->getSpyByIndex(connected2SignalIndex)->takeFirst(); QCOMPARE(arguments.at(0).toBool(), true); - _multiSpy->clearSignalsByMask(connectedSignalMask); - - // Test server->link data path - - QByteArray bytesOut("test"); - - // Write data from server to link - serverSocket->write(bytesOut); - - // Make sure we get the bytesReceived signal, with the correct data - QCOMPARE(_multiSpy->waitForSignalByIndex(bytesReceivedSignalIndex, 1000), true); - QCOMPARE(_multiSpy->checkOnlySignalByMask(bytesReceivedSignalMask), true); - arguments = _multiSpy->getSpyByIndex(bytesReceivedSignalIndex)->takeFirst(); - QCOMPARE(arguments.at(1), QVariant(bytesOut)); - _multiSpy->clearSignalByIndex(bytesReceivedSignalIndex); + _multiSpy->clearAllSignals(); // Test link->server data path + QByteArray bytesOut("test"); + // Write data from link to server + const char* bytesWrittenSignal = SIGNAL(bytesWritten(qint64)); + MultiSignalSpy bytesWrittenSpy; + QCOMPARE(bytesWrittenSpy.init(_link->getSocket(), &bytesWrittenSignal, 1), true); _link->writeBytes(bytesOut.data(), bytesOut.size()); - QCOMPARE(_link->getSocket()->waitForBytesWritten(1000), true); + _multiSpy->clearAllSignals(); + + // We emit this signal such that it will be queued and run on the TCPLink thread. This in turn + // allows the TCPLink object to pump the bytes through. + connect(this, SIGNAL(waitForBytesWritten(int)), _link, SLOT(waitForBytesWritten(int))); + emit waitForBytesWritten(1000); - // Make sure we get readyRead on server - QCOMPARE(serverSocket->waitForReadyRead(1000), true); + // Check for loopback, both from signal received and actual bytes returned + QCOMPARE(_multiSpy->waitForSignalByIndex(bytesReceivedSignalIndex, 1000), true); + QCOMPARE(_multiSpy->checkOnlySignalByMask(bytesReceivedSignalMask), true); + // Read the data and make sure it matches - QByteArray bytesIn = serverSocket->read(bytesOut.size() + 100); - QCOMPARE(bytesIn, bytesOut); + arguments = _multiSpy->getSpyByIndex(bytesReceivedSignalIndex)->takeFirst(); + QVERIFY(arguments.at(1).toByteArray() == bytesOut); + _multiSpy->clearAllSignals(); + // Disconnect the link _link->disconnect(); @@ -196,27 +191,21 @@ void TCPLinkUnitTest::_connectSucceed_test(void) QCOMPARE(_multiSpy->checkOnlySignalByMask(disconnectedSignalMask | connected2SignalMask), true); arguments = _multiSpy->getSpyByIndex(connected2SignalIndex)->takeFirst(); QCOMPARE(arguments.at(0).toBool(), false); - _multiSpy->clearSignalsByMask(disconnectedSignalMask); - - // Make sure we get disconnected signals from the server side - QCOMPARE(serverSocket->waitForDisconnected(1000), true ); + _multiSpy->clearAllSignals(); // Try to connect again to make sure everything was cleaned up correctly from previous connection // Connect to the server QCOMPARE(_link->connect(), true); - // Wait for the connection to come through on server side - QCOMPARE(server->waitForNewConnection(1000), true); - serverSocket = server->nextPendingConnection(); - Q_ASSERT(serverSocket); - // Make sure we get the two different connected signals QCOMPARE(_multiSpy->waitForSignalByIndex(connectedSignalIndex, 1000), true); QCOMPARE(_multiSpy->checkOnlySignalByMask(connectedSignalMask | connected2SignalMask), true); arguments = _multiSpy->getSpyByIndex(connected2SignalIndex)->takeFirst(); QCOMPARE(arguments.at(0).toBool(), true); - _multiSpy->clearSignalsByMask(connectedSignalMask); - + _multiSpy->clearAllSignals(); + + server->quit(); + QTest::qWait(500); // Wait a little for server thread to terminate delete server; } diff --git a/src/qgcunittest/TCPLinkTest.h b/src/qgcunittest/TCPLinkTest.h index 120fa96b14..61a0fa81db 100644 --- a/src/qgcunittest/TCPLinkTest.h +++ b/src/qgcunittest/TCPLinkTest.h @@ -43,6 +43,10 @@ class TCPLinkUnitTest : public QObject public: TCPLinkUnitTest(void); + +signals: + void waitForBytesWritten(int msecs); + void waitForReadyRead(int msecs); private slots: void init(void); diff --git a/src/qgcunittest/TCPLoopBackServer.cc b/src/qgcunittest/TCPLoopBackServer.cc new file mode 100644 index 0000000000..07c1644f31 --- /dev/null +++ b/src/qgcunittest/TCPLoopBackServer.cc @@ -0,0 +1,65 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. + + ======================================================================*/ + +#include "TCPLoopBackServer.h" + +TCPLoopBackServer::TCPLoopBackServer(QHostAddress hostAddress, quint16 port) : + _hostAddress(hostAddress), + _port(port), + _tcpSocket(NULL) +{ + moveToThread(this); + start(HighPriority); +} + +void TCPLoopBackServer::run(void) +{ + // Start the server side + _tcpServer = new QTcpServer(this); + Q_CHECK_PTR(_tcpServer); + + bool connected = QObject::connect(_tcpServer, SIGNAL(newConnection()), this, SLOT(_newConnection())); + Q_ASSERT(connected); + + Q_ASSERT(_tcpServer->listen(_hostAddress, _port)); + + // Fall into main event loop + exec(); +} + +void TCPLoopBackServer::_newConnection(void) +{ + Q_ASSERT(_tcpServer); + _tcpSocket = _tcpServer->nextPendingConnection(); + Q_ASSERT(_tcpSocket); + bool connected = QObject::connect(_tcpSocket, SIGNAL(readyRead()), this, SLOT(_readBytes())); + Q_ASSERT(connected); +} + +void TCPLoopBackServer::_readBytes(void) +{ + Q_ASSERT(_tcpSocket); + QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable()); + Q_ASSERT(_tcpSocket->write(bytesIn) == bytesIn.count()); + Q_ASSERT(_tcpSocket->waitForBytesWritten(1000)); +} diff --git a/src/qgcunittest/TCPLoopBackServer.h b/src/qgcunittest/TCPLoopBackServer.h new file mode 100644 index 0000000000..b433efc229 --- /dev/null +++ b/src/qgcunittest/TCPLoopBackServer.h @@ -0,0 +1,55 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. + + ======================================================================*/ + +#ifndef TCPLOOPBACKSERVER_H +#define TCPLOOPBACKSERVER_H + +#include <QThread> +#include <QTcpServer> +#include <QTcpSocket> + +class TCPLoopBackServer : public QThread +{ + Q_OBJECT + +public: + TCPLoopBackServer(QHostAddress hostAddress, quint16 port); + +signals: + void newConnection(void); + +protected: + virtual void run(void); + +private slots: + void _newConnection(void); + void _readBytes(void); + +private: + QHostAddress _hostAddress; + quint16 _port; + QTcpServer* _tcpServer; + QTcpSocket* _tcpSocket; +}; + +#endif \ No newline at end of file -- GitLab From c97c855764c1e8f881ae1f5b267f7f8e8c755f94 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sun, 15 Jun 2014 15:04:01 -0700 Subject: [PATCH 26/53] Can't call _socket methods from primary thread --- src/comm/TCPLink.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index 7eee21cf5b..9cef75e10e 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -198,7 +198,6 @@ bool TCPLink::disconnect() if (_socket) { - _socket->disconnectFromHost(); _socketIsConnected = false; delete _socket; _socket = NULL; -- GitLab From 163383cb990441c7ab9720c8ff33c208957ebed9 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sun, 15 Jun 2014 15:28:17 -0700 Subject: [PATCH 27/53] Comments --- src/qgcunittest/TCPLoopBackServer.cc | 5 +++++ src/qgcunittest/TCPLoopBackServer.h | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/src/qgcunittest/TCPLoopBackServer.cc b/src/qgcunittest/TCPLoopBackServer.cc index 07c1644f31..0198ade158 100644 --- a/src/qgcunittest/TCPLoopBackServer.cc +++ b/src/qgcunittest/TCPLoopBackServer.cc @@ -23,6 +23,11 @@ #include "TCPLoopBackServer.h" +/// @file +/// @brief Simple TCP loop back server +/// +/// @author Don Gagne <don@thegagnes.com> + TCPLoopBackServer::TCPLoopBackServer(QHostAddress hostAddress, quint16 port) : _hostAddress(hostAddress), _port(port), diff --git a/src/qgcunittest/TCPLoopBackServer.h b/src/qgcunittest/TCPLoopBackServer.h index b433efc229..c4036719ca 100644 --- a/src/qgcunittest/TCPLoopBackServer.h +++ b/src/qgcunittest/TCPLoopBackServer.h @@ -28,6 +28,11 @@ #include <QTcpServer> #include <QTcpSocket> +/// @file +/// @brief Simple TCP loop back server +/// +/// @author Don Gagne <don@thegagnes.com> + class TCPLoopBackServer : public QThread { Q_OBJECT -- GitLab From 83a092f348a6dc7c5687b456899f618ad9aa6b05 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Sun, 15 Jun 2014 15:28:46 -0700 Subject: [PATCH 28/53] deleteLater on _socket This way the delete happens on the right thread. --- src/comm/TCPLink.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index 9cef75e10e..51c222348a 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -199,7 +199,7 @@ bool TCPLink::disconnect() if (_socket) { _socketIsConnected = false; - delete _socket; + _socket->deleteLater(); // Make sure delete happens on correct thread _socket = NULL; emit disconnected(); -- GitLab From e2f5a8c3fea98d5a1af7290235dd05f5b8acaa96 Mon Sep 17 00:00:00 2001 From: Thomas Gubler <thomasgubler@gmail.com> Date: Mon, 16 Jun 2014 15:51:22 +0200 Subject: [PATCH 29/53] espeak: provide string length with 0 character, fixes problems with qgc reading out strange values/chars at the end of the sentence --- src/GAudioOutput.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/GAudioOutput.cc b/src/GAudioOutput.cc index ff88dfe943..35aef2ff74 100644 --- a/src/GAudioOutput.cc +++ b/src/GAudioOutput.cc @@ -212,7 +212,8 @@ bool GAudioOutput::say(QString text, int severity) #endif // _MSC_VER #if defined Q_OS_LINUX - unsigned int espeak_size = strlen(text.toStdString().c_str()); + // Set size of string for espeak: +1 for the null-character + unsigned int espeak_size = strlen(text.toStdString().c_str()) + 1; espeak_Synth(text.toStdString().c_str(), espeak_size, 0, POS_CHARACTER, 0, espeakCHARS_AUTO, NULL, NULL); #endif // Q_OS_LINUX -- GitLab From b61b0601ffa0122922e22f90bbb117344ea6ceb0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Thu, 19 Jun 2014 19:32:11 +0200 Subject: [PATCH 30/53] Prevent the system from sending a stop HIL command if HIL is not actually active --- src/uas/UAS.cc | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 5d46139d2d..8ca1920dfd 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2864,16 +2864,19 @@ void UAS::toggleArmedState() void UAS::goAutonomous() { setMode((base_mode & ~(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED)) | (MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED), 0); + qDebug() << __FILE__ << __LINE__ << "Going autonomous"; } void UAS::goManual() { setMode((base_mode & ~(MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED)) | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, 0); + qDebug() << __FILE__ << __LINE__ << "Going manual"; } void UAS::toggleAutonomy() { setMode(base_mode ^ MAV_MODE_FLAG_AUTO_ENABLED ^ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED ^ MAV_MODE_FLAG_GUIDED_ENABLED ^ MAV_MODE_FLAG_STABILIZE_ENABLED, 0); + qDebug() << __FILE__ << __LINE__ << "Toggling autonomy"; } /** @@ -3291,6 +3294,7 @@ void UAS::startHil() hilEnabled = true; sensorHil = false; setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode); + qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable."; // Connect HIL simulation link simulation->connectSimulation(); } @@ -3300,8 +3304,11 @@ void UAS::startHil() */ void UAS::stopHil() { - if (simulation) simulation->disconnectSimulation(); - setMode(base_mode & ~MAV_MODE_FLAG_HIL_ENABLED, custom_mode); + if (simulation && simulation->isConnected()) { + simulation->disconnectSimulation(); + setMode(base_mode & ~MAV_MODE_FLAG_HIL_ENABLED, custom_mode); + qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable."; + } hilEnabled = false; sensorHil = false; } -- GitLab From 0ccecde870ee394f22d10adda4767eedf3f45ae8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Thu, 19 Jun 2014 19:52:18 +0200 Subject: [PATCH 31/53] Better defaults for Takeoff pitch and better visual indication --- src/Waypoint.cc | 10 ++++++++++ src/ui/mission/QGCMissionNavTakeoff.ui | 16 ++++++++++++++-- 2 files changed, 24 insertions(+), 2 deletions(-) diff --git a/src/Waypoint.cc b/src/Waypoint.cc index dc9d3a6c93..33e0bf62a8 100644 --- a/src/Waypoint.cc +++ b/src/Waypoint.cc @@ -191,6 +191,16 @@ void Waypoint::setAction(MAV_CMD action) { if (this->action != action) { this->action = action; + + // Flick defaults according to WP type + + switch (this->action) { + case MAV_CMD_NAV_TAKEOFF: + // We default to 15 degrees minimum takeoff pitch + this->param1 = 15.0; + break; + } + emit changed(this); } } diff --git a/src/ui/mission/QGCMissionNavTakeoff.ui b/src/ui/mission/QGCMissionNavTakeoff.ui index 7536c844f4..bf0aab426e 100644 --- a/src/ui/mission/QGCMissionNavTakeoff.ui +++ b/src/ui/mission/QGCMissionNavTakeoff.ui @@ -32,7 +32,16 @@ <property name="spacing"> <number>5</number> </property> - <property name="margin"> + <property name="leftMargin"> + <number>0</number> + </property> + <property name="topMargin"> + <number>0</number> + </property> + <property name="rightMargin"> + <number>0</number> + </property> + <property name="bottomMargin"> <number>0</number> </property> <item> @@ -296,7 +305,7 @@ <bool>false</bool> </property> <property name="prefix"> - <string/> + <string>heading </string> </property> <property name="suffix"> <string>°</string> @@ -329,6 +338,9 @@ <property name="keyboardTracking"> <bool>false</bool> </property> + <property name="prefix"> + <string>min. pitch </string> + </property> <property name="suffix"> <string>°</string> </property> -- GitLab From b7f495b1788ac8e4e0a409a5d49946abdf5f7f36 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Fri, 20 Jun 2014 14:38:20 +0200 Subject: [PATCH 32/53] Fix HIL link reconnect issues due to missing threading flag usage, warn user about missing config and take him to config view if necessary --- qgroundcontrol.pro | 6 +- src/comm/QGCXPlaneLink.cc | 114 +++++++++++++++++--------------- src/uas/QGCMAVLinkUASFactory.cc | 15 +++++ src/uas/QGXPX4UAS.cc | 37 +++++++++++ src/uas/QGXPX4UAS.h | 21 ++++++ src/uas/UAS.cc | 1 + src/uas/UAS.h | 1 + src/uas/UASInterface.h | 5 ++ src/ui/MainWindow.cc | 21 ++++++ src/ui/MainWindow.h | 1 + 10 files changed, 168 insertions(+), 54 deletions(-) create mode 100644 src/uas/QGXPX4UAS.cc create mode 100644 src/uas/QGXPX4UAS.h diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 6475dc52f6..08d39331d6 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -562,7 +562,8 @@ HEADERS += \ src/uas/UASManagerInterface.h \ src/uas/QGCUASParamManagerInterface.h \ src/uas/QGCUASWorker.h \ - src/CmdLineOptParser.h + src/CmdLineOptParser.h \ + src/uas/QGXPX4UAS.h SOURCES += \ src/main.cc \ @@ -747,4 +748,5 @@ SOURCES += \ src/ui/designer/QGCXYPlot.cc \ src/ui/menuactionhelper.cpp \ src/uas/QGCUASWorker.cc \ - src/CmdLineOptParser.cc + src/CmdLineOptParser.cc \ + src/uas/QGXPX4UAS.cc diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index b30b5216e4..f829b7e128 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -64,9 +64,12 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress // http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/ moveToThread(this); + setTerminationEnabled(false); + this->localHost = localHost; this->localPort = localPort/*+mav->getUASID()*/; - this->connectState = false; + connectState = false; + this->name = tr("X-Plane Link (localPort:%1)").arg(localPort); setRemoteHost(remoteHost); loadSettings(); @@ -151,13 +154,27 @@ void QGCXPlaneLink::setVersion(unsigned int version) **/ void QGCXPlaneLink::run() { - if (!mav) return; - if (connectState) return; + if (!mav) { + emit statusMessage("No MAV present"); + return; + } + + if (connectState) { + emit statusMessage("Already connected"); + return; + } socket = new QUdpSocket(this); socket->moveToThread(this); connectState = socket->bind(localHost, localPort); - if (!connectState) return; + if (!connectState) { + + emit statusMessage("Binding socket failed!"); + + delete socket; + socket = NULL; + return; + } QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); @@ -208,8 +225,6 @@ void QGCXPlaneLink::run() } } - //qDebug() << "REQ SEND TO:" << localAddrStr << localPortStr; - ip.index = 0; strncpy(ip.str_ipad_them, localAddrStr.toAscii(), qMin((int)sizeof(ip.str_ipad_them), 16)); strncpy(ip.str_port_them, localPortStr.toAscii(), qMin((int)sizeof(ip.str_port_them), 6)); @@ -217,10 +232,36 @@ void QGCXPlaneLink::run() writeBytes((const char*)&ip, sizeof(ip)); + _should_exit = false; + while(!_should_exit) { QCoreApplication::processEvents(); QGC::SLEEP::msleep(5); } + + if (mav) + { + disconnect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); + disconnect(mav, SIGNAL(hilActuatorsChanged(quint64, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(quint64,float,float,float,float,float,float,float,float))); + + disconnect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); + disconnect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); + disconnect(this, SIGNAL(sensorHilGpsChanged(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), mav, SLOT(sendHilGps(quint64,double,double,double,int,float,float,float,float,float,float,float,int))); + disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); + + // Do not toggle HIL state on the UAS - this is not the job of this link, but of the + // UAS object + } + + connectState = false; + + socket->close(); + delete socket; + socket = NULL; + + emit simulationDisconnected(); + emit simulationConnected(false); + emit finished(); } void QGCXPlaneLink::setPort(int localPort) @@ -839,50 +880,15 @@ qint64 QGCXPlaneLink::bytesAvailable() **/ bool QGCXPlaneLink::disconnectSimulation() { - if (!connectState) return true; - - connectState = false; - - if (process) disconnect(process, SIGNAL(error(QProcess::ProcessError)), - this, SLOT(processError(QProcess::ProcessError))); - if (mav) + if (connectState) { - disconnect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8))); - disconnect(mav, SIGNAL(hilActuatorsChanged(quint64, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(quint64,float,float,float,float,float,float,float,float))); - - disconnect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); - disconnect(this, SIGNAL(hilStateChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilState(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); - disconnect(this, SIGNAL(sensorHilGpsChanged(quint64,double,double,double,int,float,float,float,float,float,float,float,int)), mav, SLOT(sendHilGps(quint64,double,double,double,int,float,float,float,float,float,float,float,int))); - disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32))); - - UAS* uas = dynamic_cast<UAS*>(mav); - if (uas) - { - uas->stopHil(); - } + _should_exit = true; + wait(); + } else { + emit simulationDisconnected(); + emit simulationConnected(false); } - if (process) - { - process->close(); - delete process; - process = NULL; - } - if (terraSync) - { - terraSync->close(); - delete terraSync; - terraSync = NULL; - } - if (socket) - { - socket->close(); - delete socket; - socket = NULL; - } - - emit simulationDisconnected(); - emit simulationConnected(false); return !connectState; } @@ -1017,11 +1023,15 @@ void QGCXPlaneLink::setRandomAttitude() **/ bool QGCXPlaneLink::connectSimulation() { - qDebug() << "STARTING X-PLANE LINK, CONNECTING TO" << remoteHost << ":" << remotePort; - // XXX Hack - storeSettings(); - - start(HighPriority); + if (connectState) { + qDebug() << "Simulation already active"; + } else { + qDebug() << "STARTING X-PLANE LINK, CONNECTING TO" << remoteHost << ":" << remotePort; + // XXX Hack + storeSettings(); + + start(HighPriority); + } return true; } diff --git a/src/uas/QGCMAVLinkUASFactory.cc b/src/uas/QGCMAVLinkUASFactory.cc index 5a607c8907..0906e6c4fd 100644 --- a/src/uas/QGCMAVLinkUASFactory.cc +++ b/src/uas/QGCMAVLinkUASFactory.cc @@ -1,6 +1,7 @@ #include "QGCMAVLinkUASFactory.h" #include "UASManager.h" #include "QGCUASWorker.h" +#include "QGXPX4UAS.h" QGCMAVLinkUASFactory::QGCMAVLinkUASFactory(QObject *parent) : QObject(parent) @@ -57,6 +58,20 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte uas = mav; } break; + case MAV_AUTOPILOT_PX4: + { + QGXPX4UAS* px4 = new QGXPX4UAS(mavlink, worker, sysid); + // Set the system type + px4->setSystemType((int)heartbeat->type); + + // Connect this robot to the UAS object + // it is IMPORTANT here to use the right object type, + // else the slot of the parent object is called (and thus the special + // packets never reach their goal) + connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), px4, SLOT(receiveMessage(LinkInterface*, mavlink_message_t))); + uas = px4; + } + break; case MAV_AUTOPILOT_SLUGS: { SlugsMAV* mav = new SlugsMAV(mavlink, worker, sysid); diff --git a/src/uas/QGXPX4UAS.cc b/src/uas/QGXPX4UAS.cc new file mode 100644 index 0000000000..723c7d4836 --- /dev/null +++ b/src/uas/QGXPX4UAS.cc @@ -0,0 +1,37 @@ +#include "QGXPX4UAS.h" + +QGXPX4UAS::QGXPX4UAS(MAVLinkProtocol* mavlink, QThread* thread, int id) : + UAS(mavlink, thread, id) +{ +} + +/** + * This function is called by MAVLink once a complete, uncorrupted (CRC check valid) + * mavlink packet is received. + * + * @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port). + * messages can be sent back to the system via this link + * @param message MAVLink message, as received from the MAVLink protocol stack + */ +void QGXPX4UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) +{ + UAS::receiveMessage(link, message); +} + +void QGXPX4UAS::processParamValueMsgHook(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue) +{ + int compId = msg.compid; + if (paramName == "SYS_AUTOSTART") { + + bool ok; + + int val = parameters.value(compId)->value(paramName).toInt(&ok); + + if (ok && val == 0) { + emit misconfigurationDetected(this); + qDebug() << "HINTING MISCONFIGURATION"; + } + + qDebug() << "SYS_AUTOSTART FOUND WITH VAL: " << val; + } +} diff --git a/src/uas/QGXPX4UAS.h b/src/uas/QGXPX4UAS.h new file mode 100644 index 0000000000..9876ee49bd --- /dev/null +++ b/src/uas/QGXPX4UAS.h @@ -0,0 +1,21 @@ +#ifndef QGXPX4UAS_H +#define QGXPX4UAS_H + +#include "UAS.h" + +class QGXPX4UAS : public UAS +{ + Q_OBJECT + Q_INTERFACES(UASInterface) +public: + QGXPX4UAS(MAVLinkProtocol* mavlink, QThread* thread, int id); + +public slots: + /** @brief Receive a MAVLink message from this MAV */ + void receiveMessage(LinkInterface* link, mavlink_message_t message); + + virtual void processParamValueMsgHook(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue); + +}; + +#endif // QGXPX4UAS_H diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 8ca1920dfd..d8db2ea640 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1044,6 +1044,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) paramVal.type = rawValue.param_type; processParamValueMsg(message, parameterName,rawValue,paramVal); + processParamValueMsgHook(message, parameterName,rawValue,paramVal); } break; diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 6b57f9c881..b1a367529e 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -974,6 +974,7 @@ protected: quint64 getUnixReferenceTime(quint64 time); virtual void processParamValueMsg(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue); + virtual void processParamValueMsgHook(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue) {}; int componentID[256]; bool componentMulti[256]; diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index e918104a55..92c5db3e20 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -430,6 +430,11 @@ signals: void poiFound(UASInterface* uas, int type, int colorIndex, QString message, float x, float y, float z); void poiConnectionFound(UASInterface* uas, int type, int colorIndex, QString message, float x1, float y1, float z1, float x2, float y2, float z2); + /** + * @brief A misconfiguration has been detected by the UAS + */ + void misconfigurationDetected(UASInterface* uas); + /** @brief A text message from the system has been received */ void textMessageReceived(int uasid, int componentid, int severity, QString text); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index da0a849644..9734be07a3 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -1700,6 +1700,7 @@ void MainWindow::UASCreated(UASInterface* uas) connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int))); connect(uas, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), this, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64))); + connect(uas, SIGNAL(misconfigurationDetected(UASInterface*)), this, SLOT(handleMisconfiguration(UASInterface*))); // HIL showHILConfigurationWidget(uas); @@ -1945,6 +1946,26 @@ void MainWindow::setAdvancedMode(bool isAdvancedMode) settings.setValue("ADVANCED_MODE",isAdvancedMode); } +void MainWindow::handleMisconfiguration(UASInterface* uas) { + + // Ask user if he wants to handle this now + QMessageBox msgBox(this); + msgBox.setIcon(QMessageBox::Information); + msgBox.setText(tr("Missing or Invalid Onboard Configuration")); + msgBox.setInformativeText(tr("The onboard system configuration is missing or incomplete. Do you want to resolve this now?")); + msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); + msgBox.setDefaultButton(QMessageBox::Ok); + int val = msgBox.exec(); + + if (val == QMessageBox::Ok) { + // He wants to handle it, make sure this system is selected + UASManager::instance()->setActiveUAS(uas); + + // Flick to config view + loadHardwareConfigView(); + } +} + void MainWindow::loadEngineerView() { if (currentView != VIEW_ENGINEER) diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 8e2ee961b3..55ecf08937 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -222,6 +222,7 @@ public slots: /** @brief Sets advanced mode, allowing for editing of tool widget locations */ void setAdvancedMode(bool isAdvancedMode); + void handleMisconfiguration(UASInterface* uas); /** @brief Load configuration views */ void loadHardwareConfigView(); void loadSoftwareConfigView(); -- GitLab From 7932dff56ebec842a3f4abbb087e57323a7385a4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Sat, 21 Jun 2014 13:04:14 +0200 Subject: [PATCH 33/53] Improve main tool bar labels --- src/ui/MainWindow.ui | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index a457b98e46..baba762170 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -51,7 +51,7 @@ <x>0</x> <y>0</y> <width>1024</width> - <height>21</height> + <height>22</height> </rect> </property> <widget class="QMenu" name="menuMGround"> @@ -318,7 +318,7 @@ <normaloff>:/files/images/status/network-wireless-encrypted.svg</normaloff>:/files/images/status/network-wireless-encrypted.svg</iconset> </property> <property name="text"> - <string>Flight</string> + <string>Instruments</string> </property> </action> <action name="actionNewCustomWidget"> @@ -416,9 +416,6 @@ <property name="checkable"> <bool>true</bool> </property> - <property name="visible"> - <bool>false</bool> - </property> <property name="icon"> <iconset resource="../../qgroundcontrol.qrc"> <normaloff>:/files/images/status/software-update-available.svg</normaloff>:/files/images/status/software-update-available.svg</iconset> @@ -429,6 +426,9 @@ <property name="toolTip"> <string>Update the firmware of one of the connected autopilots</string> </property> + <property name="visible"> + <bool>false</bool> + </property> </action> <action name="actionHardwareConfig"> <property name="checkable"> -- GitLab From 6e8454d2adb5e6aa73a8fb0078df0f28f69ff074 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Mon, 23 Jun 2014 12:03:18 +0200 Subject: [PATCH 34/53] Fix parse error in project file --- qgroundcontrol.pro | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 338a5182ee..90d0a58e57 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -188,7 +188,7 @@ DebugBuild { src/qgcunittest/MockQGCUASParamManager.h \ src/qgcunittest/MultiSignalSpy.h \ src/qgcunittest/FlightModeConfigTest.h \ - src/qgcunittest/FlightGearTest.h + src/qgcunittest/FlightGearTest.h \ src/qgcunittest/TCPLinkTest.h \ src/qgcunittest/TCPLoopBackServer.h @@ -199,7 +199,7 @@ DebugBuild { src/qgcunittest/MockQGCUASParamManager.cc \ src/qgcunittest/MultiSignalSpy.cc \ src/qgcunittest/FlightModeConfigTest.cc \ - src/qgcunittest/FlightGearTest.cc + src/qgcunittest/FlightGearTest.cc \ src/qgcunittest/TCPLinkTest.cc \ src/qgcunittest/TCPLoopBackServer.cc } -- GitLab From 43f4c3708e509e6172dc0d0ff5ba5b8d8dc44419 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Mon, 23 Jun 2014 14:58:11 +0200 Subject: [PATCH 35/53] Make RC config more robust --- src/ui/QGCPX4VehicleConfig.cc | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index 0268b9c7db..1aa427af52 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -660,14 +660,12 @@ void QGCPX4VehicleConfig::stopCalibrationRC() mav->endRadioControlCalibration(); if (QMessageBox::Cancel == msgBoxResult) { + QMessageBox::information(0,"Aborting Calibration","Aborted writing configuration."); return; //don't commit these values } else { QMessageBox::information(0,"Uploading the RC Calibration","The configuration will now be uploaded and permanently stored."); writeCalibrationRC(); } - - // Read calibration back to update widget states and validate - paramMgr->requestParameterList(); } void QGCPX4VehicleConfig::loadQgcConfig(bool primary) @@ -1338,7 +1336,7 @@ void QGCPX4VehicleConfig::writeCalibrationRC() paramMgr->setPendingParam(0, "RC_MAP_AUX2", (int32_t)(rcMapping[10]+1)); //let the param mgr manage sending all the pending RC_foo updates and persisting after - paramMgr->sendPendingParameters(true); + paramMgr->sendPendingParameters(true, true); } -- GitLab From 8f30c8bee1a2cf7f1eee14e970ad8461bef231ae Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Mon, 23 Jun 2014 14:58:41 +0200 Subject: [PATCH 36/53] Let map ripper stop once finished --- libs/opmapcontrol/src/mapwidget/mapripper.cpp | 52 +++++++++++-------- 1 file changed, 29 insertions(+), 23 deletions(-) diff --git a/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/libs/opmapcontrol/src/mapwidget/mapripper.cpp index ef376e5a18..7dc3004ff1 100644 --- a/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -52,31 +52,37 @@ namespace mapcontrol } void MapRipper::finish() { - if(zoom<maxzoom) + if(zoom<maxzoom) { - ++zoom; - QMessageBox msgBox; - msgBox.setText(tr("Continue Ripping at zoom level %1? (Continuing automatically after 3s)").arg(zoom)); - // msgBox.setInformativeText("Do you want to save your changes?"); - msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No); - msgBox.setDefaultButton(QMessageBox::Yes); - QTimer::singleShot(3000, &msgBox, SLOT(accept())); - msgBox.exec(); - int ret = msgBox.result(); + ++zoom; + QMessageBox msgBox; + msgBox.setText(tr("Continue Ripping at zoom level %1? (Continuing automatically after 3s)").arg(zoom)); + // msgBox.setInformativeText("Do you want to save your changes?"); + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No); + msgBox.setDefaultButton(QMessageBox::Yes); + QTimer::singleShot(3000, &msgBox, SLOT(accept())); + msgBox.exec(); + int ret = msgBox.result(); - if(ret==QMessageBox::Yes || ret == 1) - { - points.clear(); - points=core->Projection()->GetAreaTileList(area,zoom,0); - this->start(); - } - else - { - progressForm->close(); - delete progressForm; - this->deleteLater(); - } - } + if(ret==QMessageBox::Yes || ret == 1) + { + points.clear(); + points=core->Projection()->GetAreaTileList(area,zoom,0); + this->start(); + } + else + { + progressForm->close(); + delete progressForm; + this->deleteLater(); + } + } + else + { + progressForm->close(); + delete progressForm; + this->deleteLater(); + } } -- GitLab From 2e4ac6be5e198fd81553f366992f6d0507afca9b Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Mon, 23 Jun 2014 14:59:41 +0200 Subject: [PATCH 37/53] Add RC channel handling --- src/uas/UAS.cc | 55 +++++++++++++++++++++++++++++++++++++++++++++++--- 1 file changed, 52 insertions(+), 3 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 174dce7b53..da9c88423a 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1003,6 +1003,55 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit remoteControlChannelRawChanged(channels.port * portWidth + 6, channels.chan7_raw); if (channels.chan8_raw != UINT16_MAX) emit remoteControlChannelRawChanged(channels.port * portWidth + 7, channels.chan8_raw); + } + break; + case MAVLINK_MSG_ID_RC_CHANNELS: + { + mavlink_rc_channels_t channels; + mavlink_msg_rc_channels_decode(&message, &channels); + + // UINT8_MAX indicates this value is unknown + if (channels.rssi != UINT8_MAX) { + emit remoteControlRSSIChanged(channels.rssi/100.0f); + } + + if (channels.chan1_raw != UINT16_MAX && channels.chancount > 0) + emit remoteControlChannelRawChanged(0, channels.chan1_raw); + if (channels.chan2_raw != UINT16_MAX && channels.chancount > 1) + emit remoteControlChannelRawChanged(1, channels.chan2_raw); + if (channels.chan3_raw != UINT16_MAX && channels.chancount > 2) + emit remoteControlChannelRawChanged(2, channels.chan3_raw); + if (channels.chan4_raw != UINT16_MAX && channels.chancount > 3) + emit remoteControlChannelRawChanged(3, channels.chan4_raw); + if (channels.chan5_raw != UINT16_MAX && channels.chancount > 4) + emit remoteControlChannelRawChanged(4, channels.chan5_raw); + if (channels.chan6_raw != UINT16_MAX && channels.chancount > 5) + emit remoteControlChannelRawChanged(5, channels.chan6_raw); + if (channels.chan7_raw != UINT16_MAX && channels.chancount > 6) + emit remoteControlChannelRawChanged(6, channels.chan7_raw); + if (channels.chan8_raw != UINT16_MAX && channels.chancount > 7) + emit remoteControlChannelRawChanged(7, channels.chan8_raw); + if (channels.chan9_raw != UINT16_MAX && channels.chancount > 8) + emit remoteControlChannelRawChanged(8, channels.chan9_raw); + if (channels.chan10_raw != UINT16_MAX && channels.chancount > 9) + emit remoteControlChannelRawChanged(9, channels.chan10_raw); + if (channels.chan11_raw != UINT16_MAX && channels.chancount > 10) + emit remoteControlChannelRawChanged(10, channels.chan11_raw); + if (channels.chan12_raw != UINT16_MAX && channels.chancount > 11) + emit remoteControlChannelRawChanged(11, channels.chan12_raw); + if (channels.chan13_raw != UINT16_MAX && channels.chancount > 12) + emit remoteControlChannelRawChanged(12, channels.chan13_raw); + if (channels.chan14_raw != UINT16_MAX && channels.chancount > 13) + emit remoteControlChannelRawChanged(13, channels.chan14_raw); + if (channels.chan15_raw != UINT16_MAX && channels.chancount > 14) + emit remoteControlChannelRawChanged(14, channels.chan15_raw); + if (channels.chan16_raw != UINT16_MAX && channels.chancount > 15) + emit remoteControlChannelRawChanged(15, channels.chan16_raw); + if (channels.chan17_raw != UINT16_MAX && channels.chancount > 16) + emit remoteControlChannelRawChanged(16, channels.chan17_raw); + if (channels.chan18_raw != UINT16_MAX && channels.chancount > 17) + emit remoteControlChannelRawChanged(17, channels.chan18_raw); + } break; case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: @@ -1444,9 +1493,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) break; #endif - // Messages to ignore - case MAVLINK_MSG_ID_RAW_IMU: - case MAVLINK_MSG_ID_SCALED_IMU: case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: { //mavlink_set_local_position_setpoint_t p; @@ -1462,6 +1508,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error); } break; + // Messages to ignore + case MAVLINK_MSG_ID_RAW_IMU: + case MAVLINK_MSG_ID_SCALED_IMU: case MAVLINK_MSG_ID_RAW_PRESSURE: case MAVLINK_MSG_ID_SCALED_PRESSURE: case MAVLINK_MSG_ID_OPTICAL_FLOW: -- GitLab From f96c178ca60b46ba9f431bdbf7b00d8893ffd320 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 22:37:51 -0700 Subject: [PATCH 38/53] QString::toAscii() doesn't exist in Qt5, using toLatin1() instead. --- src/GAudioOutput.cc | 2 +- src/comm/QGCFlightGearLink.cc | 2 +- src/comm/QGCJSBSimLink.cc | 2 +- src/comm/QGCParamID.h | 2 +- src/comm/QGCXPlaneLink.cc | 4 ++-- src/comm/XbeeLink.cpp | 2 +- src/uas/UAS.cc | 6 +++--- src/ui/MainWindow.cc | 2 +- src/ui/map3D/Q3DWidget.cc | 4 ++-- src/ui/mavlink/QGCMAVLinkMessageSender.cc | 6 +++--- 10 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/GAudioOutput.cc b/src/GAudioOutput.cc index 35aef2ff74..9d479bc590 100644 --- a/src/GAudioOutput.cc +++ b/src/GAudioOutput.cc @@ -223,7 +223,7 @@ bool GAudioOutput::say(QString text, int severity) text = "\\" + text; QStdWString str = text.toStdWString(); unsigned char str2[1024] = {}; - memcpy(str2, text.toAscii().data(), str.length()); + memcpy(str2, text.toLatin1().data(), str.length()); SpeakString(str2); res = true; #endif // Q_OS_MAC diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index ce54a3e792..f570adf5ef 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -236,7 +236,7 @@ void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float p { QString state("%1\t%2\t%3\t%4\t%5\n"); state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle); - writeBytes(state.toAscii().constData(), state.length()); + writeBytes(state.toLatin1().constData(), state.length()); //qDebug() << "Updated controls" << rollAilerons << pitchElevator << yawRudder << throttle; //qDebug() << "Updated controls" << state; } diff --git a/src/comm/QGCJSBSimLink.cc b/src/comm/QGCJSBSimLink.cc index 947161d148..56f03d7124 100644 --- a/src/comm/QGCJSBSimLink.cc +++ b/src/comm/QGCJSBSimLink.cc @@ -257,7 +257,7 @@ void QGCJSBSimLink::updateControls(quint64 time, float rollAilerons, float pitch { QString state("%1\t%2\t%3\t%4\t%5\n"); state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle); - writeBytes(state.toAscii().constData(), state.length()); + writeBytes(state.toLatin1().constData(), state.length()); } else { diff --git a/src/comm/QGCParamID.h b/src/comm/QGCParamID.h index 2df351ff1b..44f9ddead9 100644 --- a/src/comm/QGCParamID.h +++ b/src/comm/QGCParamID.h @@ -72,7 +72,7 @@ public: return static_cast<const QString>(data); } int8_t* toInt8_t() const { - return (int8_t*)data.toAscii().data(); + return (int8_t*)data.toLatin1().data(); } protected: diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index f829b7e128..2d35e0f8c0 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -226,8 +226,8 @@ void QGCXPlaneLink::run() } ip.index = 0; - strncpy(ip.str_ipad_them, localAddrStr.toAscii(), qMin((int)sizeof(ip.str_ipad_them), 16)); - strncpy(ip.str_port_them, localPortStr.toAscii(), qMin((int)sizeof(ip.str_port_them), 6)); + strncpy(ip.str_ipad_them, localAddrStr.toLatin1(), qMin((int)sizeof(ip.str_ipad_them), 16)); + strncpy(ip.str_port_them, localPortStr.toLatin1(), qMin((int)sizeof(ip.str_port_them), 6)); ip.use_ip = 1; writeBytes((const char*)&ip, sizeof(ip)); diff --git a/src/comm/XbeeLink.cpp b/src/comm/XbeeLink.cpp index 767da686d5..337c961fca 100644 --- a/src/comm/XbeeLink.cpp +++ b/src/comm/XbeeLink.cpp @@ -73,7 +73,7 @@ bool XbeeLink::setPortName(QString portName) m_portName = new char[this->m_portNameLength]; for(int i=0;i<list[0].size();i++) { - this->m_portName[i]=list[0][i].toAscii(); + this->m_portName[i]=list[0][i].toLatin1(); } this->m_portName[list[0].size()] = '\0'; } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index da9c88423a..652ad6a3cc 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2563,7 +2563,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant& switch ((int)value.type()) { case QVariant::Char: - union_value.param_float = (unsigned char)value.toChar().toAscii(); + union_value.param_float = (unsigned char)value.toChar().toLatin1(); p.param_type = MAV_PARAM_TYPE_INT8; break; case QVariant::Int: @@ -2588,7 +2588,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant& switch ((int)value.type()) { case QVariant::Char: - union_value.param_int8 = (unsigned char)value.toChar().toAscii(); + union_value.param_int8 = (unsigned char)value.toChar().toLatin1(); p.param_type = MAV_PARAM_TYPE_INT8; break; case QVariant::Int: @@ -2621,7 +2621,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant& // String characters if ((int)i < paramId.length()) { - p.param_id[i] = paramId.toAscii()[i]; + p.param_id[i] = paramId.toLatin1()[i]; } else { diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index eb6e52597c..dc832b77e3 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -1185,7 +1185,7 @@ void MainWindow::saveScreen() if (!screenFileName.isEmpty()) { - window.save(screenFileName, format.toAscii()); + window.save(screenFileName, format.toLatin1()); } } void MainWindow::enableDockWidgetTitleBars(bool enabled) diff --git a/src/ui/map3D/Q3DWidget.cc b/src/ui/map3D/Q3DWidget.cc index 54fc876fa9..aa8918aa00 100644 --- a/src/ui/map3D/Q3DWidget.cc +++ b/src/ui/map3D/Q3DWidget.cc @@ -254,7 +254,7 @@ Q3DWidget::handleKeyPressEvent(QKeyEvent* event) { mOsgGW->getEventQueue()->keyPress( static_cast<osgGA::GUIEventAdapter::KeySymbol>( - *(event->text().toAscii().data()))); + *(event->text().toLatin1().data()))); } } @@ -274,7 +274,7 @@ Q3DWidget::handleKeyReleaseEvent(QKeyEvent* event) { mOsgGW->getEventQueue()->keyRelease( static_cast<osgGA::GUIEventAdapter::KeySymbol>( - *(event->text().toAscii().data()))); + *(event->text().toLatin1().data()))); } } diff --git a/src/ui/mavlink/QGCMAVLinkMessageSender.cc b/src/ui/mavlink/QGCMAVLinkMessageSender.cc index fabf249978..6a93ed1950 100644 --- a/src/ui/mavlink/QGCMAVLinkMessageSender.cc +++ b/src/ui/mavlink/QGCMAVLinkMessageSender.cc @@ -81,7 +81,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) { // Single char char* b = ((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); - *b = field->data(1, Qt::DisplayRole).toChar().toAscii(); + *b = field->data(1, Qt::DisplayRole).toChar().toLatin1(); } break; case MAVLINK_TYPE_UINT8_T: @@ -100,7 +100,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) { // Single value uint8_t* u = (m+messageInfo[msgid].fields[fieldid].wire_offset); - *u = field->data(1, Qt::DisplayRole).toChar().toAscii(); + *u = field->data(1, Qt::DisplayRole).toChar().toLatin1(); } break; case MAVLINK_TYPE_INT8_T: @@ -119,7 +119,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) { // Single value int8_t* u = reinterpret_cast<int8_t*>(m+messageInfo[msgid].fields[fieldid].wire_offset); - *u = field->data(1, Qt::DisplayRole).toChar().toAscii(); + *u = field->data(1, Qt::DisplayRole).toChar().toLatin1(); } break; case MAVLINK_TYPE_INT16_T: -- GitLab From da5a348c104c358a742278f6de312c51a89f1186 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 22:38:38 -0700 Subject: [PATCH 39/53] QImage::setNumColors() renamed to setColorCount() --- src/apps/qgcvideo/QGCVideoWidget.cc | 4 ++-- src/ui/CameraView.cc | 6 +++--- src/ui/HUD.cc | 4 ++-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/apps/qgcvideo/QGCVideoWidget.cc b/src/apps/qgcvideo/QGCVideoWidget.cc index 8fc9b85ad8..ba0be9c158 100644 --- a/src/apps/qgcvideo/QGCVideoWidget.cc +++ b/src/apps/qgcvideo/QGCVideoWidget.cc @@ -151,7 +151,7 @@ QGCVideoWidget::QGCVideoWidget(QWidget* parent) // Fill with black background QImage fill = QImage(640, 480, QImage::Format_Indexed8); - fill.setNumColors(3); + fill.setColorCount(3); fill.setColor(0, qRgb(0, 0, 0)); fill.setColor(1, qRgb(0, 0, 0)); fill.setColor(2, qRgb(0, 0, 0)); @@ -1136,7 +1136,7 @@ void QGCVideoWidget::commitRawDataToGL() QImage* newImage = new QImage(rawImage, receivedWidth, receivedHeight, format); if (format == QImage::Format_Indexed8) { // Create matching color table - newImage->setNumColors(256); + newImage->setColorCount(256); for (int i = 0; i < 256; i++) { newImage->setColor(i, qRgb(i, i, i)); //qDebug() << __FILE__ << __LINE__ << std::hex << i; diff --git a/src/ui/CameraView.cc b/src/ui/CameraView.cc index 13bc86bb6b..f23e96fabb 100644 --- a/src/ui/CameraView.cc +++ b/src/ui/CameraView.cc @@ -49,7 +49,7 @@ CameraView::CameraView(int width, int height, int depth, int channels, QWidget* // Fill with black background QImage fill = QImage(width, height, QImage::Format_Indexed8); - fill.setNumColors(1); + fill.setColorCount(1); fill.setColor(0, qRgb(70, 200, 70)); fill.fill(CameraView::initialColor); glImage = QGLWidget::convertToGLFormat(fill); @@ -104,7 +104,7 @@ void CameraView::setImageSize(int width, int height, int depth, int channels) if (depth <= 8 && channels == 1) { image = new QImage(receivedWidth, receivedHeight, QImage::Format_Indexed8); // Create matching color table - image->setNumColors(256); + image->setColorCount(256); for (int i = 0; i < 256; i++) { image->setColor(i, qRgb(i, i, i)); //qDebug() << __FILE__ << __LINE__ << std::hex << i; @@ -162,7 +162,7 @@ void CameraView::commitRawDataToGL() QImage* newImage = new QImage(rawImage, receivedWidth, receivedHeight, format); if (format == QImage::Format_Indexed8) { // Create matching color table - newImage->setNumColors(256); + newImage->setColorCount(256); for (int i = 0; i < 256; i++) { newImage->setColor(i, qRgb(i, i, i)); //qDebug() << __FILE__ << __LINE__ << std::hex << i; diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 90b1ca0b7f..2c13dc5761 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -1212,7 +1212,7 @@ void HUD::setImageSize(int width, int height, int depth, int channels) if (depth <= 8 && channels == 1) { image = new QImage(receivedWidth, receivedHeight, QImage::Format_Indexed8); // Create matching color table - image->setNumColors(256); + image->setColorCount(256); for (int i = 0; i < 256; i++) { image->setColor(i, qRgb(i, i, i)); //qDebug() << __FILE__ << __LINE__ << std::hex << i; @@ -1277,7 +1277,7 @@ void HUD::commitRawDataToGL() QImage* newImage = new QImage(rawImage, receivedWidth, receivedHeight, format); if (format == QImage::Format_Indexed8) { // Create matching color table - newImage->setNumColors(256); + newImage->setColorCount(256); for (int i = 0; i < 256; i++) { newImage->setColor(i, qRgb(i, i, i)); //qDebug() << __FILE__ << __LINE__ << std::hex << i; -- GitLab From 1f4c371fe95b43e5269d93f0644c5ec67b87ec02 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 22:40:42 -0700 Subject: [PATCH 40/53] QThread::finished() no longer emittable by subclasses. --- src/comm/QGCXPlaneLink.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index 2d35e0f8c0..106e3c654c 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -261,7 +261,6 @@ void QGCXPlaneLink::run() emit simulationDisconnected(); emit simulationConnected(false); - emit finished(); } void QGCXPlaneLink::setPort(int localPort) -- GitLab From 3f5ba935e53b0d9b67751de9c18fc5a5cba61db6 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 22:41:13 -0700 Subject: [PATCH 41/53] QApplication::UnicodeUTF8 no longer exists as it is now the default. --- src/ui/MainWindow.cc | 32 ++++++++++++++++---------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index dc832b77e3..65000c43ca 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -366,23 +366,23 @@ void MainWindow::init() // Set OS dependent keyboard shortcuts for the main window, non OS dependent shortcuts are set in MainWindow.ui #ifdef Q_OS_MACX - ui.actionFlightView->setShortcut(QApplication::translate("MainWindow", "Meta+1", 0, QApplication::UnicodeUTF8)); - ui.actionMissionView->setShortcut(QApplication::translate("MainWindow", "Meta+2", 0, QApplication::UnicodeUTF8)); - ui.actionHardwareConfig->setShortcut(QApplication::translate("MainWindow", "Meta+3", 0, QApplication::UnicodeUTF8)); - ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Meta+4", 0, QApplication::UnicodeUTF8)); - ui.actionEngineersView->setShortcut(QApplication::translate("MainWindow", "Meta+5", 0, QApplication::UnicodeUTF8)); - ui.actionMavlinkView->setShortcut(QApplication::translate("MainWindow", "Meta+M", 0, QApplication::UnicodeUTF8)); - ui.actionUnconnectedView->setShortcut(QApplication::translate("MainWindow", "Meta+U", 0, QApplication::UnicodeUTF8)); - ui.actionFullscreen->setShortcut(QApplication::translate("MainWindow", "Meta+Return", 0, QApplication::UnicodeUTF8)); + ui.actionFlightView->setShortcut(QApplication::translate("MainWindow", "Meta+1", 0)); + ui.actionMissionView->setShortcut(QApplication::translate("MainWindow", "Meta+2", 0)); + ui.actionHardwareConfig->setShortcut(QApplication::translate("MainWindow", "Meta+3", 0)); + ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Meta+4", 0)); + ui.actionEngineersView->setShortcut(QApplication::translate("MainWindow", "Meta+5", 0)); + ui.actionMavlinkView->setShortcut(QApplication::translate("MainWindow", "Meta+M", 0)); + ui.actionUnconnectedView->setShortcut(QApplication::translate("MainWindow", "Meta+U", 0)); + ui.actionFullscreen->setShortcut(QApplication::translate("MainWindow", "Meta+Return", 0)); #else - ui.actionFlightView->setShortcut(QApplication::translate("MainWindow", "Ctrl+1", 0, QApplication::UnicodeUTF8)); - ui.actionMissionView->setShortcut(QApplication::translate("MainWindow", "Ctrl+2", 0, QApplication::UnicodeUTF8)); - ui.actionHardwareConfig->setShortcut(QApplication::translate("MainWindow", "Ctrl+3", 0, QApplication::UnicodeUTF8)); - ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Ctrl+4", 0, QApplication::UnicodeUTF8)); - ui.actionEngineersView->setShortcut(QApplication::translate("MainWindow", "Ctrl+5", 0, QApplication::UnicodeUTF8)); - ui.actionMavlinkView->setShortcut(QApplication::translate("MainWindow", "Ctrl+M", 0, QApplication::UnicodeUTF8)); - ui.actionUnconnectedView->setShortcut(QApplication::translate("MainWindow", "Ctrl+U", 0, QApplication::UnicodeUTF8)); - ui.actionFullscreen->setShortcut(QApplication::translate("MainWindow", "Ctrl+Return", 0, QApplication::UnicodeUTF8)); + ui.actionFlightView->setShortcut(QApplication::translate("MainWindow", "Ctrl+1", 0)); + ui.actionMissionView->setShortcut(QApplication::translate("MainWindow", "Ctrl+2", 0)); + ui.actionHardwareConfig->setShortcut(QApplication::translate("MainWindow", "Ctrl+3", 0)); + ui.actionSimulationView->setShortcut(QApplication::translate("MainWindow", "Ctrl+4", 0)); + ui.actionEngineersView->setShortcut(QApplication::translate("MainWindow", "Ctrl+5", 0)); + ui.actionMavlinkView->setShortcut(QApplication::translate("MainWindow", "Ctrl+M", 0)); + ui.actionUnconnectedView->setShortcut(QApplication::translate("MainWindow", "Ctrl+U", 0)); + ui.actionFullscreen->setShortcut(QApplication::translate("MainWindow", "Ctrl+Return", 0)); #endif connect(&windowNameUpdateTimer, SIGNAL(timeout()), this, SLOT(configureWindowName())); -- GitLab From 1a8b58e5f80d6c09d72b23317af2e5d17eef70d3 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 22:41:55 -0700 Subject: [PATCH 42/53] qVariantValue no longer exists, .value<T>() replaces it. --- src/ui/MainWindow.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 65000c43ca..33dc092bfb 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -899,7 +899,7 @@ void MainWindow::addToCentralStackedWidget(QWidget* widget, VIEW_SECTIONS viewSe void MainWindow::showCentralWidget() { QAction* act = qobject_cast<QAction *>(sender()); - QWidget* widget = qVariantValue<QWidget *>(act->data()); + QWidget* widget = act->data().value<QWidget *>(); centerStack->setCurrentWidget(widget); } -- GitLab From 93c130c8c247a956b8bc40259bd9843cb84ddc23 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 22:42:21 -0700 Subject: [PATCH 43/53] QDesktopWidget include now required for MainWindow.cc --- src/ui/MainWindow.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 33dc092bfb..d38db5f4ba 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -71,6 +71,7 @@ This file is part of the QGROUNDCONTROL project #include "SerialSettingsDialog.h" #include "terminalconsole.h" #include "menuactionhelper.h" +#include <QDesktopWidget> // Add support for the MAVLink generator UI if it's been requested. #ifdef QGC_MAVGEN_ENABLED -- GitLab From f7a8627fb6101664eff3e03991fa5b1de285265b Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 22:42:59 -0700 Subject: [PATCH 44/53] QDesktopWidget() doesn't work in Qt5, use QApplication::desktop() instead. --- src/ui/QGCSettingsWidget.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ui/QGCSettingsWidget.cc b/src/ui/QGCSettingsWidget.cc index fa61cc75db..0d7539d747 100644 --- a/src/ui/QGCSettingsWidget.cc +++ b/src/ui/QGCSettingsWidget.cc @@ -20,7 +20,7 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) : // Center the window on the screen. QRect position = frameGeometry(); - position.moveCenter(QDesktopWidget().availableGeometry().center()); + position.moveCenter(QApplication::desktop()->availableGeometry().center()); move(position.topLeft()); // Add all protocols -- GitLab From 3bb40ff9bc988452ceecd0cfefe8679f256edb5d Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Tue, 24 Jun 2014 23:05:52 -0700 Subject: [PATCH 45/53] Plotting data now defaults to drawing a line with no symbols. Also deleted invalid line drawing options. --- src/ui/QGCDataPlot2D.ui | 15 ++++----------- 1 file changed, 4 insertions(+), 11 deletions(-) diff --git a/src/ui/QGCDataPlot2D.ui b/src/ui/QGCDataPlot2D.ui index 1cd5288e49..dba1807270 100644 --- a/src/ui/QGCDataPlot2D.ui +++ b/src/ui/QGCDataPlot2D.ui @@ -36,9 +36,12 @@ </item> <item row="0" column="5" colspan="2"> <widget class="QComboBox" name="style"> + <property name="toolTip"> + <string>Set line style</string> + </property> <item> <property name="text"> - <string>Style..</string> + <string>Only lines</string> </property> </item> <item> @@ -56,11 +59,6 @@ <string>Only rectangles</string> </property> </item> - <item> - <property name="text"> - <string>Only symbols</string> - </property> - </item> <item> <property name="text"> <string>Lines and crosses</string> @@ -76,11 +74,6 @@ <string>Lines and rects</string> </property> </item> - <item> - <property name="text"> - <string>Lines and symbols</string> - </property> - </item> <item> <property name="text"> <string>Dotted lines and crosses</string> -- GitLab From c96458cf3b2d07ecefc5a1e0a33e874c70068480 Mon Sep 17 00:00:00 2001 From: Bryant <bwmairs@ucsc.edu> Date: Wed, 25 Jun 2014 18:55:39 -0700 Subject: [PATCH 46/53] Update Qwt to 6.1. We also document how we got the source code and keep our modifications out of the Qwt directory. --- libs/README.md | 9 + libs/qwt.pri | 149 ++ libs/qwt/qwt_abstract_legend.cpp | 38 + libs/qwt/qwt_abstract_legend.h | 71 + libs/qwt/qwt_abstract_scale.cpp | 362 +++-- libs/qwt/qwt_abstract_scale.h | 69 +- libs/qwt/qwt_abstract_scale_draw.cpp | 269 ++-- libs/qwt/qwt_abstract_scale_draw.h | 100 +- libs/qwt/qwt_abstract_slider.cpp | 1003 +++++++----- libs/qwt/qwt_abstract_slider.h | 218 ++- libs/qwt/qwt_analog_clock.cpp | 221 +-- libs/qwt/qwt_analog_clock.h | 50 +- libs/qwt/qwt_arrow_button.cpp | 289 ++-- libs/qwt/qwt_arrow_button.h | 20 +- libs/qwt/qwt_clipper.cpp | 731 +++++---- libs/qwt/qwt_clipper.h | 25 +- libs/qwt/qwt_color_map.cpp | 288 ++-- libs/qwt/qwt_color_map.h | 130 +- libs/qwt/qwt_column_symbol.cpp | 293 ++++ libs/qwt/qwt_column_symbol.h | 161 ++ libs/qwt/qwt_compass.cpp | 335 ++-- libs/qwt/qwt_compass.h | 64 +- libs/qwt/qwt_compass_rose.cpp | 253 ++- libs/qwt/qwt_compass_rose.h | 62 +- libs/qwt/qwt_compat.h | 42 + libs/qwt/qwt_counter.cpp | 950 ++++++----- libs/qwt/qwt_counter.h | 147 +- libs/qwt/qwt_curve_fitter.cpp | 393 ++++- libs/qwt/qwt_curve_fitter.h | 124 +- libs/qwt/qwt_date.cpp | 654 ++++++++ libs/qwt/qwt_date.h | 128 ++ libs/qwt/qwt_date_scale_draw.cpp | 269 ++++ libs/qwt/qwt_date_scale_draw.h | 77 + libs/qwt/qwt_date_scale_engine.cpp | 1300 +++++++++++++++ libs/qwt/qwt_date_scale_engine.h | 77 + libs/qwt/qwt_dial.cpp | 1283 ++++++--------- libs/qwt/qwt_dial.h | 175 +-- libs/qwt/qwt_dial_needle.cpp | 725 ++++----- libs/qwt/qwt_dial_needle.h | 140 +- libs/qwt/qwt_dyngrid_layout.cpp | 573 +++---- libs/qwt/qwt_dyngrid_layout.h | 60 +- libs/qwt/qwt_event_pattern.cpp | 212 ++- libs/qwt/qwt_event_pattern.h | 235 +-- libs/qwt/qwt_global.h | 24 +- libs/qwt/qwt_graphic.cpp | 986 ++++++++++++ libs/qwt/qwt_graphic.h | 172 ++ libs/qwt/qwt_interval.cpp | 354 +++++ libs/qwt/qwt_interval.h | 320 ++++ libs/qwt/qwt_interval_symbol.cpp | 319 ++++ libs/qwt/qwt_interval_symbol.h | 87 ++ libs/qwt/qwt_knob.cpp | 936 +++++++---- libs/qwt/qwt_knob.h | 164 +- libs/qwt/qwt_legend.cpp | 1000 +++++++----- libs/qwt/qwt_legend.h | 130 +- libs/qwt/qwt_legend_data.cpp | 129 ++ libs/qwt/qwt_legend_data.h | 87 ++ libs/qwt/qwt_legend_label.cpp | 421 +++++ libs/qwt/qwt_legend_label.h | 80 + libs/qwt/qwt_magnifier.cpp | 334 ++-- libs/qwt/qwt_magnifier.h | 48 +- libs/qwt/qwt_math.cpp | 47 +- libs/qwt/qwt_math.h | 199 +-- libs/qwt/qwt_matrix_raster_data.cpp | 298 ++++ libs/qwt/qwt_matrix_raster_data.h | 74 + libs/qwt/qwt_null_paintdevice.cpp | 593 +++++++ libs/qwt/qwt_null_paintdevice.h | 126 ++ libs/qwt/qwt_painter.cpp | 1475 +++++++++++------ libs/qwt/qwt_painter.h | 243 +-- libs/qwt/qwt_painter_command.cpp | 237 +++ libs/qwt/qwt_painter_command.h | 173 ++ libs/qwt/qwt_panner.cpp | 476 +++--- libs/qwt/qwt_panner.h | 58 +- libs/qwt/qwt_picker.cpp | 1464 +++++++++-------- libs/qwt/qwt_picker.h | 365 ++--- libs/qwt/qwt_picker_machine.cpp | 615 +++++--- libs/qwt/qwt_picker_machine.h | 116 +- libs/qwt/qwt_pixel_matrix.cpp | 51 + libs/qwt/qwt_pixel_matrix.h | 98 ++ libs/qwt/qwt_plot.cpp | 1240 +++++++++------ libs/qwt/qwt_plot.h | 290 ++-- libs/qwt/qwt_plot_abstract_barchart.cpp | 367 +++++ libs/qwt/qwt_plot_abstract_barchart.h | 97 ++ libs/qwt/qwt_plot_axis.cpp | 516 +++--- libs/qwt/qwt_plot_barchart.cpp | 459 ++++++ libs/qwt/qwt_plot_barchart.h | 118 ++ libs/qwt/qwt_plot_canvas.cpp | 1147 +++++++++++--- libs/qwt/qwt_plot_canvas.h | 162 +- libs/qwt/qwt_plot_curve.cpp | 1592 +++++++++---------- libs/qwt/qwt_plot_curve.h | 395 +++-- libs/qwt/qwt_plot_dict.cpp | 162 +- libs/qwt/qwt_plot_dict.h | 33 +- libs/qwt/qwt_plot_directpainter.cpp | 317 ++++ libs/qwt/qwt_plot_directpainter.h | 100 ++ libs/qwt/qwt_plot_glcanvas.cpp | 357 +++++ libs/qwt/qwt_plot_glcanvas.h | 136 ++ libs/qwt/qwt_plot_grid.cpp | 359 +++-- libs/qwt/qwt_plot_grid.h | 43 +- libs/qwt/qwt_plot_histogram.cpp | 690 ++++++++ libs/qwt/qwt_plot_histogram.h | 139 ++ libs/qwt/qwt_plot_intervalcurve.cpp | 603 +++++++ libs/qwt/qwt_plot_intervalcurve.h | 132 ++ libs/qwt/qwt_plot_item.cpp | 569 ++++--- libs/qwt/qwt_plot_item.h | 271 +++- libs/qwt/qwt_plot_layout.cpp | 1226 +++++++++------ libs/qwt/qwt_plot_layout.h | 99 +- libs/qwt/qwt_plot_legenditem.cpp | 865 ++++++++++ libs/qwt/qwt_plot_legenditem.h | 136 ++ libs/qwt/qwt_plot_magnifier.cpp | 81 +- libs/qwt/qwt_plot_magnifier.h | 13 +- libs/qwt/qwt_plot_marker.cpp | 571 +++++-- libs/qwt/qwt_plot_marker.h | 90 +- libs/qwt/qwt_plot_multi_barchart.cpp | 744 +++++++++ libs/qwt/qwt_plot_multi_barchart.h | 127 ++ libs/qwt/qwt_plot_panner.cpp | 204 ++- libs/qwt/qwt_plot_panner.h | 21 +- libs/qwt/qwt_plot_picker.cpp | 295 ++-- libs/qwt/qwt_plot_picker.h | 61 +- libs/qwt/qwt_plot_rasteritem.cpp | 873 +++++++++-- libs/qwt/qwt_plot_rasteritem.h | 124 +- libs/qwt/qwt_plot_renderer.cpp | 1014 ++++++++++++ libs/qwt/qwt_plot_renderer.h | 170 ++ libs/qwt/qwt_plot_rescaler.cpp | 631 ++++++++ libs/qwt/qwt_plot_rescaler.h | 142 ++ libs/qwt/qwt_plot_scaleitem.cpp | 291 ++-- libs/qwt/qwt_plot_scaleitem.h | 39 +- libs/qwt/qwt_plot_seriesitem.cpp | 112 ++ libs/qwt/qwt_plot_seriesitem.h | 66 + libs/qwt/qwt_plot_shapeitem.cpp | 491 ++++++ libs/qwt/qwt_plot_shapeitem.h | 111 ++ libs/qwt/qwt_plot_spectrocurve.cpp | 321 ++++ libs/qwt/qwt_plot_spectrocurve.h | 79 + libs/qwt/qwt_plot_spectrogram.cpp | 614 ++++---- libs/qwt/qwt_plot_spectrogram.h | 90 +- libs/qwt/qwt_plot_svgitem.cpp | 201 +-- libs/qwt/qwt_plot_svgitem.h | 33 +- libs/qwt/qwt_plot_textlabel.cpp | 261 ++++ libs/qwt/qwt_plot_textlabel.h | 75 + libs/qwt/qwt_plot_tradingcurve.cpp | 682 ++++++++ libs/qwt/qwt_plot_tradingcurve.h | 174 +++ libs/qwt/qwt_plot_xml.cpp | 23 +- libs/qwt/qwt_plot_zoneitem.cpp | 315 ++++ libs/qwt/qwt_plot_zoneitem.h | 65 + libs/qwt/qwt_plot_zoomer.cpp | 387 ++--- libs/qwt/qwt_plot_zoomer.h | 147 +- libs/qwt/qwt_point_3d.cpp | 22 + libs/qwt/qwt_point_3d.h | 189 +++ libs/qwt/qwt_point_data.cpp | 304 ++++ libs/qwt/qwt_point_data.h | 146 ++ libs/qwt/qwt_point_mapper.cpp | 721 +++++++++ libs/qwt/qwt_point_mapper.h | 89 ++ libs/qwt/qwt_point_polar.cpp | 121 ++ libs/qwt/qwt_point_polar.h | 201 +++ libs/qwt/qwt_raster_data.cpp | 389 +++-- libs/qwt/qwt_raster_data.h | 114 +- libs/qwt/qwt_round_scale_draw.cpp | 232 +-- libs/qwt/qwt_round_scale_draw.h | 40 +- libs/qwt/qwt_samples.h | 239 +++ libs/qwt/qwt_sampling_thread.cpp | 106 ++ libs/qwt/qwt_sampling_thread.h | 50 + libs/qwt/qwt_scale_div.cpp | 295 +++- libs/qwt/qwt_scale_div.h | 134 +- libs/qwt/qwt_scale_draw.cpp | 809 +++++----- libs/qwt/qwt_scale_draw.h | 93 +- libs/qwt/qwt_scale_engine.cpp | 1041 +++++++----- libs/qwt/qwt_scale_engine.h | 184 ++- libs/qwt/qwt_scale_map.cpp | 301 ++-- libs/qwt/qwt_scale_map.h | 152 +- libs/qwt/qwt_scale_widget.cpp | 777 ++++----- libs/qwt/qwt_scale_widget.h | 106 +- libs/qwt/qwt_series_data.cpp | 346 ++++ libs/qwt/qwt_series_data.h | 355 +++++ libs/qwt/qwt_series_store.h | 199 +++ libs/qwt/qwt_slider.cpp | 1332 +++++++++------- libs/qwt/qwt_slider.h | 132 +- libs/qwt/qwt_spline.cpp | 260 +-- libs/qwt/qwt_spline.h | 59 +- libs/qwt/qwt_symbol.cpp | 1912 ++++++++++++++++++++--- libs/qwt/qwt_symbol.h | 251 ++- libs/qwt/qwt_system_clock.cpp | 396 +++++ libs/qwt/qwt_system_clock.h | 47 + libs/qwt/qwt_text.cpp | 473 +++--- libs/qwt/qwt_text.h | 196 ++- libs/qwt/qwt_text_engine.cpp | 299 ++-- libs/qwt/qwt_text_engine.h | 82 +- libs/qwt/qwt_text_label.cpp | 163 +- libs/qwt/qwt_text_label.h | 34 +- libs/qwt/qwt_thermo.cpp | 1247 ++++++++------- libs/qwt/qwt_thermo.h | 195 ++- libs/qwt/qwt_transform.cpp | 165 ++ libs/qwt/qwt_transform.h | 137 ++ libs/qwt/qwt_wheel.cpp | 1469 ++++++++++++----- libs/qwt/qwt_wheel.h | 164 +- libs/qwt/qwt_widget_overlay.cpp | 373 +++++ libs/qwt/qwt_widget_overlay.h | 148 ++ 194 files changed, 47558 insertions(+), 17162 deletions(-) create mode 100644 libs/README.md create mode 100644 libs/qwt.pri create mode 100644 libs/qwt/qwt_abstract_legend.cpp create mode 100644 libs/qwt/qwt_abstract_legend.h create mode 100644 libs/qwt/qwt_column_symbol.cpp create mode 100644 libs/qwt/qwt_column_symbol.h create mode 100644 libs/qwt/qwt_compat.h create mode 100644 libs/qwt/qwt_date.cpp create mode 100644 libs/qwt/qwt_date.h create mode 100644 libs/qwt/qwt_date_scale_draw.cpp create mode 100644 libs/qwt/qwt_date_scale_draw.h create mode 100644 libs/qwt/qwt_date_scale_engine.cpp create mode 100644 libs/qwt/qwt_date_scale_engine.h create mode 100644 libs/qwt/qwt_graphic.cpp create mode 100644 libs/qwt/qwt_graphic.h create mode 100644 libs/qwt/qwt_interval.cpp create mode 100644 libs/qwt/qwt_interval.h create mode 100644 libs/qwt/qwt_interval_symbol.cpp create mode 100644 libs/qwt/qwt_interval_symbol.h create mode 100644 libs/qwt/qwt_legend_data.cpp create mode 100644 libs/qwt/qwt_legend_data.h create mode 100644 libs/qwt/qwt_legend_label.cpp create mode 100644 libs/qwt/qwt_legend_label.h create mode 100644 libs/qwt/qwt_matrix_raster_data.cpp create mode 100644 libs/qwt/qwt_matrix_raster_data.h create mode 100644 libs/qwt/qwt_null_paintdevice.cpp create mode 100644 libs/qwt/qwt_null_paintdevice.h create mode 100644 libs/qwt/qwt_painter_command.cpp create mode 100644 libs/qwt/qwt_painter_command.h create mode 100644 libs/qwt/qwt_pixel_matrix.cpp create mode 100644 libs/qwt/qwt_pixel_matrix.h create mode 100644 libs/qwt/qwt_plot_abstract_barchart.cpp create mode 100644 libs/qwt/qwt_plot_abstract_barchart.h create mode 100644 libs/qwt/qwt_plot_barchart.cpp create mode 100644 libs/qwt/qwt_plot_barchart.h create mode 100644 libs/qwt/qwt_plot_directpainter.cpp create mode 100644 libs/qwt/qwt_plot_directpainter.h create mode 100644 libs/qwt/qwt_plot_glcanvas.cpp create mode 100644 libs/qwt/qwt_plot_glcanvas.h create mode 100644 libs/qwt/qwt_plot_histogram.cpp create mode 100644 libs/qwt/qwt_plot_histogram.h create mode 100644 libs/qwt/qwt_plot_intervalcurve.cpp create mode 100644 libs/qwt/qwt_plot_intervalcurve.h create mode 100644 libs/qwt/qwt_plot_legenditem.cpp create mode 100644 libs/qwt/qwt_plot_legenditem.h create mode 100644 libs/qwt/qwt_plot_multi_barchart.cpp create mode 100644 libs/qwt/qwt_plot_multi_barchart.h create mode 100644 libs/qwt/qwt_plot_renderer.cpp create mode 100644 libs/qwt/qwt_plot_renderer.h create mode 100644 libs/qwt/qwt_plot_rescaler.cpp create mode 100644 libs/qwt/qwt_plot_rescaler.h create mode 100644 libs/qwt/qwt_plot_seriesitem.cpp create mode 100644 libs/qwt/qwt_plot_seriesitem.h create mode 100644 libs/qwt/qwt_plot_shapeitem.cpp create mode 100644 libs/qwt/qwt_plot_shapeitem.h create mode 100644 libs/qwt/qwt_plot_spectrocurve.cpp create mode 100644 libs/qwt/qwt_plot_spectrocurve.h create mode 100644 libs/qwt/qwt_plot_textlabel.cpp create mode 100644 libs/qwt/qwt_plot_textlabel.h create mode 100644 libs/qwt/qwt_plot_tradingcurve.cpp create mode 100644 libs/qwt/qwt_plot_tradingcurve.h create mode 100644 libs/qwt/qwt_plot_zoneitem.cpp create mode 100644 libs/qwt/qwt_plot_zoneitem.h create mode 100644 libs/qwt/qwt_point_3d.cpp create mode 100644 libs/qwt/qwt_point_3d.h create mode 100644 libs/qwt/qwt_point_data.cpp create mode 100644 libs/qwt/qwt_point_data.h create mode 100644 libs/qwt/qwt_point_mapper.cpp create mode 100644 libs/qwt/qwt_point_mapper.h create mode 100644 libs/qwt/qwt_point_polar.cpp create mode 100644 libs/qwt/qwt_point_polar.h create mode 100644 libs/qwt/qwt_samples.h create mode 100644 libs/qwt/qwt_sampling_thread.cpp create mode 100644 libs/qwt/qwt_sampling_thread.h create mode 100644 libs/qwt/qwt_series_data.cpp create mode 100644 libs/qwt/qwt_series_data.h create mode 100644 libs/qwt/qwt_series_store.h create mode 100644 libs/qwt/qwt_system_clock.cpp create mode 100644 libs/qwt/qwt_system_clock.h create mode 100644 libs/qwt/qwt_transform.cpp create mode 100644 libs/qwt/qwt_transform.h create mode 100644 libs/qwt/qwt_widget_overlay.cpp create mode 100644 libs/qwt/qwt_widget_overlay.h diff --git a/libs/README.md b/libs/README.md new file mode 100644 index 0000000000..f0f9a48a2a --- /dev/null +++ b/libs/README.md @@ -0,0 +1,9 @@ +This folder contains the various required libraries for QGC to compile. They are distributed with the codebase to ease development. + +# Qwt +Qt Widgets for Technical Applications +Version: 6.1 +Source obtained: `svn checkout svn://svn.code.sf.net/p/qwt/code/branches/qwt-6.1 qwt` + +Contents of `/libs/qwt` is the contents of the `/src` directory from the Qwt repository. +qwt.pri file is custom made to compile all necessary Qwt code in with QGC. diff --git a/libs/qwt.pri b/libs/qwt.pri new file mode 100644 index 0000000000..ecb19d61fd --- /dev/null +++ b/libs/qwt.pri @@ -0,0 +1,149 @@ +###################################################################### +# Automatically generated by qmake (2.01a) Wed Feb 10 11:43:43 2010 +###################################################################### + +QWTSRCDIR = libs/qwt +DEPENDPATH += $$QWTSRCDIR +INCLUDEPATH += $$QWTSRCDIR + +# Input +HEADERS += $$QWTSRCDIR/qwt.h \ + $$QWTSRCDIR/qwt_abstract_legend.h \ + $$QWTSRCDIR/qwt_abstract_scale.h \ + $$QWTSRCDIR/qwt_abstract_scale_draw.h \ + $$QWTSRCDIR/qwt_abstract_slider.h \ + $$QWTSRCDIR/qwt_analog_clock.h \ + $$QWTSRCDIR/qwt_arrow_button.h \ + $$QWTSRCDIR/qwt_clipper.h \ + $$QWTSRCDIR/qwt_color_map.h \ + $$QWTSRCDIR/qwt_compass.h \ + $$QWTSRCDIR/qwt_compass_rose.h \ + $$QWTSRCDIR/qwt_counter.h \ + $$QWTSRCDIR/qwt_curve_fitter.h \ + $$QWTSRCDIR/qwt_dial.h \ + $$QWTSRCDIR/qwt_dial_needle.h \ + $$QWTSRCDIR/qwt_dyngrid_layout.h \ + $$QWTSRCDIR/qwt_event_pattern.h \ + $$QWTSRCDIR/qwt_global.h \ + $$QWTSRCDIR/qwt_graphic.h \ + $$QWTSRCDIR/qwt_interval.h \ + $$QWTSRCDIR/qwt_knob.h \ + $$QWTSRCDIR/qwt_legend.h \ + $$QWTSRCDIR/qwt_legend_data.h \ + $$QWTSRCDIR/qwt_legend_label.h \ + $$QWTSRCDIR/qwt_magnifier.h \ + $$QWTSRCDIR/qwt_math.h \ + $$QWTSRCDIR/qwt_null_paintdevice.h \ + $$QWTSRCDIR/qwt_painter.h \ + $$QWTSRCDIR/qwt_painter_command.h \ + $$QWTSRCDIR/qwt_panner.h \ + $$QWTSRCDIR/qwt_picker.h \ + $$QWTSRCDIR/qwt_picker_machine.h \ + $$QWTSRCDIR/qwt_pixel_matrix.h \ + $$QWTSRCDIR/qwt_plot.h \ + $$QWTSRCDIR/qwt_plot_canvas.h \ + $$QWTSRCDIR/qwt_plot_curve.h \ + $$QWTSRCDIR/qwt_plot_dict.h \ + $$QWTSRCDIR/qwt_plot_grid.h \ + $$QWTSRCDIR/qwt_plot_item.h \ + $$QWTSRCDIR/qwt_plot_layout.h \ + $$QWTSRCDIR/qwt_plot_magnifier.h \ + $$QWTSRCDIR/qwt_plot_marker.h \ + $$QWTSRCDIR/qwt_plot_panner.h \ + $$QWTSRCDIR/qwt_plot_picker.h \ + $$QWTSRCDIR/qwt_plot_rasteritem.h \ + $$QWTSRCDIR/qwt_plot_scaleitem.h \ + $$QWTSRCDIR/qwt_plot_seriesitem.h \ + $$QWTSRCDIR/qwt_plot_spectrogram.h \ + $$QWTSRCDIR/qwt_plot_svgitem.h \ + $$QWTSRCDIR/qwt_plot_zoomer.h \ + $$QWTSRCDIR/qwt_point_mapper.h \ + $$QWTSRCDIR/qwt_point_data.h \ + $$QWTSRCDIR/qwt_raster_data.h \ + $$QWTSRCDIR/qwt_round_scale_draw.h \ + $$QWTSRCDIR/qwt_scale_div.h \ + $$QWTSRCDIR/qwt_scale_draw.h \ + $$QWTSRCDIR/qwt_scale_engine.h \ + $$QWTSRCDIR/qwt_scale_map.h \ + $$QWTSRCDIR/qwt_scale_widget.h \ + $$QWTSRCDIR/qwt_series_data.h \ + $$QWTSRCDIR/qwt_slider.h \ + $$QWTSRCDIR/qwt_spline.h \ + $$QWTSRCDIR/qwt_symbol.h \ + $$QWTSRCDIR/qwt_text.h \ + $$QWTSRCDIR/qwt_text_engine.h \ + $$QWTSRCDIR/qwt_text_label.h \ + $$QWTSRCDIR/qwt_thermo.h \ + $$QWTSRCDIR/qwt_transform.h \ + $$QWTSRCDIR/qwt_wheel.h \ + $$QWTSRCDIR/qwt_widget_overlay.h +SOURCES += $$QWTSRCDIR/qwt_abstract_legend.cpp \ + $$QWTSRCDIR/qwt_abstract_scale.cpp \ + $$QWTSRCDIR/qwt_abstract_scale_draw.cpp \ + $$QWTSRCDIR/qwt_abstract_slider.cpp \ + $$QWTSRCDIR/qwt_analog_clock.cpp \ + $$QWTSRCDIR/qwt_arrow_button.cpp \ + $$QWTSRCDIR/qwt_clipper.cpp \ + $$QWTSRCDIR/qwt_color_map.cpp \ + $$QWTSRCDIR/qwt_compass.cpp \ + $$QWTSRCDIR/qwt_compass_rose.cpp \ + $$QWTSRCDIR/qwt_counter.cpp \ + $$QWTSRCDIR/qwt_curve_fitter.cpp \ + $$QWTSRCDIR/qwt_dial.cpp \ + $$QWTSRCDIR/qwt_dial_needle.cpp \ + $$QWTSRCDIR/qwt_dyngrid_layout.cpp \ + $$QWTSRCDIR/qwt_event_pattern.cpp \ + $$QWTSRCDIR/qwt_graphic.cpp \ + $$QWTSRCDIR/qwt_interval.cpp \ + $$QWTSRCDIR/qwt_knob.cpp \ + $$QWTSRCDIR/qwt_legend.cpp \ + $$QWTSRCDIR/qwt_legend_data.cpp \ + $$QWTSRCDIR/qwt_legend_label.cpp \ + $$QWTSRCDIR/qwt_magnifier.cpp \ + $$QWTSRCDIR/qwt_math.cpp \ + $$QWTSRCDIR/qwt_null_paintdevice.cpp \ + $$QWTSRCDIR/qwt_painter.cpp \ + $$QWTSRCDIR/qwt_painter_command.cpp \ + $$QWTSRCDIR/qwt_panner.cpp \ + $$QWTSRCDIR/qwt_picker.cpp \ + $$QWTSRCDIR/qwt_picker_machine.cpp \ + $$QWTSRCDIR/qwt_pixel_matrix.cpp \ + $$QWTSRCDIR/qwt_plot.cpp \ + $$QWTSRCDIR/qwt_plot_axis.cpp \ + $$QWTSRCDIR/qwt_plot_canvas.cpp \ + $$QWTSRCDIR/qwt_plot_curve.cpp \ + $$QWTSRCDIR/qwt_plot_dict.cpp \ + $$QWTSRCDIR/qwt_plot_grid.cpp \ + $$QWTSRCDIR/qwt_plot_item.cpp \ + $$QWTSRCDIR/qwt_plot_layout.cpp \ + $$QWTSRCDIR/qwt_plot_magnifier.cpp \ + $$QWTSRCDIR/qwt_plot_marker.cpp \ + $$QWTSRCDIR/qwt_plot_panner.cpp \ + $$QWTSRCDIR/qwt_plot_picker.cpp \ + $$QWTSRCDIR/qwt_plot_rasteritem.cpp \ + $$QWTSRCDIR/qwt_plot_scaleitem.cpp \ + $$QWTSRCDIR/qwt_plot_seriesitem.cpp \ + $$QWTSRCDIR/qwt_plot_spectrogram.cpp \ + $$QWTSRCDIR/qwt_plot_svgitem.cpp \ + $$QWTSRCDIR/qwt_plot_xml.cpp \ + $$QWTSRCDIR/qwt_plot_zoomer.cpp \ + $$QWTSRCDIR/qwt_point_mapper.cpp \ + $$QWTSRCDIR/qwt_point_data.cpp \ + $$QWTSRCDIR/qwt_raster_data.cpp \ + $$QWTSRCDIR/qwt_round_scale_draw.cpp \ + $$QWTSRCDIR/qwt_scale_div.cpp \ + $$QWTSRCDIR/qwt_scale_draw.cpp \ + $$QWTSRCDIR/qwt_scale_engine.cpp \ + $$QWTSRCDIR/qwt_scale_map.cpp \ + $$QWTSRCDIR/qwt_scale_widget.cpp \ + $$QWTSRCDIR/qwt_series_data.cpp \ + $$QWTSRCDIR/qwt_slider.cpp \ + $$QWTSRCDIR/qwt_spline.cpp \ + $$QWTSRCDIR/qwt_symbol.cpp \ + $$QWTSRCDIR/qwt_text.cpp \ + $$QWTSRCDIR/qwt_text_engine.cpp \ + $$QWTSRCDIR/qwt_text_label.cpp \ + $$QWTSRCDIR/qwt_thermo.cpp \ + $$QWTSRCDIR/qwt_transform.cpp \ + $$QWTSRCDIR/qwt_wheel.cpp \ + $$QWTSRCDIR/qwt_widget_overlay.cpp diff --git a/libs/qwt/qwt_abstract_legend.cpp b/libs/qwt/qwt_abstract_legend.cpp new file mode 100644 index 0000000000..4ecaac61d9 --- /dev/null +++ b/libs/qwt/qwt_abstract_legend.cpp @@ -0,0 +1,38 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_abstract_legend.h" + +/*! + Constructor + + \param parent Parent widget +*/ +QwtAbstractLegend::QwtAbstractLegend( QWidget *parent ): + QFrame( parent ) +{ +} + +//! Destructor +QwtAbstractLegend::~QwtAbstractLegend() +{ +} + +/*! + Return the extent, that is needed for elements to scroll + the legend ( usually scrollbars ), + + \param orientation Orientation + \return Extent of the corresponding scroll element +*/ +int QwtAbstractLegend::scrollExtent( Qt::Orientation orientation ) const +{ + Q_UNUSED( orientation ); + return 0; +} diff --git a/libs/qwt/qwt_abstract_legend.h b/libs/qwt/qwt_abstract_legend.h new file mode 100644 index 0000000000..18bd3f4b96 --- /dev/null +++ b/libs/qwt/qwt_abstract_legend.h @@ -0,0 +1,71 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_ABSTRACT_LEGEND_H +#define QWT_ABSTRACT_LEGEND_H + +#include "qwt_global.h" +#include "qwt_legend_data.h" +#include <qframe.h> +#include <qlist.h> + +class QVariant; + +/*! + \brief Abstract base class for legend widgets + + Legends, that need to be under control of the QwtPlot layout system + need to be derived from QwtAbstractLegend. + + \note Other type of legends can be implemented by connecting to + the QwtPlot::legendDataChanged() signal. But as these legends + are unknown to the plot layout system the layout code + ( on screen and for QwtPlotRenderer ) need to be organized + in application code. + + \sa QwtLegend + */ +class QWT_EXPORT QwtAbstractLegend : public QFrame +{ + Q_OBJECT + +public: + explicit QwtAbstractLegend( QWidget *parent = NULL ); + virtual ~QwtAbstractLegend(); + + /*! + Render the legend into a given rectangle. + + \param painter Painter + \param rect Bounding rectangle + \param fillBackground When true, fill rect with the widget background + + \sa renderLegend() is used by QwtPlotRenderer + */ + virtual void renderLegend( QPainter *painter, + const QRectF &rect, bool fillBackground ) const = 0; + + //! \return True, when no plot item is inserted + virtual bool isEmpty() const = 0; + + virtual int scrollExtent( Qt::Orientation ) const; + +public Q_SLOTS: + + /*! + \brief Update the entries for a plot item + + \param itemInfo Info about an item + \param data List of legend entry attributes for the item + */ + virtual void updateLegend( const QVariant &itemInfo, + const QList<QwtLegendData> &data ) = 0; +}; + +#endif diff --git a/libs/qwt/qwt_abstract_scale.cpp b/libs/qwt/qwt_abstract_scale.cpp index 1f89a45a09..3018b854ea 100644 --- a/libs/qwt/qwt_abstract_scale.cpp +++ b/libs/qwt/qwt_abstract_scale.cpp @@ -7,26 +7,27 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_abstract_scale.h" #include "qwt_scale_engine.h" #include "qwt_scale_draw.h" #include "qwt_scale_div.h" #include "qwt_scale_map.h" -#include "qwt_double_interval.h" -#include "qwt_abstract_scale.h" +#include "qwt_interval.h" class QwtAbstractScale::PrivateData { public: PrivateData(): - maxMajor(5), - maxMinor(3), - stepSize(0.0), - autoScale(true) { - scaleEngine = new QwtLinearScaleEngine; + maxMajor( 5 ), + maxMinor( 3 ), + stepSize( 0.0 ) + { + scaleEngine = new QwtLinearScaleEngine(); scaleDraw = new QwtScaleDraw(); } - ~PrivateData() { + ~PrivateData() + { delete scaleEngine; delete scaleDraw; } @@ -37,21 +38,25 @@ public: int maxMajor; int maxMinor; double stepSize; - - bool autoScale; }; /*! Constructor + \param parent Parent widget + Creates a default QwtScaleDraw and a QwtLinearScaleEngine. - Autoscaling is enabled, and the stepSize is initialized by 0.0. + The initial scale boundaries are set to [ 0.0, 100.0 ] + + The scaleStepSize() is initialized to 0.0, scaleMaxMajor() to 5 + and scaleMaxMajor to 3. */ -QwtAbstractScale::QwtAbstractScale() +QwtAbstractScale::QwtAbstractScale( QWidget *parent ): + QWidget( parent ) { d_data = new PrivateData; - rescale(0.0, 100.0); + rescale( 0.0, 100.0, d_data->stepSize ); } //! Destructor @@ -61,138 +66,166 @@ QwtAbstractScale::~QwtAbstractScale() } /*! - \brief Specify a scale. + Set the lower bound of the scale - Disable autoscaling and define a scale by an interval and a step size + \param value Lower bound - \param vmin lower limit of the scale interval - \param vmax upper limit of the scale interval - \param stepSize major step size - \sa setAutoScale() + \sa lowerBound(), setScale(), setUpperBound() + \note For inverted scales the lower bound + is greater than the upper bound */ -void QwtAbstractScale::setScale(double vmin, double vmax, double stepSize) +void QwtAbstractScale::setLowerBound( double value ) { - d_data->autoScale = false; - d_data->stepSize = stepSize; + setScale( value, upperBound() ); +} - rescale(vmin, vmax, stepSize); +/*! + \return Lower bound of the scale + \sa setLowerBound(), setScale(), upperBound() +*/ +double QwtAbstractScale::lowerBound() const +{ + return d_data->scaleDraw->scaleDiv().lowerBound(); } /*! - \brief Specify a scale. + Set the upper bound of the scale - Disable autoscaling and define a scale by an interval and a step size + \param value Upper bound - \param interval Interval - \param stepSize major step size - \sa setAutoScale() + \sa upperBound(), setScale(), setLowerBound() + \note For inverted scales the lower bound + is greater than the upper bound */ -void QwtAbstractScale::setScale(const QwtDoubleInterval &interval, - double stepSize) +void QwtAbstractScale::setUpperBound( double value ) { - setScale(interval.minValue(), interval.maxValue(), stepSize); + setScale( lowerBound(), value ); } +/*! + \return Upper bound of the scale + \sa setUpperBound(), setScale(), lowerBound() +*/ +double QwtAbstractScale::upperBound() const +{ + return d_data->scaleDraw->scaleDiv().upperBound(); +} /*! \brief Specify a scale. - Disable autoscaling and define a scale by a scale division + Define a scale by an interval - \param scaleDiv Scale division - \sa setAutoScale() + The ticks are calculated using scaleMaxMinor(), + scaleMaxMajor() and scaleStepSize(). + + \param lowerBound lower limit of the scale interval + \param upperBound upper limit of the scale interval + + \note For inverted scales the lower bound + is greater than the upper bound */ -void QwtAbstractScale::setScale(const QwtScaleDiv &scaleDiv) +void QwtAbstractScale::setScale( double lowerBound, double upperBound ) { - d_data->autoScale = false; - - if (scaleDiv != d_data->scaleDraw->scaleDiv()) { - d_data->scaleDraw->setScaleDiv(scaleDiv); - scaleChange(); - } + rescale( lowerBound, upperBound, d_data->stepSize ); } /*! - Recalculate the scale division and update the scale draw. + \brief Specify a scale. - \param vmin Lower limit of the scale interval - \param vmax Upper limit of the scale interval - \param stepSize Major step size + Define a scale by an interval - \sa scaleChange() + The ticks are calculated using scaleMaxMinor(), + scaleMaxMajor() and scaleStepSize(). + + \param interval Interval */ -void QwtAbstractScale::rescale(double vmin, double vmax, double stepSize) +void QwtAbstractScale::setScale( const QwtInterval &interval ) { - const QwtScaleDiv scaleDiv = d_data->scaleEngine->divideScale( - vmin, vmax, d_data->maxMajor, d_data->maxMinor, stepSize); - - if ( scaleDiv != d_data->scaleDraw->scaleDiv() ) { - d_data->scaleDraw->setTransformation( - d_data->scaleEngine->transformation()); - d_data->scaleDraw->setScaleDiv(scaleDiv); - scaleChange(); - } + setScale( interval.minValue(), interval.maxValue() ); } /*! - \brief Advise the widget to control the scale range internally. + \brief Specify a scale. - Autoscaling is on by default. - \sa setScale(), autoScale() + scaleMaxMinor(), scaleMaxMajor() and scaleStepSize() and have no effect. + + \param scaleDiv Scale division + \sa setAutoScale() */ -void QwtAbstractScale::setAutoScale() +void QwtAbstractScale::setScale( const QwtScaleDiv &scaleDiv ) { - if (!d_data->autoScale) { - d_data->autoScale = true; + if ( scaleDiv != d_data->scaleDraw->scaleDiv() ) + { +#if 1 + if ( d_data->scaleEngine ) + { + d_data->scaleDraw->setTransformation( + d_data->scaleEngine->transformation() ); + } +#endif + + d_data->scaleDraw->setScaleDiv( scaleDiv ); + scaleChange(); } } -/*! - \return \c true if autoscaling is enabled -*/ -bool QwtAbstractScale::autoScale() const -{ - return d_data->autoScale; -} - /*! \brief Set the maximum number of major tick intervals. The scale's major ticks are calculated automatically such that the number of major intervals does not exceed ticks. + The default value is 5. - \param ticks maximal number of major ticks. - \sa QwtAbstractScaleDraw + + \param ticks Maximal number of major ticks. + + \sa scaleMaxMajor(), setScaleMaxMinor(), + setScaleStepSize(), QwtScaleEngine::divideInterval() */ -void QwtAbstractScale::setScaleMaxMajor(int ticks) +void QwtAbstractScale::setScaleMaxMajor( int ticks ) { - if (ticks != d_data->maxMajor) { + if ( ticks != d_data->maxMajor ) + { d_data->maxMajor = ticks; updateScaleDraw(); } } +/*! + \return Maximal number of major tick intervals + \sa setScaleMaxMajor(), scaleMaxMinor() +*/ +int QwtAbstractScale::scaleMaxMajor() const +{ + return d_data->maxMajor; +} + /*! \brief Set the maximum number of minor tick intervals The scale's minor ticks are calculated automatically such that the number of minor intervals does not exceed ticks. The default value is 3. - \param ticks - \sa QwtAbstractScaleDraw + + \param ticks Maximal number of minor ticks. + + \sa scaleMaxMajor(), setScaleMaxMinor(), + setScaleStepSize(), QwtScaleEngine::divideInterval() */ -void QwtAbstractScale::setScaleMaxMinor(int ticks) +void QwtAbstractScale::setScaleMaxMinor( int ticks ) { - if ( ticks != d_data->maxMinor) { + if ( ticks != d_data->maxMinor ) + { d_data->maxMinor = ticks; updateScaleDraw(); } } /*! - \return Max. number of minor tick intervals - The default value is 3. + \return Maximal number of minor tick intervals + \sa setScaleMaxMinor(), scaleMaxMajor() */ int QwtAbstractScale::scaleMaxMinor() const { @@ -200,27 +233,52 @@ int QwtAbstractScale::scaleMaxMinor() const } /*! - \return Max. number of major tick intervals - The default value is 5. + \brief Set the step size used for calculating a scale division + + The step size is hint for calculating the intervals for + the major ticks of the scale. A value of 0.0 is interpreted + as no hint. + + \param stepSize Hint for the step size of the scale + + \sa scaleStepSize(), QwtScaleEngine::divideScale() + + \note Position and distance between the major ticks also + depends on scaleMaxMajor(). */ -int QwtAbstractScale::scaleMaxMajor() const +void QwtAbstractScale::setScaleStepSize( double stepSize ) { - return d_data->maxMajor; + if ( stepSize != d_data->stepSize ) + { + d_data->stepSize = stepSize; + updateScaleDraw(); + } +} + +/*! + \return Hint for the step size of the scale + \sa setScaleStepSize(), QwtScaleEngine::divideScale() +*/ +double QwtAbstractScale::scaleStepSize() const +{ + return d_data->stepSize; } /*! \brief Set a scale draw scaleDraw has to be created with new and will be deleted in - ~QwtAbstractScale or the next call of setAbstractScaleDraw. + the destructor or the next call of setAbstractScaleDraw(). + + \sa abstractScaleDraw() */ -void QwtAbstractScale::setAbstractScaleDraw(QwtAbstractScaleDraw *scaleDraw) +void QwtAbstractScale::setAbstractScaleDraw( QwtAbstractScaleDraw *scaleDraw ) { if ( scaleDraw == NULL || scaleDraw == d_data->scaleDraw ) return; if ( d_data->scaleDraw != NULL ) - scaleDraw->setScaleDiv(d_data->scaleDraw->scaleDiv()); + scaleDraw->setScaleDiv( d_data->scaleDraw->scaleDiv() ); delete d_data->scaleDraw; d_data->scaleDraw = scaleDraw; @@ -244,32 +302,27 @@ const QwtAbstractScaleDraw *QwtAbstractScale::abstractScaleDraw() const return d_data->scaleDraw; } -void QwtAbstractScale::updateScaleDraw() -{ - rescale( d_data->scaleDraw->scaleDiv().lBound(), - d_data->scaleDraw->scaleDiv().hBound(), d_data->stepSize); -} - /*! \brief Set a scale engine - The scale engine is responsible for calculating the scale division, - and in case of auto scaling how to align the scale. + The scale engine is responsible for calculating the scale division + and provides a transformation between scale and widget coordinates. scaleEngine has to be created with new and will be deleted in - ~QwtAbstractScale or the next call of setScaleEngine. + the destructor or the next call of setScaleEngine. */ -void QwtAbstractScale::setScaleEngine(QwtScaleEngine *scaleEngine) +void QwtAbstractScale::setScaleEngine( QwtScaleEngine *scaleEngine ) { - if ( scaleEngine != NULL && scaleEngine != d_data->scaleEngine ) { + if ( scaleEngine != NULL && scaleEngine != d_data->scaleEngine ) + { delete d_data->scaleEngine; d_data->scaleEngine = scaleEngine; } } /*! - \return Scale engine - \sa setScaleEngine() + \return Scale engine + \sa setScaleEngine() */ const QwtScaleEngine *QwtAbstractScale::scaleEngine() const { @@ -277,8 +330,8 @@ const QwtScaleEngine *QwtAbstractScale::scaleEngine() const } /*! - \return Scale engine - \sa setScaleEngine() + \return Scale engine + \sa setScaleEngine() */ QwtScaleEngine *QwtAbstractScale::scaleEngine() { @@ -286,18 +339,111 @@ QwtScaleEngine *QwtAbstractScale::scaleEngine() } /*! - \brief Notify changed scale + \return Scale boundaries and positions of the ticks - Dummy empty implementation, intended to be overloaded by derived classes -*/ -void QwtAbstractScale::scaleChange() + The scale division might have been assigned explicitly + or calculated implicitly by rescale(). + */ +const QwtScaleDiv &QwtAbstractScale::scaleDiv() const { + return d_data->scaleDraw->scaleDiv(); } /*! - \return abstractScaleDraw()->scaleMap() -*/ + \return Map to translate between scale and widget coordinates + */ const QwtScaleMap &QwtAbstractScale::scaleMap() const { return d_data->scaleDraw->scaleMap(); } + +/*! + Translate a scale value into a widget coordinate + + \param value Scale value + \return Corresponding widget coordinate for value + \sa scaleMap(), invTransform() + */ +int QwtAbstractScale::transform( double value ) const +{ + return qRound( d_data->scaleDraw->scaleMap().transform( value ) ); +} + +/*! + Translate a widget coordinate into a scale value + + \param value Widget coordinate + \return Corresponding scale coordinate for value + \sa scaleMap(), transform() + */ +double QwtAbstractScale::invTransform( int value ) const +{ + return d_data->scaleDraw->scaleMap().invTransform( value ); +} + +/*! + \return True, when the scale is increasing in opposite direction + to the widget coordinates + */ +bool QwtAbstractScale::isInverted() const +{ + return d_data->scaleDraw->scaleMap().isInverting(); +} + +/*! + \return The boundary with the smaller value + \sa maximum(), lowerBound(), upperBound() + */ +double QwtAbstractScale::minimum() const +{ + return qMin( d_data->scaleDraw->scaleDiv().lowerBound(), + d_data->scaleDraw->scaleDiv().upperBound() ); +} + +/*! + \return The boundary with the larger value + \sa minimum(), lowerBound(), upperBound() + */ +double QwtAbstractScale::maximum() const +{ + return qMax( d_data->scaleDraw->scaleDiv().lowerBound(), + d_data->scaleDraw->scaleDiv().upperBound() ); +} + +//! Notify changed scale +void QwtAbstractScale::scaleChange() +{ +} + +/*! + Recalculate the scale division and update the scale. + + \param lowerBound Lower limit of the scale interval + \param upperBound Upper limit of the scale interval + \param stepSize Major step size + + \sa scaleChange() +*/ +void QwtAbstractScale::rescale( + double lowerBound, double upperBound, double stepSize ) +{ + const QwtScaleDiv scaleDiv = d_data->scaleEngine->divideScale( + lowerBound, upperBound, d_data->maxMajor, d_data->maxMinor, stepSize ); + + if ( scaleDiv != d_data->scaleDraw->scaleDiv() ) + { +#if 1 + d_data->scaleDraw->setTransformation( + d_data->scaleEngine->transformation() ); +#endif + + d_data->scaleDraw->setScaleDiv( scaleDiv ); + scaleChange(); + } +} + +void QwtAbstractScale::updateScaleDraw() +{ + rescale( d_data->scaleDraw->scaleDiv().lowerBound(), + d_data->scaleDraw->scaleDiv().upperBound(), d_data->stepSize ); +} diff --git a/libs/qwt/qwt_abstract_scale.h b/libs/qwt/qwt_abstract_scale.h index dac0aa3f81..4ed6616aa8 100644 --- a/libs/qwt/qwt_abstract_scale.h +++ b/libs/qwt/qwt_abstract_scale.h @@ -11,50 +11,85 @@ #define QWT_ABSTRACT_SCALE_H #include "qwt_global.h" +#include <qwidget.h> class QwtScaleEngine; class QwtAbstractScaleDraw; class QwtScaleDiv; class QwtScaleMap; -class QwtDoubleInterval; +class QwtInterval; /*! - \brief An abstract base class for classes containing a scale + \brief An abstract base class for widgets having a scale - QwtAbstractScale is used to provide classes with a QwtScaleDraw, - and a QwtScaleDiv. The QwtScaleDiv might be set explicitely - or calculated by a QwtScaleEngine. + The scale of an QwtAbstractScale is determined by a QwtScaleDiv + definition, that contains the boundaries and the ticks of the scale. + The scale is painted using a QwtScaleDraw object. + + The scale division might be assigned explicitly - but usually + it is calculated from the boundaries using a QwtScaleEngine. + + The scale engine also decides the type of transformation of the scale + ( linear, logarithmic ... ). */ -class QWT_EXPORT QwtAbstractScale +class QWT_EXPORT QwtAbstractScale: public QWidget { + Q_OBJECT + + Q_PROPERTY( double lowerBound READ lowerBound WRITE setLowerBound ) + Q_PROPERTY( double upperBound READ upperBound WRITE setUpperBound ) + + Q_PROPERTY( int scaleMaxMajor READ scaleMaxMajor WRITE setScaleMaxMajor ) + Q_PROPERTY( int scaleMaxMinor READ scaleMaxMinor WRITE setScaleMaxMinor ) + + Q_PROPERTY( double scaleStepSize READ scaleStepSize WRITE setScaleStepSize ) + public: - QwtAbstractScale(); + QwtAbstractScale( QWidget *parent = NULL ); virtual ~QwtAbstractScale(); - void setScale(double vmin, double vmax, double step = 0.0); - void setScale(const QwtDoubleInterval &, double step = 0.0); - void setScale(const QwtScaleDiv &s); + void setScale( double lowerBound, double upperBound ); + void setScale( const QwtInterval & ); + void setScale( const QwtScaleDiv & ); + + const QwtScaleDiv& scaleDiv() const; - void setAutoScale(); - bool autoScale() const; + void setLowerBound( double value ); + double lowerBound() const; - void setScaleMaxMajor( int ticks); + void setUpperBound( double value ); + double upperBound() const; + + void setScaleStepSize( double stepSize ); + double scaleStepSize() const; + + void setScaleMaxMajor( int ticks ); int scaleMaxMinor() const; - void setScaleMaxMinor( int ticks); + void setScaleMaxMinor( int ticks ); int scaleMaxMajor() const; - void setScaleEngine(QwtScaleEngine *); + void setScaleEngine( QwtScaleEngine * ); const QwtScaleEngine *scaleEngine() const; QwtScaleEngine *scaleEngine(); + int transform( double ) const; + double invTransform( int ) const; + + bool isInverted() const; + + double minimum() const; + double maximum() const; + const QwtScaleMap &scaleMap() const; protected: - void rescale(double vmin, double vmax, double step = 0.0); + void rescale( double lowerBound, + double upperBound, double stepSize ); + + void setAbstractScaleDraw( QwtAbstractScaleDraw * ); - void setAbstractScaleDraw(QwtAbstractScaleDraw *); const QwtAbstractScaleDraw *abstractScaleDraw() const; QwtAbstractScaleDraw *abstractScaleDraw(); diff --git a/libs/qwt/qwt_abstract_scale_draw.cpp b/libs/qwt/qwt_abstract_scale_draw.cpp index b04f2f5eb4..2011733039 100644 --- a/libs/qwt/qwt_abstract_scale_draw.cpp +++ b/libs/qwt/qwt_abstract_scale_draw.cpp @@ -7,39 +7,43 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <qpainter.h> -#include <qpalette.h> -#include <qmap.h> -#include <qlocale.h> +#include "qwt_abstract_scale_draw.h" #include "qwt_math.h" #include "qwt_text.h" #include "qwt_painter.h" #include "qwt_scale_map.h" -#include "qwt_scale_draw.h" +#include <qpainter.h> +#include <qpalette.h> +#include <qmap.h> +#include <qlocale.h> class QwtAbstractScaleDraw::PrivateData { public: PrivateData(): - components(Backbone | Ticks | Labels), - spacing(4), - minExtent(0) { - tickLength[QwtScaleDiv::MinorTick] = 4; - tickLength[QwtScaleDiv::MediumTick] = 6; - tickLength[QwtScaleDiv::MajorTick] = 8; + spacing( 4.0 ), + penWidth( 0 ), + minExtent( 0.0 ) + { + components = QwtAbstractScaleDraw::Backbone + | QwtAbstractScaleDraw::Ticks + | QwtAbstractScaleDraw::Labels; + + tickLength[QwtScaleDiv::MinorTick] = 4.0; + tickLength[QwtScaleDiv::MediumTick] = 6.0; + tickLength[QwtScaleDiv::MajorTick] = 8.0; } - int components; + ScaleComponents components; QwtScaleMap map; - QwtScaleDiv scldiv; + QwtScaleDiv scaleDiv; - int spacing; - int tickLength[QwtScaleDiv::NTickTypes]; + double spacing; + double tickLength[QwtScaleDiv::NTickTypes]; + int penWidth; - int minExtent; + double minExtent; QMap<double, QwtText> labelCache; }; @@ -56,23 +60,11 @@ QwtAbstractScaleDraw::QwtAbstractScaleDraw() d_data = new QwtAbstractScaleDraw::PrivateData; } -//! Copy constructor -QwtAbstractScaleDraw::QwtAbstractScaleDraw(const QwtAbstractScaleDraw &other) -{ - d_data = new QwtAbstractScaleDraw::PrivateData(*other.d_data); -} - //! Destructor QwtAbstractScaleDraw::~QwtAbstractScaleDraw() { delete d_data; } -//! Assignment operator -QwtAbstractScaleDraw &QwtAbstractScaleDraw::operator=(const QwtAbstractScaleDraw &other) -{ - *d_data = *other.d_data; - return *this; -} /*! En/Disable a component of the scale @@ -80,10 +72,10 @@ QwtAbstractScaleDraw &QwtAbstractScaleDraw::operator=(const QwtAbstractScaleDraw \param component Scale component \param enable On/Off - \sa QwtAbstractScaleDraw::hasComponent + \sa hasComponent() */ void QwtAbstractScaleDraw::enableComponent( - ScaleComponent component, bool enable) + ScaleComponent component, bool enable ) { if ( enable ) d_data->components |= component; @@ -93,21 +85,24 @@ void QwtAbstractScaleDraw::enableComponent( /*! Check if a component is enabled - \sa QwtAbstractScaleDraw::enableComponent + + \param component Component type + \return true, when component is enabled + \sa enableComponent() */ -bool QwtAbstractScaleDraw::hasComponent(ScaleComponent component) const +bool QwtAbstractScaleDraw::hasComponent( ScaleComponent component ) const { - return (d_data->components & component); + return ( d_data->components & component ); } /*! Change the scale division - \param sd New scale division + \param scaleDiv New scale division */ -void QwtAbstractScaleDraw::setScaleDiv(const QwtScaleDiv &sd) +void QwtAbstractScaleDraw::setScaleDiv( const QwtScaleDiv &scaleDiv ) { - d_data->scldiv = sd; - d_data->map.setScaleInterval(sd.lBound(), sd.hBound()); + d_data->scaleDiv = scaleDiv; + d_data->map.setScaleInterval( scaleDiv.lowerBound(), scaleDiv.upperBound() ); d_data->labelCache.clear(); } @@ -116,13 +111,13 @@ void QwtAbstractScaleDraw::setScaleDiv(const QwtScaleDiv &sd) \param transformation New scale transformation */ void QwtAbstractScaleDraw::setTransformation( - QwtScaleTransformation *transformation) + QwtTransform *transformation ) { - d_data->map.setTransformation(transformation); + d_data->map.setTransformation( transformation ); } //! \return Map how to translate between scale and pixel values -const QwtScaleMap &QwtAbstractScaleDraw::map() const +const QwtScaleMap &QwtAbstractScaleDraw::scaleMap() const { return d_data->map; } @@ -136,22 +131,31 @@ QwtScaleMap &QwtAbstractScaleDraw::scaleMap() //! \return scale division const QwtScaleDiv& QwtAbstractScaleDraw::scaleDiv() const { - return d_data->scldiv; + return d_data->scaleDiv; } -#if QT_VERSION < 0x040000 /*! - \brief Draw the scale + \brief Specify the width of the scale pen + \param width Pen width + \sa penWidth() +*/ +void QwtAbstractScaleDraw::setPenWidth( int width ) +{ + if ( width < 0 ) + width = 0; - \param painter The painter + if ( width != d_data->penWidth ) + d_data->penWidth = width; +} - \param colorGroup Color group, text color is used for the labels, - foreground color for ticks and backbone +/*! + \return Scale pen width + \sa setPenWidth() */ -void QwtAbstractScaleDraw::draw(QPainter *painter, - const QColorGroup& colorGroup) const - -#else +int QwtAbstractScaleDraw::penWidth() const +{ + return d_data->penWidth; +} /*! \brief Draw the scale @@ -161,70 +165,75 @@ void QwtAbstractScaleDraw::draw(QPainter *painter, \param palette Palette, text color is used for the labels, foreground color for ticks and backbone */ -void QwtAbstractScaleDraw::draw(QPainter *painter, - const QPalette& palette) const -#endif +void QwtAbstractScaleDraw::draw( QPainter *painter, + const QPalette& palette ) const { - if ( hasComponent(QwtAbstractScaleDraw::Labels) ) { - painter->save(); + painter->save(); -#if QT_VERSION < 0x040000 - painter->setPen(colorGroup.text()); // ignore pen style -#else - painter->setPen(palette.color(QPalette::Text)); // ignore pen style -#endif + QPen pen = painter->pen(); + pen.setWidth( d_data->penWidth ); + pen.setCosmetic( false ); + painter->setPen( pen ); - const QwtValueList &majorTicks = - d_data->scldiv.ticks(QwtScaleDiv::MajorTick); + if ( hasComponent( QwtAbstractScaleDraw::Labels ) ) + { + painter->save(); + painter->setPen( palette.color( QPalette::Text ) ); // ignore pen style + + const QList<double> &majorTicks = + d_data->scaleDiv.ticks( QwtScaleDiv::MajorTick ); - for (int i = 0; i < (int)majorTicks.count(); i++) { + for ( int i = 0; i < majorTicks.count(); i++ ) + { const double v = majorTicks[i]; - if ( d_data->scldiv.contains(v) ) - drawLabel(painter, majorTicks[i]); + if ( d_data->scaleDiv.contains( v ) ) + drawLabel( painter, v ); } painter->restore(); } - if ( hasComponent(QwtAbstractScaleDraw::Ticks) ) { + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) + { painter->save(); QPen pen = painter->pen(); -#if QT_VERSION < 0x040000 - pen.setColor(colorGroup.foreground()); -#else - pen.setColor(palette.color(QPalette::Foreground)); -#endif - painter->setPen(pen); + pen.setColor( palette.color( QPalette::WindowText ) ); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); for ( int tickType = QwtScaleDiv::MinorTick; - tickType < QwtScaleDiv::NTickTypes; tickType++ ) { - const QwtValueList &ticks = d_data->scldiv.ticks(tickType); - for (int i = 0; i < (int)ticks.count(); i++) { + tickType < QwtScaleDiv::NTickTypes; tickType++ ) + { + const QList<double> &ticks = d_data->scaleDiv.ticks( tickType ); + for ( int i = 0; i < ticks.count(); i++ ) + { const double v = ticks[i]; - if ( d_data->scldiv.contains(v) ) - drawTick(painter, v, d_data->tickLength[tickType]); + if ( d_data->scaleDiv.contains( v ) ) + drawTick( painter, v, d_data->tickLength[tickType] ); } } painter->restore(); } - if ( hasComponent(QwtAbstractScaleDraw::Backbone) ) { + if ( hasComponent( QwtAbstractScaleDraw::Backbone ) ) + { painter->save(); QPen pen = painter->pen(); -#if QT_VERSION < 0x040000 - pen.setColor(colorGroup.foreground()); -#else - pen.setColor(palette.color(QPalette::Foreground)); -#endif - painter->setPen(pen); + pen.setColor( palette.color( QPalette::WindowText ) ); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); - drawBackbone(painter); + drawBackbone( painter ); painter->restore(); } + + painter->restore(); } /*! @@ -235,9 +244,9 @@ void QwtAbstractScaleDraw::draw(QPainter *painter, \param spacing Spacing - \sa QwtAbstractScaleDraw::spacing + \sa spacing() */ -void QwtAbstractScaleDraw::setSpacing(int spacing) +void QwtAbstractScaleDraw::setSpacing( double spacing ) { if ( spacing < 0 ) spacing = 0; @@ -251,9 +260,10 @@ void QwtAbstractScaleDraw::setSpacing(int spacing) The spacing is the distance between ticks and labels. The default spacing is 4 pixels. - \sa QwtAbstractScaleDraw::setSpacing + \return Spacing + \sa setSpacing() */ -int QwtAbstractScaleDraw::spacing() const +double QwtAbstractScaleDraw::spacing() const { return d_data->spacing; } @@ -261,7 +271,7 @@ int QwtAbstractScaleDraw::spacing() const /*! \brief Set a minimum for the extent - The extent is calculated from the coomponents of the + The extent is calculated from the components of the scale draw. In situations, where the labels are changing and the layout depends on the extent (f.e scrolling a scale), setting an upper limit as minimum extent will @@ -271,19 +281,20 @@ int QwtAbstractScaleDraw::spacing() const \sa extent(), minimumExtent() */ -void QwtAbstractScaleDraw::setMinimumExtent(int minExtent) +void QwtAbstractScaleDraw::setMinimumExtent( double minExtent ) { - if ( minExtent < 0 ) - minExtent = 0; + if ( minExtent < 0.0 ) + minExtent = 0.0; d_data->minExtent = minExtent; } /*! Get the minimum extent + \return Minimum extent \sa extent(), setMinimumExtent() */ -int QwtAbstractScaleDraw::minimumExtent() const +double QwtAbstractScaleDraw::minimumExtent() const { return d_data->minExtent; } @@ -297,33 +308,33 @@ int QwtAbstractScaleDraw::minimumExtent() const \warning the length is limited to [0..1000] */ void QwtAbstractScaleDraw::setTickLength( - QwtScaleDiv::TickType tickType, int length) + QwtScaleDiv::TickType tickType, double length ) { if ( tickType < QwtScaleDiv::MinorTick || - tickType > QwtScaleDiv::MajorTick ) { + tickType > QwtScaleDiv::MajorTick ) + { return; } - if ( length < 0 ) - length = 0; + if ( length < 0.0 ) + length = 0.0; - const int maxTickLen = 1000; + const double maxTickLen = 1000.0; if ( length > maxTickLen ) - length = 1000; + length = maxTickLen; d_data->tickLength[tickType] = length; } /*! - Return the length of the ticks - - \sa QwtAbstractScaleDraw::setTickLength, - QwtAbstractScaleDraw::majTickLength + \return Length of the ticks + \sa setTickLength(), maxTickLength() */ -int QwtAbstractScaleDraw::tickLength(QwtScaleDiv::TickType tickType) const +double QwtAbstractScaleDraw::tickLength( QwtScaleDiv::TickType tickType ) const { if ( tickType < QwtScaleDiv::MinorTick || - tickType > QwtScaleDiv::MajorTick ) { + tickType > QwtScaleDiv::MajorTick ) + { return 0; } @@ -331,27 +342,34 @@ int QwtAbstractScaleDraw::tickLength(QwtScaleDiv::TickType tickType) const } /*! - The same as QwtAbstractScaleDraw::tickLength(QwtScaleDiv::MajorTick). + \return Length of the longest tick + + Useful for layout calculations + \sa tickLength(), setTickLength() */ -int QwtAbstractScaleDraw::majTickLength() const +double QwtAbstractScaleDraw::maxTickLength() const { - return d_data->tickLength[QwtScaleDiv::MajorTick]; + double length = 0.0; + for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) + length = qMax( length, d_data->tickLength[i] ); + + return length; } /*! \brief Convert a value into its representing label The value is converted to a plain text using - QLocale::system().toString(value). + QLocale().toString(value). This method is often overloaded by applications to have individual labels. \param value Value \return Label string. */ -QwtText QwtAbstractScaleDraw::label(double value) const +QwtText QwtAbstractScaleDraw::label( double value ) const { - return QLocale::system().toString(value); + return QLocale().toString( value ); } /*! @@ -368,28 +386,29 @@ QwtText QwtAbstractScaleDraw::label(double value) const \return Tick label */ const QwtText &QwtAbstractScaleDraw::tickLabel( - const QFont &font, double value) const + const QFont &font, double value ) const { - QMap<double, QwtText>::const_iterator it = d_data->labelCache.find(value); - if ( it == d_data->labelCache.end() ) { - QwtText lbl = label(value); - lbl.setRenderFlags(0); - lbl.setLayoutAttribute(QwtText::MinimumLayout); + QMap<double, QwtText>::const_iterator it = d_data->labelCache.find( value ); + if ( it == d_data->labelCache.end() ) + { + QwtText lbl = label( value ); + lbl.setRenderFlags( 0 ); + lbl.setLayoutAttribute( QwtText::MinimumLayout ); - (void)lbl.textSize(font); // initialize the internal cache + ( void )lbl.textSize( font ); // initialize the internal cache - it = d_data->labelCache.insert(value, lbl); + it = d_data->labelCache.insert( value, lbl ); } - return (*it); + return ( *it ); } /*! - Invalidate the cache used by QwtAbstractScaleDraw::tickLabel + Invalidate the cache used by tickLabel() The cache is invalidated, when a new QwtScaleDiv is set. If the labels need to be changed. while the same QwtScaleDiv is set, - QwtAbstractScaleDraw::invalidateCache needs to be called manually. + invalidateCache() needs to be called manually. */ void QwtAbstractScaleDraw::invalidateCache() { diff --git a/libs/qwt/qwt_abstract_scale_draw.h b/libs/qwt/qwt_abstract_scale_draw.h index a2b7895f4c..d0f1ec3c3b 100644 --- a/libs/qwt/qwt_abstract_scale_draw.h +++ b/libs/qwt/qwt_abstract_scale_draw.h @@ -14,15 +14,10 @@ #include "qwt_scale_div.h" #include "qwt_text.h" - -#if QT_VERSION < 0x040000 -class QColorGroup; -#else class QPalette; -#endif class QPainter; class QFont; -class QwtScaleTransformation; +class QwtTransform; class QwtScaleMap; /*! @@ -31,8 +26,7 @@ class QwtScaleMap; QwtAbstractScaleDraw can be used to draw linear or logarithmic scales. After a scale division has been specified as a QwtScaleDiv object - using QwtAbstractScaleDraw::setScaleDiv(const QwtScaleDiv &s), - the scale can be drawn with the QwtAbstractScaleDraw::draw() member. + using setScaleDiv(), the scale can be drawn with the draw() member. */ class QWT_EXPORT QwtAbstractScaleDraw { @@ -40,66 +34,66 @@ public: /*! Components of a scale + \sa enableComponent(), hasComponent + */ + enum ScaleComponent + { + //! Backbone = the line where the ticks are located + Backbone = 0x01, - - Backbone - - Ticks - - Labels - - \sa QwtAbstractScaleDraw::enableComponent, - QwtAbstractScaleDraw::hasComponent - */ + //! Ticks + Ticks = 0x02, - enum ScaleComponent { - Backbone = 1, - Ticks = 2, - Labels = 4 + //! Labels + Labels = 0x04 }; + //! Scale components + typedef QFlags<ScaleComponent> ScaleComponents; + QwtAbstractScaleDraw(); - QwtAbstractScaleDraw( const QwtAbstractScaleDraw & ); virtual ~QwtAbstractScaleDraw(); - QwtAbstractScaleDraw &operator=(const QwtAbstractScaleDraw &); - - void setScaleDiv(const QwtScaleDiv &s); + void setScaleDiv( const QwtScaleDiv &s ); const QwtScaleDiv& scaleDiv() const; - void setTransformation(QwtScaleTransformation *); - const QwtScaleMap &map() const; + void setTransformation( QwtTransform * ); + const QwtScaleMap &scaleMap() const; + QwtScaleMap &scaleMap(); - void enableComponent(ScaleComponent, bool enable = true); - bool hasComponent(ScaleComponent) const; + void enableComponent( ScaleComponent, bool enable = true ); + bool hasComponent( ScaleComponent ) const; - void setTickLength(QwtScaleDiv::TickType, int length); - int tickLength(QwtScaleDiv::TickType) const; - int majTickLength() const; + void setTickLength( QwtScaleDiv::TickType, double length ); + double tickLength( QwtScaleDiv::TickType ) const; + double maxTickLength() const; - void setSpacing(int margin); - int spacing() const; + void setSpacing( double margin ); + double spacing() const; -#if QT_VERSION < 0x040000 - virtual void draw(QPainter *, const QColorGroup &) const; -#else - virtual void draw(QPainter *, const QPalette &) const; -#endif + void setPenWidth( int width ); + int penWidth() const; + + virtual void draw( QPainter *, const QPalette & ) const; - virtual QwtText label(double) const; + virtual QwtText label( double ) const; /*! Calculate the extent - The extent is the distcance from the baseline to the outermost + The extent is the distance from the baseline to the outermost pixel of the scale draw in opposite to its orientation. It is at least minimumExtent() pixels. + \param font Font used for drawing the tick labels + \return Number of pixels + \sa setMinimumExtent(), minimumExtent() */ - virtual int extent(const QPen &, const QFont &) const = 0; + virtual double extent( const QFont &font ) const = 0; - void setMinimumExtent(int); - int minimumExtent() const; - - QwtScaleMap &scaleMap(); + void setMinimumExtent( double ); + double minimumExtent() const; protected: /*! @@ -107,11 +101,11 @@ protected: \param painter Painter \param value Value of the tick - \param len Lenght of the tick + \param len Length of the tick \sa drawBackbone(), drawLabel() */ - virtual void drawTick(QPainter *painter, double value, int len) const = 0; + virtual void drawTick( QPainter *painter, double value, double len ) const = 0; /*! Draws the baseline of the scale @@ -119,7 +113,7 @@ protected: \sa drawTick(), drawLabel() */ - virtual void drawBackbone(QPainter *painter) const = 0; + virtual void drawBackbone( QPainter *painter ) const = 0; /*! Draws the label for a major scale tick @@ -127,19 +121,21 @@ protected: \param painter Painter \param value Value - \sa drawTick, drawBackbone + \sa drawTick(), drawBackbone() */ - virtual void drawLabel(QPainter *painter, double value) const = 0; + virtual void drawLabel( QPainter *painter, double value ) const = 0; void invalidateCache(); - const QwtText &tickLabel(const QFont &, double value) const; + const QwtText &tickLabel( const QFont &, double value ) const; private: - int operator==(const QwtAbstractScaleDraw &) const; - int operator!=(const QwtAbstractScaleDraw &) const; + QwtAbstractScaleDraw( const QwtAbstractScaleDraw & ); + QwtAbstractScaleDraw &operator=( const QwtAbstractScaleDraw & ); class PrivateData; PrivateData *d_data; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtAbstractScaleDraw::ScaleComponents ) + #endif diff --git a/libs/qwt/qwt_abstract_slider.cpp b/libs/qwt/qwt_abstract_slider.cpp index 0f4dcb2bb2..7bac22e613 100644 --- a/libs/qwt/qwt_abstract_slider.cpp +++ b/libs/qwt/qwt_abstract_slider.cpp @@ -7,84 +7,149 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qevent.h> -#include <qdatetime.h> #include "qwt_abstract_slider.h" +#include "qwt_abstract_scale_draw.h" #include "qwt_math.h" +#include "qwt_scale_map.h" +#include <qevent.h> -#ifndef WHEEL_DELTA -#define WHEEL_DELTA 120 +#if QT_VERSION < 0x040601 +#define qFabs(x) ::fabs(x) #endif +static double qwtAlignToScaleDiv( + const QwtAbstractSlider *slider, double value ) +{ + const QwtScaleDiv &sd = slider->scaleDiv(); + + const int tValue = slider->transform( value ); + + if ( tValue == slider->transform( sd.lowerBound() ) ) + return sd.lowerBound(); + + if ( tValue == slider->transform( sd.lowerBound() ) ) + return sd.upperBound(); + + for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) + { + const QList<double> ticks = sd.ticks( i ); + for ( int j = 0; j < ticks.size(); j++ ) + { + if ( slider->transform( ticks[ j ] ) == tValue ) + return ticks[ j ]; + } + } + + return value; +} + class QwtAbstractSlider::PrivateData { public: PrivateData(): - scrollMode(ScrNone), - mouseOffset(0.0), - tracking(true), - tmrID(0), - updTime(150), - mass(0.0), - readOnly(false) { + isScrolling( false ), + isTracking( true ), + pendingValueChanged( false ), + readOnly( false ), + totalSteps( 100 ), + singleSteps( 1 ), + pageSteps( 10 ), + stepAlignment( true ), + isValid( false ), + value( 0.0 ), + wrapping( false ), + invertedControls( false ) + { } - int scrollMode; - double mouseOffset; - int direction; - int tracking; - - int tmrID; - int updTime; - int timerTick; - QTime time; - double speed; - double mass; - Qt::Orientation orientation; + bool isScrolling; + bool isTracking; + bool pendingValueChanged; + bool readOnly; + + uint totalSteps; + uint singleSteps; + uint pageSteps; + bool stepAlignment; + + bool isValid; + double value; + + bool wrapping; + bool invertedControls; }; /*! - \brief Constructor + \brief Constructor + + The scale is initialized to [0.0, 100.0], the + number of steps is set to 100 with 1 and 10 and single + an page step sizes. Step alignment is enabled. + + The initial value is invalid. - \param orientation Orientation - \param parent Parent widget + \param parent Parent widget */ -QwtAbstractSlider::QwtAbstractSlider( - Qt::Orientation orientation, QWidget *parent): - QWidget(parent, NULL) +QwtAbstractSlider::QwtAbstractSlider( QWidget *parent ): + QwtAbstractScale( parent ) { d_data = new QwtAbstractSlider::PrivateData; - d_data->orientation = orientation; -#if QT_VERSION >= 0x040000 - using namespace Qt; -#endif - setFocusPolicy(TabFocus); + setScale( 0.0, 100.0 ); + setFocusPolicy( Qt::StrongFocus ); } //! Destructor QwtAbstractSlider::~QwtAbstractSlider() { - if(d_data->tmrID) - killTimer(d_data->tmrID); - delete d_data; } +/*! + Set the value to be valid/invalid + + \param on When true, the value is invalidated + + \sa setValue() +*/ +void QwtAbstractSlider::setValid( bool on ) +{ + if ( on != d_data->isValid ) + { + d_data->isValid = on; + sliderChange(); + + Q_EMIT valueChanged( d_data->value ); + } +} + +//! \return True, when the value is invalid +bool QwtAbstractSlider::isValid() const +{ + return d_data->isValid; +} + /*! En/Disable read only mode In read only mode the slider can't be controlled by mouse or keyboard. - \param readOnly Enables in case of true + \param on Enables in case of true \sa isReadOnly() + + \warning The focus policy is set to Qt::StrongFocus or Qt::NoFocus */ -void QwtAbstractSlider::setReadOnly(bool readOnly) +void QwtAbstractSlider::setReadOnly( bool on ) { - d_data->readOnly = readOnly; - update(); + if ( d_data->readOnly != on ) + { + d_data->readOnly = on; + setFocusPolicy( on ? Qt::StrongFocus : Qt::NoFocus ); + + update(); + } } /*! @@ -100,452 +165,658 @@ bool QwtAbstractSlider::isReadOnly() const } /*! - \brief Set the orientation. - \param o Orientation. Allowed values are - Qt::Horizontal and Qt::Vertical. -*/ -void QwtAbstractSlider::setOrientation(Qt::Orientation o) -{ - d_data->orientation = o; -} + \brief Enables or disables tracking. -/*! - \return Orientation - \sa setOrientation() -*/ -Qt::Orientation QwtAbstractSlider::orientation() const -{ - return d_data->orientation; -} + If tracking is enabled, the slider emits the valueChanged() + signal while the movable part of the slider is being dragged. + If tracking is disabled, the slider emits the valueChanged() signal + only when the user releases the slider. -//! Stop updating if automatic scrolling is active + Tracking is enabled by default. + \param on \c true (enable) or \c false (disable) tracking. -void QwtAbstractSlider::stopMoving() + \sa isTracking(), sliderMoved() +*/ +void QwtAbstractSlider::setTracking( bool on ) { - if(d_data->tmrID) { - killTimer(d_data->tmrID); - d_data->tmrID = 0; - } + d_data->isTracking = on; } /*! - \brief Specify the update interval for automatic scrolling - \param t update interval in milliseconds - \sa getScrollMode() + \return True, when tracking has been enabled + \sa setTracking() */ -void QwtAbstractSlider::setUpdateTime(int t) +bool QwtAbstractSlider::isTracking() const { - if (t < 50) - t = 50; - d_data->updTime = t; + return d_data->isTracking; } - -//! Mouse press event handler -void QwtAbstractSlider::mousePressEvent(QMouseEvent *e) +/*! + Mouse press event handler + \param event Mouse event +*/ +void QwtAbstractSlider::mousePressEvent( QMouseEvent *event ) { - if ( isReadOnly() ) { - e->ignore(); + if ( isReadOnly() ) + { + event->ignore(); return; } - if ( !isValid() ) - return; - - const QPoint &p = e->pos(); - d_data->timerTick = 0; - - getScrollMode(p, d_data->scrollMode, d_data->direction); - stopMoving(); + if ( !d_data->isValid || lowerBound() == upperBound() ) + return; - switch(d_data->scrollMode) { - case ScrPage: - case ScrTimer: - d_data->mouseOffset = 0; - d_data->tmrID = startTimer(qwtMax(250, 2 * d_data->updTime)); - break; + d_data->isScrolling = isScrollPosition( event->pos() ); - case ScrMouse: - d_data->time.start(); - d_data->speed = 0; - d_data->mouseOffset = getValue(p) - value(); - emit sliderPressed(); - break; + if ( d_data->isScrolling ) + { + d_data->pendingValueChanged = false; - default: - d_data->mouseOffset = 0; - d_data->direction = 0; - break; + Q_EMIT sliderPressed(); } } - -//! Emits a valueChanged() signal if necessary -void QwtAbstractSlider::buttonReleased() -{ - if ((!d_data->tracking) || (value() != prevValue())) - emit valueChanged(value()); -} - - -//! Mouse Release Event handler -void QwtAbstractSlider::mouseReleaseEvent(QMouseEvent *e) +/*! + Mouse Move Event handler + \param event Mouse event +*/ +void QwtAbstractSlider::mouseMoveEvent( QMouseEvent *event ) { - if ( isReadOnly() ) { - e->ignore(); + if ( isReadOnly() ) + { + event->ignore(); return; } - if ( !isValid() ) - return; - const double inc = step(); - - switch(d_data->scrollMode) { - case ScrMouse: { - setPosition(e->pos()); - d_data->direction = 0; - d_data->mouseOffset = 0; - if (d_data->mass > 0.0) { - const int ms = d_data->time.elapsed(); - if ((fabs(d_data->speed) > 0.0) && (ms < 50)) - d_data->tmrID = startTimer(d_data->updTime); - } else { - d_data->scrollMode = ScrNone; - buttonReleased(); - } - emit sliderReleased(); + if ( d_data->isValid && d_data->isScrolling ) + { + double value = scrolledTo( event->pos() ); + if ( value != d_data->value ) + { + value = boundedValue( value ); - break; - } + if ( d_data->stepAlignment ) + { + value = alignedValue( value ); + } + else + { + value = qwtAlignToScaleDiv( this, value ); + } - case ScrDirect: { - setPosition(e->pos()); - d_data->direction = 0; - d_data->mouseOffset = 0; - d_data->scrollMode = ScrNone; - buttonReleased(); - break; - } + if ( value != d_data->value ) + { + d_data->value = value; - case ScrPage: { - stopMoving(); - if (!d_data->timerTick) - QwtDoubleRange::incPages(d_data->direction); - d_data->timerTick = 0; - buttonReleased(); - d_data->scrollMode = ScrNone; - break; - } + sliderChange(); - case ScrTimer: { - stopMoving(); - if (!d_data->timerTick) - QwtDoubleRange::fitValue(value() + double(d_data->direction) * inc); - d_data->timerTick = 0; - buttonReleased(); - d_data->scrollMode = ScrNone; - break; - } + Q_EMIT sliderMoved( d_data->value ); - default: { - d_data->scrollMode = ScrNone; - buttonReleased(); - } + if ( d_data->isTracking ) + Q_EMIT valueChanged( d_data->value ); + else + d_data->pendingValueChanged = true; + } + } } } - /*! - Move the slider to a specified point, adjust the value - and emit signals if necessary. + Mouse Release Event handler + \param event Mouse event */ -void QwtAbstractSlider::setPosition(const QPoint &p) +void QwtAbstractSlider::mouseReleaseEvent( QMouseEvent *event ) { - QwtDoubleRange::fitValue(getValue(p) - d_data->mouseOffset); -} + if ( isReadOnly() ) + { + event->ignore(); + return; + } + if ( d_data->isScrolling && d_data->isValid ) + { + d_data->isScrolling = false; -/*! - \brief Enables or disables tracking. + if ( d_data->pendingValueChanged ) + Q_EMIT valueChanged( d_data->value ); - If tracking is enabled, the slider emits a - valueChanged() signal whenever its value - changes (the default behaviour). If tracking - is disabled, the value changed() signal will only - be emitted if:<ul> - <li>the user releases the mouse - button and the value has changed or - <li>at the end of automatic scrolling.</ul> - Tracking is enabled by default. - \param enable \c true (enable) or \c false (disable) tracking. -*/ -void QwtAbstractSlider::setTracking(bool enable) -{ - d_data->tracking = enable; + Q_EMIT sliderReleased(); + } } /*! - Mouse Move Event handler - \param e Mouse event + Wheel Event handler + + In/decreases the value by s number of steps. The direction + depends on the invertedControls() property. + + When the control or shift modifier is pressed the wheel delta + ( divided by 120 ) is mapped to an increment according to + pageSteps(). Otherwise it is mapped to singleSteps(). + + \param event Wheel event */ -void QwtAbstractSlider::mouseMoveEvent(QMouseEvent *e) +void QwtAbstractSlider::wheelEvent( QWheelEvent *event ) { - if ( isReadOnly() ) { - e->ignore(); + if ( isReadOnly() ) + { + event->ignore(); return; } - if ( !isValid() ) + if ( !d_data->isValid || d_data->isScrolling ) return; - if (d_data->scrollMode == ScrMouse ) { - setPosition(e->pos()); - if (d_data->mass > 0.0) { - double ms = double(d_data->time.elapsed()); - if (ms < 1.0) - ms = 1.0; - d_data->speed = (exactValue() - exactPrevValue()) / ms; - d_data->time.start(); - } - if (value() != prevValue()) - emit sliderMoved(value()); - } -} + int numSteps = 0; -/*! - Wheel Event handler - \param e Whell event -*/ -void QwtAbstractSlider::wheelEvent(QWheelEvent *e) -{ - if ( isReadOnly() ) { - e->ignore(); - return; + if ( ( event->modifiers() & Qt::ControlModifier) || + ( event->modifiers() & Qt::ShiftModifier ) ) + { + // one page regardless of delta + numSteps = d_data->pageSteps; + if ( event->delta() < 0 ) + numSteps = -numSteps; + } + else + { + const int numTurns = ( event->delta() / 120 ); + numSteps = numTurns * d_data->singleSteps; } - if ( !isValid() ) - return; + if ( d_data->invertedControls ) + numSteps = -numSteps; - int mode = ScrNone, direction = 0; + const double value = incrementedValue( d_data->value, numSteps ); + if ( value != d_data->value ) + { + d_data->value = value; + sliderChange(); - // Give derived classes a chance to say ScrNone - getScrollMode(e->pos(), mode, direction); - if ( mode != ScrNone ) { - const int inc = e->delta() / WHEEL_DELTA; - QwtDoubleRange::incPages(inc); - if (value() != prevValue()) - emit sliderMoved(value()); + Q_EMIT sliderMoved( d_data->value ); + Q_EMIT valueChanged( d_data->value ); } } /*! Handles key events - - Key_Down, KeyLeft\n - Decrement by 1 - - Key_Up, Key_Right\n - Increment by 1 - - \param e Key event + QwtAbstractSlider handles the following keys: + + - Qt::Key_Left\n + Add/Subtract singleSteps() in direction to lowerBound(); + - Qt::Key_Right\n + Add/Subtract singleSteps() in direction to upperBound(); + - Qt::Key_Down\n + Subtract singleSteps(), when invertedControls() is false + - Qt::Key_Up\n + Add singleSteps(), when invertedControls() is false + - Qt::Key_PageDown\n + Subtract pageSteps(), when invertedControls() is false + - Qt::Key_PageUp\n + Add pageSteps(), when invertedControls() is false + - Qt::Key_Home\n + Set the value to the minimum() + - Qt::Key_End\n + Set the value to the maximum() + + \param event Key event \sa isReadOnly() */ -void QwtAbstractSlider::keyPressEvent(QKeyEvent *e) +void QwtAbstractSlider::keyPressEvent( QKeyEvent *event ) { - if ( isReadOnly() ) { - e->ignore(); + if ( isReadOnly() ) + { + event->ignore(); return; } - if ( !isValid() ) + if ( !d_data->isValid || d_data->isScrolling ) return; - int increment = 0; - switch ( e->key() ) { - case Qt::Key_Down: - if ( orientation() == Qt::Vertical ) - increment = -1; - break; - case Qt::Key_Up: - if ( orientation() == Qt::Vertical ) - increment = 1; - break; - case Qt::Key_Left: - if ( orientation() == Qt::Horizontal ) - increment = -1; - break; - case Qt::Key_Right: - if ( orientation() == Qt::Horizontal ) - increment = 1; - break; - default: - ; - e->ignore(); - } + int numSteps = 0; + double value = d_data->value; - if ( increment != 0 ) { - QwtDoubleRange::incValue(increment); - if (value() != prevValue()) - emit sliderMoved(value()); - } -} + switch ( event->key() ) + { + case Qt::Key_Left: + { + numSteps = -static_cast<int>( d_data->singleSteps ); + if ( isInverted() ) + numSteps = -numSteps; -/*! - Qt timer event - \param e Timer event -*/ -void QwtAbstractSlider::timerEvent(QTimerEvent *) -{ - const double inc = step(); - - switch (d_data->scrollMode) { - case ScrMouse: { - if (d_data->mass > 0.0) { - d_data->speed *= exp( - double(d_data->updTime) * 0.001 / d_data->mass ); - const double newval = - exactValue() + d_data->speed * double(d_data->updTime); - QwtDoubleRange::fitValue(newval); - // stop if d_data->speed < one step per second - if (fabs(d_data->speed) < 0.001 * fabs(step())) { - d_data->speed = 0; - stopMoving(); - buttonReleased(); - } + break; + } + case Qt::Key_Right: + { + numSteps = d_data->singleSteps; + if ( isInverted() ) + numSteps = -numSteps; - } else - stopMoving(); - break; - } + break; + } + case Qt::Key_Down: + { + numSteps = -static_cast<int>( d_data->singleSteps ); + if ( d_data->invertedControls ) + numSteps = -numSteps; + break; + } + case Qt::Key_Up: + { + numSteps = d_data->singleSteps; + if ( d_data->invertedControls ) + numSteps = -numSteps; - case ScrPage: { - QwtDoubleRange::incPages(d_data->direction); - if (!d_data->timerTick) { - killTimer(d_data->tmrID); - d_data->tmrID = startTimer(d_data->updTime); + break; } - break; - } - case ScrTimer: { - QwtDoubleRange::fitValue(value() + double(d_data->direction) * inc); - if (!d_data->timerTick) { - killTimer(d_data->tmrID); - d_data->tmrID = startTimer(d_data->updTime); + case Qt::Key_PageUp: + { + numSteps = d_data->pageSteps; + if ( d_data->invertedControls ) + numSteps = -numSteps; + break; + } + case Qt::Key_PageDown: + { + numSteps = -static_cast<int>( d_data->pageSteps ); + if ( d_data->invertedControls ) + numSteps = -numSteps; + break; + } + case Qt::Key_Home: + { + value = minimum(); + break; + } + case Qt::Key_End: + { + value = maximum(); + break; + } + default:; + { + event->ignore(); } - break; } - default: { - stopMoving(); - break; + + if ( numSteps != 0 ) + { + value = incrementedValue( d_data->value, numSteps ); } + + if ( value != d_data->value ) + { + d_data->value = value; + sliderChange(); + + Q_EMIT sliderMoved( d_data->value ); + Q_EMIT valueChanged( d_data->value ); } +} - d_data->timerTick = 1; +/*! + \brief Set the number of steps + + The range of the slider is divided into a number of steps from + which the value increments according to user inputs depend. + + The default setting is 100. + + \param stepCount Number of steps + + \sa totalSteps(), setSingleSteps(), setPageSteps() + */ +void QwtAbstractSlider::setTotalSteps( uint stepCount ) +{ + d_data->totalSteps = stepCount; } +/*! + \return Number of steps + \sa setTotalSteps(), singleSteps(), pageSteps() + */ +uint QwtAbstractSlider::totalSteps() const +{ + return d_data->totalSteps; +} /*! - Notify change of value + \brief Set the number of steps for a single increment - This function can be reimplemented by derived classes - in order to keep track of changes, i.e. repaint the widget. - The default implementation emits a valueChanged() signal - if tracking is enabled. -*/ -void QwtAbstractSlider::valueChange() + The range of the slider is divided into a number of steps from + which the value increments according to user inputs depend. + + \param stepCount Number of steps + + \sa singleSteps(), setTotalSteps(), setPageSteps() + */ + +void QwtAbstractSlider::setSingleSteps( uint stepCount ) { - if (d_data->tracking) - emit valueChanged(value()); -} + d_data->singleSteps = stepCount; +} /*! - \brief Set the slider's mass for flywheel effect. + \return Number of steps + \sa setSingleSteps(), totalSteps(), pageSteps() + */ +uint QwtAbstractSlider::singleSteps() const +{ + return d_data->singleSteps; +} + +/*! + \brief Set the number of steps for a page increment + + The range of the slider is divided into a number of steps from + which the value increments according to user inputs depend. + + \param stepCount Number of steps + + \sa pageSteps(), setTotalSteps(), setSingleSteps() + */ + +void QwtAbstractSlider::setPageSteps( uint stepCount ) +{ + d_data->pageSteps = stepCount; +} - If the slider's mass is greater then 0, it will continue - to move after the mouse button has been released. Its speed - decreases with time at a rate depending on the slider's mass. - A large mass means that it will continue to move for a - long time. +/*! + \return Number of steps + \sa setPageSteps(), totalSteps(), singleSteps() + */ +uint QwtAbstractSlider::pageSteps() const +{ + return d_data->pageSteps; +} - Derived widgets may overload this function to make it public. +/*! + \brief Enable step alignment - \param val New mass in kg + When step alignment is enabled values resulting from slider + movements are aligned to the step size. - \bug If the mass is smaller than 1g, it is set to zero. - The maximal mass is limited to 100kg. - \sa mass() + \param on Enable step alignment when true + \sa stepAlignment() */ -void QwtAbstractSlider::setMass(double val) +void QwtAbstractSlider::setStepAlignment( bool on ) +{ + if ( on != d_data->stepAlignment ) + { + d_data->stepAlignment = on; + } +} + +/*! + \return True, when step alignment is enabled + \sa setStepAlignment() + */ +bool QwtAbstractSlider::stepAlignment() const { - if (val < 0.001) - d_data->mass = 0.0; - else if (val > 100.0) - d_data->mass = 100.0; - else - d_data->mass = val; + return d_data->stepAlignment; } /*! - \return mass - \sa setMass() + Set the slider to the specified value + + \param value New value + \sa setValid(), sliderChange(), valueChanged() */ -double QwtAbstractSlider::mass() const +void QwtAbstractSlider::setValue( double value ) { - return d_data->mass; + value = qBound( minimum(), value, maximum() ); + + const bool changed = ( d_data->value != value ) || !d_data->isValid; + + d_data->value = value; + d_data->isValid = true; + + if ( changed ) + { + sliderChange(); + Q_EMIT valueChanged( d_data->value ); + } } +//! Returns the current value. +double QwtAbstractSlider::value() const +{ + return d_data->value; +} /*! - \brief Move the slider to a specified value + If wrapping is true stepping up from upperBound() value will + take you to the minimum() value and vice versa. - This function can be used to move the slider to a value - which is not an integer multiple of the step size. - \param val new value - \sa fitValue() + \param on En/Disable wrapping + \sa wrapping() */ -void QwtAbstractSlider::setValue(double val) +void QwtAbstractSlider::setWrapping( bool on ) +{ + d_data->wrapping = on; +} + +/*! + \return True, when wrapping is set + \sa setWrapping() + */ +bool QwtAbstractSlider::wrapping() const { - if (d_data->scrollMode == ScrMouse) - stopMoving(); - QwtDoubleRange::setValue(val); + return d_data->wrapping; } +/*! + Invert wheel and key events + + Usually scrolling the mouse wheel "up" and using keys like page + up will increase the slider's value towards its maximum. + When invertedControls() is enabled the value is scrolled + towards its minimum. + + Inverting the controls might be f.e. useful for a vertical slider + with an inverted scale ( decreasing from top to bottom ). + + \param on Invert controls, when true + + \sa invertedControls(), keyEvent(), wheelEvent() + */ +void QwtAbstractSlider::setInvertedControls( bool on ) +{ + d_data->invertedControls = on; +} + +/*! + \return True, when the controls are inverted + \sa setInvertedControls() + */ +bool QwtAbstractSlider::invertedControls() const +{ + return d_data->invertedControls; +} /*! - \brief Set the slider's value to the nearest integer multiple - of the step size. + Increment the slider - \param valeu Value - \sa setValue(), incValue() -*/ -void QwtAbstractSlider::fitValue(double value) + The step size depends on the number of totalSteps() + + \param stepCount Number of steps + \sa setTotalSteps(), incrementedValue() + */ +void QwtAbstractSlider::incrementValue( int stepCount ) { - if (d_data->scrollMode == ScrMouse) - stopMoving(); - QwtDoubleRange::fitValue(value); + const double value = incrementedValue( + d_data->value, stepCount ); + + if ( value != d_data->value ) + { + d_data->value = value; + sliderChange(); + } } /*! - \brief Increment the value by a specified number of steps - \param steps number of steps - \sa setValue() -*/ -void QwtAbstractSlider::incValue(int steps) + Increment a value + + \param value Value + \param stepCount Number of steps + + \return Incremented value + */ +double QwtAbstractSlider::incrementedValue( + double value, int stepCount ) const { - if (d_data->scrollMode == ScrMouse) - stopMoving(); - QwtDoubleRange::incValue(steps); + if ( d_data->totalSteps == 0 ) + return value; + + const QwtTransform *transformation = + scaleMap().transformation(); + + if ( transformation == NULL ) + { + const double range = maximum() - minimum(); + value += stepCount * range / d_data->totalSteps; + } + else + { + QwtScaleMap map = scaleMap(); + map.setPaintInterval( 0, d_data->totalSteps ); + + // we need equidant steps according to + // paint device coordinates + const double range = transformation->transform( maximum() ) + - transformation->transform( minimum() ); + + const double stepSize = range / d_data->totalSteps; + + double v = transformation->transform( value ); + + v = qRound( v / stepSize ) * stepSize; + v += stepCount * range / d_data->totalSteps; + + value = transformation->invTransform( v ); + } + + value = boundedValue( value ); + + if ( d_data->stepAlignment ) + value = alignedValue( value ); + + return value; +} + +double QwtAbstractSlider::boundedValue( double value ) const +{ + const double vmin = minimum(); + const double vmax = maximum(); + + if ( d_data->wrapping && vmin != vmax ) + { + const int fullCircle = 360 * 16; + + const double pd = scaleMap().pDist(); + if ( int( pd / fullCircle ) * fullCircle == pd ) + { + // full circle scales: min and max are the same + const double range = vmax - vmin; + + if ( value < vmin ) + { + value += ::ceil( ( vmin - value ) / range ) * range; + } + else if ( value > vmax ) + { + value -= ::ceil( ( value - vmax ) / range ) * range; + } + } + else + { + if ( value < vmin ) + value = vmax; + else if ( value > vmax ) + value = vmin; + } + } + else + { + value = qBound( vmin, value, vmax ); + } + + return value; } -void QwtAbstractSlider::setMouseOffset(double offset) +double QwtAbstractSlider::alignedValue( double value ) const { - d_data->mouseOffset = offset; + if ( d_data->totalSteps == 0 ) + return value; + + double stepSize; + + if ( scaleMap().transformation() == NULL ) + { + stepSize = ( maximum() - minimum() ) / d_data->totalSteps; + if ( stepSize > 0.0 ) + { + value = lowerBound() + + qRound( ( value - lowerBound() ) / stepSize ) * stepSize; + } + } + else + { + stepSize = ( scaleMap().p2() - scaleMap().p1() ) / d_data->totalSteps; + + if ( stepSize > 0.0 ) + { + double v = scaleMap().transform( value ); + + v = scaleMap().p1() + + qRound( ( v - scaleMap().p1() ) / stepSize ) * stepSize; + + value = scaleMap().invTransform( v ); + } + } + + if ( qAbs( stepSize ) > 1e-12 ) + { + if ( qFuzzyCompare( value + 1.0, 1.0 ) ) + { + // correct rounding error if value = 0 + value = 0.0; + } + else + { + // correct rounding error at the border + if ( qFuzzyCompare( value, upperBound() ) ) + value = upperBound(); + else if ( qFuzzyCompare( value, lowerBound() ) ) + value = lowerBound(); + } + } + + return value; } -double QwtAbstractSlider::mouseOffset() const +/*! + Update the slider according to modifications of the scale + */ +void QwtAbstractSlider::scaleChange() { - return d_data->mouseOffset; + const double value = qBound( minimum(), d_data->value, maximum() ); + + const bool changed = ( value != d_data->value ); + if ( changed ) + { + d_data->value = value; + } + + if ( d_data->isValid || changed ) + Q_EMIT valueChanged( d_data->value ); + + updateGeometry(); + update(); } -int QwtAbstractSlider::scrollMode() const +//! Calling update() +void QwtAbstractSlider::sliderChange() { - return d_data->scrollMode; + update(); } diff --git a/libs/qwt/qwt_abstract_slider.h b/libs/qwt/qwt_abstract_slider.h index 3a4a48fe43..c91dcb6048 100644 --- a/libs/qwt/qwt_abstract_slider.h +++ b/libs/qwt/qwt_abstract_slider.h @@ -10,112 +10,95 @@ #ifndef QWT_ABSTRACT_SLIDER_H #define QWT_ABSTRACT_SLIDER_H -#include <qwidget.h> #include "qwt_global.h" -#include "qwt_double_range.h" +#include "qwt_abstract_scale.h" /*! - \brief An abstract base class for slider widgets - - QwtAbstractSlider is a base class for - slider widgets. It handles mouse events - and updates the slider's value accordingly. Derived classes - only have to implement the getValue() and - getScrollMode() members, and should react to a - valueChange(), which normally requires repainting. + \brief An abstract base class for slider widgets with a scale + + A slider widget displays a value according to a scale. + The class is designed as a common super class for widgets like + QwtKnob, QwtDial and QwtSlider. + + When the slider is nor readOnly() its value can be modified + by keyboard, mouse and wheel inputs. + + The range of the slider is divided into a number of steps from + which the value increments according to user inputs depend. + Only for linear scales the number of steps correspond with + a fixed step size. */ -class QWT_EXPORT QwtAbstractSlider : public QWidget, public QwtDoubleRange +class QWT_EXPORT QwtAbstractSlider: public QwtAbstractScale { Q_OBJECT + + Q_PROPERTY( double value READ value WRITE setValue ) + + Q_PROPERTY( uint totalSteps READ totalSteps WRITE setTotalSteps ) + Q_PROPERTY( uint singleSteps READ singleSteps WRITE setSingleSteps ) + Q_PROPERTY( uint pageSteps READ pageSteps WRITE setPageSteps ) + Q_PROPERTY( bool stepAlignment READ stepAlignment WRITE setStepAlignment ) + Q_PROPERTY( bool readOnly READ isReadOnly WRITE setReadOnly ) - Q_PROPERTY( bool valid READ isValid WRITE setValid ) - Q_PROPERTY( double mass READ mass WRITE setMass ) -#ifndef Q_MOC_RUN // Qt3 moc -#define QWT_PROPERTY Q_PROPERTY - Q_PROPERTY( Orientation orientation - READ orientation WRITE setOrientation ) -#else // Qt4 moc -// MOC_SKIP_BEGIN - Q_PROPERTY( Qt::Orientation orientation - READ orientation WRITE setOrientation ) -// MOC_SKIP_END -#endif + Q_PROPERTY( bool tracking READ isTracking WRITE setTracking ) + Q_PROPERTY( bool wrapping READ wrapping WRITE setWrapping ) + + Q_PROPERTY( bool invertedControls READ invertedControls WRITE setInvertedControls ) public: - /*! - Scroll mode - \sa getScrollMode() - */ - enum ScrollMode { - ScrNone, - ScrMouse, - ScrTimer, - ScrDirect, - ScrPage - }; - - explicit QwtAbstractSlider(Qt::Orientation, QWidget *parent = NULL); + explicit QwtAbstractSlider( QWidget *parent = NULL ); virtual ~QwtAbstractSlider(); - void setUpdateTime(int t); - void stopMoving(); - void setTracking(bool enable); + void setValid( bool ); + bool isValid() const; - virtual void setMass(double val); - virtual double mass() const; + double value() const; -#if QT_VERSION >= 0x040000 - virtual void setOrientation(Qt::Orientation o); - Qt::Orientation orientation() const; -#else - virtual void setOrientation(Orientation o); - Orientation orientation() const; -#endif + void setWrapping( bool ); + bool wrapping() const; - bool isReadOnly() const; + void setTotalSteps( uint ); + uint totalSteps() const; - /* - Wrappers for QwtDblRange::isValid/QwtDblRange::setValid made - to be available as Q_PROPERTY in the designer. - */ + void setSingleSteps( uint ); + uint singleSteps() const; - /*! - \sa QwtDblRange::isValid - */ - bool isValid() const { - return QwtDoubleRange::isValid(); - } + void setPageSteps( uint ); + uint pageSteps() const; - /*! - \sa QwtDblRange::isValid - */ - void setValid(bool valid) { - QwtDoubleRange::setValid(valid); - } + void setStepAlignment( bool ); + bool stepAlignment() const; -public slots: - virtual void setValue(double val); - virtual void fitValue(double val); - virtual void incValue(int steps); + void setTracking( bool ); + bool isTracking() const; + + void setReadOnly( bool ); + bool isReadOnly() const; - virtual void setReadOnly(bool); + void setInvertedControls( bool ); + bool invertedControls() const; -signals: +public Q_SLOTS: + void setValue( double val ); + +Q_SIGNALS: /*! \brief Notify a change of value. - In the default setting - (tracking enabled), this signal will be emitted every - time the value changes ( see setTracking() ). - \param value new value + When tracking is enabled (default setting), + this signal will be emitted every time the value changes. + + \param value New value + + \sa setTracking(), sliderMoved() */ - void valueChanged(double value); + void valueChanged( double value ); /*! This signal is emitted when the user presses the - movable part of the slider (start ScrMouse Mode). + movable part of the slider. */ void sliderPressed(); @@ -123,70 +106,59 @@ signals: This signal is emitted when the user releases the movable part of the slider. */ - void sliderReleased(); + /*! This signal is emitted when the user moves the slider with the mouse. - \param value new value + + \param value New value + + \sa valueChanged() */ - void sliderMoved(double value); + void sliderMoved( double value ); protected: - virtual void setPosition(const QPoint &); - virtual void valueChange(); - - virtual void timerEvent(QTimerEvent *e); - virtual void mousePressEvent(QMouseEvent *e); - virtual void mouseReleaseEvent(QMouseEvent *e); - virtual void mouseMoveEvent(QMouseEvent *e); - virtual void keyPressEvent(QKeyEvent *e); - virtual void wheelEvent(QWheelEvent *e); + virtual void mousePressEvent( QMouseEvent * ); + virtual void mouseReleaseEvent( QMouseEvent * ); + virtual void mouseMoveEvent( QMouseEvent * ); + virtual void keyPressEvent( QKeyEvent * ); + virtual void wheelEvent( QWheelEvent * ); /*! - \brief Determine the value corresponding to a specified poind + \brief Determine what to do when the user presses a mouse button. + + \param pos Mouse position - This is an abstract virtual function which is called when - the user presses or releases a mouse button or moves the - mouse. It has to be implemented by the derived class. - \param p point + \retval True, when pos is a valid scroll position + \sa scrolledTo() */ - virtual double getValue(const QPoint & p) = 0; + virtual bool isScrollPosition( const QPoint &pos ) const = 0; + /*! - \brief Determine what to do when the user presses a mouse button. + \brief Determine the value for a new position of the + movable part of the slider - This function is abstract and has to be implemented by derived classes. - It is called on a mousePress event. The derived class can determine - what should happen next in dependence of the position where the mouse - was pressed by returning scrolling mode and direction. QwtAbstractSlider - knows the following modes:<dl> - <dt>QwtAbstractSlider::ScrNone - <dd>Scrolling switched off. Don't change the value. - <dt>QwtAbstractSlider::ScrMouse - <dd>Change the value while the user keeps the - button pressed and moves the mouse. - <dt>QwtAbstractSlider::ScrTimer - <dd>Automatic scrolling. Increment the value - in the specified direction as long as - the user keeps the button pressed. - <dt>QwtAbstractSlider::ScrPage - <dd>Automatic scrolling. Same as ScrTimer, but - increment by page size.</dl> - - \param p point where the mouse was pressed - \retval scrollMode The scrolling mode - \retval direction direction: 1, 0, or -1. + \param pos Mouse position + + \return Value for the mouse position + \sa isScrollPosition() */ - virtual void getScrollMode( const QPoint &p, - int &scrollMode, int &direction) = 0; + virtual double scrolledTo( const QPoint &pos ) const = 0; + + void incrementValue( int numSteps ); - void setMouseOffset(double); - double mouseOffset() const; + virtual void scaleChange(); + +protected: + virtual void sliderChange(); - int scrollMode() const; + double incrementedValue( + double value, int stepCount ) const; private: - void buttonReleased(); + double alignedValue( double ) const; + double boundedValue( double ) const; class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_analog_clock.cpp b/libs/qwt/qwt_analog_clock.cpp index e42c6b6616..1d44a95cb2 100644 --- a/libs/qwt/qwt_analog_clock.cpp +++ b/libs/qwt/qwt_analog_clock.cpp @@ -8,69 +8,94 @@ *****************************************************************************/ #include "qwt_analog_clock.h" +#include "qwt_round_scale_draw.h" +#include <qmath.h> +#include <qlocale.h> -/*! - Constructor - \param parent Parent widget -*/ -QwtAnalogClock::QwtAnalogClock(QWidget *parent): - QwtDial(parent) +class QwtAnalogClockScaleDraw: public QwtRoundScaleDraw { - initClock(); -} +public: + QwtAnalogClockScaleDraw() + { + setSpacing( 8 ); + + enableComponent( QwtAbstractScaleDraw::Backbone, false ); + + setTickLength( QwtScaleDiv::MinorTick, 2 ); + setTickLength( QwtScaleDiv::MediumTick, 4 ); + setTickLength( QwtScaleDiv::MajorTick, 8 ); + + setPenWidth( 1 ); + } + + virtual QwtText label( double value ) const + { + if ( qFuzzyCompare( value + 1.0, 1.0 ) ) + value = 60.0 * 60.0 * 12.0; + + return QLocale().toString( qRound( value / ( 60.0 * 60.0 ) ) ); + } +}; -#if QT_VERSION < 0x040000 /*! Constructor \param parent Parent widget - \param name Object name */ -QwtAnalogClock::QwtAnalogClock(QWidget* parent, const char *name): - QwtDial(parent, name) +QwtAnalogClock::QwtAnalogClock( QWidget *parent ): + QwtDial( parent ) { - initClock(); -} -#endif + setWrapping( true ); + setReadOnly( true ); -void QwtAnalogClock::initClock() -{ - setWrapping(true); - setReadOnly(true); + setOrigin( 270.0 ); + setScaleDraw( new QwtAnalogClockScaleDraw() ); + + setTotalSteps( 60 ); + + const int secondsPerHour = 60.0 * 60.0; - setOrigin(270.0); - setRange(0.0, 60.0 * 60.0 * 12.0); // seconds - setScale(-1, 5, 60.0 * 60.0); + QList<double> majorTicks; + QList<double> minorTicks; - setScaleOptions(ScaleTicks | ScaleLabel); - setScaleTicks(1, 0, 8); - scaleDraw()->setSpacing(8); + for ( int i = 0; i < 12; i++ ) + { + majorTicks += i * secondsPerHour; - QColor knobColor = -#if QT_VERSION < 0x040000 - palette().color(QPalette::Active, QColorGroup::Text); -#else - palette().color(QPalette::Active, QPalette::Text); -#endif - knobColor = knobColor.dark(120); + for ( int j = 1; j < 5; j++ ) + minorTicks += i * secondsPerHour + j * secondsPerHour / 5.0; + } + + QwtScaleDiv scaleDiv; + scaleDiv.setInterval( 0.0, 12.0 * secondsPerHour ); + scaleDiv.setTicks( QwtScaleDiv::MajorTick, majorTicks ); + scaleDiv.setTicks( QwtScaleDiv::MinorTick, minorTicks ); + setScale( scaleDiv ); + + QColor knobColor = palette().color( QPalette::Active, QPalette::Text ); + knobColor = knobColor.dark( 120 ); QColor handColor; int width; - for ( int i = 0; i < NHands; i++ ) { - if ( i == SecondHand ) { + for ( int i = 0; i < NHands; i++ ) + { + if ( i == SecondHand ) + { width = 2; - handColor = knobColor.dark(120); - } else { + handColor = knobColor.dark( 120 ); + } + else + { width = 8; handColor = knobColor; } QwtDialSimpleNeedle *hand = new QwtDialSimpleNeedle( - QwtDialSimpleNeedle::Arrow, true, handColor, knobColor); - hand->setWidth(width); + QwtDialSimpleNeedle::Arrow, true, handColor, knobColor ); + hand->setWidth( width ); d_hand[i] = NULL; - setHand((Hand)i, hand); + setHand( static_cast<Hand>( i ), hand ); } } @@ -82,24 +107,25 @@ QwtAnalogClock::~QwtAnalogClock() } /*! - Nop method, use setHand instead - \sa QwtAnalogClock::setHand + Nop method, use setHand() instead + \sa setHand() */ -void QwtAnalogClock::setNeedle(QwtDialNeedle *) +void QwtAnalogClock::setNeedle( QwtDialNeedle * ) { // no op return; } /*! - Set a clockhand + Set a clock hand \param hand Specifies the type of hand \param needle Hand - \sa QwtAnalogClock::hand() + \sa hand() */ -void QwtAnalogClock::setHand(Hand hand, QwtDialNeedle *needle) +void QwtAnalogClock::setHand( Hand hand, QwtDialNeedle *needle ) { - if ( hand >= 0 || hand < NHands ) { + if ( hand >= 0 && hand < NHands ) + { delete d_hand[hand]; d_hand[hand] = needle; } @@ -108,9 +134,9 @@ void QwtAnalogClock::setHand(Hand hand, QwtDialNeedle *needle) /*! \return Clock hand \param hd Specifies the type of hand - \sa QwtAnalogClock::setHand + \sa setHand() */ -QwtDialNeedle *QwtAnalogClock::hand(Hand hd) +QwtDialNeedle *QwtAnalogClock::hand( Hand hd ) { if ( hd < 0 || hd >= NHands ) return NULL; @@ -121,81 +147,75 @@ QwtDialNeedle *QwtAnalogClock::hand(Hand hd) /*! \return Clock hand \param hd Specifies the type of hand - \sa QwtAnalogClock::setHand + \sa setHand() */ -const QwtDialNeedle *QwtAnalogClock::hand(Hand hd) const +const QwtDialNeedle *QwtAnalogClock::hand( Hand hd ) const { - return ((QwtAnalogClock *)this)->hand(hd); + return const_cast<QwtAnalogClock *>( this )->hand( hd ); } /*! \brief Set the current time - - This is the same as QwtAnalogClock::setTime(), but Qt < 3.0 - can't handle default parameters for slots. */ void QwtAnalogClock::setCurrentTime() { - setTime(QTime::currentTime()); + setTime( QTime::currentTime() ); } /*! Set a time \param time Time to display */ -void QwtAnalogClock::setTime(const QTime &time) -{ - if ( time.isValid() ) { - setValue((time.hour() % 12) * 60.0 * 60.0 - + time.minute() * 60.0 + time.second()); - } else - setValid(false); -} - -/*! - Find the scale label for a given value - - \param value Value - \return Label -*/ -QwtText QwtAnalogClock::scaleLabel(double value) const +void QwtAnalogClock::setTime( const QTime &time ) { - if ( value == 0.0 ) - value = 60.0 * 60.0 * 12.0; - - return QString::number(int(value / (60.0 * 60.0))); + if ( time.isValid() ) + { + setValue( ( time.hour() % 12 ) * 60.0 * 60.0 + + time.minute() * 60.0 + time.second() ); + } + else + setValid( false ); } /*! \brief Draw the needle - A clock has no single needle but three hands instead. drawNeedle + A clock has no single needle but three hands instead. drawNeedle() translates value() into directions for the hands and calls drawHand(). \param painter Painter \param center Center of the clock \param radius Maximum length for the hands - \param direction Dummy, not used. - \param cg ColorGroup + \param dir Dummy, not used. + \param colorGroup ColorGroup - \sa QwtAnalogClock::drawHand() + \sa drawHand() */ -void QwtAnalogClock::drawNeedle(QPainter *painter, const QPoint ¢er, - int radius, double, QPalette::ColorGroup cg) const +void QwtAnalogClock::drawNeedle( QPainter *painter, const QPointF ¢er, + double radius, double dir, QPalette::ColorGroup colorGroup ) const { - if ( isValid() ) { - const double hours = value() / (60.0 * 60.0); - const double minutes = (value() - (int)hours * 60.0 * 60.0) / 60.0; - const double seconds = value() - (int)hours * 60.0 * 60.0 - - (int)minutes * 60.0; - - drawHand(painter, HourHand, center, radius, - 360.0 - (origin() + 360.0 * hours / 12.0), cg); - drawHand(painter, MinuteHand, center, radius, - 360.0 - (origin() + 360.0 * minutes / 60.0), cg); - drawHand(painter, SecondHand, center, radius, - 360.0 - (origin() + 360.0 * seconds / 60.0), cg); + Q_UNUSED( dir ); + + if ( isValid() ) + { + const double hours = value() / ( 60.0 * 60.0 ); + const double minutes = + ( value() - qFloor(hours) * 60.0 * 60.0 ) / 60.0; + const double seconds = value() - qFloor(hours) * 60.0 * 60.0 + - qFloor(minutes) * 60.0; + + double angle[NHands]; + angle[HourHand] = 360.0 * hours / 12.0; + angle[MinuteHand] = 360.0 * minutes / 60.0; + angle[SecondHand] = 360.0 * seconds / 60.0; + + for ( int hand = 0; hand < NHands; hand++ ) + { + const double d = 360.0 - angle[hand] - origin(); + drawHand( painter, static_cast<Hand>( hand ), + center, radius, d, colorGroup ); + } } } @@ -209,15 +229,16 @@ void QwtAnalogClock::drawNeedle(QPainter *painter, const QPoint ¢er, \param direction Direction of the hand in degrees, counter clockwise \param cg ColorGroup */ -void QwtAnalogClock::drawHand(QPainter *painter, Hand hd, - const QPoint ¢er, int radius, double direction, - QPalette::ColorGroup cg) const +void QwtAnalogClock::drawHand( QPainter *painter, Hand hd, + const QPointF ¢er, double radius, double direction, + QPalette::ColorGroup cg ) const { - const QwtDialNeedle *needle = hand(hd); - if ( needle ) { + const QwtDialNeedle *needle = hand( hd ); + if ( needle ) + { if ( hd == HourHand ) - radius = qRound(0.8 * radius); + radius = qRound( 0.8 * radius ); - needle->draw(painter, center, radius, direction, cg); + needle->draw( painter, center, radius, direction, cg ); } } diff --git a/libs/qwt/qwt_analog_clock.h b/libs/qwt/qwt_analog_clock.h index a660a9d4ee..ffe27e2cdb 100644 --- a/libs/qwt/qwt_analog_clock.h +++ b/libs/qwt/qwt_analog_clock.h @@ -10,10 +10,10 @@ #ifndef QWT_ANALOG_CLOCK_H #define QWT_ANALOG_CLOCK_H -#include <qdatetime.h> #include "qwt_global.h" #include "qwt_dial.h" #include "qwt_dial_needle.h" +#include <qdatetime.h> /*! \brief An analog clock @@ -21,7 +21,8 @@ \image html analogclock.png \par Example - \verbatim #include <qwt_analog_clock.h> + \code + #include <qwt_analog_clock.h> QwtAnalogClock *clock = new QwtAnalogClock(...); clock->scaleDraw()->setPenWidth(3); @@ -34,10 +35,7 @@ timer->connect(timer, SIGNAL(timeout()), clock, SLOT(setCurrentTime())); timer->start(1000); - \endverbatim - - Qwt is missing a set of good looking hands. - Contributions are very welcome. + \endcode \note The examples/dials example shows how to use QwtAnalogClock. */ @@ -51,41 +49,43 @@ public: Hand type \sa setHand(), hand() */ - - enum Hand { + enum Hand + { + //! Needle displaying the seconds SecondHand, + + //! Needle displaying the minutes MinuteHand, + + //! Needle displaying the hours HourHand, + //! Number of needles NHands }; - explicit QwtAnalogClock(QWidget* parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtAnalogClock(QWidget* parent, const char *name); -#endif + explicit QwtAnalogClock( QWidget* parent = NULL ); virtual ~QwtAnalogClock(); - virtual void setHand(Hand, QwtDialNeedle *); - const QwtDialNeedle *hand(Hand) const; - QwtDialNeedle *hand(Hand); + void setHand( Hand, QwtDialNeedle * ); -public slots: + const QwtDialNeedle *hand( Hand ) const; + QwtDialNeedle *hand( Hand ); + +public Q_SLOTS: void setCurrentTime(); - void setTime(const QTime & = QTime::currentTime()); + void setTime( const QTime & ); protected: - virtual QwtText scaleLabel(double) const; - - virtual void drawNeedle(QPainter *, const QPoint &, - int radius, double direction, QPalette::ColorGroup) const; + virtual void drawNeedle( QPainter *, const QPointF &, + double radius, double direction, QPalette::ColorGroup ) const; - virtual void drawHand(QPainter *, Hand, const QPoint &, - int radius, double direction, QPalette::ColorGroup) const; + virtual void drawHand( QPainter *, Hand, const QPointF &, + double radius, double direction, QPalette::ColorGroup ) const; private: - virtual void setNeedle(QwtDialNeedle *); - void initClock(); + // use setHand instead + void setNeedle( QwtDialNeedle * ); QwtDialNeedle *d_hand[NHands]; }; diff --git a/libs/qwt/qwt_arrow_button.cpp b/libs/qwt/qwt_arrow_button.cpp index d51c445ad9..bd20f91e9c 100644 --- a/libs/qwt/qwt_arrow_button.cpp +++ b/libs/qwt/qwt_arrow_button.cpp @@ -7,12 +7,13 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_arrow_button.h" +#include "qwt_math.h" #include <qpainter.h> #include <qstyle.h> +#include <qstyleoption.h> #include <qevent.h> -#include "qwt_math.h" -#include "qwt_polygon.h" -#include "qwt_arrow_button.h" +#include <qapplication.h> static const int MaxNum = 3; static const int Margin = 2; @@ -25,56 +26,53 @@ public: Qt::ArrowType arrowType; }; - -#if QT_VERSION >= 0x040000 -#include <qstyleoption.h> -static QStyleOptionButton styleOpt(const QwtArrowButton* btn) +static QStyleOptionButton styleOpt( const QwtArrowButton* btn ) { QStyleOptionButton option; - option.init(btn); + option.init( btn ); option.features = QStyleOptionButton::None; - if (btn->isFlat()) + if ( btn->isFlat() ) option.features |= QStyleOptionButton::Flat; - if (btn->menu()) + if ( btn->menu() ) option.features |= QStyleOptionButton::HasMenu; - if (btn->autoDefault() || btn->isDefault()) + if ( btn->autoDefault() || btn->isDefault() ) option.features |= QStyleOptionButton::AutoDefaultButton; - if (btn->isDefault()) + if ( btn->isDefault() ) option.features |= QStyleOptionButton::DefaultButton; - if (btn->isDown()) + if ( btn->isDown() ) option.state |= QStyle::State_Sunken; - if (!btn->isFlat() && !btn->isDown()) + if ( !btn->isFlat() && !btn->isDown() ) option.state |= QStyle::State_Raised; return option; } -#endif /*! \param num Number of arrows - \param arrowType see Qt::ArowType in the Qt docs. + \param arrowType see Qt::ArrowType in the Qt docs. \param parent Parent widget */ -QwtArrowButton::QwtArrowButton(int num, - Qt::ArrowType arrowType, QWidget *parent): - QPushButton(parent) +QwtArrowButton::QwtArrowButton( int num, + Qt::ArrowType arrowType, QWidget *parent ): + QPushButton( parent ) { d_data = new PrivateData; - d_data->num = qwtLim(num, 1, MaxNum); + d_data->num = qBound( 1, num, MaxNum ); d_data->arrowType = arrowType; - setAutoRepeat(true); - setAutoDefault(false); - - switch(d_data->arrowType) { - case Qt::LeftArrow: - case Qt::RightArrow: - setSizePolicy(QSizePolicy::Expanding, - QSizePolicy::Fixed); - break; - default: - setSizePolicy(QSizePolicy::Fixed, - QSizePolicy::Expanding); + setAutoRepeat( true ); + setAutoDefault( false ); + + switch ( d_data->arrowType ) + { + case Qt::LeftArrow: + case Qt::RightArrow: + setSizePolicy( QSizePolicy::Expanding, + QSizePolicy::Fixed ); + break; + default: + setSizePolicy( QSizePolicy::Fixed, + QSizePolicy::Expanding ); } } @@ -102,60 +100,51 @@ int QwtArrowButton::num() const } /*! - \return the bounding rect for the label + \return the bounding rectangle for the label */ QRect QwtArrowButton::labelRect() const { const int m = Margin; QRect r = rect(); - r.setRect(r.x() + m, r.y() + m, - r.width() - 2 * m, r.height() - 2 * m); - - if ( isDown() ) { - int ph, pv; -#if QT_VERSION < 0x040000 - ph = style().pixelMetric( - QStyle::PM_ButtonShiftHorizontal, this); - pv = style().pixelMetric( - QStyle::PM_ButtonShiftVertical, this); - r.moveBy(ph, pv); -#else - QStyleOptionButton option = styleOpt(this); - ph = style()->pixelMetric( - QStyle::PM_ButtonShiftHorizontal, &option, this); - pv = style()->pixelMetric( - QStyle::PM_ButtonShiftVertical, &option, this); - r.translate(ph, pv); -#endif + r.setRect( r.x() + m, r.y() + m, + r.width() - 2 * m, r.height() - 2 * m ); + + if ( isDown() ) + { + QStyleOptionButton option = styleOpt( this ); + const int ph = style()->pixelMetric( + QStyle::PM_ButtonShiftHorizontal, &option, this ); + const int pv = style()->pixelMetric( + QStyle::PM_ButtonShiftVertical, &option, this ); + + r.translate( ph, pv ); } return r; } -#if QT_VERSION >= 0x040000 /*! Paint event handler \param event Paint event */ -void QwtArrowButton::paintEvent(QPaintEvent *event) +void QwtArrowButton::paintEvent( QPaintEvent *event ) { - QPushButton::paintEvent(event); - QPainter painter(this); - drawButtonLabel(&painter); + QPushButton::paintEvent( event ); + QPainter painter( this ); + drawButtonLabel( &painter ); } -#endif /*! \brief Draw the button label \param painter Painter - \sa The Qt Manual on QPushButton + \sa The Qt Manual for QPushButton */ -void QwtArrowButton::drawButtonLabel(QPainter *painter) +void QwtArrowButton::drawButtonLabel( QPainter *painter ) { const bool isVertical = d_data->arrowType == Qt::UpArrow || - d_data->arrowType == Qt::DownArrow; + d_data->arrowType == Qt::DownArrow; const QRect r = labelRect(); QSize boundingSize = labelRect().size(); @@ -163,32 +152,36 @@ void QwtArrowButton::drawButtonLabel(QPainter *painter) boundingSize.transpose(); const int w = - (boundingSize.width() - (MaxNum - 1) * Spacing) / MaxNum; + ( boundingSize.width() - ( MaxNum - 1 ) * Spacing ) / MaxNum; - QSize arrow = arrowSize(Qt::RightArrow, - QSize(w, boundingSize.height())); + QSize arrow = arrowSize( Qt::RightArrow, + QSize( w, boundingSize.height() ) ); if ( isVertical ) arrow.transpose(); QRect contentsSize; // aligned rect where to paint all arrows - if ( d_data->arrowType == Qt::LeftArrow || d_data->arrowType == Qt::RightArrow ) { - contentsSize.setWidth(d_data->num * arrow.width() - + (d_data->num - 1) * Spacing); - contentsSize.setHeight(arrow.height()); - } else { - contentsSize.setWidth(arrow.width()); - contentsSize.setHeight(d_data->num * arrow.height() - + (d_data->num - 1) * Spacing); + if ( d_data->arrowType == Qt::LeftArrow || d_data->arrowType == Qt::RightArrow ) + { + contentsSize.setWidth( d_data->num * arrow.width() + + ( d_data->num - 1 ) * Spacing ); + contentsSize.setHeight( arrow.height() ); + } + else + { + contentsSize.setWidth( arrow.width() ); + contentsSize.setHeight( d_data->num * arrow.height() + + ( d_data->num - 1 ) * Spacing ); } - QRect arrowRect(contentsSize); - arrowRect.moveCenter(r.center()); - arrowRect.setSize(arrow); + QRect arrowRect( contentsSize ); + arrowRect.moveCenter( r.center() ); + arrowRect.setSize( arrow ); painter->save(); - for (int i = 0; i < d_data->num; i++) { - drawArrow(painter, arrowRect, d_data->arrowType); + for ( int i = 0; i < d_data->num; i++ ) + { + drawArrow( painter, arrowRect, d_data->arrowType ); int dx = 0; int dy = 0; @@ -198,77 +191,66 @@ void QwtArrowButton::drawButtonLabel(QPainter *painter) else dx = arrow.width() + Spacing; -#if QT_VERSION >= 0x040000 - arrowRect.translate(dx, dy); -#else - arrowRect.moveBy(dx, dy); -#endif + arrowRect.translate( dx, dy ); } painter->restore(); - if ( hasFocus() ) { -#if QT_VERSION >= 0x040000 + if ( hasFocus() ) + { QStyleOptionFocusRect option; - option.init(this); - option.backgroundColor = palette().color(QPalette::Background); - - style()->drawPrimitive(QStyle::PE_FrameFocusRect, - &option, painter, this); -#else - const QRect focusRect = - style().subRect(QStyle::SR_PushButtonFocusRect, this); - style().drawPrimitive(QStyle::PE_FocusRect, painter, - focusRect, colorGroup()); -#endif + option.init( this ); + option.backgroundColor = palette().color( QPalette::Window ); + + style()->drawPrimitive( QStyle::PE_FrameFocusRect, + &option, painter, this ); } } /*! - Draw an arrow int a bounding rect + Draw an arrow int a bounding rectangle \param painter Painter \param r Rectangle where to paint the arrow \param arrowType Arrow type */ -void QwtArrowButton::drawArrow(QPainter *painter, - const QRect &r, Qt::ArrowType arrowType) const +void QwtArrowButton::drawArrow( QPainter *painter, + const QRect &r, Qt::ArrowType arrowType ) const { - QwtPolygon pa(3); - - switch(arrowType) { - case Qt::UpArrow: - pa.setPoint(0, r.bottomLeft()); - pa.setPoint(1, r.bottomRight()); - pa.setPoint(2, r.center().x(), r.top()); - break; - case Qt::DownArrow: - pa.setPoint(0, r.topLeft()); - pa.setPoint(1, r.topRight()); - pa.setPoint(2, r.center().x(), r.bottom()); - break; - case Qt::RightArrow: - pa.setPoint(0, r.topLeft()); - pa.setPoint(1, r.bottomLeft()); - pa.setPoint(2, r.right(), r.center().y()); - break; - case Qt::LeftArrow: - pa.setPoint(0, r.topRight()); - pa.setPoint(1, r.bottomRight()); - pa.setPoint(2, r.left(), r.center().y()); - break; - default: - break; + QPolygon pa( 3 ); + + switch ( arrowType ) + { + case Qt::UpArrow: + pa.setPoint( 0, r.bottomLeft() ); + pa.setPoint( 1, r.bottomRight() ); + pa.setPoint( 2, r.center().x(), r.top() ); + break; + case Qt::DownArrow: + pa.setPoint( 0, r.topLeft() ); + pa.setPoint( 1, r.topRight() ); + pa.setPoint( 2, r.center().x(), r.bottom() ); + break; + case Qt::RightArrow: + pa.setPoint( 0, r.topLeft() ); + pa.setPoint( 1, r.bottomLeft() ); + pa.setPoint( 2, r.right(), r.center().y() ); + break; + case Qt::LeftArrow: + pa.setPoint( 0, r.topRight() ); + pa.setPoint( 1, r.bottomRight() ); + pa.setPoint( 2, r.left(), r.center().y() ); + break; + default: + break; } painter->save(); -#if QT_VERSION < 0x040000 - painter->setPen(colorGroup().buttonText()); - painter->setBrush(colorGroup().brush(QColorGroup::ButtonText)); -#else - painter->setPen(palette().color(QPalette::ButtonText)); - painter->setBrush(palette().brush(QPalette::ButtonText)); -#endif - painter->drawPolygon(pa); + + painter->setRenderHint( QPainter::Antialiasing, true ); + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().brush( QPalette::ButtonText ) ); + painter->drawPolygon( pa ); + painter->restore(); } @@ -277,7 +259,8 @@ void QwtArrowButton::drawArrow(QPainter *painter, */ QSize QwtArrowButton::sizeHint() const { - return minimumSizeHint(); + const QSize hint = minimumSizeHint(); + return hint.expandedTo( QApplication::globalStrut() ); } /*! @@ -285,43 +268,34 @@ QSize QwtArrowButton::sizeHint() const */ QSize QwtArrowButton::minimumSizeHint() const { - const QSize asz = arrowSize(Qt::RightArrow, QSize()); + const QSize asz = arrowSize( Qt::RightArrow, QSize() ); QSize sz( - 2 * Margin + (MaxNum - 1) * Spacing + MaxNum * asz.width(), + 2 * Margin + ( MaxNum - 1 ) * Spacing + MaxNum * asz.width(), 2 * Margin + asz.height() ); if ( d_data->arrowType == Qt::UpArrow || d_data->arrowType == Qt::DownArrow ) sz.transpose(); -#if QT_VERSION >= 0x040000 QStyleOption styleOption; - styleOption.init(this); - - const QSize hsz = style()->sizeFromContents(QStyle::CT_PushButton, - &styleOption, sz, this); -#if QT_VERSION < 0x040300 - if ( hsz.width() != 80 ) // avoid a bug in the Cleanlooks style -#endif - sz = hsz; + styleOption.init( this ); -#else - sz = style().sizeFromContents(QStyle::CT_PushButton, this, sz); -#endif + sz = style()->sizeFromContents( QStyle::CT_PushButton, + &styleOption, sz, this ); return sz; } /*! - Calculate the size for a arrow that fits into a rect of a given size + Calculate the size for a arrow that fits into a rectangle of a given size \param arrowType Arrow type \param boundingSize Bounding size \return Size of the arrow */ -QSize QwtArrowButton::arrowSize(Qt::ArrowType arrowType, - const QSize &boundingSize) const +QSize QwtArrowButton::arrowSize( Qt::ArrowType arrowType, + const QSize &boundingSize ) const { QSize bs = boundingSize; if ( arrowType == Qt::UpArrow || arrowType == Qt::DownArrow ) @@ -329,17 +303,18 @@ QSize QwtArrowButton::arrowSize(Qt::ArrowType arrowType, const int MinLen = 2; const QSize sz = bs.expandedTo( - QSize(MinLen, 2 * MinLen - 1)); // minimum + QSize( MinLen, 2 * MinLen - 1 ) ); // minimum int w = sz.width(); int h = 2 * w - 1; - if ( h > sz.height() ) { + if ( h > sz.height() ) + { h = sz.height(); - w = (h + 1) / 2; + w = ( h + 1 ) / 2; } - QSize arrSize(w, h); + QSize arrSize( w, h ); if ( arrowType == Qt::UpArrow || arrowType == Qt::DownArrow ) arrSize.transpose(); @@ -349,10 +324,10 @@ QSize QwtArrowButton::arrowSize(Qt::ArrowType arrowType, /*! \brief autoRepeat for the space keys */ -void QwtArrowButton::keyPressEvent(QKeyEvent *e) +void QwtArrowButton::keyPressEvent( QKeyEvent *event ) { - if ( e->isAutoRepeat() && e->key() == Qt::Key_Space ) - emit clicked(); + if ( event->isAutoRepeat() && event->key() == Qt::Key_Space ) + Q_EMIT clicked(); - QPushButton::keyPressEvent(e); + QPushButton::keyPressEvent( event ); } diff --git a/libs/qwt/qwt_arrow_button.h b/libs/qwt/qwt_arrow_button.h index a47d3236f5..ae436fec0f 100644 --- a/libs/qwt/qwt_arrow_button.h +++ b/libs/qwt/qwt_arrow_button.h @@ -10,8 +10,8 @@ #ifndef QWT_ARROW_BUTTON_H #define QWT_ARROW_BUTTON_H -#include <qpushbutton.h> #include "qwt_global.h" +#include <qpushbutton.h> /*! \brief Arrow Button @@ -23,7 +23,7 @@ class QWT_EXPORT QwtArrowButton : public QPushButton { public: - explicit QwtArrowButton (int num, Qt::ArrowType, QWidget *parent = NULL); + explicit QwtArrowButton ( int num, Qt::ArrowType, QWidget *parent = NULL ); virtual ~QwtArrowButton(); Qt::ArrowType arrowType() const; @@ -33,18 +33,16 @@ public: virtual QSize minimumSizeHint() const; protected: -#if QT_VERSION >= 0x040000 - virtual void paintEvent(QPaintEvent *event); -#endif + virtual void paintEvent( QPaintEvent *event ); - virtual void drawButtonLabel(QPainter *p); - virtual void drawArrow(QPainter *, - const QRect &, Qt::ArrowType) const; + virtual void drawButtonLabel( QPainter *p ); + virtual void drawArrow( QPainter *, + const QRect &, Qt::ArrowType ) const; virtual QRect labelRect() const; - virtual QSize arrowSize(Qt::ArrowType, - const QSize &boundingSize) const; + virtual QSize arrowSize( Qt::ArrowType, + const QSize &boundingSize ) const; - virtual void keyPressEvent(QKeyEvent *); + virtual void keyPressEvent( QKeyEvent * ); private: class PrivateData; diff --git a/libs/qwt/qwt_clipper.cpp b/libs/qwt/qwt_clipper.cpp index 7c25157891..51614aa37f 100644 --- a/libs/qwt/qwt_clipper.cpp +++ b/libs/qwt/qwt_clipper.cpp @@ -7,373 +7,365 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qrect.h> -#include "qwt_math.h" #include "qwt_clipper.h" +#include "qwt_point_polar.h" +#include <qrect.h> +#include <string.h> +#include <stdlib.h> -static inline QwtDoubleRect boundingRect(const QwtPolygonF &polygon) -{ -#if QT_VERSION < 0x040000 - if (polygon.isEmpty()) - return QwtDoubleRect(0, 0, 0, 0); - - register const QwtDoublePoint *pd = polygon.data(); - - double minx, maxx, miny, maxy; - minx = maxx = pd->x(); - miny = maxy = pd->y(); - pd++; - - for (uint i = 1; i < polygon.size(); i++, pd++) { - if (pd->x() < minx) - minx = pd->x(); - else if (pd->x() > maxx) - maxx = pd->x(); - if (pd->y() < miny) - miny = pd->y(); - else if (pd->y() > maxy) - maxy = pd->y(); - } - return QwtDoubleRect(minx, miny, maxx - minx, maxy - miny); -#else - return polygon.boundingRect(); +#if QT_VERSION < 0x040601 +#define qAtan(x) ::atan(x) #endif -} -enum Edge { - Left, - Top, - Right, - Bottom, - NEdges -}; +namespace QwtClip +{ + // some templates used for inlining + template <class Point, typename T> class LeftEdge; + template <class Point, typename T> class RightEdge; + template <class Point, typename T> class TopEdge; + template <class Point, typename T> class BottomEdge; -class QwtPolygonClipper: public QRect + template <class Point> class PointBuffer; +} + +template <class Point, typename Value> +class QwtClip::LeftEdge { public: - QwtPolygonClipper(const QRect &r); + inline LeftEdge( Value x1, Value, Value, Value ): + d_x1( x1 ) + { + } - QwtPolygon clipPolygon(const QwtPolygon &) const; + inline bool isInside( const Point &p ) const + { + return p.x() >= d_x1; + } + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dy = ( p1.y() - p2.y() ) / double( p1.x() - p2.x() ); + return Point( d_x1, static_cast< Value >( p2.y() + ( d_x1 - p2.x() ) * dy ) ); + } private: - void clipEdge(Edge, const QwtPolygon &, QwtPolygon &) const; - bool insideEdge(const QPoint &, Edge edge) const; - QPoint intersectEdge(const QPoint &p1, - const QPoint &p2, Edge edge) const; - - void addPoint(QwtPolygon &, uint pos, const QPoint &point) const; + const Value d_x1; }; -class QwtPolygonClipperF: public QwtDoubleRect +template <class Point, typename Value> +class QwtClip::RightEdge { public: - QwtPolygonClipperF(const QwtDoubleRect &r); - QwtPolygonF clipPolygon(const QwtPolygonF &) const; + inline RightEdge( Value, Value x2, Value, Value ): + d_x2( x2 ) + { + } -private: - void clipEdge(Edge, const QwtPolygonF &, QwtPolygonF &) const; - bool insideEdge(const QwtDoublePoint &, Edge edge) const; - QwtDoublePoint intersectEdge(const QwtDoublePoint &p1, - const QwtDoublePoint &p2, Edge edge) const; + inline bool isInside( const Point &p ) const + { + return p.x() <= d_x2; + } + + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dy = ( p1.y() - p2.y() ) / double( p1.x() - p2.x() ); + return Point( d_x2, static_cast<Value>( p2.y() + ( d_x2 - p2.x() ) * dy ) ); + } - void addPoint(QwtPolygonF &, uint pos, const QwtDoublePoint &point) const; +private: + const Value d_x2; }; -#if QT_VERSION >= 0x040000 -class QwtCircleClipper: public QwtDoubleRect +template <class Point, typename Value> +class QwtClip::TopEdge { public: - QwtCircleClipper(const QwtDoubleRect &r); - QwtArray<QwtDoubleInterval> clipCircle( - const QwtDoublePoint &, double radius) const; + inline TopEdge( Value, Value, Value y1, Value ): + d_y1( y1 ) + { + } + + inline bool isInside( const Point &p ) const + { + return p.y() >= d_y1; + } + + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dx = ( p1.x() - p2.x() ) / double( p1.y() - p2.y() ); + return Point( static_cast<Value>( p2.x() + ( d_y1 - p2.y() ) * dx ), d_y1 ); + } private: - QList<QwtDoublePoint> cuttingPoints( - Edge, const QwtDoublePoint &pos, double radius) const; - double toAngle(const QwtDoublePoint &, const QwtDoublePoint &) const; + const Value d_y1; }; -#endif -QwtPolygonClipper::QwtPolygonClipper(const QRect &r): - QRect(r) +template <class Point, typename Value> +class QwtClip::BottomEdge { -} +public: + inline BottomEdge( Value, Value, Value, Value y2 ): + d_y2( y2 ) + { + } -inline void QwtPolygonClipper::addPoint( - QwtPolygon &pa, uint pos, const QPoint &point) const -{ - if ( uint(pa.size()) <= pos ) - pa.resize(pos + 5); + inline bool isInside( const Point &p ) const + { + return p.y() <= d_y2; + } - pa.setPoint(pos, point); -} + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dx = ( p1.x() - p2.x() ) / double( p1.y() - p2.y() ); + return Point( static_cast<Value>( p2.x() + ( d_y2 - p2.y() ) * dx ), d_y2 ); + } + +private: + const Value d_y2; +}; -//! Sutherland-Hodgman polygon clipping -QwtPolygon QwtPolygonClipper::clipPolygon(const QwtPolygon &pa) const +template<class Point> +class QwtClip::PointBuffer { - if ( contains( pa.boundingRect() ) ) - return pa; +public: + PointBuffer( int capacity = 0 ): + m_capacity( 0 ), + m_size( 0 ), + m_buffer( NULL ) + { + if ( capacity > 0 ) + reserve( capacity ); + } - QwtPolygon cpa(pa.size()); + ~PointBuffer() + { + if ( m_buffer ) + ::free( m_buffer ); + } - clipEdge((Edge)0, pa, cpa); + inline void setPoints( int numPoints, const Point *points ) + { + reserve( numPoints ); - for ( uint edge = 1; edge < NEdges; edge++ ) { - const QwtPolygon rpa = cpa; -#if QT_VERSION < 0x040000 - cpa.detach(); -#endif - clipEdge((Edge)edge, rpa, cpa); + m_size = numPoints; + ::memcpy( m_buffer, points, m_size * sizeof( Point ) ); } - return cpa; -} - -bool QwtPolygonClipper::insideEdge(const QPoint &p, Edge edge) const -{ - switch(edge) { - case Left: - return p.x() > left(); - case Top: - return p.y() > top(); - case Right: - return p.x() < right(); - case Bottom: - return p.y() < bottom(); - default: - break; + inline void reset() + { + m_size = 0; } - return false; -} + inline int size() const + { + return m_size; + } -QPoint QwtPolygonClipper::intersectEdge(const QPoint &p1, - const QPoint &p2, Edge edge ) const -{ - int x=0, y=0; - double m = 0; - - const double dy = p2.y() - p1.y(); - const double dx = p2.x() - p1.x(); - - switch ( edge ) { - case Left: - x = left(); - m = double(qwtAbs(p1.x() - x)) / qwtAbs(dx); - y = p1.y() + int(dy * m); - break; - case Top: - y = top(); - m = double(qwtAbs(p1.y() - y)) / qwtAbs(dy); - x = p1.x() + int(dx * m); - break; - case Right: - x = right(); - m = double(qwtAbs(p1.x() - x)) / qwtAbs(dx); - y = p1.y() + int(dy * m); - break; - case Bottom: - y = bottom(); - m = double(qwtAbs(p1.y() - y)) / qwtAbs(dy); - x = p1.x() + int(dx * m); - break; - default: - break; + inline Point *data() const + { + return m_buffer; } - return QPoint(x,y); -} + inline Point &operator[]( int i ) + { + return m_buffer[i]; + } -void QwtPolygonClipper::clipEdge(Edge edge, - const QwtPolygon &pa, QwtPolygon &cpa) const -{ - if ( pa.count() == 0 ) { - cpa.resize(0); - return; + inline const Point &operator[]( int i ) const + { + return m_buffer[i]; } - unsigned int count = 0; - - QPoint p1 = pa.point(0); - if ( insideEdge(p1, edge) ) - addPoint(cpa, count++, p1); - - const uint nPoints = pa.size(); - for ( uint i = 1; i < nPoints; i++ ) { - const QPoint p2 = pa.point(i); - if ( insideEdge(p2, edge) ) { - if ( insideEdge(p1, edge) ) - addPoint(cpa, count++, p2); - else { - addPoint(cpa, count++, intersectEdge(p1, p2, edge)); - addPoint(cpa, count++, p2); - } - } else { - if ( insideEdge(p1, edge) ) - addPoint(cpa, count++, intersectEdge(p1, p2, edge)); - } - p1 = p2; + inline void add( const Point &point ) + { + if ( m_capacity <= m_size ) + reserve( m_size + 1 ); + + m_buffer[m_size++] = point; } - cpa.resize(count); -} -QwtPolygonClipperF::QwtPolygonClipperF(const QwtDoubleRect &r): - QwtDoubleRect(r) -{ -} +private: + inline void reserve( int size ) + { + if ( m_capacity == 0 ) + m_capacity = 1; -inline void QwtPolygonClipperF::addPoint(QwtPolygonF &pa, uint pos, const QwtDoublePoint &point) const -{ - if ( uint(pa.size()) <= pos ) - pa.resize(pos + 5); + while ( m_capacity < size ) + m_capacity *= 2; - pa[(int)pos] = point; -} + m_buffer = static_cast<Point *>( + ::realloc( m_buffer, m_capacity * sizeof( Point ) ) ); + } -//! Sutherland-Hodgman polygon clipping -QwtPolygonF QwtPolygonClipperF::clipPolygon(const QwtPolygonF &pa) const -{ - if ( contains( ::boundingRect(pa) ) ) - return pa; + int m_capacity; + int m_size; + Point *m_buffer; +}; - QwtPolygonF cpa(pa.size()); +using namespace QwtClip; - clipEdge((Edge)0, pa, cpa); +template <class Polygon, class Rect, class Point, typename T> +class QwtPolygonClipper +{ +public: + QwtPolygonClipper( const Rect &clipRect ): + d_clipRect( clipRect ) + { + } - for ( uint edge = 1; edge < NEdges; edge++ ) { - const QwtPolygonF rpa = cpa; -#if QT_VERSION < 0x040000 - cpa.detach(); + Polygon clipPolygon( const Polygon &polygon, bool closePolygon ) const + { +#if 0 + if ( d_clipRect.contains( polygon.boundingRect() ) ) + return polygon; #endif - clipEdge((Edge)edge, rpa, cpa); - } - return cpa; -} + PointBuffer<Point> points1; + PointBuffer<Point> points2( qMin( 256, polygon.size() ) ); -bool QwtPolygonClipperF::insideEdge(const QwtDoublePoint &p, Edge edge) const -{ - switch(edge) { - case Left: - return p.x() > left(); - case Top: - return p.y() > top(); - case Right: - return p.x() < right(); - case Bottom: - return p.y() < bottom(); - default: - break; - } + points1.setPoints( polygon.size(), polygon.data() ); - return false; -} + clipEdge< LeftEdge<Point, T> >( closePolygon, points1, points2 ); + clipEdge< RightEdge<Point, T> >( closePolygon, points2, points1 ); + clipEdge< TopEdge<Point, T> >( closePolygon, points1, points2 ); + clipEdge< BottomEdge<Point, T> >( closePolygon, points2, points1 ); -QwtDoublePoint QwtPolygonClipperF::intersectEdge(const QwtDoublePoint &p1, - const QwtDoublePoint &p2, Edge edge ) const -{ - double x=0.0, y=0.0; - double m = 0; - - const double dy = p2.y() - p1.y(); - const double dx = p2.x() - p1.x(); - - switch ( edge ) { - case Left: - x = left(); - m = double(qwtAbs(p1.x() - x)) / qwtAbs(dx); - y = p1.y() + int(dy * m); - break; - case Top: - y = top(); - m = double(qwtAbs(p1.y() - y)) / qwtAbs(dy); - x = p1.x() + int(dx * m); - break; - case Right: - x = right(); - m = double(qwtAbs(p1.x() - x)) / qwtAbs(dx); - y = p1.y() + int(dy * m); - break; - case Bottom: - y = bottom(); - m = double(qwtAbs(p1.y() - y)) / qwtAbs(dy); - x = p1.x() + int(dx * m); - break; - default: - break; + Polygon p; + p.resize( points1.size() ); + ::memcpy( p.data(), points1.data(), points1.size() * sizeof( Point ) ); + + return p; } - return QwtDoublePoint(x,y); -} +private: + template <class Edge> + inline void clipEdge( bool closePolygon, + PointBuffer<Point> &points, PointBuffer<Point> &clippedPoints ) const + { + clippedPoints.reset(); + + if ( points.size() < 2 ) + { + if ( points.size() == 1 ) + clippedPoints.add( points[0] ); + return; + } -void QwtPolygonClipperF::clipEdge(Edge edge, - const QwtPolygonF &pa, QwtPolygonF &cpa) const -{ - if ( pa.count() == 0 ) { - cpa.resize(0); - return; - } + const Edge edge( d_clipRect.x(), d_clipRect.x() + d_clipRect.width(), + d_clipRect.y(), d_clipRect.y() + d_clipRect.height() ); + + int lastPos, start; + if ( closePolygon ) + { + start = 0; + lastPos = points.size() - 1; + } + else + { + start = 1; + lastPos = 0; - unsigned int count = 0; - - QwtDoublePoint p1 = pa[0]; - if ( insideEdge(p1, edge) ) - addPoint(cpa, count++, p1); - - const uint nPoints = pa.size(); - for ( uint i = 1; i < nPoints; i++ ) { - const QwtDoublePoint p2 = pa[(int)i]; - if ( insideEdge(p2, edge) ) { - if ( insideEdge(p1, edge) ) - addPoint(cpa, count++, p2); - else { - addPoint(cpa, count++, intersectEdge(p1, p2, edge)); - addPoint(cpa, count++, p2); + if ( edge.isInside( points[0] ) ) + clippedPoints.add( points[0] ); + } + + const uint nPoints = points.size(); + for ( uint i = start; i < nPoints; i++ ) + { + const Point &p1 = points[i]; + const Point &p2 = points[lastPos]; + + if ( edge.isInside( p1 ) ) + { + if ( edge.isInside( p2 ) ) + { + clippedPoints.add( p1 ); + } + else + { + clippedPoints.add( edge.intersection( p1, p2 ) ); + clippedPoints.add( p1 ); + } + } + else + { + if ( edge.isInside( p2 ) ) + { + clippedPoints.add( edge.intersection( p1, p2 ) ); + } } - } else { - if ( insideEdge(p1, edge) ) - addPoint(cpa, count++, intersectEdge(p1, p2, edge)); + lastPos = i; } - p1 = p2; } - cpa.resize(count); -} -#if QT_VERSION >= 0x040000 + const Rect d_clipRect; +}; + +class QwtCircleClipper +{ +public: + QwtCircleClipper( const QRectF &r ); + QVector<QwtInterval> clipCircle( const QPointF &, double radius ) const; + +private: + enum Edge + { + Left, + Top, + Right, + Bottom, + + NEdges + }; + + QList<QPointF> cuttingPoints( + Edge, const QPointF &pos, double radius ) const; + + double toAngle( const QPointF &, const QPointF & ) const; + + const QRectF d_rect; +}; + -QwtCircleClipper::QwtCircleClipper(const QwtDoubleRect &r): - QwtDoubleRect(r) +QwtCircleClipper::QwtCircleClipper( const QRectF &r ): + d_rect( r ) { } -QwtArray<QwtDoubleInterval> QwtCircleClipper::clipCircle( - const QwtDoublePoint &pos, double radius) const +QVector<QwtInterval> QwtCircleClipper::clipCircle( + const QPointF &pos, double radius ) const { - QList<QwtDoublePoint> points; + QList<QPointF> points; for ( int edge = 0; edge < NEdges; edge++ ) - points += cuttingPoints((Edge)edge, pos, radius); - - QwtArray<QwtDoubleInterval> intv; - if ( points.size() <= 0 ) { - QwtDoubleRect cRect(0, 0, 2 * radius, 2* radius); - cRect.moveCenter(pos); - if ( contains(cRect) ) - intv += QwtDoubleInterval(0.0, 2 * M_PI); - } else { + points += cuttingPoints( static_cast<Edge>(edge), pos, radius ); + + QVector<QwtInterval> intv; + if ( points.size() <= 0 ) + { + QRectF cRect( 0, 0, 2 * radius, 2 * radius ); + cRect.moveCenter( pos ); + if ( d_rect.contains( cRect ) ) + intv += QwtInterval( 0.0, 2 * M_PI ); + } + else + { QList<double> angles; for ( int i = 0; i < points.size(); i++ ) - angles += toAngle(pos, points[i]); - qSort(angles); - - const int in = contains(qwtPolar2Pos(pos, radius, - angles[0] + (angles[1] - angles[0]) / 2)); - if ( in ) { - for ( int i = 0; i < angles.size() - 1; i += 2) - intv += QwtDoubleInterval(angles[i], angles[i+1]); - } else { - for ( int i = 1; i < angles.size() - 1; i += 2) - intv += QwtDoubleInterval(angles[i], angles[i+1]); - intv += QwtDoubleInterval(angles.last(), angles.first()); + angles += toAngle( pos, points[i] ); + qSort( angles ); + + const int in = d_rect.contains( qwtPolar2Pos( pos, radius, + angles[0] + ( angles[1] - angles[0] ) / 2 ) ); + + if ( in ) + { + for ( int i = 0; i < angles.size() - 1; i += 2 ) + intv += QwtInterval( angles[i], angles[i+1] ); + } + else + { + for ( int i = 1; i < angles.size() - 1; i += 2 ) + intv += QwtInterval( angles[i], angles[i+1] ); + intv += QwtInterval( angles.last(), angles.first() ); } } @@ -381,18 +373,21 @@ QwtArray<QwtDoubleInterval> QwtCircleClipper::clipCircle( } double QwtCircleClipper::toAngle( - const QwtDoublePoint &from, const QwtDoublePoint &to) const + const QPointF &from, const QPointF &to ) const { if ( from.x() == to.x() ) return from.y() <= to.y() ? M_PI / 2.0 : 3 * M_PI / 2.0; - const double m = qwtAbs((to.y() - from.y()) / (to.x() - from.x()) ); + const double m = qAbs( ( to.y() - from.y() ) / ( to.x() - from.x() ) ); - double angle = ::atan(m); - if ( to.x() > from.x() ) { + double angle = qAtan( m ); + if ( to.x() > from.x() ) + { if ( to.y() > from.y() ) angle = 2 * M_PI - angle; - } else { + } + else + { if ( to.y() > from.y() ) angle = M_PI + angle; else @@ -402,58 +397,114 @@ double QwtCircleClipper::toAngle( return angle; } -QList<QwtDoublePoint> QwtCircleClipper::cuttingPoints( - Edge edge, const QwtDoublePoint &pos, double radius) const +QList<QPointF> QwtCircleClipper::cuttingPoints( + Edge edge, const QPointF &pos, double radius ) const { - QList<QwtDoublePoint> points; - - if ( edge == Left || edge == Right ) { - const double x = (edge == Left) ? left() : right(); - if ( qwtAbs(pos.x() - x) < radius ) { - const double off = ::sqrt(qwtSqr(radius) - qwtSqr(pos.x() - x)); - const double y1 = pos.y() + off; - if ( y1 >= top() && y1 <= bottom() ) - points += QwtDoublePoint(x, y1); - const double y2 = pos.y() - off; - if ( y2 >= top() && y2 <= bottom() ) - points += QwtDoublePoint(x, y2); + QList<QPointF> points; + + if ( edge == Left || edge == Right ) + { + const double x = ( edge == Left ) ? d_rect.left() : d_rect.right(); + if ( qAbs( pos.x() - x ) < radius ) + { + const double off = qSqrt( qwtSqr( radius ) - qwtSqr( pos.x() - x ) ); + const double m_y1 = pos.y() + off; + if ( m_y1 >= d_rect.top() && m_y1 <= d_rect.bottom() ) + points += QPointF( x, m_y1 ); + + const double m_y2 = pos.y() - off; + if ( m_y2 >= d_rect.top() && m_y2 <= d_rect.bottom() ) + points += QPointF( x, m_y2 ); } - } else { - const double y = (edge == Top) ? top() : bottom(); - if ( qwtAbs(pos.y() - y) < radius ) { - const double off = ::sqrt(qwtSqr(radius) - qwtSqr(pos.y() - y)); + } + else + { + const double y = ( edge == Top ) ? d_rect.top() : d_rect.bottom(); + if ( qAbs( pos.y() - y ) < radius ) + { + const double off = qSqrt( qwtSqr( radius ) - qwtSqr( pos.y() - y ) ); const double x1 = pos.x() + off; - if ( x1 >= left() && x1 <= right() ) - points += QwtDoublePoint(x1, y); - const double x2 = pos.x() - off; - if ( x2 >= left() && x2 <= right() ) - points += QwtDoublePoint(x2, y); + if ( x1 >= d_rect.left() && x1 <= d_rect.right() ) + points += QPointF( x1, y ); + + const double m_x2 = pos.x() - off; + if ( m_x2 >= d_rect.left() && m_x2 <= d_rect.right() ) + points += QPointF( m_x2, y ); } } return points; } -#endif -QwtPolygon QwtClipper::clipPolygon( - const QRect &clipRect, const QwtPolygon &polygon) +/*! + Sutherland-Hodgman polygon clipping + + \param clipRect Clip rectangle + \param polygon Polygon + \param closePolygon True, when the polygon is closed + + \return Clipped polygon +*/ +QPolygon QwtClipper::clipPolygon( + const QRectF &clipRect, const QPolygon &polygon, bool closePolygon ) +{ + const int minX = qCeil( clipRect.left() ); + const int maxX = qFloor( clipRect.right() ); + const int minY = qCeil( clipRect.top() ); + const int maxY = qFloor( clipRect.bottom() ); + + const QRect r( minX, minY, maxX - minX, maxY - minY ); + + QwtPolygonClipper<QPolygon, QRect, QPoint, int> clipper( r ); + return clipper.clipPolygon( polygon, closePolygon ); +} +/*! + Sutherland-Hodgman polygon clipping + + \param clipRect Clip rectangle + \param polygon Polygon + \param closePolygon True, when the polygon is closed + + \return Clipped polygon +*/ +QPolygon QwtClipper::clipPolygon( + const QRect &clipRect, const QPolygon &polygon, bool closePolygon ) { - QwtPolygonClipper clipper(clipRect); - return clipper.clipPolygon(polygon); + QwtPolygonClipper<QPolygon, QRect, QPoint, int> clipper( clipRect ); + return clipper.clipPolygon( polygon, closePolygon ); } -QwtPolygonF QwtClipper::clipPolygonF( - const QwtDoubleRect &clipRect, const QwtPolygonF &polygon) +/*! + Sutherland-Hodgman polygon clipping + + \param clipRect Clip rectangle + \param polygon Polygon + \param closePolygon True, when the polygon is closed + + \return Clipped polygon +*/ +QPolygonF QwtClipper::clipPolygonF( + const QRectF &clipRect, const QPolygonF &polygon, bool closePolygon ) { - QwtPolygonClipperF clipper(clipRect); - return clipper.clipPolygon(polygon); + QwtPolygonClipper<QPolygonF, QRectF, QPointF, double> clipper( clipRect ); + return clipper.clipPolygon( polygon, closePolygon ); } -#if QT_VERSION >= 0x040000 -QwtArray<QwtDoubleInterval> QwtClipper::clipCircle( - const QwtDoubleRect &clipRect, - const QwtDoublePoint ¢er, double radius) +/*! + Circle clipping + + clipCircle() divides a circle into intervals of angles representing arcs + of the circle. When the circle is completely inside the clip rectangle + an interval [0.0, 2 * M_PI] is returned. + + \param clipRect Clip rectangle + \param center Center of the circle + \param radius Radius of the circle + + \return Arcs of the circle +*/ +QVector<QwtInterval> QwtClipper::clipCircle( const QRectF &clipRect, + const QPointF ¢er, double radius ) { - QwtCircleClipper clipper(clipRect); - return clipper.clipCircle(center, radius); + QwtCircleClipper clipper( clipRect ); + return clipper.clipCircle( center, radius ); } -#endif diff --git a/libs/qwt/qwt_clipper.h b/libs/qwt/qwt_clipper.h index b3fe16f90b..1b1820bb02 100644 --- a/libs/qwt/qwt_clipper.h +++ b/libs/qwt/qwt_clipper.h @@ -11,27 +11,30 @@ #define QWT_CLIPPER_H #include "qwt_global.h" -#include "qwt_array.h" -#include "qwt_polygon.h" -#include "qwt_double_rect.h" -#include "qwt_double_interval.h" +#include "qwt_interval.h" +#include <qpolygon.h> +#include <qvector.h> class QRect; +class QRectF; /*! - \brief Some clipping algos + \brief Some clipping algorithms */ class QWT_EXPORT QwtClipper { public: - static QwtPolygon clipPolygon(const QRect &, const QwtPolygon &); - static QwtPolygonF clipPolygonF(const QwtDoubleRect &, const QwtPolygonF &); + static QPolygon clipPolygon( const QRect &, + const QPolygon &, bool closePolygon = false ); + static QPolygon clipPolygon( const QRectF &, + const QPolygon &, bool closePolygon = false ); -#if QT_VERSION >= 0x040000 - static QwtArray<QwtDoubleInterval> clipCircle( - const QwtDoubleRect &, const QwtDoublePoint &, double radius); -#endif + static QPolygonF clipPolygonF( const QRectF &, + const QPolygonF &, bool closePolygon = false ); + + static QVector<QwtInterval> clipCircle( + const QRectF &, const QPointF &, double radius ); }; #endif diff --git a/libs/qwt/qwt_color_map.cpp b/libs/qwt/qwt_color_map.cpp index 3ea3b129e5..571c1380dd 100644 --- a/libs/qwt/qwt_color_map.cpp +++ b/libs/qwt/qwt_color_map.cpp @@ -7,31 +7,23 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include "qwt_array.h" -#include "qwt_math.h" -#include "qwt_double_interval.h" #include "qwt_color_map.h" - -#if QT_VERSION < 0x040000 -#include <qvaluelist.h> -typedef QValueVector<QRgb> QwtColorTable; -#else -typedef QVector<QRgb> QwtColorTable; -#endif +#include "qwt_math.h" +#include "qwt_interval.h" +#include <qnumeric.h> class QwtLinearColorMap::ColorStops { public: - ColorStops() { -#if QT_VERSION >= 0x040000 - _stops.reserve(256); -#endif + ColorStops() + { + _stops.reserve( 256 ); } - void insert(double pos, const QColor &color); - QRgb rgb(QwtLinearColorMap::Mode, double pos) const; + void insert( double pos, const QColor &color ); + QRgb rgb( QwtLinearColorMap::Mode, double pos ) const; - QwtArray<double> stops() const; + QVector<double> stops() const; private: @@ -39,16 +31,18 @@ private: { public: ColorStop(): - pos(0.0), - rgb(0) { + pos( 0.0 ), + rgb( 0 ) + { }; - ColorStop(double p, const QColor &c): - pos(p), - rgb(c.rgb()) { - r = qRed(rgb); - g = qGreen(rgb); - b = qBlue(rgb); + ColorStop( double p, const QColor &c ): + pos( p ), + rgb( c.rgb() ) + { + r = qRed( rgb ); + g = qGreen( rgb ); + b = qBlue( rgb ); } double pos; @@ -56,11 +50,11 @@ private: int r, g, b; }; - inline int findUpper(double pos) const; - QwtArray<ColorStop> _stops; + inline int findUpper( double pos ) const; + QVector<ColorStop> _stops; }; -void QwtLinearColorMap::ColorStops::insert(double pos, const QColor &color) +void QwtLinearColorMap::ColorStops::insert( double pos, const QColor &color ) { // Lookups need to be very fast, insertions are not so important. // Anyway, a balanced tree is what we need here. TODO ... @@ -69,53 +63,52 @@ void QwtLinearColorMap::ColorStops::insert(double pos, const QColor &color) return; int index; - if ( _stops.size() == 0 ) { + if ( _stops.size() == 0 ) + { index = 0; -#if QT_VERSION < 0x040000 - _stops.resize(1, QGArray::SpeedOptim); -#else - _stops.resize(1); -#endif - } else { - index = findUpper(pos); - if ( index == (int)_stops.size() || - qwtAbs(_stops[index].pos - pos) >= 0.001 ) { -#if QT_VERSION < 0x040000 - _stops.resize(_stops.size() + 1, QGArray::SpeedOptim); -#else - _stops.resize(_stops.size() + 1); -#endif + _stops.resize( 1 ); + } + else + { + index = findUpper( pos ); + if ( index == _stops.size() || + qAbs( _stops[index].pos - pos ) >= 0.001 ) + { + _stops.resize( _stops.size() + 1 ); for ( int i = _stops.size() - 1; i > index; i-- ) _stops[i] = _stops[i-1]; } } - _stops[index] = ColorStop(pos, color); + _stops[index] = ColorStop( pos, color ); } -inline QwtArray<double> QwtLinearColorMap::ColorStops::stops() const +inline QVector<double> QwtLinearColorMap::ColorStops::stops() const { - QwtArray<double> positions(_stops.size()); - for ( int i = 0; i < (int)_stops.size(); i++ ) + QVector<double> positions( _stops.size() ); + for ( int i = 0; i < _stops.size(); i++ ) positions[i] = _stops[i].pos; return positions; } -inline int QwtLinearColorMap::ColorStops::findUpper(double pos) const +inline int QwtLinearColorMap::ColorStops::findUpper( double pos ) const { int index = 0; int n = _stops.size(); const ColorStop *stops = _stops.data(); - while (n > 0) { + while ( n > 0 ) + { const int half = n >> 1; const int middle = index + half; - if ( stops[middle].pos <= pos ) { + if ( stops[middle].pos <= pos ) + { index = middle + 1; n -= half + 1; - } else + } + else n = half; } @@ -123,33 +116,36 @@ inline int QwtLinearColorMap::ColorStops::findUpper(double pos) const } inline QRgb QwtLinearColorMap::ColorStops::rgb( - QwtLinearColorMap::Mode mode, double pos) const + QwtLinearColorMap::Mode mode, double pos ) const { if ( pos <= 0.0 ) return _stops[0].rgb; if ( pos >= 1.0 ) - return _stops[(int)(_stops.size() - 1)].rgb; + return _stops[ _stops.size() - 1 ].rgb; - const int index = findUpper(pos); - if ( mode == FixedColors ) { + const int index = findUpper( pos ); + if ( mode == FixedColors ) + { return _stops[index-1].rgb; - } else { + } + else + { const ColorStop &s1 = _stops[index-1]; const ColorStop &s2 = _stops[index]; - const double ratio = (pos - s1.pos) / (s2.pos - s1.pos); + const double ratio = ( pos - s1.pos ) / ( s2.pos - s1.pos ); - const int r = s1.r + qRound(ratio * (s2.r - s1.r)); - const int g = s1.g + qRound(ratio * (s2.g - s1.g)); - const int b = s1.b + qRound(ratio * (s2.b - s1.b)); + const int r = s1.r + qRound( ratio * ( s2.r - s1.r ) ); + const int g = s1.g + qRound( ratio * ( s2.g - s1.g ) ); + const int b = s1.b + qRound( ratio * ( s2.b - s1.b ) ); - return qRgb(r, g, b); + return qRgb( r, g, b ); } } //! Constructor -QwtColorMap::QwtColorMap(Format format): - d_format(format) +QwtColorMap::QwtColorMap( Format format ): + d_format( format ) { } @@ -167,15 +163,15 @@ QwtColorMap::~QwtColorMap() \param interval Range for the values \return A color table, that can be used for a QImage */ -QwtColorTable QwtColorMap::colorTable( - const QwtDoubleInterval &interval) const +QVector<QRgb> QwtColorMap::colorTable( const QwtInterval &interval ) const { - QwtColorTable table(256); + QVector<QRgb> table( 256 ); - if ( interval.isValid() ) { - const double step = interval.width() / (table.size() - 1); - for ( int i = 0; i < (int) table.size(); i++ ) - table[i] = rgb(interval, interval.minValue() + step * i); + if ( interval.isValid() ) + { + const double step = interval.width() / ( table.size() - 1 ); + for ( int i = 0; i < table.size(); i++ ) + table[i] = rgb( interval, interval.minValue() + step * i ); } return table; @@ -194,21 +190,13 @@ public: \param format Preferred format of the color map */ -QwtLinearColorMap::QwtLinearColorMap(QwtColorMap::Format format): - QwtColorMap(format) +QwtLinearColorMap::QwtLinearColorMap( QwtColorMap::Format format ): + QwtColorMap( format ) { d_data = new PrivateData; d_data->mode = ScaledColors; - setColorInterval( Qt::blue, Qt::yellow); -} - -//! Copy constructor -QwtLinearColorMap::QwtLinearColorMap(const QwtLinearColorMap &other): - QwtColorMap(other) -{ - d_data = new PrivateData; - *this = other; + setColorInterval( Qt::blue, Qt::yellow ); } /*! @@ -216,15 +204,15 @@ QwtLinearColorMap::QwtLinearColorMap(const QwtLinearColorMap &other): \param color1 Color used for the minimum value of the value interval \param color2 Color used for the maximum value of the value interval - \param format Preferred format of the coor map + \param format Preferred format for the color map */ -QwtLinearColorMap::QwtLinearColorMap(const QColor &color1, - const QColor &color2, QwtColorMap::Format format): - QwtColorMap(format) +QwtLinearColorMap::QwtLinearColorMap( const QColor &color1, + const QColor &color2, QwtColorMap::Format format ): + QwtColorMap( format ) { d_data = new PrivateData; d_data->mode = ScaledColors; - setColorInterval(color1, color2); + setColorInterval( color1, color2 ); } //! Destructor @@ -233,24 +221,6 @@ QwtLinearColorMap::~QwtLinearColorMap() delete d_data; } -//! Assignment operator -QwtLinearColorMap &QwtLinearColorMap::operator=( - const QwtLinearColorMap &other) -{ - QwtColorMap::operator=(other); - *d_data = *other.d_data; - return *this; -} - -//! Clone the color map -QwtColorMap *QwtLinearColorMap::copy() const -{ - QwtLinearColorMap* map = new QwtLinearColorMap(); - *map = *this; - - return map; -} - /*! \brief Set the mode of the color map @@ -260,7 +230,7 @@ QwtColorMap *QwtLinearColorMap::copy() const \sa mode() */ -void QwtLinearColorMap::setMode(Mode mode) +void QwtLinearColorMap::setMode( Mode mode ) { d_data->mode = mode; } @@ -285,11 +255,11 @@ QwtLinearColorMap::Mode QwtLinearColorMap::mode() const \sa color1(), color2() */ void QwtLinearColorMap::setColorInterval( - const QColor &color1, const QColor &color2) + const QColor &color1, const QColor &color2 ) { d_data->colorStops = ColorStops(); - d_data->colorStops.insert(0.0, color1); - d_data->colorStops.insert(1.0, color2); + d_data->colorStops.insert( 0.0, color1 ); + d_data->colorStops.insert( 1.0, color2 ); } /*! @@ -302,16 +272,16 @@ void QwtLinearColorMap::setColorInterval( \param value Value between [0.0, 1.0] \param color Color stop */ -void QwtLinearColorMap::addColorStop(double value, const QColor& color) +void QwtLinearColorMap::addColorStop( double value, const QColor& color ) { if ( value >= 0.0 && value <= 1.0 ) - d_data->colorStops.insert(value, color); + d_data->colorStops.insert( value, color ); } /*! - Return all positions of color stops in increasing order + \return Positions of color stops in increasing order */ -QwtArray<double> QwtLinearColorMap::colorStops() const +QVector<double> QwtLinearColorMap::colorStops() const { return d_data->colorStops.stops(); } @@ -322,7 +292,7 @@ QwtArray<double> QwtLinearColorMap::colorStops() const */ QColor QwtLinearColorMap::color1() const { - return QColor(d_data->colorStops.rgb(d_data->mode, 0.0)); + return QColor( d_data->colorStops.rgb( d_data->mode, 0.0 ) ); } /*! @@ -331,51 +301,58 @@ QColor QwtLinearColorMap::color1() const */ QColor QwtLinearColorMap::color2() const { - return QColor(d_data->colorStops.rgb(d_data->mode, 1.0)); + return QColor( d_data->colorStops.rgb( d_data->mode, 1.0 ) ); } /*! - Map a value of a given interval into a rgb value + Map a value of a given interval into a RGB value \param interval Range for all values - \param value Value to map into a rgb value + \param value Value to map into a RGB value + + \return RGB value for value */ QRgb QwtLinearColorMap::rgb( - const QwtDoubleInterval &interval, double value) const + const QwtInterval &interval, double value ) const { + if ( qIsNaN(value) ) + return qRgba(0, 0, 0, 0); + const double width = interval.width(); double ratio = 0.0; if ( width > 0.0 ) - ratio = (value - interval.minValue()) / width; + ratio = ( value - interval.minValue() ) / width; - return d_data->colorStops.rgb(d_data->mode, ratio); + return d_data->colorStops.rgb( d_data->mode, ratio ); } /*! - Map a value of a given interval into a color index, between 0 and 255 + \brief Map a value of a given interval into a color index \param interval Range for all values \param value Value to map into a color index + + \return Index, between 0 and 255 */ unsigned char QwtLinearColorMap::colorIndex( - const QwtDoubleInterval &interval, double value) const + const QwtInterval &interval, double value ) const { const double width = interval.width(); - if ( width <= 0.0 || value <= interval.minValue() ) + if ( qIsNaN(value) || width <= 0.0 || value <= interval.minValue() ) return 0; if ( value >= interval.maxValue() ) - return (unsigned char)255; + return 255; - const double ratio = (value - interval.minValue()) / width; + const double ratio = ( value - interval.minValue() ) / width; unsigned char index; if ( d_data->mode == FixedColors ) - index = (unsigned char)(ratio * 255); // always floor + index = static_cast<unsigned char>( ratio * 255 ); // always floor else - index = (unsigned char)qRound(ratio * 255); + index = static_cast<unsigned char>( qRound( ratio * 255 ) ); return index; } @@ -392,23 +369,12 @@ public: Constructor \param color Color of the map */ -QwtAlphaColorMap::QwtAlphaColorMap(const QColor &color): - QwtColorMap(QwtColorMap::RGB) +QwtAlphaColorMap::QwtAlphaColorMap( const QColor &color ): + QwtColorMap( QwtColorMap::RGB ) { d_data = new PrivateData; d_data->color = color; - d_data->rgb = color.rgb() & qRgba(255, 255, 255, 0); -} - -/*! - Copy constructor - \param other Other color map -*/ -QwtAlphaColorMap::QwtAlphaColorMap(const QwtAlphaColorMap &other): - QwtColorMap(other) -{ - d_data = new PrivateData; - *this = other; + d_data->rgb = color.rgb() & qRgba( 255, 255, 255, 0 ); } //! Destructor @@ -417,35 +383,13 @@ QwtAlphaColorMap::~QwtAlphaColorMap() delete d_data; } -/*! - Assignment operator - \param other Other color map - \return *this -*/ -QwtAlphaColorMap &QwtAlphaColorMap::operator=( - const QwtAlphaColorMap &other) -{ - QwtColorMap::operator=(other); - *d_data = *other.d_data; - return *this; -} - -//! Clone the color map -QwtColorMap *QwtAlphaColorMap::copy() const -{ - QwtAlphaColorMap* map = new QwtAlphaColorMap(); - *map = *this; - - return map; -} - /*! Set the color \param color Color \sa color() */ -void QwtAlphaColorMap::setColor(const QColor &color) +void QwtAlphaColorMap::setColor( const QColor &color ) { d_data->color = color; d_data->rgb = color.rgb(); @@ -466,22 +410,22 @@ QColor QwtAlphaColorMap::color() const alpha := (value - interval.minValue()) / interval.width(); \param interval Range for all values - \param value Value to map into a rgb value - \return rgb value, with an alpha value + \param value Value to map into a RGB value + \return RGB value, with an alpha value */ -QRgb QwtAlphaColorMap::rgb(const QwtDoubleInterval &interval, - double value) const +QRgb QwtAlphaColorMap::rgb( const QwtInterval &interval, double value ) const { const double width = interval.width(); - if ( width >= 0.0 ) { - const double ratio = (value - interval.minValue()) / width; - int alpha = qRound(255 * ratio); + if ( !qIsNaN(value) && width >= 0.0 ) + { + const double ratio = ( value - interval.minValue() ) / width; + int alpha = qRound( 255 * ratio ); if ( alpha < 0 ) alpha = 0; if ( alpha > 255 ) alpha = 255; - return d_data->rgb | (alpha << 24); + return d_data->rgb | ( alpha << 24 ); } return d_data->rgb; } @@ -494,7 +438,7 @@ QRgb QwtAlphaColorMap::rgb(const QwtDoubleInterval &interval, \return Always 0 */ unsigned char QwtAlphaColorMap::colorIndex( - const QwtDoubleInterval &, double) const + const QwtInterval &, double ) const { return 0; } diff --git a/libs/qwt/qwt_color_map.h b/libs/qwt/qwt_color_map.h index 759ac5a5ba..91a92bd0cc 100644 --- a/libs/qwt/qwt_color_map.h +++ b/libs/qwt/qwt_color_map.h @@ -10,21 +10,10 @@ #ifndef QWT_COLOR_MAP_H #define QWT_COLOR_MAP_H -#include <qglobal.h> +#include "qwt_global.h" +#include "qwt_interval.h" #include <qcolor.h> -#if QT_VERSION < 0x040000 -#include <qvaluevector.h> -#else #include <qvector.h> -#endif -#include "qwt_array.h" -#include "qwt_double_interval.h" - -#if defined(QWT_TEMPLATEDLL) -// MOC_SKIP_BEGIN -template class QWT_EXPORT QwtArray<double>; -// MOC_SKIP_END -#endif /*! \brief QwtColorMap is used to map values into colors. @@ -45,67 +34,60 @@ class QWT_EXPORT QwtColorMap { public: /*! - - RGB\n - The map is intended to map into QRgb values. - - Indexed\n - The map is intended to map into 8 bit values, that - are indices into the color table. - + Format for color mapping \sa rgb(), colorIndex(), colorTable() */ - enum Format { + enum Format + { + //! The map is intended to map into RGB values. RGB, + + /*! + The map is intended to map into 8 bit values, that + are indices into the color table. + */ Indexed }; - QwtColorMap(Format = QwtColorMap::RGB ); + QwtColorMap( Format = QwtColorMap::RGB ); virtual ~QwtColorMap(); - inline Format format() const; - - //! Clone the color map - virtual QwtColorMap *copy() const = 0; + Format format() const; /*! - Map a value of a given interval into a rgb value. + Map a value of a given interval into a RGB value. + \param interval Range for the values \param value Value - \return rgb value, corresponding to value + \return RGB value, corresponding to value */ - virtual QRgb rgb( - const QwtDoubleInterval &interval, double value) const = 0; + virtual QRgb rgb( const QwtInterval &interval, + double value ) const = 0; /*! Map a value of a given interval into a color index + \param interval Range for the values \param value Value \return color index, corresponding to value */ virtual unsigned char colorIndex( - const QwtDoubleInterval &interval, double value) const = 0; + const QwtInterval &interval, double value ) const = 0; - QColor color(const QwtDoubleInterval &, double value) const; -#if QT_VERSION < 0x040000 - virtual QValueVector<QRgb> colorTable(const QwtDoubleInterval &) const; -#else - virtual QVector<QRgb> colorTable(const QwtDoubleInterval &) const; -#endif + QColor color( const QwtInterval &, double value ) const; + virtual QVector<QRgb> colorTable( const QwtInterval & ) const; private: Format d_format; }; - /*! \brief QwtLinearColorMap builds a color map from color stops. A color stop is a color at a specific position. The valid range for the positions is [0.0, 1.0]. When mapping a value - into a color it is translated into this interval. If - mode() == FixedColors the color is calculated from the next lower - color stop. If mode() == ScaledColors the color is calculated - by interpolating the colors of the adjacent stops. + into a color it is translated into this interval according to mode(). */ class QWT_EXPORT QwtLinearColorMap: public QwtColorMap { @@ -114,67 +96,66 @@ public: Mode of color map \sa setMode(), mode() */ - enum Mode { + enum Mode + { + //! Return the color from the next lower color stop FixedColors, + + //! Interpolating the colors of the adjacent stops. ScaledColors }; - QwtLinearColorMap(QwtColorMap::Format = QwtColorMap::RGB); + QwtLinearColorMap( QwtColorMap::Format = QwtColorMap::RGB ); QwtLinearColorMap( const QColor &from, const QColor &to, - QwtColorMap::Format = QwtColorMap::RGB); - - QwtLinearColorMap(const QwtLinearColorMap &); + QwtColorMap::Format = QwtColorMap::RGB ); virtual ~QwtLinearColorMap(); - QwtLinearColorMap &operator=(const QwtLinearColorMap &); - - virtual QwtColorMap *copy() const; - - void setMode(Mode); + void setMode( Mode ); Mode mode() const; - void setColorInterval(const QColor &color1, const QColor &color2); - void addColorStop(double value, const QColor&); - QwtArray<double> colorStops() const; + void setColorInterval( const QColor &color1, const QColor &color2 ); + void addColorStop( double value, const QColor& ); + QVector<double> colorStops() const; QColor color1() const; QColor color2() const; - virtual QRgb rgb(const QwtDoubleInterval &, double value) const; + virtual QRgb rgb( const QwtInterval &, double value ) const; virtual unsigned char colorIndex( - const QwtDoubleInterval &, double value) const; + const QwtInterval &, double value ) const; class ColorStops; private: + // Disabled copy constructor and operator= + QwtLinearColorMap( const QwtLinearColorMap & ); + QwtLinearColorMap &operator=( const QwtLinearColorMap & ); + class PrivateData; PrivateData *d_data; }; /*! - \brief QwtAlphaColorMap variies the alpha value of a color + \brief QwtAlphaColorMap varies the alpha value of a color */ class QWT_EXPORT QwtAlphaColorMap: public QwtColorMap { public: - QwtAlphaColorMap(const QColor & = QColor(Qt::gray)); - QwtAlphaColorMap(const QwtAlphaColorMap &); - + QwtAlphaColorMap( const QColor & = QColor( Qt::gray ) ); virtual ~QwtAlphaColorMap(); - QwtAlphaColorMap &operator=(const QwtAlphaColorMap &); - - virtual QwtColorMap *copy() const; - - void setColor(const QColor &); + void setColor( const QColor & ); QColor color() const; - virtual QRgb rgb(const QwtDoubleInterval &, double value) const; + virtual QRgb rgb( const QwtInterval &, double value ) const; private: + QwtAlphaColorMap( const QwtAlphaColorMap & ); + QwtAlphaColorMap &operator=( const QwtAlphaColorMap & ); + virtual unsigned char colorIndex( - const QwtDoubleInterval &, double value) const; + const QwtInterval &, double value ) const; class PrivateData; PrivateData *d_data; @@ -194,13 +175,16 @@ private: color table once and find the color using colorIndex(). */ inline QColor QwtColorMap::color( - const QwtDoubleInterval &interval, double value) const + const QwtInterval &interval, double value ) const { - if ( d_format == RGB ) { - return QColor( rgb(interval, value) ); - } else { - const unsigned int index = colorIndex(interval, value); - return colorTable(interval)[index]; // slow + if ( d_format == RGB ) + { + return QColor( rgb( interval, value ) ); + } + else + { + const unsigned int index = colorIndex( interval, value ); + return colorTable( interval )[index]; // slow } } diff --git a/libs/qwt/qwt_column_symbol.cpp b/libs/qwt/qwt_column_symbol.cpp new file mode 100644 index 0000000000..d6f0f1a635 --- /dev/null +++ b/libs/qwt/qwt_column_symbol.cpp @@ -0,0 +1,293 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_column_symbol.h" +#include "qwt_math.h" +#include "qwt_painter.h" +#include <qpainter.h> +#include <qpalette.h> + +static void qwtDrawBox( QPainter *p, const QRectF &rect, + const QPalette &pal, double lw ) +{ + if ( lw > 0.0 ) + { + if ( rect.width() == 0.0 ) + { + p->setPen( pal.dark().color() ); + p->drawLine( rect.topLeft(), rect.bottomLeft() ); + return; + } + + if ( rect.height() == 0.0 ) + { + p->setPen( pal.dark().color() ); + p->drawLine( rect.topLeft(), rect.topRight() ); + return; + } + + lw = qMin( lw, rect.height() / 2.0 - 1.0 ); + lw = qMin( lw, rect.width() / 2.0 - 1.0 ); + + const QRectF outerRect = rect.adjusted( 0, 0, 1, 1 ); + QPolygonF polygon( outerRect ); + + if ( outerRect.width() > 2 * lw && + outerRect.height() > 2 * lw ) + { + const QRectF innerRect = outerRect.adjusted( lw, lw, -lw, -lw ); + polygon = polygon.subtracted( innerRect ); + } + + p->setPen( Qt::NoPen ); + + p->setBrush( pal.dark() ); + p->drawPolygon( polygon ); + } + + const QRectF windowRect = rect.adjusted( lw, lw, -lw + 1, -lw + 1 ); + if ( windowRect.isValid() ) + p->fillRect( windowRect, pal.window() ); +} + +static void qwtDrawPanel( QPainter *painter, const QRectF &rect, + const QPalette &pal, double lw ) +{ + if ( lw > 0.0 ) + { + if ( rect.width() == 0.0 ) + { + painter->setPen( pal.window().color() ); + painter->drawLine( rect.topLeft(), rect.bottomLeft() ); + return; + } + + if ( rect.height() == 0.0 ) + { + painter->setPen( pal.window().color() ); + painter->drawLine( rect.topLeft(), rect.topRight() ); + return; + } + + lw = qMin( lw, rect.height() / 2.0 - 1.0 ); + lw = qMin( lw, rect.width() / 2.0 - 1.0 ); + + const QRectF outerRect = rect.adjusted( 0, 0, 1, 1 ); + const QRectF innerRect = outerRect.adjusted( lw, lw, -lw, -lw ); + + QPolygonF lines[2]; + + lines[0] += outerRect.bottomLeft(); + lines[0] += outerRect.topLeft(); + lines[0] += outerRect.topRight(); + lines[0] += innerRect.topRight(); + lines[0] += innerRect.topLeft(); + lines[0] += innerRect.bottomLeft(); + + lines[1] += outerRect.topRight(); + lines[1] += outerRect.bottomRight(); + lines[1] += outerRect.bottomLeft(); + lines[1] += innerRect.bottomLeft(); + lines[1] += innerRect.bottomRight(); + lines[1] += innerRect.topRight(); + + painter->setPen( Qt::NoPen ); + + painter->setBrush( pal.light() ); + painter->drawPolygon( lines[0] ); + painter->setBrush( pal.dark() ); + painter->drawPolygon( lines[1] ); + } + + painter->fillRect( rect.adjusted( lw, lw, -lw + 1, -lw + 1 ), pal.window() ); +} + +class QwtColumnSymbol::PrivateData +{ +public: + PrivateData(): + style( QwtColumnSymbol::Box ), + frameStyle( QwtColumnSymbol::Raised ), + lineWidth( 2 ) + { + palette = QPalette( Qt::gray ); + } + + QwtColumnSymbol::Style style; + QwtColumnSymbol::FrameStyle frameStyle; + + QPalette palette; + int lineWidth; +}; + +/*! + Constructor + + \param style Style of the symbol + \sa setStyle(), style(), Style +*/ +QwtColumnSymbol::QwtColumnSymbol( Style style ) +{ + d_data = new PrivateData(); + d_data->style = style; +} + +//! Destructor +QwtColumnSymbol::~QwtColumnSymbol() +{ + delete d_data; +} + +/*! + Specify the symbol style + + \param style Style + \sa style(), setPalette() +*/ +void QwtColumnSymbol::setStyle( Style style ) +{ + d_data->style = style; +} + +/*! + \return Current symbol style + \sa setStyle() +*/ +QwtColumnSymbol::Style QwtColumnSymbol::style() const +{ + return d_data->style; +} + +/*! + Assign a palette for the symbol + + \param palette Palette + \sa palette(), setStyle() +*/ +void QwtColumnSymbol::setPalette( const QPalette &palette ) +{ + d_data->palette = palette; +} + +/*! + \return Current palette + \sa setPalette() +*/ +const QPalette& QwtColumnSymbol::palette() const +{ + return d_data->palette; +} + +/*! + Set the frame, that is used for the Box style. + + \param frameStyle Frame style + \sa frameStyle(), setLineWidth(), setStyle() +*/ +void QwtColumnSymbol::setFrameStyle( FrameStyle frameStyle ) +{ + d_data->frameStyle = frameStyle; +} + +/*! + \return Current frame style, that is used for the Box style. + \sa setFrameStyle(), lineWidth(), setStyle() +*/ +QwtColumnSymbol::FrameStyle QwtColumnSymbol::frameStyle() const +{ + return d_data->frameStyle; +} + +/*! + Set the line width of the frame, that is used for the Box style. + + \param width Width + \sa lineWidth(), setFrameStyle() +*/ +void QwtColumnSymbol::setLineWidth( int width ) +{ + if ( width < 0 ) + width = 0; + + d_data->lineWidth = width; +} + +/*! + \return Line width of the frame, that is used for the Box style. + \sa setLineWidth(), frameStyle(), setStyle() +*/ +int QwtColumnSymbol::lineWidth() const +{ + return d_data->lineWidth; +} + +/*! + Draw the symbol depending on its style. + + \param painter Painter + \param rect Directed rectangle + + \sa drawBox() +*/ +void QwtColumnSymbol::draw( QPainter *painter, + const QwtColumnRect &rect ) const +{ + painter->save(); + + switch ( d_data->style ) + { + case QwtColumnSymbol::Box: + { + drawBox( painter, rect ); + break; + } + default:; + } + + painter->restore(); +} + +/*! + Draw the symbol when it is in Box style. + + \param painter Painter + \param rect Directed rectangle + + \sa draw() +*/ +void QwtColumnSymbol::drawBox( QPainter *painter, + const QwtColumnRect &rect ) const +{ + QRectF r = rect.toRect(); + if ( QwtPainter::roundingAlignment( painter ) ) + { + r.setLeft( qRound( r.left() ) ); + r.setRight( qRound( r.right() ) ); + r.setTop( qRound( r.top() ) ); + r.setBottom( qRound( r.bottom() ) ); + } + + switch ( d_data->frameStyle ) + { + case QwtColumnSymbol::Raised: + { + qwtDrawPanel( painter, r, d_data->palette, d_data->lineWidth ); + break; + } + case QwtColumnSymbol::Plain: + { + qwtDrawBox( painter, r, d_data->palette, d_data->lineWidth ); + break; + } + default: + { + painter->fillRect( r, d_data->palette.window() ); + } + } +} diff --git a/libs/qwt/qwt_column_symbol.h b/libs/qwt/qwt_column_symbol.h new file mode 100644 index 0000000000..918fe4a3cc --- /dev/null +++ b/libs/qwt/qwt_column_symbol.h @@ -0,0 +1,161 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_COLUMN_SYMBOL_H +#define QWT_COLUMN_SYMBOL_H + +#include "qwt_global.h" +#include "qwt_interval.h" +#include <qpen.h> +#include <qsize.h> +#include <qrect.h> + +class QPainter; +class QPalette; +class QRect; +class QwtText; + +/*! + \brief Directed rectangle representing bounding rectangle and orientation + of a column. +*/ +class QWT_EXPORT QwtColumnRect +{ +public: + //! Direction of the column + enum Direction + { + //! From left to right + LeftToRight, + + //! From right to left + RightToLeft, + + //! From bottom to top + BottomToTop, + + //! From top to bottom + TopToBottom + }; + + //! Build an rectangle with invalid intervals directed BottomToTop. + QwtColumnRect(): + direction( BottomToTop ) + { + } + + //! \return A normalized QRect built from the intervals + QRectF toRect() const + { + QRectF r( hInterval.minValue(), vInterval.minValue(), + hInterval.maxValue() - hInterval.minValue(), + vInterval.maxValue() - vInterval.minValue() ); + r = r.normalized(); + + if ( hInterval.borderFlags() & QwtInterval::ExcludeMinimum ) + r.adjust( 1, 0, 0, 0 ); + if ( hInterval.borderFlags() & QwtInterval::ExcludeMaximum ) + r.adjust( 0, 0, -1, 0 ); + if ( vInterval.borderFlags() & QwtInterval::ExcludeMinimum ) + r.adjust( 0, 1, 0, 0 ); + if ( vInterval.borderFlags() & QwtInterval::ExcludeMaximum ) + r.adjust( 0, 0, 0, -1 ); + + return r; + } + + //! \return Orientation + Qt::Orientation orientation() const + { + if ( direction == LeftToRight || direction == RightToLeft ) + return Qt::Horizontal; + + return Qt::Vertical; + } + + //! Interval for the horizontal coordinates + QwtInterval hInterval; + + //! Interval for the vertical coordinates + QwtInterval vInterval; + + //! Direction + Direction direction; +}; + +//! A drawing primitive for columns +class QWT_EXPORT QwtColumnSymbol +{ +public: + /*! + Style + \sa setStyle(), style() + */ + enum Style + { + //! No Style, the symbol draws nothing + NoStyle = -1, + + /*! + The column is painted with a frame depending on the frameStyle() + and lineWidth() using the palette(). + */ + Box, + + /*! + Styles >= QwtColumnSymbol::UserStyle are reserved for derived + classes of QwtColumnSymbol that overload draw() with + additional application specific symbol types. + */ + UserStyle = 1000 + }; + + /*! + Frame Style used in Box style(). + \sa Style, setFrameStyle(), frameStyle(), setStyle(), setPalette() + */ + enum FrameStyle + { + //! No frame + NoFrame, + + //! A plain frame style + Plain, + + //! A raised frame style + Raised + }; + +public: + QwtColumnSymbol( Style = NoStyle ); + virtual ~QwtColumnSymbol(); + + void setFrameStyle( FrameStyle style ); + FrameStyle frameStyle() const; + + void setLineWidth( int width ); + int lineWidth() const; + + void setPalette( const QPalette & ); + const QPalette &palette() const; + + void setStyle( Style ); + Style style() const; + + virtual void draw( QPainter *, const QwtColumnRect & ) const; + +protected: + void drawBox( QPainter *, const QwtColumnRect & ) const; + +private: + class PrivateData; + PrivateData* d_data; +}; + +#endif diff --git a/libs/qwt/qwt_compass.cpp b/libs/qwt/qwt_compass.cpp index e2ce650408..4e2c9ffdf5 100644 --- a/libs/qwt/qwt_compass.cpp +++ b/libs/qwt/qwt_compass.cpp @@ -7,33 +7,126 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <math.h> -#include <qpainter.h> -#include <qpixmap.h> -#include <qevent.h> +#include "qwt_compass.h" +#include "qwt_compass_rose.h" #include "qwt_math.h" #include "qwt_scale_draw.h" -#include "qwt_paint_buffer.h" #include "qwt_painter.h" #include "qwt_dial_needle.h" -#include "qwt_compass_rose.h" -#include "qwt_compass.h" +#include <qpainter.h> +#include <qpixmap.h> +#include <qevent.h> + +/*! + \brief Constructor + + Initializes a label map for multiples of 45 degrees + */ +QwtCompassScaleDraw::QwtCompassScaleDraw() +{ + enableComponent( QwtAbstractScaleDraw::Backbone, false ); + enableComponent( QwtAbstractScaleDraw::Ticks, false ); + + d_labelMap.insert( 0.0, QString::fromLatin1( "N" ) ); + d_labelMap.insert( 45.0, QString::fromLatin1( "NE" ) ); + d_labelMap.insert( 90.0, QString::fromLatin1( "E" ) ); + d_labelMap.insert( 135.0, QString::fromLatin1( "SE" ) ); + d_labelMap.insert( 180.0, QString::fromLatin1( "S" ) ); + d_labelMap.insert( 225.0, QString::fromLatin1( "SW" ) ); + d_labelMap.insert( 270.0, QString::fromLatin1( "W" ) ); + d_labelMap.insert( 315.0, QString::fromLatin1( "NW" ) ); + +#if 0 + d_labelMap.insert( 22.5, QString::fromLatin1( "NNE" ) ); + d_labelMap.insert( 67.5, QString::fromLatin1( "NEE" ) ); + d_labelMap.insert( 112.5, QString::fromLatin1( "SEE" ) ); + d_labelMap.insert( 157.5, QString::fromLatin1( "SSE" ) ); + d_labelMap.insert( 202.5, QString::fromLatin1( "SSW" ) ); + d_labelMap.insert( 247.5, QString::fromLatin1( "SWW" ) ); + d_labelMap.insert( 292.5, QString::fromLatin1( "NWW" ) ); + d_labelMap.insert( 337.5, QString::fromLatin1( "NNW" ) ); +#endif +} + +/*! + \brief Constructor + + \param map Value to label map + */ +QwtCompassScaleDraw::QwtCompassScaleDraw( const QMap<double, QString> &map ): + d_labelMap( map ) +{ + enableComponent( QwtAbstractScaleDraw::Backbone, false ); + enableComponent( QwtAbstractScaleDraw::Ticks, false ); +} + +/*! + \brief Set a map, mapping values to labels + \param map Value to label map + + The values of the major ticks are found by looking into this + map. The default map consists of the labels N, NE, E, SE, S, SW, W, NW. + + \warning The map will have no effect for values that are no major + tick values. Major ticks can be changed by QwtScaleDraw::setScale + + \sa labelMap(), scaleDraw(), setScale() +*/ +void QwtCompassScaleDraw::setLabelMap( const QMap<double, QString> &map ) +{ + d_labelMap = map; +} + + +/*! + \return map, mapping values to labels + \sa setLabelMap() +*/ +QMap<double, QString> QwtCompassScaleDraw::labelMap() const +{ + return d_labelMap; +} + +/*! + Map a value to a corresponding label + + \param value Value that will be mapped + + label() looks in the labelMap() for a corresponding label for value + or returns an null text. + + \return Label, or QString::null + \sa labelMap(), setLabelMap() +*/ + +QwtText QwtCompassScaleDraw::label( double value ) const +{ + if ( qFuzzyCompare( value + 1.0, 1.0 ) ) + value = 0.0; + + if ( value < 0.0 ) + value += 360.0; + + if ( d_labelMap.contains( value ) ) + return d_labelMap[value]; + + return QwtText(); +} class QwtCompass::PrivateData { public: PrivateData(): - rose(NULL) { + rose( NULL ) + { } - ~PrivateData() { + ~PrivateData() + { delete rose; } QwtCompassRose *rose; - QMap<double, QString> labelMap; }; /*! @@ -45,31 +138,22 @@ public: mouse and keyboard inputs and has no step size. The default mode is QwtDial::RotateNeedle. */ -QwtCompass::QwtCompass(QWidget* parent): - QwtDial(parent) +QwtCompass::QwtCompass( QWidget* parent ): + QwtDial( parent ) { - initCompass(); -} + d_data = new PrivateData; -#if QT_VERSION < 0x040000 + setScaleDraw( new QwtCompassScaleDraw() ); -/*! - \brief Constructor - \param parent Parent widget - \param name Object name + setOrigin( 270.0 ); + setWrapping( true ); - Create a compass widget with a scale, no needle and no rose. - The default origin is 270.0 with no valid value. It accepts - mouse and keyboard inputs and has no step size. The default mode - is QwtDial::RotateNeedle. -*/ -QwtCompass::QwtCompass(QWidget* parent, const char *name): - QwtDial(parent, name) -{ - initCompass(); -} + setScaleMaxMajor( 36 ); + setScaleMaxMinor( 10 ); -#endif + setScale( 0.0, 360.0 ); // degrees as default + setTotalSteps( 360 ); +} //! Destructor QwtCompass::~QwtCompass() @@ -77,40 +161,16 @@ QwtCompass::~QwtCompass() delete d_data; } -void QwtCompass::initCompass() -{ - d_data = new PrivateData; - - setScaleOptions(ScaleLabel); // Only labels, no backbone, no ticks - - setOrigin(270.0); - setWrapping(true); - - d_data->labelMap.insert(0.0, QString::fromLatin1("N")); - d_data->labelMap.insert(45.0, QString::fromLatin1("NE")); - d_data->labelMap.insert(90.0, QString::fromLatin1("E")); - d_data->labelMap.insert(135.0, QString::fromLatin1("SE")); - d_data->labelMap.insert(180.0, QString::fromLatin1("S")); - d_data->labelMap.insert(225.0, QString::fromLatin1("SW")); - d_data->labelMap.insert(270.0, QString::fromLatin1("W")); - d_data->labelMap.insert(315.0, QString::fromLatin1("NW")); - -#if 0 - d_data->labelMap.insert(22.5, QString::fromLatin1("NNE")); - d_data->labelMap.insert(67.5, QString::fromLatin1("NEE")); - d_data->labelMap.insert(112.5, QString::fromLatin1("SEE")); - d_data->labelMap.insert(157.5, QString::fromLatin1("SSE")); - d_data->labelMap.insert(202.5, QString::fromLatin1("SSW")); - d_data->labelMap.insert(247.5, QString::fromLatin1("SWW")); - d_data->labelMap.insert(292.5, QString::fromLatin1("NWW")); - d_data->labelMap.insert(337.5, QString::fromLatin1("NNW")); -#endif -} +/*! + Draw the contents of the scale -//! Draw the contents of the scale -void QwtCompass::drawScaleContents(QPainter *painter, - const QPoint ¢er, int radius) const + \param painter Painter + \param center Center of the content circle + \param radius Radius of the content circle +*/ +void QwtCompass::drawScaleContents( QPainter *painter, + const QPointF ¢er, double radius ) const { QPalette::ColorGroup cg; if ( isEnabled() ) @@ -119,13 +179,14 @@ void QwtCompass::drawScaleContents(QPainter *painter, cg = QPalette::Disabled; double north = origin(); - if ( isValid() ) { + if ( isValid() ) + { if ( mode() == RotateScale ) north -= value(); } const int margin = 4; - drawRose(painter, center, radius - margin, 360.0 - north, cg); + drawRose( painter, center, radius - margin, 360.0 - north, cg ); } /*! @@ -137,11 +198,11 @@ void QwtCompass::drawScaleContents(QPainter *painter, \param north Direction pointing north, in degrees counter clockwise \param cg Color group */ -void QwtCompass::drawRose(QPainter *painter, const QPoint ¢er, - int radius, double north, QPalette::ColorGroup cg) const +void QwtCompass::drawRose( QPainter *painter, const QPointF ¢er, + double radius, double north, QPalette::ColorGroup cg ) const { if ( d_data->rose ) - d_data->rose->draw(painter, center, radius, north, cg); + d_data->rose->draw( painter, center, radius, north, cg ); } /*! @@ -151,9 +212,10 @@ void QwtCompass::drawRose(QPainter *painter, const QPoint ¢er, set or in ~QwtCompass \sa rose() */ -void QwtCompass::setRose(QwtCompassRose *rose) +void QwtCompass::setRose( QwtCompassRose *rose ) { - if ( rose != d_data->rose ) { + if ( rose != d_data->rose ) + { if ( d_data->rose ) delete d_data->rose; @@ -189,13 +251,14 @@ QwtCompassRose *QwtCompass::rose() \sa isReadOnly() */ -void QwtCompass::keyPressEvent(QKeyEvent *kev) +void QwtCompass::keyPressEvent( QKeyEvent *kev ) { - if (isReadOnly()) + if ( isReadOnly() ) return; #if 0 - if ( kev->key() == Key_5 ) { + if ( kev->key() == Key_5 ) + { invalidate(); // signal ??? return; } @@ -203,101 +266,43 @@ void QwtCompass::keyPressEvent(QKeyEvent *kev) double newValue = value(); - if ( kev->key() >= Qt::Key_1 && kev->key() <= Qt::Key_9 ) { + if ( kev->key() >= Qt::Key_1 && kev->key() <= Qt::Key_9 ) + { if ( mode() != RotateNeedle || kev->key() == Qt::Key_5 ) return; - switch (kev->key()) { - case Qt::Key_6: - newValue = 180.0 * 0.0; - break; - case Qt::Key_3: - newValue = 180.0 * 0.25; - break; - case Qt::Key_2: - newValue = 180.0 * 0.5; - break; - case Qt::Key_1: - newValue = 180.0 * 0.75; - break; - case Qt::Key_4: - newValue = 180.0 * 1.0; - break; - case Qt::Key_7: - newValue = 180.0 * 1.25; - break; - case Qt::Key_8: - newValue = 180.0 * 1.5; - break; - case Qt::Key_9: - newValue = 180.0 * 1.75; - break; + switch ( kev->key() ) + { + case Qt::Key_6: + newValue = 180.0 * 0.0; + break; + case Qt::Key_3: + newValue = 180.0 * 0.25; + break; + case Qt::Key_2: + newValue = 180.0 * 0.5; + break; + case Qt::Key_1: + newValue = 180.0 * 0.75; + break; + case Qt::Key_4: + newValue = 180.0 * 1.0; + break; + case Qt::Key_7: + newValue = 180.0 * 1.25; + break; + case Qt::Key_8: + newValue = 180.0 * 1.5; + break; + case Qt::Key_9: + newValue = 180.0 * 1.75; + break; } newValue -= origin(); - setValue(newValue); - } else { - QwtDial::keyPressEvent(kev); + setValue( newValue ); + } + else + { + QwtDial::keyPressEvent( kev ); } -} - -/*! - \return map, mapping values to labels - \sa setLabelMap() -*/ -const QMap<double, QString> &QwtCompass::labelMap() const -{ - return d_data->labelMap; -} - -/*! - \return map, mapping values to labels - \sa setLabelMap() -*/ -QMap<double, QString> &QwtCompass::labelMap() -{ - return d_data->labelMap; -} - -/*! - \brief Set a map, mapping values to labels - \param map value to label map - - The values of the major ticks are found by looking into this - map. The default map consists of the labels N, NE, E, SE, S, SW, W, NW. - - \warning The map will have no effect for values that are no major - tick values. Major ticks can be changed by QwtScaleDraw::setScale - - \sa labelMap(), scaleDraw(), setScale() -*/ -void QwtCompass::setLabelMap(const QMap<double, QString> &map) -{ - d_data->labelMap = map; -} - -/*! - Map a value to a corresponding label - \param value Value that will be mapped - \return Label, or QString::null - - label() looks in a map for a corresponding label for value - or return an null text. - \sa labelMap(), setLabelMap() -*/ - -QwtText QwtCompass::scaleLabel(double value) const -{ -#if 0 - // better solution ??? - if ( value == -0 ) - value = 0.0; -#endif - - if ( value < 0.0 ) - value += 360.0; - - if ( d_data->labelMap.contains(value) ) - return d_data->labelMap[value]; - - return QwtText(); } diff --git a/libs/qwt/qwt_compass.h b/libs/qwt/qwt_compass.h index ed6d06d0a9..b9a3c95bff 100644 --- a/libs/qwt/qwt_compass.h +++ b/libs/qwt/qwt_compass.h @@ -10,29 +10,38 @@ #ifndef QWT_COMPASS_H #define QWT_COMPASS_H 1 +#include "qwt_global.h" +#include "qwt_dial.h" +#include "qwt_round_scale_draw.h" #include <qstring.h> #include <qmap.h> -#include "qwt_dial.h" -#if defined(QWT_TEMPLATEDLL) +class QwtCompassRose; + +/*! + \brief A special scale draw made for QwtCompass -#if defined(QT_NO_STL) || QT_VERSION < 0x040000 || QT_VERSION > 0x040001 -/* - Unfortunately Qt 4.0.0/Qt 4.0.1 contains uncompilable - code in the STL adaptors of qmap.h. The declaration below - instantiates this code resulting in compiler errors. - If you really need the map to be exported, remove the condition above - and fix the qmap.h + QwtCompassScaleDraw maps values to strings using + a special map, that can be modified by the application + + The default map consists of the labels N, NE, E, SE, S, SW, W, NW. + + \sa QwtCompass */ -// MOC_SKIP_BEGIN -template class QWT_EXPORT QMap<double, QString>; -// MOC_SKIP_END -#endif +class QWT_EXPORT QwtCompassScaleDraw: public QwtRoundScaleDraw +{ +public: + explicit QwtCompassScaleDraw(); + explicit QwtCompassScaleDraw( const QMap<double, QString> &map ); -#endif + void setLabelMap( const QMap<double, QString> &map ); + QMap<double, QString> labelMap() const; + virtual QwtText label( double value ) const; -class QwtCompassRose; +private: + QMap<double, QString> d_labelMap; +}; /*! \brief A Compass Widget @@ -50,34 +59,23 @@ class QWT_EXPORT QwtCompass: public QwtDial Q_OBJECT public: - explicit QwtCompass( QWidget* parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtCompass(QWidget* parent, const char *name); -#endif + explicit QwtCompass( QWidget* parent = NULL ); virtual ~QwtCompass(); - void setRose(QwtCompassRose *rose); + void setRose( QwtCompassRose *rose ); const QwtCompassRose *rose() const; QwtCompassRose *rose(); - const QMap<double, QString> &labelMap() const; - QMap<double, QString> &labelMap(); - void setLabelMap(const QMap<double, QString> &map); - protected: - virtual QwtText scaleLabel(double value) const; + virtual void drawRose( QPainter *, const QPointF ¢er, + double radius, double north, QPalette::ColorGroup ) const; - virtual void drawRose(QPainter *, const QPoint ¢er, - int radius, double north, QPalette::ColorGroup) const; + virtual void drawScaleContents( QPainter *, + const QPointF ¢er, double radius ) const; - virtual void drawScaleContents(QPainter *, - const QPoint ¢er, int radius) const; - - virtual void keyPressEvent(QKeyEvent *); + virtual void keyPressEvent( QKeyEvent * ); private: - void initCompass(); - class PrivateData; PrivateData *d_data; }; diff --git a/libs/qwt/qwt_compass_rose.cpp b/libs/qwt/qwt_compass_rose.cpp index 6e412e4ce9..21a35f2444 100644 --- a/libs/qwt/qwt_compass_rose.cpp +++ b/libs/qwt/qwt_compass_rose.cpp @@ -7,48 +7,40 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <math.h> -#include <qpainter.h> -#include "qwt_math.h" -#include "qwt_painter.h" #include "qwt_compass_rose.h" +#include "qwt_point_polar.h" +#include "qwt_painter.h" +#include <qpainter.h> -static QPoint cutPoint(QPoint p11, QPoint p12, QPoint p21, QPoint p22) +static QPointF qwtIntersection( + QPointF p11, QPointF p12, QPointF p21, QPointF p22 ) { - double dx1 = p12.x() - p11.x(); - double dy1 = p12.y() - p11.y(); - double dx2 = p22.x() - p21.x(); - double dy2 = p22.y() - p21.y(); - - if ( dx1 == 0.0 && dx2 == 0.0 ) - return QPoint(); - - if ( dx1 == 0.0 ) { - const double m = dy2 / dx2; - const double t = p21.y() - m * p21.x(); - return QPoint(p11.x(), qRound(m * p11.x() + t)); - } + const QLineF line1( p11, p12 ); + const QLineF line2( p21, p22 ); - if ( dx2 == 0 ) { - const double m = dy1 / dx1; - const double t = p11.y() - m * p11.x(); - return QPoint(p21.x(), qRound(m * p21.x() + t)); - } - - const double m1 = dy1 / dx1; - const double t1 = p11.y() - m1 * p11.x(); + QPointF pos; + if ( line1.intersect( line2, &pos ) == QLineF::NoIntersection ) + return QPointF(); - const double m2 = dy2 / dx2; - const double t2 = p21.y() - m2 * p21.x(); - - if ( m1 == m2 ) - return QPoint(); + return pos; +} - const double x = ( t2 - t1 ) / ( m1 - m2 ); - const double y = t1 + m1 * x; +class QwtSimpleCompassRose::PrivateData +{ +public: + PrivateData(): + width( 0.2 ), + numThorns( 8 ), + numThornLevels( -1 ), + shrinkFactor( 0.9 ) + { + } - return QPoint(qRound(x), qRound(y)); -} + double width; + int numThorns; + int numThornLevels; + double shrinkFactor; +}; /*! Constructor @@ -56,31 +48,48 @@ static QPoint cutPoint(QPoint p11, QPoint p12, QPoint p21, QPoint p22) \param numThorns Number of thorns \param numThornLevels Number of thorn levels */ -QwtSimpleCompassRose::QwtSimpleCompassRose(int numThorns, int numThornLevels): - d_width(0.2), - d_numThorns(numThorns), - d_numThornLevels(numThornLevels), - d_shrinkFactor(0.9) +QwtSimpleCompassRose::QwtSimpleCompassRose( + int numThorns, int numThornLevels ) { - const QColor dark(128,128,255); - const QColor light(192,255,255); + d_data = new PrivateData(); + d_data->numThorns = numThorns; + d_data->numThornLevels = numThornLevels; + + const QColor dark( 128, 128, 255 ); + const QColor light( 192, 255, 255 ); QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) { -#if QT_VERSION < 0x040000 - palette.setColor((QPalette::ColorGroup)i, - QColorGroup::Dark, dark); - palette.setColor((QPalette::ColorGroup)i, - QColorGroup::Light, light); -#else - palette.setColor((QPalette::ColorGroup)i, - QPalette::Dark, dark); - palette.setColor((QPalette::ColorGroup)i, - QPalette::Light, light); -#endif - } + palette.setColor( QPalette::Dark, dark ); + palette.setColor( QPalette::Light, light ); - setPalette(palette); + setPalette( palette ); +} + +//! Destructor +QwtSimpleCompassRose::~QwtSimpleCompassRose() +{ + delete d_data; +} + +/*! + Set the Factor how to shrink the thorns with each level + The default value is 0.9. + + \param factor Shrink factor + \sa shrinkFactor() +*/ +void QwtSimpleCompassRose::setShrinkFactor( double factor ) +{ + d_data->shrinkFactor = factor; +} + +/*! + \return Factor how to shrink the thorns with each level + \sa setShrinkFactor() +*/ +double QwtSimpleCompassRose::shrinkFactor() const +{ + return d_data->shrinkFactor; } /*! @@ -92,28 +101,14 @@ QwtSimpleCompassRose::QwtSimpleCompassRose(int numThorns, int numThornLevels): \param north Position \param cg Color group */ -void QwtSimpleCompassRose::draw(QPainter *painter, const QPoint ¢er, - int radius, double north, QPalette::ColorGroup cg) const +void QwtSimpleCompassRose::draw( QPainter *painter, const QPointF ¢er, + double radius, double north, QPalette::ColorGroup cg ) const { -#if QT_VERSION < 0x040000 - QColorGroup colorGroup; - switch(cg) { - case QPalette::Disabled: - colorGroup = palette().disabled(); - case QPalette::Inactive: - colorGroup = palette().inactive(); - default: - colorGroup = palette().active(); - } - - drawRose(painter, colorGroup, center, radius, north, d_width, - d_numThorns, d_numThornLevels, d_shrinkFactor); -#else QPalette pal = palette(); - pal.setCurrentColorGroup(cg); - drawRose(painter, pal, center, radius, north, d_width, - d_numThorns, d_numThornLevels, d_shrinkFactor); -#endif + pal.setCurrentColorGroup( cg ); + + drawRose( painter, pal, center, radius, north, d_data->width, + d_data->numThorns, d_data->numThornLevels, d_data->shrinkFactor ); } /*! @@ -131,13 +126,9 @@ void QwtSimpleCompassRose::draw(QPainter *painter, const QPoint ¢er, */ void QwtSimpleCompassRose::drawRose( QPainter *painter, -#if QT_VERSION < 0x040000 - const QColorGroup &cg, -#else const QPalette &palette, -#endif - const QPoint ¢er, int radius, double north, double width, - int numThorns, int numThornLevels, double shrinkFactor) + const QPointF ¢er, double radius, double north, double width, + int numThorns, int numThornLevels, double shrinkFactor ) { if ( numThorns < 4 ) numThorns = 4; @@ -156,15 +147,17 @@ void QwtSimpleCompassRose::drawRose( painter->save(); - painter->setPen(Qt::NoPen); + painter->setPen( Qt::NoPen ); - for ( int j = 1; j <= numThornLevels; j++ ) { - double step = pow(2.0, j) * M_PI / (double)numThorns; + for ( int j = 1; j <= numThornLevels; j++ ) + { + double step = qPow( 2.0, j ) * M_PI / numThorns; if ( step > M_PI_2 ) break; double r = radius; - for ( int k = 0; k < 3; k++ ) { + for ( int k = 0; k < 3; k++ ) + { if ( j + k < numThornLevels ) r *= shrinkFactor; } @@ -173,37 +166,31 @@ void QwtSimpleCompassRose::drawRose( if ( 2.0 * M_PI / step > 32 ) leafWidth = 16; - const double origin = north / 180.0 * M_PI; + const double origin = qwtRadians( north ); for ( double angle = origin; - angle < 2.0 * M_PI + origin; angle += step) { - const QPoint p = qwtPolar2Pos(center, r, angle); - QPoint p1 = qwtPolar2Pos(center, leafWidth, angle + M_PI_2); - QPoint p2 = qwtPolar2Pos(center, leafWidth, angle - M_PI_2); - - QwtPolygon pa(3); - pa.setPoint(0, center); - pa.setPoint(1, p); - - QPoint p3 = qwtPolar2Pos(center, r, angle + step / 2.0); - p1 = cutPoint(center, p3, p1, p); - pa.setPoint(2, p1); -#if QT_VERSION < 0x040000 - painter->setBrush(cg.brush(QColorGroup::Dark)); -#else - painter->setBrush(palette.brush(QPalette::Dark)); -#endif - painter->drawPolygon(pa); - - QPoint p4 = qwtPolar2Pos(center, r, angle - step / 2.0); - p2 = cutPoint(center, p4, p2, p); - - pa.setPoint(2, p2); -#if QT_VERSION < 0x040000 - painter->setBrush(cg.brush(QColorGroup::Light)); -#else - painter->setBrush(palette.brush(QPalette::Light)); -#endif - painter->drawPolygon(pa); + angle < 2.0 * M_PI + origin; angle += step ) + { + const QPointF p = qwtPolar2Pos( center, r, angle ); + const QPointF p1 = qwtPolar2Pos( center, leafWidth, angle + M_PI_2 ); + const QPointF p2 = qwtPolar2Pos( center, leafWidth, angle - M_PI_2 ); + const QPointF p3 = qwtPolar2Pos( center, r, angle + step / 2.0 ); + const QPointF p4 = qwtPolar2Pos( center, r, angle - step / 2.0 ); + + QPainterPath darkPath; + darkPath.moveTo( center ); + darkPath.lineTo( p ); + darkPath.lineTo( qwtIntersection( center, p3, p1, p ) ); + + painter->setBrush( palette.brush( QPalette::Dark ) ); + painter->drawPath( darkPath ); + + QPainterPath lightPath; + lightPath.moveTo( center ); + lightPath.lineTo( p ); + lightPath.lineTo( qwtIntersection( center, p4, p2, p ) ); + + painter->setBrush( palette.brush( QPalette::Light ) ); + painter->drawPath( lightPath ); } } painter->restore(); @@ -215,15 +202,23 @@ void QwtSimpleCompassRose::drawRose( \param width Width */ - -void QwtSimpleCompassRose::setWidth(double width) +void QwtSimpleCompassRose::setWidth( double width ) { - d_width = width; - if (d_width < 0.03) - d_width = 0.03; + d_data->width = width; + if ( d_data->width < 0.03 ) + d_data->width = 0.03; + + if ( d_data->width > 0.4 ) + d_data->width = 0.4; +} - if (d_width > 0.4) - d_width = 0.4; +/*! + \return Width of the rose + \sa setWidth() + */ +double QwtSimpleCompassRose::width() const +{ + return d_data->width; } /*! @@ -233,7 +228,7 @@ void QwtSimpleCompassRose::setWidth(double width) \param numThorns Number of thorns \sa numThorns(), setNumThornLevels() */ -void QwtSimpleCompassRose::setNumThorns(int numThorns) +void QwtSimpleCompassRose::setNumThorns( int numThorns ) { if ( numThorns < 4 ) numThorns = 4; @@ -241,7 +236,7 @@ void QwtSimpleCompassRose::setNumThorns(int numThorns) if ( numThorns % 4 ) numThorns += 4 - numThorns % 4; - d_numThorns = numThorns; + d_data->numThorns = numThorns; } /*! @@ -250,7 +245,7 @@ void QwtSimpleCompassRose::setNumThorns(int numThorns) */ int QwtSimpleCompassRose::numThorns() const { - return d_numThorns; + return d_data->numThorns; } /*! @@ -259,9 +254,9 @@ int QwtSimpleCompassRose::numThorns() const \param numThornLevels Number of thorns levels \sa setNumThorns(), numThornLevels() */ -void QwtSimpleCompassRose::setNumThornLevels(int numThornLevels) +void QwtSimpleCompassRose::setNumThornLevels( int numThornLevels ) { - d_numThornLevels = numThornLevels; + d_data->numThornLevels = numThornLevels; } /*! @@ -270,5 +265,5 @@ void QwtSimpleCompassRose::setNumThornLevels(int numThornLevels) */ int QwtSimpleCompassRose::numThornLevels() const { - return d_numThornLevels; + return d_data->numThornLevels; } diff --git a/libs/qwt/qwt_compass_rose.h b/libs/qwt/qwt_compass_rose.h index a87c4da386..9b715dfe02 100644 --- a/libs/qwt/qwt_compass_rose.h +++ b/libs/qwt/qwt_compass_rose.h @@ -10,8 +10,8 @@ #ifndef QWT_COMPASS_ROSE_H #define QWT_COMPASS_ROSE_H 1 -#include <qpalette.h> #include "qwt_global.h" +#include <qpalette.h> class QPainter; @@ -21,12 +21,18 @@ class QPainter; class QWT_EXPORT QwtCompassRose { public: + //! Destructor virtual ~QwtCompassRose() {}; - virtual void setPalette(const QPalette &p) { + //! Assign a palette + virtual void setPalette( const QPalette &p ) + { d_palette = p; } - const QPalette &palette() const { + + //! \return Current palette + const QPalette &palette() const + { return d_palette; } @@ -39,9 +45,9 @@ public: \param north Position \param colorGroup Color group */ - virtual void draw(QPainter *painter, const QPoint ¢er, - int radius, double north, - QPalette::ColorGroup colorGroup = QPalette::Active) const = 0; + virtual void draw( QPainter *painter, + const QPointF ¢er, double radius, double north, + QPalette::ColorGroup colorGroup = QPalette::Active ) const = 0; private: QPalette d_palette; @@ -53,43 +59,31 @@ private: class QWT_EXPORT QwtSimpleCompassRose: public QwtCompassRose { public: - QwtSimpleCompassRose(int numThorns = 8, int numThornLevels = -1); + QwtSimpleCompassRose( int numThorns = 8, int numThornLevels = -1 ); + virtual ~QwtSimpleCompassRose(); - void setWidth(double w); - double width() const { - return d_width; - } + void setWidth( double w ); + double width() const; - void setNumThorns(int count); + void setNumThorns( int count ); int numThorns() const; - void setNumThornLevels(int count); + void setNumThornLevels( int count ); int numThornLevels() const; - void setShrinkFactor(double factor) { - d_shrinkFactor = factor; - } - double shrinkFactor() const { - return d_shrinkFactor; - } + void setShrinkFactor( double factor ); + double shrinkFactor() const; - virtual void draw(QPainter *, const QPoint ¢er, int radius, - double north, QPalette::ColorGroup = QPalette::Active) const; + virtual void draw( QPainter *, const QPointF ¢er, double radius, + double north, QPalette::ColorGroup = QPalette::Active ) const; - static void drawRose(QPainter *, -#if QT_VERSION < 0x040000 - const QColorGroup &, -#else - const QPalette &, -#endif - const QPoint ¢er, int radius, double origin, double width, - int numThorns, int numThornLevels, double shrinkFactor); + static void drawRose( QPainter *, const QPalette &, + const QPointF ¢er, double radius, double origin, double width, + int numThorns, int numThornLevels, double shrinkFactor ); private: - double d_width; - int d_numThorns; - int d_numThornLevels; - double d_shrinkFactor; + class PrivateData; + PrivateData *d_data; }; -#endif // QWT_COMPASS_ROSE_H +#endif diff --git a/libs/qwt/qwt_compat.h b/libs/qwt/qwt_compat.h new file mode 100644 index 0000000000..c97cf6b9c8 --- /dev/null +++ b/libs/qwt/qwt_compat.h @@ -0,0 +1,42 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef _QWT_COMPAT_H_ +#define _QWT_COMPAT_H_ + +#include "qwt_global.h" +#include "qwt_interval.h" +#include "qwt_point_3d.h" +#include <qlist.h> +#include <qvector.h> +#include <qpoint.h> +#include <qsize.h> +#include <qrect.h> +#include <qpolygon.h> + +// A couple of definition for Qwt5 compatibility + +#define qwtMax qMax +#define qwtMin qMin +#define qwtAbs qAbs +#define qwtRound qRound + +#define QwtArray QVector + +typedef QList<double> QwtValueList; +typedef QPointF QwtDoublePoint; +typedef QSizeF QwtDoubleSize; +typedef QRectF QwtDoubleRect; + +typedef QPolygon QwtPolygon; +typedef QPolygonF QwtPolygonF; +typedef QwtInterval QwtDoubleInterval; +typedef QwtPoint3D QwtDoublePoint3D; + +#endif diff --git a/libs/qwt/qwt_counter.cpp b/libs/qwt/qwt_counter.cpp index c3236d36c2..31c05c8df3 100644 --- a/libs/qwt/qwt_counter.cpp +++ b/libs/qwt/qwt_counter.cpp @@ -7,22 +7,26 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_arrow_button.h" +#include "qwt_math.h" +#include "qwt_counter.h" #include <qlayout.h> #include <qlineedit.h> #include <qvalidator.h> #include <qevent.h> #include <qstyle.h> -#include "qwt_math.h" -#include "qwt_counter.h" -#include "qwt_arrow_button.h" class QwtCounter::PrivateData { public: PrivateData(): - editable(true) { + minimum( 0.0 ), + maximum( 0.0 ), + singleStep( 1.0 ), + isValid( false ), + value( 0.0 ), + wrapping( false ) + { increment[Button1] = 1; increment[Button2] = 10; increment[Button3] = 100; @@ -33,27 +37,22 @@ public: QLineEdit *valueEdit; int increment[ButtonCnt]; - int nButtons; + int numButtons; - bool editable; -}; + double minimum; + double maximum; + double singleStep; -/*! - The default number of buttons is set to 2. The default increments are: - \li Button 1: 1 step - \li Button 2: 10 steps - \li Button 3: 100 steps + bool isValid; + double value; - \param parent - */ -QwtCounter::QwtCounter(QWidget *parent): - QWidget(parent) -{ - initCounter(); -} + bool wrapping; +}; -#if QT_VERSION < 0x040000 /*! + The counter is initialized with a range is set to [0.0, 1.0] with + 0.01 as single step size. The value is invalid. + The default number of buttons is set to 2. The default increments are: \li Button 1: 1 step \li Button 2: 10 steps @@ -61,79 +60,68 @@ QwtCounter::QwtCounter(QWidget *parent): \param parent */ -QwtCounter::QwtCounter(QWidget *parent, const char *name): - QWidget(parent, name) +QwtCounter::QwtCounter( QWidget *parent ): + QWidget( parent ) { initCounter(); } -#endif void QwtCounter::initCounter() { d_data = new PrivateData; -#if QT_VERSION >= 0x040000 - using namespace Qt; -#endif - - QHBoxLayout *layout = new QHBoxLayout(this); - layout->setSpacing(0); - layout->setMargin(0); + QHBoxLayout *layout = new QHBoxLayout( this ); + layout->setSpacing( 0 ); + layout->setMargin( 0 ); - int i; - for(i = ButtonCnt - 1; i >= 0; i--) { + for ( int i = ButtonCnt - 1; i >= 0; i-- ) + { QwtArrowButton *btn = - new QwtArrowButton(i+1, Qt::DownArrow,this); - btn->setFocusPolicy(NoFocus); - btn->installEventFilter(this); - layout->addWidget(btn); + new QwtArrowButton( i + 1, Qt::DownArrow, this ); + btn->setFocusPolicy( Qt::NoFocus ); + btn->installEventFilter( this ); + layout->addWidget( btn ); - connect(btn, SIGNAL(released()), SLOT(btnReleased())); - connect(btn, SIGNAL(clicked()), SLOT(btnClicked())); + connect( btn, SIGNAL( released() ), SLOT( btnReleased() ) ); + connect( btn, SIGNAL( clicked() ), SLOT( btnClicked() ) ); d_data->buttonDown[i] = btn; } - d_data->valueEdit = new QLineEdit(this); - d_data->valueEdit->setReadOnly(false); - d_data->valueEdit->setValidator(new QDoubleValidator(d_data->valueEdit)); - layout->addWidget(d_data->valueEdit); - -#if QT_VERSION >= 0x040000 - connect( d_data->valueEdit, SIGNAL(editingFinished()), - SLOT(textChanged()) ); -#else - connect( d_data->valueEdit, SIGNAL(returnPressed()), SLOT(textChanged()) ); - connect( d_data->valueEdit, SIGNAL(lostFocus()), SLOT(textChanged()) ); -#endif + d_data->valueEdit = new QLineEdit( this ); + d_data->valueEdit->setReadOnly( false ); + d_data->valueEdit->setValidator( new QDoubleValidator( d_data->valueEdit ) ); + layout->addWidget( d_data->valueEdit ); - layout->setStretchFactor(d_data->valueEdit, 10); + connect( d_data->valueEdit, SIGNAL( editingFinished() ), + SLOT( textChanged() ) ); - for(i = 0; i < ButtonCnt; i++) { -#if QT_VERSION >= 0x040000 - using namespace Qt; -#endif + layout->setStretchFactor( d_data->valueEdit, 10 ); + + for ( int i = 0; i < ButtonCnt; i++ ) + { QwtArrowButton *btn = - new QwtArrowButton(i+1, Qt::UpArrow, this); - btn->setFocusPolicy(NoFocus); - btn->installEventFilter(this); - layout->addWidget(btn); + new QwtArrowButton( i + 1, Qt::UpArrow, this ); + btn->setFocusPolicy( Qt::NoFocus ); + btn->installEventFilter( this ); + layout->addWidget( btn ); - connect(btn, SIGNAL(released()), SLOT(btnReleased())); - connect(btn, SIGNAL(clicked()), SLOT(btnClicked())); + connect( btn, SIGNAL( released() ), SLOT( btnReleased() ) ); + connect( btn, SIGNAL( clicked() ), SLOT( btnClicked() ) ); d_data->buttonUp[i] = btn; } - setNumButtons(2); - setRange(0.0,1.0,0.001); - setValue(0.0); + setNumButtons( 2 ); + setRange( 0.0, 1.0 ); + setSingleStep( 0.001 ); + setValue( 0.0 ); setSizePolicy( - QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed)); + QSizePolicy( QSizePolicy::Preferred, QSizePolicy::Fixed ) ); - setFocusProxy(d_data->valueEdit); - setFocusPolicy(StrongFocus); + setFocusProxy( d_data->valueEdit ); + setFocusPolicy( Qt::StrongFocus ); } //! Destructor @@ -142,193 +130,265 @@ QwtCounter::~QwtCounter() delete d_data; } +/*! + Set the counter to be in valid/invalid state + + When the counter is set to invalid, no numbers are displayed and + the buttons are disabled. + + \param on If true the counter will be set as valid + + \sa setValue(), isValid() +*/ +void QwtCounter::setValid( bool on ) +{ + if ( on != d_data->isValid ) + { + d_data->isValid = on; + + updateButtons(); + + if ( d_data->isValid ) + { + showNumber( value() ); + Q_EMIT valueChanged( value() ); + } + else + { + d_data->valueEdit->setText( QString::null ); + } + } +} + +/*! + \return True, if the value is valid + \sa setValid(), setValue() + */ +bool QwtCounter::isValid() const +{ + return d_data->isValid; +} + +/*! + \brief Allow/disallow the user to manually edit the value + + \param on True disable editing + \sa isReadOnly() +*/ +void QwtCounter::setReadOnly( bool on ) +{ + d_data->valueEdit->setReadOnly( on ); +} + +/*! + \return True, when the line line edit is read only. (default is no) + \sa setReadOnly() + */ +bool QwtCounter::isReadOnly() const +{ + return d_data->valueEdit->isReadOnly(); +} + /*! - Sets the minimum width for the buttons + \brief Set a new value without adjusting to the step raster + + The state of the counter is set to be valid. + + \param value New value + + \sa isValid(), value(), valueChanged() + \warning The value is clipped when it lies outside the range. */ -void QwtCounter::polish() + +void QwtCounter::setValue( double value ) { - const int w = d_data->valueEdit->fontMetrics().width("W") + 8; + const double vmin = qMin( d_data->minimum, d_data->maximum ); + const double vmax = qMax( d_data->minimum, d_data->maximum ); + + value = qBound( vmin, value, vmax ); + + if ( !d_data->isValid || value != d_data->value ) + { + d_data->isValid = true; + d_data->value = value; + + showNumber( value ); + updateButtons(); - for ( int i = 0; i < ButtonCnt; i++ ) { - d_data->buttonDown[i]->setMinimumWidth(w); - d_data->buttonUp[i]->setMinimumWidth(w); + Q_EMIT valueChanged( value ); } +} -#if QT_VERSION < 0x040000 - QWidget::polish(); -#endif +/*! + \return Current value of the counter + \sa setValue(), valueChanged() + */ +double QwtCounter::value() const +{ + return d_data->value; } -//! Set from lineedit -void QwtCounter::textChanged() +/*! + \brief Set the minimum and maximum values + + The maximum is adjusted if necessary to ensure that the range remains valid. + The value might be modified to be inside of the range. + + \param min Minimum value + \param max Maximum value + + \sa minimum(), maximum() + */ +void QwtCounter::setRange( double min, double max ) { - if ( !d_data->editable ) + max = qMax( min, max ); + + if ( d_data->maximum == max && d_data->minimum == min ) return; - bool converted = false; + d_data->minimum = min; + d_data->maximum = max; - const double value = d_data->valueEdit->text().toDouble(&converted); - if ( converted ) - setValue( value ); + setSingleStep( singleStep() ); + + const double value = qBound( min, d_data->value, max ); + + if ( value != d_data->value ) + { + d_data->value = value; + + if ( d_data->isValid ) + { + showNumber( value ); + Q_EMIT valueChanged( value ); + } + } + + updateButtons(); } -/** - \brief Allow/disallow the user to manually edit the value +/*! + Set the minimum value of the range - \param editable true enables editing - \sa editable() + \param value Minimum value + \sa setRange(), setMaximum(), minimum() + + \note The maximum is adjusted if necessary to ensure that the range remains valid. */ -void QwtCounter::setEditable(bool editable) +void QwtCounter::setMinimum( double value ) { -#if QT_VERSION >= 0x040000 - using namespace Qt; -#endif - if ( editable == d_data->editable ) - return; + setRange( value, maximum() ); +} - d_data->editable = editable; - d_data->valueEdit->setReadOnly(!editable); +/*! + \return The minimum of the range + \sa setRange(), setMinimum(), maximum() +*/ +double QwtCounter::minimum() const +{ + return d_data->minimum; } -//! returns whether the line edit is edatble. (default is yes) -bool QwtCounter::editable() const +/*! + Set the maximum value of the range + + \param value Maximum value + \sa setRange(), setMinimum(), maximum() +*/ +void QwtCounter::setMaximum( double value ) { - return d_data->editable; + setRange( minimum(), value ); } /*! - Handle PolishRequest events + \return The maximum of the range + \sa setRange(), setMaximum(), minimum() */ -bool QwtCounter::event ( QEvent * e ) +double QwtCounter::maximum() const { -#if QT_VERSION >= 0x040000 - if ( e->type() == QEvent::PolishRequest ) - polish(); -#endif - return QWidget::event(e); + return d_data->maximum; } /*! - Handles key events + \brief Set the step size of the counter - - Ctrl + Qt::Key_Home - Step to minValue() - - Ctrl + Qt::Key_End - Step to maxValue() - - Qt::Key_Up - Increment by incSteps(QwtCounter::Button1) - - Qt::Key_Down - Decrement by incSteps(QwtCounter::Button1) - - Qt::Key_PageUp - Increment by incSteps(QwtCounter::Button2) - - Qt::Key_PageDown - Decrement by incSteps(QwtCounter::Button2) - - Shift + Qt::Key_PageUp - Increment by incSteps(QwtCounter::Button3) - - Shift + Qt::Key_PageDown - Decrement by incSteps(QwtCounter::Button3) + A value <= 0.0 disables stepping + + \param stepSize Single step size + \sa singleStep() */ +void QwtCounter::setSingleStep( double stepSize ) +{ + d_data->singleStep = qMax( stepSize, 0.0 ); +} -void QwtCounter::keyPressEvent (QKeyEvent *e) +/*! + \return Single step size + \sa setSingleStep() + */ +double QwtCounter::singleStep() const { - bool accepted = true; + return d_data->singleStep; +} - switch ( e->key() ) { - case Qt::Key_Home: -#if QT_VERSION >= 0x040000 - if ( e->modifiers() & Qt::ControlModifier ) -#else - if ( e->state() & Qt::ControlButton ) -#endif - setValue(minValue()); - else - accepted = false; - break; - case Qt::Key_End: -#if QT_VERSION >= 0x040000 - if ( e->modifiers() & Qt::ControlModifier ) -#else - if ( e->state() & Qt::ControlButton ) -#endif - setValue(maxValue()); - else - accepted = false; - break; - case Qt::Key_Up: - incValue(d_data->increment[0]); - break; - case Qt::Key_Down: - incValue(-d_data->increment[0]); - break; - case Qt::Key_PageUp: - case Qt::Key_PageDown: { - int increment = d_data->increment[0]; - if ( d_data->nButtons >= 2 ) - increment = d_data->increment[1]; - if ( d_data->nButtons >= 3 ) { -#if QT_VERSION >= 0x040000 - if ( e->modifiers() & Qt::ShiftModifier ) -#else - if ( e->state() & Qt::ShiftButton ) -#endif - increment = d_data->increment[2]; - } - if ( e->key() == Qt::Key_PageDown ) - increment = -increment; - incValue(increment); - break; - } - default: - accepted = false; - } +/*! + \brief En/Disable wrapping - if ( accepted ) { - e->accept(); - return; - } + If wrapping is true stepping up from maximum() value will take + you to the minimum() value and vice versa. - QWidget::keyPressEvent (e); + \param on En/Disable wrapping + \sa wrapping() + */ +void QwtCounter::setWrapping( bool on ) +{ + d_data->wrapping = on; } -void QwtCounter::wheelEvent(QWheelEvent *e) +/*! + \return True, when wrapping is set + \sa setWrapping() + */ +bool QwtCounter::wrapping() const { - e->accept(); + return d_data->wrapping; +} - if ( d_data->nButtons <= 0 ) - return; +/*! + Specify the number of buttons on each side of the label - int increment = d_data->increment[0]; - if ( d_data->nButtons >= 2 ) { -#if QT_VERSION >= 0x040000 - if ( e->modifiers() & Qt::ControlModifier ) -#else - if ( e->state() & Qt::ControlButton ) -#endif - increment = d_data->increment[1]; - } - if ( d_data->nButtons >= 3 ) { -#if QT_VERSION >= 0x040000 - if ( e->modifiers() & Qt::ShiftModifier ) -#else - if ( e->state() & Qt::ShiftButton ) -#endif - increment = d_data->increment[2]; - } + \param numButtons Number of buttons + \sa numButtons() +*/ +void QwtCounter::setNumButtons( int numButtons ) +{ + if ( numButtons < 0 || numButtons > QwtCounter::ButtonCnt ) + return; - for ( int i = 0; i < d_data->nButtons; i++ ) { - if ( d_data->buttonDown[i]->geometry().contains(e->pos()) || - d_data->buttonUp[i]->geometry().contains(e->pos()) ) { - increment = d_data->increment[i]; + for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) + { + if ( i < numButtons ) + { + d_data->buttonDown[i]->show(); + d_data->buttonUp[i]->show(); + } + else + { + d_data->buttonDown[i]->hide(); + d_data->buttonUp[i]->hide(); } } - const int wheel_delta = 120; - - int delta = e->delta(); - if ( delta >= 2 * wheel_delta ) - delta /= 2; // Never saw an abs(delta) < 240 + d_data->numButtons = numButtons; +} - incValue(delta / wheel_delta * increment); +/*! + \return The number of buttons on each side of the widget. + \sa setNumButtons() +*/ +int QwtCounter::numButtons() const +{ + return d_data->numButtons; } /*! @@ -336,155 +396,359 @@ void QwtCounter::wheelEvent(QWheelEvent *e) is incremented or decremented when a specified button is pushed. - \param btn One of \c QwtCounter::Button1, \c QwtCounter::Button2, - \c QwtCounter::Button3 - \param nSteps Number of steps + \param button Button index + \param numSteps Number of steps + + \sa incSteps() */ -void QwtCounter::setIncSteps(QwtCounter::Button btn, int nSteps) +void QwtCounter::setIncSteps( QwtCounter::Button button, int numSteps ) { - if (( btn >= 0) && (btn < ButtonCnt)) - d_data->increment[btn] = nSteps; + if ( button >= 0 && button < QwtCounter::ButtonCnt ) + d_data->increment[ button ] = numSteps; } /*! - \return the number of steps by which a specified button increments the value - or 0 if the button is invalid. - \param btn One of \c QwtCounter::Button1, \c QwtCounter::Button2, - \c QwtCounter::Button3 + \return The number of steps by which a specified button increments the value + or 0 if the button is invalid. + \param button Button index + + \sa setIncSteps() */ -int QwtCounter::incSteps(QwtCounter::Button btn) const +int QwtCounter::incSteps( QwtCounter::Button button ) const { - if (( btn >= 0) && (btn < ButtonCnt)) - return d_data->increment[btn]; + if ( button >= 0 && button < QwtCounter::ButtonCnt ) + return d_data->increment[ button ]; return 0; } + /*! - \brief Set a new value - \param v new value - Calls QwtDoubleRange::setValue and does all visual updates. - \sa QwtDoubleRange::setValue + Set the number of increment steps for button 1 + \param nSteps Number of steps */ +void QwtCounter::setStepButton1( int nSteps ) +{ + setIncSteps( QwtCounter::Button1, nSteps ); +} -void QwtCounter::setValue(double v) +//! returns the number of increment steps for button 1 +int QwtCounter::stepButton1() const { - QwtDoubleRange::setValue(v); + return incSteps( QwtCounter::Button1 ); +} - showNum(value()); - updateButtons(); +/*! + Set the number of increment steps for button 2 + \param nSteps Number of steps +*/ +void QwtCounter::setStepButton2( int nSteps ) +{ + setIncSteps( QwtCounter::Button2, nSteps ); +} + +//! returns the number of increment steps for button 2 +int QwtCounter::stepButton2() const +{ + return incSteps( QwtCounter::Button2 ); } /*! - \brief Notify a change of value + Set the number of increment steps for button 3 + \param nSteps Number of steps */ -void QwtCounter::valueChange() +void QwtCounter::setStepButton3( int nSteps ) { - if ( isValid() ) - showNum(value()); - else - d_data->valueEdit->setText(QString::null); + setIncSteps( QwtCounter::Button3, nSteps ); +} - updateButtons(); +//! returns the number of increment steps for button 3 +int QwtCounter::stepButton3() const +{ + return incSteps( QwtCounter::Button3 ); +} + +//! Set from lineedit +void QwtCounter::textChanged() +{ + bool converted = false; + + const double value = d_data->valueEdit->text().toDouble( &converted ); + if ( converted ) + setValue( value ); +} - if ( isValid() ) - emit valueChanged(value()); +/*! + Handle QEvent::PolishRequest events + \param event Event + \return see QWidget::event() +*/ +bool QwtCounter::event( QEvent *event ) +{ + if ( event->type() == QEvent::PolishRequest ) + { + const int w = d_data->valueEdit->fontMetrics().width( "W" ) + 8; + for ( int i = 0; i < ButtonCnt; i++ ) + { + d_data->buttonDown[i]->setMinimumWidth( w ); + d_data->buttonUp[i]->setMinimumWidth( w ); + } + } + + return QWidget::event( event ); } /*! - \brief Update buttons according to the current value + Handle key events - When the QwtCounter under- or over-flows, the focus is set to the smallest - up- or down-button and counting is disabled. + - Ctrl + Qt::Key_Home\n + Step to minimum() + - Ctrl + Qt::Key_End\n + Step to maximum() + - Qt::Key_Up\n + Increment by incSteps(QwtCounter::Button1) + - Qt::Key_Down\n + Decrement by incSteps(QwtCounter::Button1) + - Qt::Key_PageUp\n + Increment by incSteps(QwtCounter::Button2) + - Qt::Key_PageDown\n + Decrement by incSteps(QwtCounter::Button2) + - Shift + Qt::Key_PageUp\n + Increment by incSteps(QwtCounter::Button3) + - Shift + Qt::Key_PageDown\n + Decrement by incSteps(QwtCounter::Button3) - Counting is re-enabled on a button release event (mouse or space bar). + \param event Key event */ -void QwtCounter::updateButtons() +void QwtCounter::keyPressEvent ( QKeyEvent *event ) { - if ( isValid() ) { - // 1. save enabled state of the smallest down- and up-button - // 2. change enabled state on under- or over-flow + bool accepted = true; - for ( int i = 0; i < ButtonCnt; i++ ) { - d_data->buttonDown[i]->setEnabled(value() > minValue()); - d_data->buttonUp[i]->setEnabled(value() < maxValue()); + switch ( event->key() ) + { + case Qt::Key_Home: + { + if ( event->modifiers() & Qt::ControlModifier ) + setValue( minimum() ); + else + accepted = false; + break; + } + case Qt::Key_End: + { + if ( event->modifiers() & Qt::ControlModifier ) + setValue( maximum() ); + else + accepted = false; + break; + } + case Qt::Key_Up: + { + incrementValue( d_data->increment[0] ); + break; } - } else { - for ( int i = 0; i < ButtonCnt; i++ ) { - d_data->buttonDown[i]->setEnabled(false); - d_data->buttonUp[i]->setEnabled(false); + case Qt::Key_Down: + { + incrementValue( -d_data->increment[0] ); + break; + } + case Qt::Key_PageUp: + case Qt::Key_PageDown: + { + int increment = d_data->increment[0]; + if ( d_data->numButtons >= 2 ) + increment = d_data->increment[1]; + if ( d_data->numButtons >= 3 ) + { + if ( event->modifiers() & Qt::ShiftModifier ) + increment = d_data->increment[2]; + } + if ( event->key() == Qt::Key_PageDown ) + increment = -increment; + incrementValue( increment ); + break; + } + default: + { + accepted = false; } } + + if ( accepted ) + { + event->accept(); + return; + } + + QWidget::keyPressEvent ( event ); } /*! - \brief Specify the number of buttons on each side of the label - \param n Number of buttons + Handle wheel events + \param event Wheel event */ -void QwtCounter::setNumButtons(int n) +void QwtCounter::wheelEvent( QWheelEvent *event ) { - if ( n<0 || n>ButtonCnt ) + event->accept(); + + if ( d_data->numButtons <= 0 ) return; - for ( int i = 0; i < ButtonCnt; i++ ) { - if ( i < n ) { - d_data->buttonDown[i]->show(); - d_data->buttonUp[i]->show(); - } else { - d_data->buttonDown[i]->hide(); - d_data->buttonUp[i]->hide(); + int increment = d_data->increment[0]; + if ( d_data->numButtons >= 2 ) + { + if ( event->modifiers() & Qt::ControlModifier ) + increment = d_data->increment[1]; + } + if ( d_data->numButtons >= 3 ) + { + if ( event->modifiers() & Qt::ShiftModifier ) + increment = d_data->increment[2]; + } + + for ( int i = 0; i < d_data->numButtons; i++ ) + { + if ( d_data->buttonDown[i]->geometry().contains( event->pos() ) || + d_data->buttonUp[i]->geometry().contains( event->pos() ) ) + { + increment = d_data->increment[i]; + } + } + + const int wheel_delta = 120; + +#if 1 + int delta = event->delta(); + if ( delta >= 2 * wheel_delta ) + delta /= 2; // Never saw an abs(delta) < 240 +#endif + + incrementValue( delta / wheel_delta * increment ); +} + +void QwtCounter::incrementValue( int numSteps ) +{ + const double min = d_data->minimum; + const double max = d_data->maximum; + double stepSize = d_data->singleStep; + + if ( !d_data->isValid || min >= max || stepSize <= 0.0 ) + return; + + +#if 1 + stepSize = qMax( stepSize, 1.0e-10 * ( max - min ) ); +#endif + + double value = d_data->value + numSteps * stepSize; + + if ( d_data->wrapping ) + { + const double range = max - min; + + if ( value < min ) + { + value += ::ceil( ( min - value ) / range ) * range; } + else if ( value > max ) + { + value -= ::ceil( ( value - max ) / range ) * range; + } + } + else + { + value = qBound( min, value, max ); } - d_data->nButtons = n; + value = min + qRound( ( value - min ) / stepSize ) * stepSize; + + if ( stepSize > 1e-12 ) + { + if ( qFuzzyCompare( value + 1.0, 1.0 ) ) + { + // correct rounding error if value = 0 + value = 0.0; + } + else if ( qFuzzyCompare( value, max ) ) + { + // correct rounding error at the border + value = max; + } + } + + if ( value != d_data->value ) + { + d_data->value = value; + showNumber( d_data->value ); + updateButtons(); + + Q_EMIT valueChanged( d_data->value ); + } } + /*! - \return The number of buttons on each side of the widget. + \brief Update buttons according to the current value + + When the QwtCounter under- or over-flows, the focus is set to the smallest + up- or down-button and counting is disabled. + + Counting is re-enabled on a button release event (mouse or space bar). */ -int QwtCounter::numButtons() const +void QwtCounter::updateButtons() { - return d_data->nButtons; + if ( d_data->isValid ) + { + // 1. save enabled state of the smallest down- and up-button + // 2. change enabled state on under- or over-flow + + for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) + { + d_data->buttonDown[i]->setEnabled( value() > minimum() ); + d_data->buttonUp[i]->setEnabled( value() < maximum() ); + } + } + else + { + for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) + { + d_data->buttonDown[i]->setEnabled( false ); + d_data->buttonUp[i]->setEnabled( false ); + } + } } +/*! + Display number string -//! Display number string -void QwtCounter::showNum(double d) + \param number Number +*/ +void QwtCounter::showNumber( double number ) { - QString v; - v.setNum(d); + QString text; + text.setNum( number ); const int cursorPos = d_data->valueEdit->cursorPosition(); - d_data->valueEdit->setText(v); - d_data->valueEdit->setCursorPosition(cursorPos); + d_data->valueEdit->setText( text ); + d_data->valueEdit->setCursorPosition( cursorPos ); } //! Button clicked void QwtCounter::btnClicked() { - for ( int i = 0; i < ButtonCnt; i++ ) { + for ( int i = 0; i < ButtonCnt; i++ ) + { if ( d_data->buttonUp[i] == sender() ) - incValue(d_data->increment[i]); + incrementValue( d_data->increment[i] ); if ( d_data->buttonDown[i] == sender() ) - incValue(-d_data->increment[i]); + incrementValue( -d_data->increment[i] ); } } //! Button released void QwtCounter::btnReleased() { - emit buttonReleased(value()); -} - -/*! - \brief Notify change of range - - This function updates the enabled property of - all buttons contained in QwtCounter. -*/ -void QwtCounter::rangeChange() -{ - updateButtons(); + Q_EMIT buttonReleased( value() ); } //! A size hint @@ -492,112 +756,30 @@ QSize QwtCounter::sizeHint() const { QString tmp; - int w = tmp.setNum(minValue()).length(); - int w1 = tmp.setNum(maxValue()).length(); + int w = tmp.setNum( minimum() ).length(); + int w1 = tmp.setNum( maximum() ).length(); if ( w1 > w ) w = w1; - w1 = tmp.setNum(minValue() + step()).length(); + w1 = tmp.setNum( minimum() + singleStep() ).length(); if ( w1 > w ) w = w1; - w1 = tmp.setNum(maxValue() - step()).length(); + w1 = tmp.setNum( maximum() - singleStep() ).length(); if ( w1 > w ) w = w1; - tmp.fill('9', w); + tmp.fill( '9', w ); - QFontMetrics fm(d_data->valueEdit->font()); - w = fm.width(tmp) + 2; -#if QT_VERSION >= 0x040000 + QFontMetrics fm( d_data->valueEdit->font() ); + w = fm.width( tmp ) + 2; if ( d_data->valueEdit->hasFrame() ) - w += 2 * style()->pixelMetric(QStyle::PM_DefaultFrameWidth); -#else - w += 2 * d_data->valueEdit->frameWidth(); -#endif + w += 2 * style()->pixelMetric( QStyle::PM_DefaultFrameWidth ); // Now we replace default sizeHint contribution of d_data->valueEdit by // what we really need. w += QWidget::sizeHint().width() - d_data->valueEdit->sizeHint().width(); - const int h = qwtMin(QWidget::sizeHint().height(), - d_data->valueEdit->minimumSizeHint().height()); - return QSize(w, h); -} - -//! returns the step size -double QwtCounter::step() const -{ - return QwtDoubleRange::step(); -} - -//! sets the step size -void QwtCounter::setStep(double s) -{ - QwtDoubleRange::setStep(s); -} - -//! returns the minimum value of the range -double QwtCounter::minVal() const -{ - return minValue(); -} - -//! sets the minimum value of the range -void QwtCounter::setMinValue(double m) -{ - setRange(m, maxValue(), step()); -} - -//! returns the maximum value of the range -double QwtCounter::maxVal() const -{ - return QwtDoubleRange::maxValue(); -} - -//! sets the maximum value of the range -void QwtCounter::setMaxValue(double m) -{ - setRange(minValue(), m, step()); -} - -//! set the number of increment steps for button 1 -void QwtCounter::setStepButton1(int nSteps) -{ - setIncSteps(Button1, nSteps); -} - -//! returns the number of increment steps for button 1 -int QwtCounter::stepButton1() const -{ - return incSteps(Button1); + const int h = qMin( QWidget::sizeHint().height(), + d_data->valueEdit->minimumSizeHint().height() ); + return QSize( w, h ); } - -//! set the number of increment steps for button 2 -void QwtCounter::setStepButton2(int nSteps) -{ - setIncSteps(Button2, nSteps); -} - -//! returns the number of increment steps for button 2 -int QwtCounter::stepButton2() const -{ - return incSteps(Button2); -} - -//! set the number of increment steps for button 3 -void QwtCounter::setStepButton3(int nSteps) -{ - setIncSteps(Button3, nSteps); -} - -//! returns the number of increment steps for button 3 -int QwtCounter::stepButton3() const -{ - return incSteps(Button3); -} - -double QwtCounter::value() const -{ - return QwtDoubleRange::value(); -} - diff --git a/libs/qwt/qwt_counter.h b/libs/qwt/qwt_counter.h index bda399cce3..8799eddcac 100644 --- a/libs/qwt/qwt_counter.h +++ b/libs/qwt/qwt_counter.h @@ -7,14 +7,11 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_COUNTER_H #define QWT_COUNTER_H -#include <qwidget.h> #include "qwt_global.h" -#include "qwt_double_range.h" +#include <qwidget.h> /*! \brief The Counter Widget @@ -24,130 +21,138 @@ of the label which can be used to increment or decrement the counter's value. - A Counter has a range from a minimum value to a maximum value - and a step size. The range can be specified using - QwtDblRange::setRange(). - The counter's value is an integer multiple of the step size. - The number of steps by which a button increments or decrements - the value can be specified using QwtCounter::setIncSteps(). - The number of buttons can be changed with - QwtCounter::setNumButtons(). - - Holding the space bar down with focus on a button is the - fastest method to step through the counter values. - When the counter underflows/overflows, the focus is set - to the smallest up/down button and counting is disabled. - Counting is re-enabled on a button release event (mouse or - space bar). + A counter has a range from a minimum value to a maximum value + and a step size. When the wrapping property is set + the counter is circular. + + The number of steps by which a button increments or decrements the value + can be specified using setIncSteps(). The number of buttons can be + changed with setNumButtons(). Example: \code -#include "../include/qwt_counter.h> +#include <qwt_counter.h> -QwtCounter *cnt; +QwtCounter *counter = new QwtCounter(parent); -cnt = new QwtCounter(parent, name); +counter->setRange(0.0, 100.0); // From 0.0 to 100 +counter->setSingleStep( 1.0 ); // Step size 1.0 +counter->setNumButtons(2); // Two buttons each side +counter->setIncSteps(QwtCounter::Button1, 1); // Button 1 increments 1 step +counter->setIncSteps(QwtCounter::Button2, 20); // Button 2 increments 20 steps -cnt->setRange(0.0, 100.0, 1.0); // From 0.0 to 100, step 1.0 -cnt->setNumButtons(2); // Two buttons each side -cnt->setIncSteps(QwtCounter::Button1, 1); // Button 1 increments 1 step -cnt->setIncSteps(QwtCounter::Button2, 20); // Button 2 increments 20 steps - -connect(cnt, SIGNAL(valueChanged(double)), my_class, SLOT(newValue(double))); +connect(counter, SIGNAL(valueChanged(double)), myClass, SLOT(newValue(double))); \endcode */ -class QWT_EXPORT QwtCounter : public QWidget, public QwtDoubleRange +class QWT_EXPORT QwtCounter : public QWidget { Q_OBJECT + Q_PROPERTY( double value READ value WRITE setValue ) + Q_PROPERTY( double minimum READ minimum WRITE setMinimum ) + Q_PROPERTY( double maximum READ maximum WRITE setMaximum ) + Q_PROPERTY( double singleStep READ singleStep WRITE setSingleStep ) + Q_PROPERTY( int numButtons READ numButtons WRITE setNumButtons ) - Q_PROPERTY( double basicstep READ step WRITE setStep ) - Q_PROPERTY( double minValue READ minVal WRITE setMinValue ) - Q_PROPERTY( double maxValue READ maxVal WRITE setMaxValue ) Q_PROPERTY( int stepButton1 READ stepButton1 WRITE setStepButton1 ) Q_PROPERTY( int stepButton2 READ stepButton2 WRITE setStepButton2 ) Q_PROPERTY( int stepButton3 READ stepButton3 WRITE setStepButton3 ) - Q_PROPERTY( double value READ value WRITE setValue ) - Q_PROPERTY( bool editable READ editable WRITE setEditable ) -public: - /*! - Button index - */ + Q_PROPERTY( bool readOnly READ isReadOnly WRITE setReadOnly ) + Q_PROPERTY( bool wrapping READ wrapping WRITE setWrapping ) - enum Button { +public: + //! Button index + enum Button + { + //! Button intended for minor steps Button1, + + //! Button intended for medium steps Button2, + + //! Button intended for large steps Button3, + + //! Number of buttons ButtonCnt }; - explicit QwtCounter(QWidget *parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtCounter(QWidget *parent, const char *name); -#endif + explicit QwtCounter( QWidget *parent = NULL ); virtual ~QwtCounter(); - bool editable() const; - void setEditable(bool); + void setValid( bool ); + bool isValid() const; - void setNumButtons(int n); + void setWrapping( bool ); + bool wrapping() const; + + bool isReadOnly() const; + void setReadOnly( bool ); + + void setNumButtons( int n ); int numButtons() const; - void setIncSteps(QwtCounter::Button btn, int nSteps); - int incSteps(QwtCounter::Button btn) const; + void setIncSteps( QwtCounter::Button btn, int nSteps ); + int incSteps( QwtCounter::Button btn ) const; - virtual void setValue(double); virtual QSize sizeHint() const; - virtual void polish(); + double singleStep() const; + void setSingleStep( double s ); + + void setRange( double min, double max ); + + double minimum() const; + void setMinimum( double min ); - // a set of dummies to help the designer + double maximum() const; + void setMaximum( double max ); - double step() const; - void setStep(double s); - double minVal() const; - void setMinValue(double m); - double maxVal() const; - void setMaxValue(double m); - void setStepButton1(int nSteps); + void setStepButton1( int nSteps ); int stepButton1() const; - void setStepButton2(int nSteps); + + void setStepButton2( int nSteps ); int stepButton2() const; - void setStepButton3(int nSteps); + + void setStepButton3( int nSteps ); int stepButton3() const; - virtual double value() const; -signals: + double value() const; + +public Q_SLOTS: + void setValue( double ); + + +Q_SIGNALS: /*! This signal is emitted when a button has been released \param value The new value */ - void buttonReleased (double value); + void buttonReleased ( double value ); /*! This signal is emitted when the counter's value has changed \param value The new value */ - void valueChanged (double value); + void valueChanged ( double value ); protected: - virtual bool event(QEvent *); - virtual void wheelEvent(QWheelEvent *); - virtual void keyPressEvent(QKeyEvent *); - virtual void rangeChange(); + virtual bool event( QEvent * ); + virtual void wheelEvent( QWheelEvent * ); + virtual void keyPressEvent( QKeyEvent * ); -private slots: +private Q_SLOTS: void btnReleased(); void btnClicked(); void textChanged(); private: + void incrementValue( int numSteps ); void initCounter(); void updateButtons(); - void showNum(double); - virtual void valueChange(); + void showNumber( double ); class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_curve_fitter.cpp b/libs/qwt/qwt_curve_fitter.cpp index 05cc82ce88..5f09d5d8d0 100644 --- a/libs/qwt/qwt_curve_fitter.cpp +++ b/libs/qwt/qwt_curve_fitter.cpp @@ -7,9 +7,15 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_curve_fitter.h" #include "qwt_math.h" #include "qwt_spline.h" -#include "qwt_curve_fitter.h" +#include <qstack.h> +#include <qvector.h> + +#if QT_VERSION < 0x040601 +#define qFabs(x) ::fabs(x) +#endif //! Constructor QwtCurveFitter::QwtCurveFitter() @@ -25,8 +31,9 @@ class QwtSplineCurveFitter::PrivateData { public: PrivateData(): - fitMode(QwtSplineCurveFitter::Auto), - splineSize(250) { + fitMode( QwtSplineCurveFitter::Auto ), + splineSize( 250 ) + { } QwtSpline spline; @@ -34,71 +41,110 @@ public: int splineSize; }; +//! Constructor QwtSplineCurveFitter::QwtSplineCurveFitter() { d_data = new PrivateData; } +//! Destructor QwtSplineCurveFitter::~QwtSplineCurveFitter() { delete d_data; } -void QwtSplineCurveFitter::setFitMode(FitMode mode) +/*! + Select the algorithm used for building the spline + + \param mode Mode representing a spline algorithm + \sa fitMode() +*/ +void QwtSplineCurveFitter::setFitMode( FitMode mode ) { d_data->fitMode = mode; } +/*! + \return Mode representing a spline algorithm + \sa setFitMode() +*/ QwtSplineCurveFitter::FitMode QwtSplineCurveFitter::fitMode() const { return d_data->fitMode; } -void QwtSplineCurveFitter::setSpline(const QwtSpline &spline) +/*! + Assign a spline + + \param spline Spline + \sa spline() +*/ +void QwtSplineCurveFitter::setSpline( const QwtSpline &spline ) { d_data->spline = spline; d_data->spline.reset(); } +/*! + \return Spline + \sa setSpline() +*/ const QwtSpline &QwtSplineCurveFitter::spline() const { return d_data->spline; } +/*! + \return Spline + \sa setSpline() +*/ QwtSpline &QwtSplineCurveFitter::spline() { return d_data->spline; } -void QwtSplineCurveFitter::setSplineSize(int splineSize) +/*! + Assign a spline size ( has to be at least 10 points ) + + \param splineSize Spline size + \sa splineSize() +*/ +void QwtSplineCurveFitter::setSplineSize( int splineSize ) { - d_data->splineSize = qwtMax(splineSize, 10); + d_data->splineSize = qMax( splineSize, 10 ); } +/*! + \return Spline size + \sa setSplineSize() +*/ int QwtSplineCurveFitter::splineSize() const { return d_data->splineSize; } -#if QT_VERSION < 0x040000 -QwtArray<QwtDoublePoint> QwtSplineCurveFitter::fitCurve( - const QwtArray<QwtDoublePoint> & points) const -#else -QPolygonF QwtSplineCurveFitter::fitCurve( - const QPolygonF &points) const -#endif +/*! + Find a curve which has the best fit to a series of data points + + \param points Series of data points + \return Curve points +*/ +QPolygonF QwtSplineCurveFitter::fitCurve( const QPolygonF &points ) const { - const int size = (int)points.size(); + const int size = points.size(); if ( size <= 2 ) return points; FitMode fitMode = d_data->fitMode; - if ( fitMode == Auto ) { + if ( fitMode == Auto ) + { fitMode = Spline; - const QwtDoublePoint *p = points.data(); - for ( int i = 1; i < size; i++ ) { - if ( p[i].x() <= p[i-1].x() ) { + const QPointF *p = points.data(); + for ( int i = 1; i < size; i++ ) + { + if ( p[i].x() <= p[i-1].x() ) + { fitMode = ParametricSpline; break; } @@ -106,109 +152,302 @@ QPolygonF QwtSplineCurveFitter::fitCurve( } if ( fitMode == ParametricSpline ) - return fitParametric(points); + return fitParametric( points ); else - return fitSpline(points); + return fitSpline( points ); } -#if QT_VERSION < 0x040000 -QwtArray<QwtDoublePoint> QwtSplineCurveFitter::fitSpline( - const QwtArray<QwtDoublePoint> &points) const -#else -QPolygonF QwtSplineCurveFitter::fitSpline( - const QPolygonF &points) const -#endif +QPolygonF QwtSplineCurveFitter::fitSpline( const QPolygonF &points ) const { - d_data->spline.setPoints(points); + d_data->spline.setPoints( points ); if ( !d_data->spline.isValid() ) return points; -#if QT_VERSION < 0x040000 - QwtArray<QwtDoublePoint> fittedPoints(d_data->splineSize); -#else - QPolygonF fittedPoints(d_data->splineSize); -#endif + QPolygonF fittedPoints( d_data->splineSize ); const double x1 = points[0].x(); - const double x2 = points[int(points.size() - 1)].x(); + const double x2 = points[int( points.size() - 1 )].x(); const double dx = x2 - x1; - const double delta = dx / (d_data->splineSize - 1); + const double delta = dx / ( d_data->splineSize - 1 ); - for (int i = 0; i < d_data->splineSize; i++) { - QwtDoublePoint &p = fittedPoints[i]; + for ( int i = 0; i < d_data->splineSize; i++ ) + { + QPointF &p = fittedPoints[i]; const double v = x1 + i * delta; - const double sv = d_data->spline.value(v); + const double sv = d_data->spline.value( v ); - p.setX(qRound(v)); - p.setY(qRound(sv)); + p.setX( v ); + p.setY( sv ); } d_data->spline.reset(); return fittedPoints; } -#if QT_VERSION < 0x040000 -QwtArray<QwtDoublePoint> QwtSplineCurveFitter::fitParametric( - const QwtArray<QwtDoublePoint> &points) const -#else -QPolygonF QwtSplineCurveFitter::fitParametric( - const QPolygonF &points) const -#endif +QPolygonF QwtSplineCurveFitter::fitParametric( const QPolygonF &points ) const { int i; const int size = points.size(); -#if QT_VERSION < 0x040000 - QwtArray<QwtDoublePoint> fittedPoints(d_data->splineSize); - QwtArray<QwtDoublePoint> splinePointsX(size); - QwtArray<QwtDoublePoint> splinePointsY(size); -#else - QPolygonF fittedPoints(d_data->splineSize); - QPolygonF splinePointsX(size); - QPolygonF splinePointsY(size); -#endif + QPolygonF fittedPoints( d_data->splineSize ); + QPolygonF splinePointsX( size ); + QPolygonF splinePointsY( size ); - const QwtDoublePoint *p = points.data(); - QwtDoublePoint *spX = splinePointsX.data(); - QwtDoublePoint *spY = splinePointsY.data(); + const QPointF *p = points.data(); + QPointF *spX = splinePointsX.data(); + QPointF *spY = splinePointsY.data(); double param = 0.0; - for (i = 0; i < size; i++) { + for ( i = 0; i < size; i++ ) + { const double x = p[i].x(); const double y = p[i].y(); - if ( i > 0 ) { - const double delta = sqrt( qwtSqr(x - spX[i-1].y()) - + qwtSqr( y - spY[i-1].y() ) ); - param += qwtMax(delta, 1.0); + if ( i > 0 ) + { + const double delta = qSqrt( qwtSqr( x - spX[i-1].y() ) + + qwtSqr( y - spY[i-1].y() ) ); + param += qMax( delta, 1.0 ); } - spX[i].setX(param); - spX[i].setY(x); - spY[i].setX(param); - spY[i].setY(y); + spX[i].setX( param ); + spX[i].setY( x ); + spY[i].setX( param ); + spY[i].setY( y ); } - d_data->spline.setPoints(splinePointsX); + d_data->spline.setPoints( splinePointsX ); if ( !d_data->spline.isValid() ) return points; const double deltaX = - splinePointsX[size - 1].x() / (d_data->splineSize-1); - for (i = 0; i < d_data->splineSize; i++) { + splinePointsX[size - 1].x() / ( d_data->splineSize - 1 ); + for ( i = 0; i < d_data->splineSize; i++ ) + { const double dtmp = i * deltaX; - fittedPoints[i].setX(qRound(d_data->spline.value(dtmp))); + fittedPoints[i].setX( d_data->spline.value( dtmp ) ); } - d_data->spline.setPoints(splinePointsY); + d_data->spline.setPoints( splinePointsY ); if ( !d_data->spline.isValid() ) return points; const double deltaY = - splinePointsY[size - 1].x() / (d_data->splineSize-1); - for (i = 0; i < d_data->splineSize; i++) { + splinePointsY[size - 1].x() / ( d_data->splineSize - 1 ); + for ( i = 0; i < d_data->splineSize; i++ ) + { const double dtmp = i * deltaY; - fittedPoints[i].setY(qRound(d_data->spline.value(dtmp))); + fittedPoints[i].setY( d_data->spline.value( dtmp ) ); } return fittedPoints; } + +class QwtWeedingCurveFitter::PrivateData +{ +public: + PrivateData(): + tolerance( 1.0 ), + chunkSize( 0 ) + { + } + + double tolerance; + uint chunkSize; +}; + +class QwtWeedingCurveFitter::Line +{ +public: + Line( int i1 = 0, int i2 = 0 ): + from( i1 ), + to( i2 ) + { + } + + int from; + int to; +}; + +/*! + Constructor + + \param tolerance Tolerance + \sa setTolerance(), tolerance() +*/ +QwtWeedingCurveFitter::QwtWeedingCurveFitter( double tolerance ) +{ + d_data = new PrivateData; + setTolerance( tolerance ); +} + +//! Destructor +QwtWeedingCurveFitter::~QwtWeedingCurveFitter() +{ + delete d_data; +} + +/*! + Assign the tolerance + + The tolerance is the maximum distance, that is acceptable + between the original curve and the smoothed curve. + + Increasing the tolerance will reduce the number of the + resulting points. + + \param tolerance Tolerance + + \sa tolerance() +*/ +void QwtWeedingCurveFitter::setTolerance( double tolerance ) +{ + d_data->tolerance = qMax( tolerance, 0.0 ); +} + +/*! + \return Tolerance + \sa setTolerance() +*/ +double QwtWeedingCurveFitter::tolerance() const +{ + return d_data->tolerance; +} + +/*! + Limit the number of points passed to a run of the algorithm + + The runtime of the Douglas Peucker algorithm increases non linear + with the number of points. For a chunk size > 0 the polygon + is split into pieces passed to the algorithm one by one. + + \param numPoints Maximum for the number of points passed to the algorithm + + \sa chunkSize() +*/ +void QwtWeedingCurveFitter::setChunkSize( uint numPoints ) +{ + if ( numPoints > 0 ) + numPoints = qMax( numPoints, 3U ); + + d_data->chunkSize = numPoints; +} + +/*! + + \return Maximum for the number of points passed to a run + of the algorithm - or 0, when unlimited + \sa setChunkSize() +*/ +uint QwtWeedingCurveFitter::chunkSize() const +{ + return d_data->chunkSize; +} + +/*! + \param points Series of data points + \return Curve points +*/ +QPolygonF QwtWeedingCurveFitter::fitCurve( const QPolygonF &points ) const +{ + QPolygonF fittedPoints; + + if ( d_data->chunkSize == 0 ) + { + fittedPoints = simplify( points ); + } + else + { + for ( int i = 0; i < points.size(); i += d_data->chunkSize ) + { + const QPolygonF p = points.mid( i, d_data->chunkSize ); + fittedPoints += simplify( p ); + } + } + + return fittedPoints; +} + +QPolygonF QwtWeedingCurveFitter::simplify( const QPolygonF &points ) const +{ + const double toleranceSqr = d_data->tolerance * d_data->tolerance; + + QStack<Line> stack; + stack.reserve( 500 ); + + const QPointF *p = points.data(); + const int nPoints = points.size(); + + QVector<bool> usePoint( nPoints, false ); + + stack.push( Line( 0, nPoints - 1 ) ); + + while ( !stack.isEmpty() ) + { + const Line r = stack.pop(); + + // initialize line segment + const double vecX = p[r.to].x() - p[r.from].x(); + const double vecY = p[r.to].y() - p[r.from].y(); + + const double vecLength = qSqrt( vecX * vecX + vecY * vecY ); + + const double unitVecX = ( vecLength != 0.0 ) ? vecX / vecLength : 0.0; + const double unitVecY = ( vecLength != 0.0 ) ? vecY / vecLength : 0.0; + + double maxDistSqr = 0.0; + int nVertexIndexMaxDistance = r.from + 1; + for ( int i = r.from + 1; i < r.to; i++ ) + { + //compare to anchor + const double fromVecX = p[i].x() - p[r.from].x(); + const double fromVecY = p[i].y() - p[r.from].y(); + + double distToSegmentSqr; + if ( fromVecX * unitVecX + fromVecY * unitVecY < 0.0 ) + { + distToSegmentSqr = fromVecX * fromVecX + fromVecY * fromVecY; + } + else + { + const double toVecX = p[i].x() - p[r.to].x(); + const double toVecY = p[i].y() - p[r.to].y(); + const double toVecLength = toVecX * toVecX + toVecY * toVecY; + + const double s = toVecX * ( -unitVecX ) + toVecY * ( -unitVecY ); + if ( s < 0.0 ) + { + distToSegmentSqr = toVecLength; + } + else + { + distToSegmentSqr = qFabs( toVecLength - s * s ); + } + } + + if ( maxDistSqr < distToSegmentSqr ) + { + maxDistSqr = distToSegmentSqr; + nVertexIndexMaxDistance = i; + } + } + if ( maxDistSqr <= toleranceSqr ) + { + usePoint[r.from] = true; + usePoint[r.to] = true; + } + else + { + stack.push( Line( r.from, nVertexIndexMaxDistance ) ); + stack.push( Line( nVertexIndexMaxDistance, r.to ) ); + } + } + + QPolygonF stripped; + for ( int i = 0; i < nPoints; i++ ) + { + if ( usePoint[i] ) + stripped += p[i]; + } + + return stripped; +} diff --git a/libs/qwt/qwt_curve_fitter.h b/libs/qwt/qwt_curve_fitter.h index 1ed31e73e1..eac376a34d 100644 --- a/libs/qwt/qwt_curve_fitter.h +++ b/libs/qwt/qwt_curve_fitter.h @@ -11,31 +11,11 @@ #define QWT_CURVE_FITTER_H #include "qwt_global.h" -#include "qwt_double_rect.h" +#include <qpolygon.h> +#include <qrect.h> class QwtSpline; -#if QT_VERSION >= 0x040000 -#include <QPolygonF> -#else -#include "qwt_array.h" -#endif - -// MOC_SKIP_BEGIN - -#if defined(QWT_TEMPLATEDLL) - -#if QT_VERSION < 0x040000 -#ifndef QWTARRAY_TEMPLATE_QWTDOUBLEPOINT // by mjo3 -#define QWTARRAY_TEMPLATE_QWTDOUBLEPOINT -template class QWT_EXPORT QwtArray<QwtDoublePoint>; -#endif //end of QWTARRAY_TEMPLATE_QWTDOUBLEPOINT -#endif - -#endif - -// MOC_SKIP_END - /*! \brief Abstract base class for a curve fitter */ @@ -44,12 +24,13 @@ class QWT_EXPORT QwtCurveFitter public: virtual ~QwtCurveFitter(); -#if QT_VERSION < 0x040000 - virtual QwtArray<QwtDoublePoint> fitCurve( - const QwtArray<QwtDoublePoint>&) const = 0; -#else - virtual QPolygonF fitCurve(const QPolygonF &) const = 0; -#endif + /*! + Find a curve which has the best fit to a series of data points + + \param polygon Series of data points + \return Curve points + */ + virtual QPolygonF fitCurve( const QPolygonF &polygon ) const = 0; protected: QwtCurveFitter(); @@ -65,42 +46,91 @@ private: class QWT_EXPORT QwtSplineCurveFitter: public QwtCurveFitter { public: - enum FitMode { + /*! + Spline type + The default setting is Auto + \sa setFitMode(), FitMode() + */ + enum FitMode + { + /*! + Use the default spline algorithm for polygons with + increasing x values ( p[i-1] < p[i] ), otherwise use + a parametric spline algorithm. + */ Auto, + + //! Use a default spline algorithm Spline, + + //! Use a parametric spline algorithm ParametricSpline }; QwtSplineCurveFitter(); virtual ~QwtSplineCurveFitter(); - void setFitMode(FitMode); + void setFitMode( FitMode ); FitMode fitMode() const; - void setSpline(const QwtSpline&); + void setSpline( const QwtSpline& ); const QwtSpline &spline() const; QwtSpline &spline(); - void setSplineSize(int size); + void setSplineSize( int size ); int splineSize() const; -#if QT_VERSION < 0x040000 - virtual QwtArray<QwtDoublePoint> fitCurve( - const QwtArray<QwtDoublePoint> &) const; -#else - virtual QPolygonF fitCurve(const QPolygonF &) const; -#endif + virtual QPolygonF fitCurve( const QPolygonF & ) const; private: -#if QT_VERSION < 0x040000 - QwtArray<QwtDoublePoint> fitSpline( - const QwtArray<QwtDoublePoint> &) const; - QwtArray<QwtDoublePoint> fitParametric( - const QwtArray<QwtDoublePoint> &) const; -#else - QPolygonF fitSpline(const QPolygonF &) const; - QPolygonF fitParametric(const QPolygonF &) const; -#endif + QPolygonF fitSpline( const QPolygonF & ) const; + QPolygonF fitParametric( const QPolygonF & ) const; + + class PrivateData; + PrivateData *d_data; +}; + +/*! + \brief A curve fitter implementing Douglas and Peucker algorithm + + The purpose of the Douglas and Peucker algorithm is that given a 'curve' + composed of line segments to find a curve not too dissimilar but that + has fewer points. The algorithm defines 'too dissimilar' based on the + maximum distance (tolerance) between the original curve and the + smoothed curve. + + The runtime of the algorithm increases non linear ( worst case O( n*n ) ) + and might be very slow for huge polygons. To avoid performance issues + it might be useful to split the polygon ( setChunkSize() ) and to run the algorithm + for these smaller parts. The disadvantage of having no interpolation + at the borders is for most use cases irrelevant. + + The smoothed curve consists of a subset of the points that defined the + original curve. + + In opposite to QwtSplineCurveFitter the Douglas and Peucker algorithm reduces + the number of points. By adjusting the tolerance parameter according to the + axis scales QwtSplineCurveFitter can be used to implement different + level of details to speed up painting of curves of many points. +*/ +class QWT_EXPORT QwtWeedingCurveFitter: public QwtCurveFitter +{ +public: + QwtWeedingCurveFitter( double tolerance = 1.0 ); + virtual ~QwtWeedingCurveFitter(); + + void setTolerance( double ); + double tolerance() const; + + void setChunkSize( uint ); + uint chunkSize() const; + + virtual QPolygonF fitCurve( const QPolygonF & ) const; + +private: + virtual QPolygonF simplify( const QPolygonF & ) const; + + class Line; class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_date.cpp b/libs/qwt/qwt_date.cpp new file mode 100644 index 0000000000..0cf5ca0d2a --- /dev/null +++ b/libs/qwt/qwt_date.cpp @@ -0,0 +1,654 @@ +#include "qwt_date.h" +#include <qdebug.h> +#include <qlocale.h> +#include <math.h> +#include <limits> +#include <limits.h> + +#if QT_VERSION >= 0x050000 + +typedef qint64 QwtJulianDay; +static const QwtJulianDay minJulianDayD = Q_INT64_C( -784350574879 ); +static const QwtJulianDay maxJulianDayD = Q_INT64_C( 784354017364 ); + +#else + +// QDate stores the Julian day as unsigned int, but +// but it is QDate::fromJulianDay( int ). That's why +// we have the range [ 1, INT_MAX ] +typedef int QwtJulianDay; +static const QwtJulianDay minJulianDayD = 1; +static const QwtJulianDay maxJulianDayD = std::numeric_limits<int>::max(); + +#endif + +static inline Qt::DayOfWeek qwtFirstDayOfWeek() +{ +#if QT_VERSION >= 0x040800 + return QLocale().firstDayOfWeek(); +#else + + switch( QLocale().country() ) + { + case QLocale::Maldives: + return Qt::Friday; + + case QLocale::Afghanistan: + case QLocale::Algeria: + case QLocale::Bahrain: + case QLocale::Djibouti: + case QLocale::Egypt: + case QLocale::Eritrea: + case QLocale::Ethiopia: + case QLocale::Iran: + case QLocale::Iraq: + case QLocale::Jordan: + case QLocale::Kenya: + case QLocale::Kuwait: + case QLocale::LibyanArabJamahiriya: + case QLocale::Morocco: + case QLocale::Oman: + case QLocale::Qatar: + case QLocale::SaudiArabia: + case QLocale::Somalia: + case QLocale::Sudan: + case QLocale::Tunisia: + case QLocale::Yemen: + return Qt::Saturday; + + case QLocale::AmericanSamoa: + case QLocale::Argentina: + case QLocale::Azerbaijan: + case QLocale::Botswana: + case QLocale::Canada: + case QLocale::China: + case QLocale::FaroeIslands: + case QLocale::Georgia: + case QLocale::Greenland: + case QLocale::Guam: + case QLocale::HongKong: + case QLocale::Iceland: + case QLocale::India: + case QLocale::Ireland: + case QLocale::Israel: + case QLocale::Jamaica: + case QLocale::Japan: + case QLocale::Kyrgyzstan: + case QLocale::Lao: + case QLocale::Malta: + case QLocale::MarshallIslands: + case QLocale::Macau: + case QLocale::Mongolia: + case QLocale::NewZealand: + case QLocale::NorthernMarianaIslands: + case QLocale::Pakistan: + case QLocale::Philippines: + case QLocale::RepublicOfKorea: + case QLocale::Singapore: + case QLocale::SyrianArabRepublic: + case QLocale::Taiwan: + case QLocale::Thailand: + case QLocale::TrinidadAndTobago: + case QLocale::UnitedStates: + case QLocale::UnitedStatesMinorOutlyingIslands: + case QLocale::USVirginIslands: + case QLocale::Uzbekistan: + case QLocale::Zimbabwe: + return Qt::Sunday; + + default: + return Qt::Monday; + } +#endif +} + +static inline void qwtFloorTime( + QwtDate::IntervalType intervalType, QDateTime &dt ) +{ + // when dt is inside the special hour where DST is ending + // an hour is no unique. Therefore we have to + // use UTC time. + + const Qt::TimeSpec timeSpec = dt.timeSpec(); + + if ( timeSpec == Qt::LocalTime ) + dt = dt.toTimeSpec( Qt::UTC ); + + const QTime t = dt.time(); + switch( intervalType ) + { + case QwtDate::Second: + { + dt.setTime( QTime( t.hour(), t.minute(), t.second() ) ); + break; + } + case QwtDate::Minute: + { + dt.setTime( QTime( t.hour(), t.minute(), 0 ) ); + break; + } + case QwtDate::Hour: + { + dt.setTime( QTime( t.hour(), 0, 0 ) ); + break; + } + default: + break; + } + + if ( timeSpec == Qt::LocalTime ) + dt = dt.toTimeSpec( Qt::LocalTime ); +} + +static inline QDateTime qwtToTimeSpec( + const QDateTime &dt, Qt::TimeSpec spec ) +{ + if ( dt.timeSpec() == spec ) + return dt; + + const qint64 jd = dt.date().toJulianDay(); + if ( jd < 0 || jd >= INT_MAX ) + { + // the conversion between local time and UTC + // is internally limited. To avoid + // overflows we simply ignore the difference + // for those dates + + QDateTime dt2 = dt; + dt2.setTimeSpec( spec ); + return dt2; + } + + return dt.toTimeSpec( spec ); +} + +static inline double qwtToJulianDay( int year, int month, int day ) +{ + // code from QDate but using doubles to avoid overflows + // for large values + + const int m1 = ( month - 14 ) / 12; + const int m2 = ( 367 * ( month - 2 - 12 * m1 ) ) / 12; + const double y1 = ::floor( ( 4900.0 + year + m1 ) / 100 ); + + return ::floor( ( 1461.0 * ( year + 4800 + m1 ) ) / 4 ) + m2 + - ::floor( ( 3 * y1 ) / 4 ) + day - 32075; +} + +static inline qint64 qwtFloorDiv64( qint64 a, int b ) +{ + if ( a < 0 ) + a -= b - 1; + + return a / b; +} + +static inline qint64 qwtFloorDiv( int a, int b ) +{ + if ( a < 0 ) + a -= b - 1; + + return a / b; +} + +static inline QDate qwtToDate( int year, int month = 1, int day = 1 ) +{ +#if QT_VERSION >= 0x050000 + return QDate( year, month, day ); +#else + if ( year > 100000 ) + { + // code from QDate but using doubles to avoid overflows + // for large values + + const int m1 = ( month - 14 ) / 12; + const int m2 = ( 367 * ( month - 2 - 12 * m1 ) ) / 12; + const double y1 = ::floor( ( 4900.0 + year + m1 ) / 100 ); + + const double jd = ::floor( ( 1461.0 * ( year + 4800 + m1 ) ) / 4 ) + m2 + - ::floor( ( 3 * y1 ) / 4 ) + day - 32075; + + if ( jd > maxJulianDayD ) + { + qWarning() << "qwtToDate: overflow"; + return QDate(); + } + + return QDate::fromJulianDay( static_cast<QwtJulianDay>( jd ) ); + } + else + { + return QDate( year, month, day ); + } +#endif +} + +/*! + Translate from double to QDateTime + + \param value Number of milliseconds since the epoch, + 1970-01-01T00:00:00 UTC + \param timeSpec Time specification + \return Datetime value + + \sa toDouble(), QDateTime::setMSecsSinceEpoch() + \note The return datetime for Qt::OffsetFromUTC will be Qt::UTC + */ +QDateTime QwtDate::toDateTime( double value, Qt::TimeSpec timeSpec ) +{ + const int msecsPerDay = 86400000; + + const double days = static_cast<qint64>( ::floor( value / msecsPerDay ) ); + + const double jd = QwtDate::JulianDayForEpoch + days; + if ( ( jd > maxJulianDayD ) || ( jd < minJulianDayD ) ) + { + qWarning() << "QwtDate::toDateTime: overflow"; + return QDateTime(); + } + + const QDate d = QDate::fromJulianDay( static_cast<QwtJulianDay>( jd ) ); + + const int msecs = static_cast<int>( value - days * msecsPerDay ); + + static const QTime timeNull( 0, 0, 0, 0 ); + + QDateTime dt( d, timeNull.addMSecs( msecs ), Qt::UTC ); + + if ( timeSpec == Qt::LocalTime ) + dt = qwtToTimeSpec( dt, timeSpec ); + + return dt; +} + +/*! + Translate from QDateTime to double + + \param dateTime Datetime value + \return Number of milliseconds since 1970-01-01T00:00:00 UTC has passed. + + \sa toDateTime(), QDateTime::toMSecsSinceEpoch() + \warning For values very far below or above 1970-01-01 UTC rounding errors + will happen due to the limited significance of a double. + */ +double QwtDate::toDouble( const QDateTime &dateTime ) +{ + const int msecsPerDay = 86400000; + + const QDateTime dt = qwtToTimeSpec( dateTime, Qt::UTC ); + + const double days = dt.date().toJulianDay() - QwtDate::JulianDayForEpoch; + + const QTime time = dt.time(); + const double secs = 3600.0 * time.hour() + + 60.0 * time.minute() + time.second(); + + return days * msecsPerDay + time.msec() + 1000.0 * secs; +} + +/*! + Ceil a datetime according the interval type + + \param dateTime Datetime value + \param intervalType Interval type, how to ceil. + F.e. when intervalType = QwtDate::Months, the result + will be ceiled to the next beginning of a month + \return Ceiled datetime + \sa floor() + */ +QDateTime QwtDate::ceil( const QDateTime &dateTime, IntervalType intervalType ) +{ + if ( dateTime.date() >= QwtDate::maxDate() ) + return dateTime; + + QDateTime dt = dateTime; + + switch ( intervalType ) + { + case QwtDate::Millisecond: + { + break; + } + case QwtDate::Second: + { + qwtFloorTime( QwtDate::Second, dt ); + if ( dt < dateTime ) + dt.addSecs( 1 ); + + break; + } + case QwtDate::Minute: + { + qwtFloorTime( QwtDate::Minute, dt ); + if ( dt < dateTime ) + dt.addSecs( 60 ); + + break; + } + case QwtDate::Hour: + { + qwtFloorTime( QwtDate::Hour, dt ); + if ( dt < dateTime ) + dt.addSecs( 3600 ); + + break; + } + case QwtDate::Day: + { + dt.setTime( QTime( 0, 0 ) ); + if ( dt < dateTime ) + dt = dt.addDays( 1 ); + + break; + } + case QwtDate::Week: + { + dt.setTime( QTime( 0, 0 ) ); + if ( dt < dateTime ) + dt = dt.addDays( 1 ); + + int days = qwtFirstDayOfWeek() - dt.date().dayOfWeek(); + if ( days < 0 ) + days += 7; + + dt = dt.addDays( days ); + + break; + } + case QwtDate::Month: + { + dt.setTime( QTime( 0, 0 ) ); + dt.setDate( qwtToDate( dateTime.date().year(), + dateTime.date().month() ) ); + + if ( dt < dateTime ) + dt.addMonths( 1 ); + + break; + } + case QwtDate::Year: + { + dt.setTime( QTime( 0, 0 ) ); + + const QDate d = dateTime.date(); + + int year = d.year(); + if ( d.month() > 1 || d.day() > 1 || !dateTime.time().isNull() ) + year++; + + if ( year == 0 ) + year++; // there is no year 0 + + dt.setDate( qwtToDate( year ) ); + break; + } + } + + return dt; +} + +/*! + Floor a datetime according the interval type + + \param dateTime Datetime value + \param intervalType Interval type, how to ceil. + F.e. when intervalType = QwtDate::Months, + the result will be ceiled to the next + beginning of a month + \return Floored datetime + \sa floor() + */ +QDateTime QwtDate::floor( const QDateTime &dateTime, + IntervalType intervalType ) +{ + if ( dateTime.date() <= QwtDate::minDate() ) + return dateTime; + + QDateTime dt = dateTime; + + switch ( intervalType ) + { + case QwtDate::Millisecond: + { + break; + } + case QwtDate::Second: + case QwtDate::Minute: + case QwtDate::Hour: + { + qwtFloorTime( intervalType, dt ); + break; + } + case QwtDate::Day: + { + dt.setTime( QTime( 0, 0 ) ); + break; + } + case QwtDate::Week: + { + dt.setTime( QTime( 0, 0 ) ); + + int days = dt.date().dayOfWeek() - qwtFirstDayOfWeek(); + if ( days < 0 ) + days += 7; + + dt = dt.addDays( -days ); + + break; + } + case QwtDate::Month: + { + dt.setTime( QTime( 0, 0 ) ); + + const QDate date = qwtToDate( dt.date().year(), + dt.date().month() ); + dt.setDate( date ); + + break; + } + case QwtDate::Year: + { + dt.setTime( QTime( 0, 0 ) ); + + const QDate date = qwtToDate( dt.date().year() ); + dt.setDate( date ); + + break; + } + } + + return dt; +} + +/*! + Minimum for the supported date range + + The range of valid dates depends on how QDate stores the + Julian day internally. + + - For Qt4 it is "Tue Jan 2 -4713" + - For Qt5 it is "Thu Jan 1 -2147483648" + + \return minimum of the date range + \sa maxDate() + */ +QDate QwtDate::minDate() +{ + static QDate date; + if ( !date.isValid() ) + date = QDate::fromJulianDay( minJulianDayD ); + + return date; +} + +/*! + Maximum for the supported date range + + The range of valid dates depends on how QDate stores the + Julian day internally. + + - For Qt4 it is "Tue Jun 3 5874898" + - For Qt5 it is "Tue Dec 31 2147483647" + + \return maximum of the date range + \sa minDate() + \note The maximum differs between Qt4 and Qt5 + */ +QDate QwtDate::maxDate() +{ + static QDate date; + if ( !date.isValid() ) + date = QDate::fromJulianDay( maxJulianDayD ); + + return date; +} + +/*! + \brief Date of the first day of the first week for a year + + The first day of a week depends on the current locale + ( QLocale::firstDayOfWeek() ). + + \param year Year + \param type Option how to identify the first week + \return First day of week 0 + + \sa QLocale::firstDayOfWeek(), weekNumber() + */ +QDate QwtDate::dateOfWeek0( int year, Week0Type type ) +{ + const Qt::DayOfWeek firstDayOfWeek = qwtFirstDayOfWeek(); + + QDate dt0( year, 1, 1 ); + + // floor to the first day of the week + int days = dt0.dayOfWeek() - firstDayOfWeek; + if ( days < 0 ) + days += 7; + + dt0 = dt0.addDays( -days ); + + if ( type == QwtDate::FirstThursday ) + { + // according to ISO 8601 the first week is defined + // by the first thursday. + + int d = Qt::Thursday - firstDayOfWeek; + if ( d < 0 ) + d += 7; + + if ( dt0.addDays( d ).year() < year ) + dt0 = dt0.addDays( 7 ); + } + + return dt0; +} + +/*! + Find the week number of a date + + - QwtDate::FirstThursday\n + Corresponding to ISO 8601 ( see QDate::weekNumber() ). + + - QwtDate::FirstDay\n + Number of weeks that have begun since dateOfWeek0(). + + \param date Date + \param type Option how to identify the first week + + \return Week number, starting with 1 + */ +int QwtDate::weekNumber( const QDate &date, Week0Type type ) +{ + int weekNo; + + if ( type == QwtDate::FirstDay ) + { + const QDate day0 = dateOfWeek0( date.year(), type ); + weekNo = day0.daysTo( date ) / 7 + 1; + } + else + { + weekNo = date.weekNumber(); + } + + return weekNo; +} + +/*! + Offset in seconds from Coordinated Universal Time + + The offset depends on the time specification of dateTime: + + - Qt::UTC + 0, dateTime has no offset + - Qt::OffsetFromUTC + returns dateTime.utcOffset() + - Qt::LocalTime: + number of seconds from the UTC + + For Qt::LocalTime the offset depends on the timezone and + daylight savings. + + \param dateTime Datetime value + \return Offset in seconds + */ +int QwtDate::utcOffset( const QDateTime &dateTime ) +{ + int seconds = 0; + + switch( dateTime.timeSpec() ) + { + case Qt::UTC: + { + break; + } + case Qt::OffsetFromUTC: + { + seconds = dateTime.utcOffset(); + } + default: + { + const QDateTime dt1( dateTime.date(), dateTime.time(), Qt::UTC ); + seconds = dateTime.secsTo( dt1 ); + } + } + + return seconds; +} + +/*! + Translate a datetime into a string + + Beside the format expressions documented in QDateTime::toString() + the following expressions are supported: + + - w\n + week number: ( 1 - 53 ) + - ww\n + week number with a leading zero ( 01 - 53 ) + + \param dateTime Datetime value + \param format Format string + \param week0Type Specification of week 0 + + \return Datetime string + \sa QDateTime::toString(), weekNumber(), QwtDateScaleDraw + */ +QString QwtDate::toString( const QDateTime &dateTime, + const QString & format, Week0Type week0Type ) +{ + QString weekNo; + weekNo.setNum( QwtDate::weekNumber( dateTime.date(), week0Type ) ); + + QString weekNoWW; + if ( weekNo.length() == 1 ) + weekNoWW += "0"; + weekNoWW += weekNo; + + QString fmt = format; + fmt.replace( "ww", weekNoWW ); + fmt.replace( "w", weekNo ); + + return dateTime.toString( fmt ); +} diff --git a/libs/qwt/qwt_date.h b/libs/qwt/qwt_date.h new file mode 100644 index 0000000000..30422a1c1c --- /dev/null +++ b/libs/qwt/qwt_date.h @@ -0,0 +1,128 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef _QWT_DATE_H_ +#define _QWT_DATE_H_ + +#include "qwt_global.h" +#include <qdatetime.h> + +/*! + \brief A collection of methods around date/time values + + Qt offers convenient classes for dealing with date/time values, + but Qwt uses coordinate systems that are based on doubles. + QwtDate offers methods to translate from QDateTime to double and v.v. + + A double is interpreted as the number of milliseconds since + 1970-01-01T00:00:00 Universal Coordinated Time - also known + as "The Epoch". + + While the range of the Julian day in Qt4 is limited to [0, MAX_INT], + Qt5 stores it as qint64 offering a huge range of valid dates. + As the significance of a double is below this ( assuming a + fraction of 52 bits ) the translation is not + bijective with rounding errors for dates very far from Epoch. + For a resolution of 1 ms those start to happen for dates above the + year 144683. + + An axis for a date/time interval is expected to be aligned + and divided in time/date units like seconds, minutes, ... + QwtDate offers several algorithms that are needed to + calculate these axes. + + \sa QwtDateScaleEngine, QwtDateScaleDraw, QDate, QTime +*/ +class QWT_EXPORT QwtDate +{ +public: + /*! + How to identify the first week of year differs between + countries. + */ + enum Week0Type + { + /*! + According to ISO 8601 the first week of a year is defined + as "the week with the year's first Thursday in it". + + FirstThursday corresponds to the numbering that is + implemented in QDate::weekNumber(). + */ + FirstThursday, + + /*! + "The week with January 1.1 in it." + + In the U.S. this definition is more common than + FirstThursday. + */ + FirstDay + }; + + /*! + Classification of an time interval + + Time intervals needs to be classified to decide how to + align and divide it. + */ + enum IntervalType + { + //! The interval is related to milliseconds + Millisecond, + + //! The interval is related to seconds + Second, + + //! The interval is related to minutes + Minute, + + //! The interval is related to hours + Hour, + + //! The interval is related to days + Day, + + //! The interval is related to weeks + Week, + + //! The interval is related to months + Month, + + //! The interval is related to years + Year + }; + + enum + { + //! The Julian day of "The Epoch" + JulianDayForEpoch = 2440588 + }; + + static QDate minDate(); + static QDate maxDate(); + + static QDateTime toDateTime( double value, + Qt::TimeSpec = Qt::UTC ); + + static double toDouble( const QDateTime & ); + + static QDateTime ceil( const QDateTime &, IntervalType ); + static QDateTime floor( const QDateTime &, IntervalType ); + + static QDate dateOfWeek0( int year, Week0Type ); + static int weekNumber( const QDate &, Week0Type ); + + static int utcOffset( const QDateTime & ); + + static QString toString( const QDateTime &, + const QString & format, Week0Type ); +}; + +#endif diff --git a/libs/qwt/qwt_date_scale_draw.cpp b/libs/qwt/qwt_date_scale_draw.cpp new file mode 100644 index 0000000000..7cfc6dec0b --- /dev/null +++ b/libs/qwt/qwt_date_scale_draw.cpp @@ -0,0 +1,269 @@ +#include "qwt_date_scale_draw.h" + +class QwtDateScaleDraw::PrivateData +{ +public: + PrivateData( Qt::TimeSpec spec ): + timeSpec( spec ), + utcOffset( 0 ), + week0Type( QwtDate::FirstThursday ) + { + dateFormats[ QwtDate::Millisecond ] = "hh:mm:ss:zzz\nddd dd MMM yyyy"; + dateFormats[ QwtDate::Second ] = "hh:mm:ss\nddd dd MMM yyyy"; + dateFormats[ QwtDate::Minute ] = "hh:mm\nddd dd MMM yyyy"; + dateFormats[ QwtDate::Hour ] = "hh:mm\nddd dd MMM yyyy"; + dateFormats[ QwtDate::Day ] = "ddd dd MMM yyyy"; + dateFormats[ QwtDate::Week ] = "Www yyyy"; + dateFormats[ QwtDate::Month ] = "MMM yyyy"; + dateFormats[ QwtDate::Year ] = "yyyy"; + } + + Qt::TimeSpec timeSpec; + int utcOffset; + QwtDate::Week0Type week0Type; + QString dateFormats[ QwtDate::Year + 1 ]; +}; + +/*! + \brief Constructor + + The default setting is to display tick labels for the + given time specification. The first week of a year is defined like + for QwtDate::FirstThursday. + + \param timeSpec Time specification + + \sa setTimeSpec(), setWeek0Type() + */ +QwtDateScaleDraw::QwtDateScaleDraw( Qt::TimeSpec timeSpec ) +{ + d_data = new PrivateData( timeSpec ); +} + +//! Destructor +QwtDateScaleDraw::~QwtDateScaleDraw() +{ + delete d_data; +} + +/*! + Set the time specification used for the tick labels + + \param timeSpec Time specification + \sa timeSpec(), setUtcOffset(), toDateTime() + */ +void QwtDateScaleDraw::setTimeSpec( Qt::TimeSpec timeSpec ) +{ + d_data->timeSpec = timeSpec; +} + +/*! + \return Time specification used for the tick labels + \sa setTimeSpec(), utcOffset(), toDateTime() + */ +Qt::TimeSpec QwtDateScaleDraw::timeSpec() const +{ + return d_data->timeSpec; +} + +/*! + Set the offset in seconds from Coordinated Universal Time + + \param seconds Offset in seconds + + \note The offset has no effect beside for the time specification + Qt::OffsetFromUTC. + + \sa QDate::utcOffset(), setTimeSpec(), toDateTime() + */ +void QwtDateScaleDraw::setUtcOffset( int seconds ) +{ + d_data->utcOffset = seconds; +} + +/*! + \return Offset in seconds from Coordinated Universal Time + \note The offset has no effect beside for the time specification + Qt::OffsetFromUTC. + + \sa QDate::setUtcOffset(), setTimeSpec(), toDateTime() + */ +int QwtDateScaleDraw::utcOffset() const +{ + return d_data->utcOffset; +} + +/*! + Sets how to identify the first week of a year. + + \param week0Type Mode how to identify the first week of a year + + \sa week0Type(). + \note week0Type has no effect beside for intervals classified as + QwtDate::Week. + */ +void QwtDateScaleDraw::setWeek0Type( QwtDate::Week0Type week0Type ) +{ + d_data->week0Type = week0Type; +} + +/*! + \return Setting how to identify the first week of a year. + \sa setWeek0Type() + */ +QwtDate::Week0Type QwtDateScaleDraw::week0Type() const +{ + return d_data->week0Type; +} + +/*! + Set the default format string for an datetime interval type + + \param intervalType Interval type + \param format Default format string + + \sa dateFormat(), dateFormatOfDate(), QwtDate::toString() + */ +void QwtDateScaleDraw::setDateFormat( + QwtDate::IntervalType intervalType, const QString &format ) +{ + if ( intervalType >= QwtDate::Millisecond && + intervalType <= QwtDate::Year ) + { + d_data->dateFormats[ intervalType ] = format; + } +} + +/*! + \param intervalType Interval type + \return Default format string for an datetime interval type + \sa setDateFormat(), dateFormatOfDate() + */ +QString QwtDateScaleDraw::dateFormat( + QwtDate::IntervalType intervalType ) const +{ + if ( intervalType >= QwtDate::Millisecond && + intervalType <= QwtDate::Year ) + { + return d_data->dateFormats[ intervalType ]; + } + + return QString::null; +} + +/*! + Format string for the representation of a datetime + + dateFormatOfDate() is intended to be overloaded for + situations, where formats are individual for specific + datetime values. + + The default setting ignores dateTime and return + the default format for the interval type. + + \param dateTime Datetime value + \param intervalType Interval type + \return Format string + + \sa setDateFormat(), QwtDate::toString() + */ +QString QwtDateScaleDraw::dateFormatOfDate( const QDateTime &dateTime, + QwtDate::IntervalType intervalType ) const +{ + Q_UNUSED( dateTime ) + + if ( intervalType >= QwtDate::Millisecond && + intervalType <= QwtDate::Year ) + { + return d_data->dateFormats[ intervalType ]; + } + + return d_data->dateFormats[ QwtDate::Second ]; +} + +/*! + \brief Convert a value into its representing label + + The value is converted to a datetime value using toDateTime() + and converted to a plain text using QwtDate::toString(). + + \param value Value + \return Label string. + + \sa dateFormatOfDate() +*/ +QwtText QwtDateScaleDraw::label( double value ) const +{ + const QDateTime dt = toDateTime( value ); + const QString fmt = dateFormatOfDate( + dt, intervalType( scaleDiv() ) ); + + return QwtDate::toString( dt, fmt, d_data->week0Type ); +} + +/*! + Find the less detailed datetime unit, where no rounding + errors happen. + + \param scaleDiv Scale division + \return Interval type + + \sa dateFormatOfDate() + */ +QwtDate::IntervalType QwtDateScaleDraw::intervalType( + const QwtScaleDiv &scaleDiv ) const +{ + int intvType = QwtDate::Year; + + bool alignedToWeeks = true; + + const QList<double> ticks = scaleDiv.ticks( QwtScaleDiv::MajorTick ); + for ( int i = 0; i < ticks.size(); i++ ) + { + const QDateTime dt = toDateTime( ticks[i] ); + for ( int j = QwtDate::Second; j <= intvType; j++ ) + { + const QDateTime dt0 = QwtDate::floor( dt, + static_cast<QwtDate::IntervalType>( j ) ); + + if ( dt0 != dt ) + { + if ( j == QwtDate::Week ) + { + alignedToWeeks = false; + } + else + { + intvType = j - 1; + break; + } + } + } + + if ( intvType == QwtDate::Millisecond ) + break; + } + + if ( intvType == QwtDate::Week && !alignedToWeeks ) + intvType = QwtDate::Day; + + return static_cast<QwtDate::IntervalType>( intvType ); +} + +/*! + Translate a double value into a QDateTime object. + + \return QDateTime object initialized with timeSpec() and utcOffset(). + \sa timeSpec(), utcOffset(), QwtDate::toDateTime() + */ +QDateTime QwtDateScaleDraw::toDateTime( double value ) const +{ + QDateTime dt = QwtDate::toDateTime( value, d_data->timeSpec ); + if ( d_data->timeSpec == Qt::OffsetFromUTC ) + { + dt = dt.addSecs( d_data->utcOffset ); + dt.setUtcOffset( d_data->utcOffset ); + } + + return dt; +} diff --git a/libs/qwt/qwt_date_scale_draw.h b/libs/qwt/qwt_date_scale_draw.h new file mode 100644 index 0000000000..92589e890f --- /dev/null +++ b/libs/qwt/qwt_date_scale_draw.h @@ -0,0 +1,77 @@ +#ifndef _QWT_DATE_SCALE_DRAW_H_ +#define _QWT_DATE_SCALE_DRAW_H_ 1 + +#include "qwt_global.h" +#include "qwt_scale_draw.h" +#include "qwt_date.h" + +/*! + \brief A class for drawing datetime scales + + QwtDateScaleDraw displays values as datetime labels. + The format of the labels depends on the alignment of + the major tick labels. + + The default format strings are: + + - Millisecond\n + "hh:mm:ss:zzz\nddd dd MMM yyyy" + - Second\n + "hh:mm:ss\nddd dd MMM yyyy" + - Minute\n + "hh:mm\nddd dd MMM yyyy" + - Hour\n + "hh:mm\nddd dd MMM yyyy" + - Day\n + "ddd dd MMM yyyy" + - Week\n + "Www yyyy" + - Month\n + "MMM yyyy" + - Year\n + "yyyy" + + The format strings can be modified using setDateFormat() + or individually for each tick label by overloading dateFormatOfDate(), + + Usually QwtDateScaleDraw is used in combination with + QwtDateScaleEngine, that calculates scales for datetime + intervals. + + \sa QwtDateScaleEngine, QwtPlot::setAxisScaleDraw() +*/ +class QWT_EXPORT QwtDateScaleDraw: public QwtScaleDraw +{ +public: + QwtDateScaleDraw( Qt::TimeSpec = Qt::LocalTime ); + virtual ~QwtDateScaleDraw(); + + void setDateFormat( QwtDate::IntervalType, const QString & ); + QString dateFormat( QwtDate::IntervalType ) const; + + void setTimeSpec( Qt::TimeSpec ); + Qt::TimeSpec timeSpec() const; + + void setUtcOffset( int seconds ); + int utcOffset() const; + + void setWeek0Type( QwtDate::Week0Type ); + QwtDate::Week0Type week0Type() const; + + virtual QwtText label( double ) const; + + QDateTime toDateTime( double ) const; + +protected: + virtual QwtDate::IntervalType + intervalType( const QwtScaleDiv & ) const; + + virtual QString dateFormatOfDate( const QDateTime &, + QwtDate::IntervalType ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_date_scale_engine.cpp b/libs/qwt/qwt_date_scale_engine.cpp new file mode 100644 index 0000000000..85c1f175a5 --- /dev/null +++ b/libs/qwt/qwt_date_scale_engine.cpp @@ -0,0 +1,1300 @@ +#include "qwt_date_scale_engine.h" +#include "qwt_math.h" +#include "qwt_transform.h" +#include <qdatetime.h> +#include <limits.h> + +static inline double qwtMsecsForType( QwtDate::IntervalType type ) +{ + static const double msecs[] = + { + 1.0, + 1000.0, + 60.0 * 1000.0, + 3600.0 * 1000.0, + 24.0 * 3600.0 * 1000.0, + 7.0 * 24.0 * 3600.0 * 1000.0, + 30.0 * 24.0 * 3600.0 * 1000.0, + 365.0 * 24.0 * 3600.0 * 1000.0, + }; + + if ( type < 0 || type >= static_cast<int>( sizeof( msecs ) / sizeof( msecs[0] ) ) ) + return 1.0; + + return msecs[ type ]; +} + +static inline int qwtAlignValue( + double value, double stepSize, bool up ) +{ + double d = value / stepSize; + d = up ? ::ceil( d ) : ::floor( d ); + + return static_cast<int>( d * stepSize ); +} + +static double qwtIntervalWidth( const QDateTime &minDate, + const QDateTime &maxDate, QwtDate::IntervalType intervalType ) +{ + switch( intervalType ) + { + case QwtDate::Millisecond: + { + const double secsTo = minDate.secsTo( maxDate ); + const double msecs = maxDate.time().msec() - + minDate.time().msec(); + + return secsTo * 1000 + msecs; + } + case QwtDate::Second: + { + return minDate.secsTo( maxDate ); + } + case QwtDate::Minute: + { + const double secsTo = minDate.secsTo( maxDate ); + return ::floor( secsTo / 60 ); + } + case QwtDate::Hour: + { + const double secsTo = minDate.secsTo( maxDate ); + return ::floor( secsTo / 3600 ); + } + case QwtDate::Day: + { + return minDate.daysTo( maxDate ); + } + case QwtDate::Week: + { + return ::floor( minDate.daysTo( maxDate ) / 7.0 ); + } + case QwtDate::Month: + { + const double years = + double( maxDate.date().year() ) - minDate.date().year(); + + int months = maxDate.date().month() - minDate.date().month(); + if ( maxDate.date().day() < minDate.date().day() ) + months--; + + return years * 12 + months; + } + case QwtDate::Year: + { + double years = + double( maxDate.date().year() ) - minDate.date().year(); + + if ( maxDate.date().month() < minDate.date().month() ) + years -= 1.0; + + return years; + } + } + + return 0.0; +} + +static double qwtRoundedIntervalWidth( + const QDateTime &minDate, const QDateTime &maxDate, + QwtDate::IntervalType intervalType ) +{ + const QDateTime minD = QwtDate::floor( minDate, intervalType ); + const QDateTime maxD = QwtDate::ceil( maxDate, intervalType ); + + return qwtIntervalWidth( minD, maxD, intervalType ); +} + +static inline int qwtStepCount( int intervalSize, int maxSteps, + const int limits[], size_t numLimits ) +{ + for ( uint i = 0; i < numLimits; i++ ) + { + const int numSteps = intervalSize / limits[ i ]; + + if ( numSteps > 1 && numSteps <= maxSteps && + numSteps * limits[ i ] == intervalSize ) + { + return numSteps; + } + } + + return 0; +} + +static int qwtStepSize( int intervalSize, int maxSteps, uint base ) +{ + if ( maxSteps <= 0 ) + return 0; + + if ( maxSteps > 2 ) + { + for ( int numSteps = maxSteps; numSteps > 1; numSteps-- ) + { + const double stepSize = double( intervalSize ) / numSteps; + + const double p = ::floor( ::log( stepSize ) / ::log( double( base ) ) ); + const double fraction = qPow( base, p ); + + for ( uint n = base; n >= 1; n /= 2 ) + { + if ( qFuzzyCompare( stepSize, n * fraction ) ) + return qRound( stepSize ); + + if ( n == 3 && ( base % 2 ) == 0 ) + { + if ( qFuzzyCompare( stepSize, 2 * fraction ) ) + return qRound( stepSize ); + } + } + } + } + + return 0; +} + +static int qwtDivideInterval( double intervalSize, int numSteps, + const int limits[], size_t numLimits ) +{ + const int v = qCeil( intervalSize / double( numSteps ) ); + + for ( uint i = 0; i < numLimits - 1; i++ ) + { + if ( v <= limits[i] ) + return limits[i]; + } + + return limits[ numLimits - 1 ]; +} + +static double qwtDivideScale( double intervalSize, int numSteps, + QwtDate::IntervalType intervalType ) +{ + if ( intervalType != QwtDate::Day ) + { + if ( ( intervalSize > numSteps ) && + ( intervalSize <= 2 * numSteps ) ) + { + return 2.0; + } + } + + double stepSize; + + switch( intervalType ) + { + case QwtDate::Second: + case QwtDate::Minute: + { + static int limits[] = { 1, 2, 5, 10, 15, 20, 30, 60 }; + + stepSize = qwtDivideInterval( intervalSize, numSteps, + limits, sizeof( limits ) / sizeof( int ) ); + + break; + } + case QwtDate::Hour: + { + static int limits[] = { 1, 2, 3, 4, 6, 12, 24 }; + + stepSize = qwtDivideInterval( intervalSize, numSteps, + limits, sizeof( limits ) / sizeof( int ) ); + + break; + } + case QwtDate::Day: + { + const double v = intervalSize / double( numSteps ); + if ( v <= 5.0 ) + stepSize = qCeil( v ); + else + stepSize = qCeil( v / 7 ) * 7; + + break; + } + case QwtDate::Week: + { + static int limits[] = { 1, 2, 4, 8, 12, 26, 52 }; + + stepSize = qwtDivideInterval( intervalSize, numSteps, + limits, sizeof( limits ) / sizeof( int ) ); + + break; + } + case QwtDate::Month: + { + static int limits[] = { 1, 2, 3, 4, 6, 12 }; + + stepSize = qwtDivideInterval( intervalSize, numSteps, + limits, sizeof( limits ) / sizeof( int ) ); + + break; + } + case QwtDate::Year: + case QwtDate::Millisecond: + default: + { + stepSize = QwtScaleArithmetic::divideInterval( + intervalSize, numSteps, 10 ); + } + } + + return stepSize; +} + +static double qwtDivideMajorStep( double stepSize, int maxMinSteps, + QwtDate::IntervalType intervalType ) +{ + double minStepSize = 0.0; + + switch( intervalType ) + { + case QwtDate::Second: + { + minStepSize = qwtStepSize( stepSize, maxMinSteps, 10 ); + if ( minStepSize == 0.0 ) + minStepSize = 0.5 * stepSize; + + break; + } + case QwtDate::Minute: + { + static int limits[] = { 1, 2, 5, 10, 15, 20, 30, 60 }; + + int numSteps; + + if ( stepSize > maxMinSteps ) + { + numSteps = qwtStepCount( stepSize, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + + } + else + { + numSteps = qwtStepCount( stepSize * 60, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + } + + if ( numSteps > 0 ) + minStepSize = double( stepSize ) / numSteps; + + break; + } + case QwtDate::Hour: + { + int numSteps = 0; + + if ( stepSize > maxMinSteps ) + { + static int limits[] = { 1, 2, 3, 4, 6, 12, 24, 48, 72 }; + + numSteps = qwtStepCount( stepSize, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + } + else + { + static int limits[] = { 1, 2, 5, 10, 15, 20, 30, 60 }; + + numSteps = qwtStepCount( stepSize * 60, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + } + + if ( numSteps > 0 ) + minStepSize = double( stepSize ) / numSteps; + + break; + } + case QwtDate::Day: + { + int numSteps = 0; + + if ( stepSize > maxMinSteps ) + { + static int limits[] = { 1, 2, 3, 7, 14, 28 }; + + numSteps = qwtStepCount( stepSize, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + } + else + { + static int limits[] = { 1, 2, 3, 4, 6, 12, 24, 48, 72 }; + + numSteps = qwtStepCount( stepSize * 24, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + } + + if ( numSteps > 0 ) + minStepSize = double( stepSize ) / numSteps; + + break; + } + case QwtDate::Week: + { + const int daysInStep = stepSize * 7; + + if ( maxMinSteps >= daysInStep ) + { + // we want to have one tick per day + minStepSize = 1.0 / 7.0; + } + else + { + // when the stepSize is more than a week we want to + // have a tick for each week + + const int stepSizeInWeeks = stepSize; + + if ( stepSizeInWeeks <= maxMinSteps ) + { + minStepSize = 1; + } + else + { + minStepSize = QwtScaleArithmetic::divideInterval( + stepSizeInWeeks, maxMinSteps, 10 ); + } + } + break; + } + case QwtDate::Month: + { + // fractions of months doesn't make any sense + + if ( stepSize < maxMinSteps ) + maxMinSteps = static_cast<int>( stepSize ); + + static int limits[] = { 1, 2, 3, 4, 6, 12 }; + + int numSteps = qwtStepCount( stepSize, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + + if ( numSteps > 0 ) + minStepSize = double( stepSize ) / numSteps; + + break; + } + case QwtDate::Year: + { + if ( stepSize >= maxMinSteps ) + { + minStepSize = QwtScaleArithmetic::divideInterval( + stepSize, maxMinSteps, 10 ); + } + else + { + // something in months + + static int limits[] = { 1, 2, 3, 4, 6, 12 }; + + int numSteps = qwtStepCount( 12 * stepSize, maxMinSteps, + limits, sizeof( limits ) / sizeof( int ) ); + + if ( numSteps > 0 ) + minStepSize = double( stepSize ) / numSteps; + } + + break; + } + default: + break; + } + + if ( intervalType != QwtDate::Month + && minStepSize == 0.0 ) + { + minStepSize = 0.5 * stepSize; + } + + return minStepSize; +} + +static QList<double> qwtDstTicks( const QDateTime &dateTime, + int secondsMajor, int secondsMinor ) +{ + if ( secondsMinor <= 0 ) + QList<double>(); + + QDateTime minDate = dateTime.addSecs( -secondsMajor ); + minDate = QwtDate::floor( minDate, QwtDate::Hour ); + + const double utcOffset = QwtDate::utcOffset( dateTime ); + + // find the hours where daylight saving time happens + + double dstMin = QwtDate::toDouble( minDate ); + while ( minDate < dateTime && + QwtDate::utcOffset( minDate ) != utcOffset ) + { + minDate = minDate.addSecs( 3600 ); + dstMin += 3600 * 1000.0; + } + + QList<double> ticks; + for ( int i = 0; i < 3600; i += secondsMinor ) + ticks += dstMin + i * 1000.0; + + return ticks; +} + +static QwtScaleDiv qwtDivideToSeconds( + const QDateTime &minDate, const QDateTime &maxDate, + double stepSize, int maxMinSteps, + QwtDate::IntervalType intervalType ) +{ + // calculate the min step size + double minStepSize = 0; + + if ( maxMinSteps > 1 ) + { + minStepSize = qwtDivideMajorStep( stepSize, + maxMinSteps, intervalType ); + } + + bool daylightSaving = false; + if ( minDate.timeSpec() == Qt::LocalTime ) + { + daylightSaving = intervalType > QwtDate::Hour; + if ( intervalType == QwtDate::Hour ) + { + daylightSaving = stepSize > 1; + } + } + + const double s = qwtMsecsForType( intervalType ) / 1000; + const int secondsMajor = static_cast<int>( stepSize * s ); + const double secondsMinor = minStepSize * s; + + // UTC excludes daylight savings. So from the difference + // of a date and its UTC counterpart we can find out + // the daylight saving hours + + const double utcOffset = QwtDate::utcOffset( minDate ); + double dstOff = 0; + + QList<double> majorTicks; + QList<double> mediumTicks; + QList<double> minorTicks; + + for ( QDateTime dt = minDate; dt <= maxDate; + dt = dt.addSecs( secondsMajor ) ) + { + if ( !dt.isValid() ) + break; + + double majorValue = QwtDate::toDouble( dt ); + + if ( daylightSaving ) + { + const double offset = utcOffset - QwtDate::utcOffset( dt ); + majorValue += offset * 1000.0; + + if ( offset > dstOff ) + { + // we add some minor ticks for the DST hour, + // otherwise the ticks will be unaligned: 0, 2, 3, 5 ... + minorTicks += qwtDstTicks( + dt, secondsMajor, qRound( secondsMinor ) ); + } + + dstOff = offset; + } + + if ( majorTicks.isEmpty() || majorTicks.last() != majorValue ) + majorTicks += majorValue; + + if ( secondsMinor > 0.0 ) + { + const int numMinorSteps = qFloor( secondsMajor / secondsMinor ); + + for ( int i = 1; i < numMinorSteps; i++ ) + { + const QDateTime mt = dt.addMSecs( + qRound64( i * secondsMinor * 1000 ) ); + + double minorValue = QwtDate::toDouble( mt ); + if ( daylightSaving ) + { + const double offset = utcOffset - QwtDate::utcOffset( mt ); + minorValue += offset * 1000.0; + } + + if ( minorTicks.isEmpty() || minorTicks.last() != minorValue ) + { + const bool isMedium = ( numMinorSteps % 2 == 0 ) + && ( i != 1 ) && ( i == numMinorSteps / 2 ); + + if ( isMedium ) + mediumTicks += minorValue; + else + minorTicks += minorValue; + } + } + } + } + + QwtScaleDiv scaleDiv; + + scaleDiv.setInterval( QwtDate::toDouble( minDate ), + QwtDate::toDouble( maxDate ) ); + + scaleDiv.setTicks( QwtScaleDiv::MajorTick, majorTicks ); + scaleDiv.setTicks( QwtScaleDiv::MediumTick, mediumTicks ); + scaleDiv.setTicks( QwtScaleDiv::MinorTick, minorTicks ); + + return scaleDiv; +} + +static QwtScaleDiv qwtDivideToMonths( + QDateTime &minDate, const QDateTime &maxDate, + double stepSize, int maxMinSteps ) +{ + // months are intervals with non + // equidistant ( in ms ) steps: we have to build the + // scale division manually + + int minStepDays = 0; + int minStepSize = 0.0; + + if ( maxMinSteps > 1 ) + { + if ( stepSize == 1 ) + { + if ( maxMinSteps >= 30 ) + minStepDays = 1; + else if ( maxMinSteps >= 6 ) + minStepDays = 5; + else if ( maxMinSteps >= 3 ) + minStepDays = 10; + + minStepDays = 15; + } + else + { + minStepSize = qwtDivideMajorStep( + stepSize, maxMinSteps, QwtDate::Month ); + } + } + + QList<double> majorTicks; + QList<double> mediumTicks; + QList<double> minorTicks; + + for ( QDateTime dt = minDate; + dt <= maxDate; dt = dt.addMonths( stepSize ) ) + { + if ( !dt.isValid() ) + break; + + majorTicks += QwtDate::toDouble( dt ); + + if ( minStepDays > 0 ) + { + for ( int days = minStepDays; + days < 30; days += minStepDays ) + { + const double tick = QwtDate::toDouble( dt.addDays( days ) ); + + if ( days == 15 && minStepDays != 15 ) + mediumTicks += tick; + else + minorTicks += tick; + } + } + else if ( minStepSize > 0.0 ) + { + const int numMinorSteps = qRound( stepSize / (double) minStepSize ); + + for ( int i = 1; i < numMinorSteps; i++ ) + { + const double minorValue = + QwtDate::toDouble( dt.addMonths( i * minStepSize ) ); + + if ( ( numMinorSteps % 2 == 0 ) && ( i == numMinorSteps / 2 ) ) + mediumTicks += minorValue; + else + minorTicks += minorValue; + } + } + } + + QwtScaleDiv scaleDiv; + scaleDiv.setInterval( QwtDate::toDouble( minDate ), + QwtDate::toDouble( maxDate ) ); + + scaleDiv.setTicks( QwtScaleDiv::MajorTick, majorTicks ); + scaleDiv.setTicks( QwtScaleDiv::MediumTick, mediumTicks ); + scaleDiv.setTicks( QwtScaleDiv::MinorTick, minorTicks ); + + return scaleDiv; +} + +static QwtScaleDiv qwtDivideToYears( + const QDateTime &minDate, const QDateTime &maxDate, + double stepSize, int maxMinSteps ) +{ + QList<double> majorTicks; + QList<double> mediumTicks; + QList<double> minorTicks; + + double minStepSize = 0.0; + + if ( maxMinSteps > 1 ) + { + minStepSize = qwtDivideMajorStep( + stepSize, maxMinSteps, QwtDate::Year ); + } + + int numMinorSteps = 0; + if ( minStepSize > 0.0 ) + numMinorSteps = qFloor( stepSize / minStepSize ); + + bool dateBC = minDate.date().year() < -1; + + for ( QDateTime dt = minDate; dt <= maxDate; + dt = dt.addYears( stepSize ) ) + { + if ( dateBC && dt.date().year() > 1 ) + { + // there is no year 0 in the Julian calendar + dt = dt.addYears( -1 ); + dateBC = false; + } + + if ( !dt.isValid() ) + break; + + majorTicks += QwtDate::toDouble( dt ); + + for ( int i = 1; i < numMinorSteps; i++ ) + { + QDateTime tickDate; + + const double years = qRound( i * minStepSize ); + if ( years >= INT_MAX / 12 ) + { + tickDate = dt.addYears( years ); + } + else + { + tickDate = dt.addMonths( qRound( years * 12 ) ); + } + + const bool isMedium = ( numMinorSteps > 2 ) && + ( numMinorSteps % 2 == 0 ) && ( i == numMinorSteps / 2 ); + + const double minorValue = QwtDate::toDouble( tickDate ); + if ( isMedium ) + mediumTicks += minorValue; + else + minorTicks += minorValue; + } + + if ( QwtDate::maxDate().addYears( -stepSize ) < dt.date() ) + { + break; + } + } + + QwtScaleDiv scaleDiv; + scaleDiv.setInterval( QwtDate::toDouble( minDate ), + QwtDate::toDouble( maxDate ) ); + + scaleDiv.setTicks( QwtScaleDiv::MajorTick, majorTicks ); + scaleDiv.setTicks( QwtScaleDiv::MediumTick, mediumTicks ); + scaleDiv.setTicks( QwtScaleDiv::MinorTick, minorTicks ); + + return scaleDiv; +} + +class QwtDateScaleEngine::PrivateData +{ +public: + PrivateData( Qt::TimeSpec spec ): + timeSpec( spec ), + utcOffset( 0 ), + week0Type( QwtDate::FirstThursday ), + maxWeeks( 4 ) + { + } + + Qt::TimeSpec timeSpec; + int utcOffset; + QwtDate::Week0Type week0Type; + int maxWeeks; +}; + + +/*! + \brief Constructor + + The engine is initialized to build scales for the + given time specification. It classifies intervals > 4 weeks + as >= Qt::Month. The first week of a year is defined like + for QwtDate::FirstThursday. + + \param timeSpec Time specification + + \sa setTimeSpec(), setMaxWeeks(), setWeek0Type() + */ +QwtDateScaleEngine::QwtDateScaleEngine( Qt::TimeSpec timeSpec ): + QwtLinearScaleEngine( 10 ) +{ + d_data = new PrivateData( timeSpec ); +} + +//! Destructor +QwtDateScaleEngine::~QwtDateScaleEngine() +{ + delete d_data; +} + +/*! + Set the time specification used by the engine + + \param timeSpec Time specification + \sa timeSpec(), setUtcOffset(), toDateTime() + */ +void QwtDateScaleEngine::setTimeSpec( Qt::TimeSpec timeSpec ) +{ + d_data->timeSpec = timeSpec; +} + +/*! + \return Time specification used by the engine + \sa setTimeSpec(), utcOffset(), toDateTime() + */ +Qt::TimeSpec QwtDateScaleEngine::timeSpec() const +{ + return d_data->timeSpec; +} + +/*! + Set the offset in seconds from Coordinated Universal Time + + \param seconds Offset in seconds + + \note The offset has no effect beside for the time specification + Qt::OffsetFromUTC. + + \sa QDate::utcOffset(), setTimeSpec(), toDateTime() + */ +void QwtDateScaleEngine::setUtcOffset( int seconds ) +{ + d_data->utcOffset = seconds; +} + +/*! + \return Offset in seconds from Coordinated Universal Time + \note The offset has no effect beside for the time specification + Qt::OffsetFromUTC. + + \sa QDate::setUtcOffset(), setTimeSpec(), toDateTime() + */ +int QwtDateScaleEngine::utcOffset() const +{ + return d_data->utcOffset; +} + +/*! + Sets how to identify the first week of a year. + + \param week0Type Mode how to identify the first week of a year + + \sa week0Type(), setMaxWeeks() + \note week0Type has no effect beside for intervals classified as + QwtDate::Week. + */ +void QwtDateScaleEngine::setWeek0Type( QwtDate::Week0Type week0Type ) +{ + d_data->week0Type = week0Type; +} + +/*! + \return Setting how to identify the first week of a year. + \sa setWeek0Type(), maxWeeks() + */ +QwtDate::Week0Type QwtDateScaleEngine::week0Type() const +{ + return d_data->week0Type; +} + +/*! + Set a upper limit for the number of weeks, when an interval + can be classified as Qt::Week. + + The default setting is 4 weeks. + + \param weeks Upper limit for the number of weeks + + \note In business charts a year is often devided + into weeks [1-52] + \sa maxWeeks(), setWeek0Type() + */ +void QwtDateScaleEngine::setMaxWeeks( int weeks ) +{ + d_data->maxWeeks = qMax( weeks, 0 ); +} + +/*! + \return Upper limit for the number of weeks, when an interval + can be classified as Qt::Week. + \sa setMaxWeeks(), week0Type() + */ +int QwtDateScaleEngine::maxWeeks() const +{ + return d_data->maxWeeks; +} + +/*! + Classification of a date/time interval division + + \param minDate Minimum ( = earlier ) of the interval + \param maxDate Maximum ( = later ) of the interval + \param maxSteps Maximum for the number of steps + + \return Interval classification + */ +QwtDate::IntervalType QwtDateScaleEngine::intervalType( + const QDateTime &minDate, const QDateTime &maxDate, + int maxSteps ) const +{ + const double jdMin = minDate.date().toJulianDay(); + const double jdMax = maxDate.date().toJulianDay(); + + if ( ( jdMax - jdMin ) / 365 > maxSteps ) + return QwtDate::Year; + + const int months = qwtRoundedIntervalWidth( minDate, maxDate, QwtDate::Month ); + if ( months > maxSteps * 6 ) + return QwtDate::Year; + + const int days = qwtRoundedIntervalWidth( minDate, maxDate, QwtDate::Day ); + const int weeks = qwtRoundedIntervalWidth( minDate, maxDate, QwtDate::Week ); + + if ( weeks > d_data->maxWeeks ) + { + if ( days > 4 * maxSteps * 7 ) + return QwtDate::Month; + } + + if ( days > maxSteps * 7 ) + return QwtDate::Week; + + const int hours = qwtRoundedIntervalWidth( minDate, maxDate, QwtDate::Hour ); + if ( hours > maxSteps * 24 ) + return QwtDate::Day; + + const int seconds = qwtRoundedIntervalWidth( minDate, maxDate, QwtDate::Second ); + + if ( seconds >= maxSteps * 3600 ) + return QwtDate::Hour; + + if ( seconds >= maxSteps * 60 ) + return QwtDate::Minute; + + if ( seconds >= maxSteps ) + return QwtDate::Second; + + return QwtDate::Millisecond; +} + +/*! + Align and divide an interval + + The algorithm aligns and divides the interval into steps. + + Datetime interval divisions are usually not equidistant and the + calculated stepSize can only be used as an approximation + for the steps calculated by divideScale(). + + \param maxNumSteps Max. number of steps + \param x1 First limit of the interval (In/Out) + \param x2 Second limit of the interval (In/Out) + \param stepSize Step size (Out) + + \sa QwtScaleEngine::setAttribute() +*/ +void QwtDateScaleEngine::autoScale( int maxNumSteps, + double &x1, double &x2, double &stepSize ) const +{ + stepSize = 0.0; + + QwtInterval interval( x1, x2 ); + interval = interval.normalized(); + + interval.setMinValue( interval.minValue() - lowerMargin() ); + interval.setMaxValue( interval.maxValue() + upperMargin() ); + + if ( testAttribute( QwtScaleEngine::Symmetric ) ) + interval = interval.symmetrize( reference() ); + + if ( testAttribute( QwtScaleEngine::IncludeReference ) ) + interval = interval.extend( reference() ); + + if ( interval.width() == 0.0 ) + interval = buildInterval( interval.minValue() ); + + const QDateTime from = toDateTime( interval.minValue() ); + const QDateTime to = toDateTime( interval.maxValue() ); + + if ( from.isValid() && to.isValid() ) + { + if ( maxNumSteps < 1 ) + maxNumSteps = 1; + + const QwtDate::IntervalType intvType = + intervalType( from, to, maxNumSteps ); + + const double width = qwtIntervalWidth( from, to, intvType ); + + const double stepWidth = qwtDivideScale( width, maxNumSteps, intvType ); + if ( stepWidth != 0.0 && !testAttribute( QwtScaleEngine::Floating ) ) + { + const QDateTime d1 = alignDate( from, stepWidth, intvType, false ); + const QDateTime d2 = alignDate( to, stepWidth, intvType, true ); + + interval.setMinValue( QwtDate::toDouble( d1 ) ); + interval.setMaxValue( QwtDate::toDouble( d2 ) ); + } + + stepSize = stepWidth * qwtMsecsForType( intvType ); + } + + x1 = interval.minValue(); + x2 = interval.maxValue(); + + if ( testAttribute( QwtScaleEngine::Inverted ) ) + { + qSwap( x1, x2 ); + stepSize = -stepSize; + } +} + +/*! + \brief Calculate a scale division for a date/time interval + + \param x1 First interval limit + \param x2 Second interval limit + \param maxMajorSteps Maximum for the number of major steps + \param maxMinorSteps Maximum number of minor steps + \param stepSize Step size. If stepSize == 0, the scaleEngine + calculates one. + \return Calculated scale division +*/ +QwtScaleDiv QwtDateScaleEngine::divideScale( double x1, double x2, + int maxMajorSteps, int maxMinorSteps, double stepSize ) const +{ + if ( maxMajorSteps < 1 ) + maxMajorSteps = 1; + + const double min = qMin( x1, x2 ); + const double max = qMax( x1, x2 ); + + const QDateTime from = toDateTime( min ); + const QDateTime to = toDateTime( max ); + + if ( from == to ) + return QwtScaleDiv(); + + stepSize = qAbs( stepSize ); + if ( stepSize > 0.0 ) + { + // as interval types above hours are not equidistant + // ( even days might have 23/25 hours because of daylight saving ) + // the stepSize is used as a hint only + + maxMajorSteps = qCeil( ( max - min ) / stepSize ); + } + + const QwtDate::IntervalType intvType = + intervalType( from, to, maxMajorSteps ); + + QwtScaleDiv scaleDiv; + + if ( intvType == QwtDate::Millisecond ) + { + // for milliseconds and below we can use the decimal system + scaleDiv = QwtLinearScaleEngine::divideScale( min, max, + maxMajorSteps, maxMinorSteps, stepSize ); + } + else + { + const QDateTime minDate = QwtDate::floor( from, intvType ); + const QDateTime maxDate = QwtDate::ceil( to, intvType ); + + scaleDiv = buildScaleDiv( minDate, maxDate, + maxMajorSteps, maxMinorSteps, intvType ); + + // scaleDiv has been calculated from an extended interval + // adjusted to the step size. We have to shrink it again. + + scaleDiv = scaleDiv.bounded( min, max ); + } + + if ( x1 > x2 ) + scaleDiv.invert(); + + return scaleDiv; +} + +QwtScaleDiv QwtDateScaleEngine::buildScaleDiv( + const QDateTime &minDate, const QDateTime &maxDate, + int maxMajorSteps, int maxMinorSteps, + QwtDate::IntervalType intervalType ) const +{ + // calculate the step size + const double stepSize = qwtDivideScale( + qwtIntervalWidth( minDate, maxDate, intervalType ), + maxMajorSteps, intervalType ); + + // align minDate to the step size + QDateTime dt0 = alignDate( minDate, stepSize, intervalType, false ); + if ( !dt0.isValid() ) + { + // the floored date is out of the range of a + // QDateTime - we ceil instead. + dt0 = alignDate( minDate, stepSize, intervalType, true ); + } + + QwtScaleDiv scaleDiv; + + if ( intervalType <= QwtDate::Week ) + { + scaleDiv = qwtDivideToSeconds( dt0, maxDate, + stepSize, maxMinorSteps, intervalType ); + } + else + { + if( intervalType == QwtDate::Month ) + { + scaleDiv = qwtDivideToMonths( dt0, maxDate, + stepSize, maxMinorSteps ); + } + else if ( intervalType == QwtDate::Year ) + { + scaleDiv = qwtDivideToYears( dt0, maxDate, + stepSize, maxMinorSteps ); + } + } + + + return scaleDiv; +} + +/*! + Align a date/time value for a step size + + For Qt::Day alignments there is no "natural day 0" - + instead the first day of the year is used to avoid jumping + major ticks positions when panning a scale. For other alignments + ( f.e according to the first day of the month ) alignDate() + has to be overloaded. + + \param dateTime Date/time value + \param stepSize Step size + \param intervalType Interval type + \param up When true dateTime is ceiled - otherwise it is floored + + \return Aligned date/time value + */ +QDateTime QwtDateScaleEngine::alignDate( + const QDateTime &dateTime, double stepSize, + QwtDate::IntervalType intervalType, bool up ) const +{ + // what about: (year == 1582 && month == 10 && day > 4 && day < 15) ?? + + QDateTime dt = dateTime; + + if ( dateTime.timeSpec() == Qt::OffsetFromUTC ) + { + dt.setUtcOffset( 0 ); + } + + switch( intervalType ) + { + case QwtDate::Millisecond: + { + const int ms = qwtAlignValue( + dt.time().msec(), stepSize, up ) ; + + dt = QwtDate::floor( dateTime, QwtDate::Second ); + dt = dt.addMSecs( ms ); + + break; + } + case QwtDate::Second: + { + int second = dt.time().second(); + if ( up ) + { + if ( dt.time().msec() > 0 ) + second++; + } + + const int s = qwtAlignValue( second, stepSize, up ); + + dt = QwtDate::floor( dt, QwtDate::Minute ); + dt = dt.addSecs( s ); + + break; + } + case QwtDate::Minute: + { + int minute = dt.time().minute(); + if ( up ) + { + if ( dt.time().msec() > 0 || dt.time().second() > 0 ) + minute++; + } + + const int m = qwtAlignValue( minute, stepSize, up ); + + dt = QwtDate::floor( dt, QwtDate::Hour ); + dt = dt.addSecs( m * 60 ); + + break; + } + case QwtDate::Hour: + { + int hour = dt.time().hour(); + if ( up ) + { + if ( dt.time().msec() > 0 || dt.time().second() > 0 + || dt.time().minute() > 0 ) + { + hour++; + } + } + const int h = qwtAlignValue( hour, stepSize, up ); + + dt = QwtDate::floor( dt, QwtDate::Day ); + dt = dt.addSecs( h * 3600 ); + + break; + } + case QwtDate::Day: + { + // What date do we expect f.e. from an alignment of 5 days ?? + // Aligning them to the beginning of the year avoids at least + // jumping major ticks when panning + + int day = dt.date().dayOfYear(); + if ( up ) + { + if ( dt.time() > QTime( 0, 0 ) ) + day++; + } + + const int d = qwtAlignValue( day, stepSize, up ); + + dt = QwtDate::floor( dt, QwtDate::Year ); + dt = dt.addDays( d - 1 ); + + break; + } + case QwtDate::Week: + { + const QDate date = QwtDate::dateOfWeek0( + dt.date().year(), d_data->week0Type ); + + int numWeeks = date.daysTo( dt.date() ) / 7; + if ( up ) + { + if ( dt.time() > QTime( 0, 0 ) || + date.daysTo( dt.date() ) % 7 ) + { + numWeeks++; + } + } + + const int d = qwtAlignValue( numWeeks, stepSize, up ) * 7; + + dt = QwtDate::floor( dt, QwtDate::Day ); + dt.setDate( date ); + dt = dt.addDays( d ); + + break; + } + case QwtDate::Month: + { + int month = dt.date().month(); + if ( up ) + { + if ( dt.date().day() > 1 || + dt.time() > QTime( 0, 0 ) ) + { + month++; + } + } + + const int m = qwtAlignValue( month - 1, stepSize, up ); + + dt = QwtDate::floor( dt, QwtDate::Year ); + dt = dt.addMonths( m ); + + break; + } + case QwtDate::Year: + { + int year = dateTime.date().year(); + if ( up ) + { + if ( dateTime.date().dayOfYear() > 1 || + dt.time() > QTime( 0, 0 ) ) + { + year++; + } + } + + const int y = qwtAlignValue( year, stepSize, up ); + + dt = QwtDate::floor( dt, QwtDate::Day ); + if ( y == 0 ) + { + // there is no year 0 in the Julian calendar + dt.setDate( QDate( stepSize, 1, 1 ).addYears( -stepSize ) ); + } + else + { + dt.setDate( QDate( y, 1, 1 ) ); + } + + break; + } + } + + if ( dateTime.timeSpec() == Qt::OffsetFromUTC ) + { + dt.setUtcOffset( dateTime.utcOffset() ); + } + + return dt; +} + +/*! + Translate a double value into a QDateTime object. + + For QDateTime result is bounded by QwtDate::minDate() and QwtDate::maxDate() + + \return QDateTime object initialized with timeSpec() and utcOffset(). + \sa timeSpec(), utcOffset(), QwtDate::toDateTime() + */ +QDateTime QwtDateScaleEngine::toDateTime( double value ) const +{ + QDateTime dt = QwtDate::toDateTime( value, d_data->timeSpec ); + if ( !dt.isValid() ) + { + const QDate date = ( value <= 0.0 ) + ? QwtDate::minDate() : QwtDate::maxDate(); + + dt = QDateTime( date, QTime( 0, 0 ), d_data->timeSpec ); + } + + if ( d_data->timeSpec == Qt::OffsetFromUTC ) + { + dt = dt.addSecs( d_data->utcOffset ); + dt.setUtcOffset( d_data->utcOffset ); + } + + return dt; +} + diff --git a/libs/qwt/qwt_date_scale_engine.h b/libs/qwt/qwt_date_scale_engine.h new file mode 100644 index 0000000000..db1d0f1342 --- /dev/null +++ b/libs/qwt/qwt_date_scale_engine.h @@ -0,0 +1,77 @@ +#ifndef _QWT_DATE_SCALE_ENGINE_H_ +#define _QWT_DATE_SCALE_ENGINE_H_ 1 + +#include "qwt_date.h" +#include "qwt_scale_engine.h" + +/*! + \brief A scale engine for date/time values + + QwtDateScaleEngine builds scales from a time intervals. + Together with QwtDateScaleDraw it can be used for + axes according to date/time values. + + Years, months, weeks, days, hours and minutes are organized + in steps with non constant intervals. QwtDateScaleEngine + classifies intervals and aligns the boundaries and tick positions + according to this classification. + + QwtDateScaleEngine supports representations depending + on Qt::TimeSpec specifications. The valid range for scales + is limited by the range of QDateTime, that differs + between Qt4 and Qt5. + + Datetime values are expected as the number of milliseconds since + 1970-01-01T00:00:00 Universal Coordinated Time - also known + as "The Epoch", that can be converted to QDateTime using + QwtDate::toDateTime(). + + \sa QwtDate, QwtPlot::setAxisScaleEngine(), + QwtAbstractScale::setScaleEngine() +*/ +class QWT_EXPORT QwtDateScaleEngine: public QwtLinearScaleEngine +{ +public: + QwtDateScaleEngine( Qt::TimeSpec = Qt::LocalTime ); + virtual ~QwtDateScaleEngine(); + + void setTimeSpec( Qt::TimeSpec ); + Qt::TimeSpec timeSpec() const; + + void setUtcOffset( int seconds ); + int utcOffset() const; + + void setWeek0Type( QwtDate::Week0Type ); + QwtDate::Week0Type week0Type() const; + + void setMaxWeeks( int ); + int maxWeeks() const; + + virtual void autoScale( int maxNumSteps, + double &x1, double &x2, double &stepSize ) const; + + virtual QwtScaleDiv divideScale( + double x1, double x2, + int maxMajorSteps, int maxMinorSteps, + double stepSize = 0.0 ) const; + + virtual QwtDate::IntervalType intervalType( + const QDateTime &, const QDateTime &, int maxSteps ) const; + + QDateTime toDateTime( double ) const; + +protected: + virtual QDateTime alignDate( const QDateTime &, double stepSize, + QwtDate::IntervalType, bool up ) const; + +private: + QwtScaleDiv buildScaleDiv( const QDateTime &, const QDateTime &, + int maxMajorSteps, int maxMinorSteps, + QwtDate::IntervalType ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_dial.cpp b/libs/qwt/qwt_dial.cpp index 35f77b022b..1440eb14a4 100644 --- a/libs/qwt/qwt_dial.cpp +++ b/libs/qwt/qwt_dial.cpp @@ -7,45 +7,93 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <math.h> -#include <qpainter.h> -#if QT_VERSION >= 0x040000 -#include <qbitmap.h> -#include <qpalette.h> -#endif -#include <qpixmap.h> -#include <qevent.h> +#include "qwt_dial.h" +#include "qwt_dial_needle.h" #include "qwt_math.h" #include "qwt_scale_engine.h" #include "qwt_scale_map.h" -#include "qwt_paint_buffer.h" +#include "qwt_round_scale_draw.h" #include "qwt_painter.h" -#include "qwt_dial_needle.h" -#include "qwt_dial.h" +#include <qpainter.h> +#include <qpalette.h> +#include <qpixmap.h> +#include <qevent.h> +#include <qalgorithms.h> +#include <qmath.h> +#include <qstyle.h> +#include <qstyleoption.h> +#include <qapplication.h> + +static inline double qwtAngleDist( double a1, double a2 ) +{ + double dist = qAbs( a2 - a1 ); + if ( dist > 360.0 ) + dist -= 360.0; + + return dist; +} + +static inline bool qwtIsOnArc( double angle, double min, double max ) +{ + if ( min < max ) + { + return ( angle >= min ) && ( angle <= max ); + } + else + { + return ( angle >= min ) || ( angle <= max ); + } +} + +static inline double qwtBoundedAngle( double min, double angle, double max ) +{ + double from = qwtNormalizeDegrees( min ); + double to = qwtNormalizeDegrees( max ); + + double a; + + if ( qwtIsOnArc( angle, from, to ) ) + { + a = angle; + if ( a < min ) + a += 360.0; + } + else + { + if ( qwtAngleDist( angle, from ) < + qwtAngleDist( angle, to ) ) + { + a = min; + } + else + { + a = max; + } + } + + return a; +} class QwtDial::PrivateData { public: PrivateData(): - visibleBackground(true), - frameShadow(Sunken), - lineWidth(0), - mode(RotateNeedle), - origin(90.0), - minScaleArc(0.0), - maxScaleArc(0.0), - scaleDraw(0), - maxMajIntv(36), - maxMinIntv(10), - scaleStep(0.0), - needle(0) { + frameShadow( Sunken ), + lineWidth( 0 ), + mode( RotateNeedle ), + origin( 90.0 ), + minScaleArc( 0.0 ), + maxScaleArc( 0.0 ), + needle( NULL ), + arcOffset( 0.0 ), + mouseOffset( 0.0 ) + { } - ~PrivateData() { - delete scaleDraw; + ~PrivateData() + { delete needle; } - bool visibleBackground; Shadow frameShadow; int lineWidth; @@ -55,177 +103,79 @@ public: double minScaleArc; double maxScaleArc; - QwtDialScaleDraw *scaleDraw; - int maxMajIntv; - int maxMinIntv; - double scaleStep; - + double scalePenWidth; QwtDialNeedle *needle; - static double previousDir; -}; - -double QwtDial::PrivateData::previousDir = -1.0; - -/*! - Constructor - - \param parent Parent dial widget -*/ -QwtDialScaleDraw::QwtDialScaleDraw(QwtDial *parent): - d_parent(parent), - d_penWidth(1) -{ -} - -/*! - Set the pen width used for painting the scale - - \param penWidth Pen width - \sa penWidth(), QwtDial::drawScale() -*/ - -void QwtDialScaleDraw::setPenWidth(uint penWidth) -{ - d_penWidth = penWidth; -} + double arcOffset; + double mouseOffset; -/*! - \return Pen width used for painting the scale - \sa setPenWidth, QwtDial::drawScale() -*/ -uint QwtDialScaleDraw::penWidth() const -{ - return d_penWidth; -} - -/*! - Call QwtDial::scaleLabel of the parent dial widget. - - \param value Value to display - - \sa QwtDial::scaleLabel -*/ -QwtText QwtDialScaleDraw::label(double value) const -{ - if ( d_parent == NULL ) - return QwtRoundScaleDraw::label(value); - - return d_parent->scaleLabel(value); -} + QPixmap pixmapCache; +}; /*! \brief Constructor \param parent Parent widget - Create a dial widget with no scale and no needle. - The default origin is 90.0 with no valid value. It accepts - mouse and keyboard inputs and has no step size. The default mode - is QwtDial::RotateNeedle. -*/ + Create a dial widget with no needle. The scale is initialized + to [ 0.0, 360.0 ] and 360 steps ( QwtAbstractSlider::setTotalSteps() ). + The origin of the scale is at 90°, -QwtDial::QwtDial(QWidget* parent): - QwtAbstractSlider(Qt::Horizontal, parent) -{ - initDial(); -} + The value is set to 0.0. -#if QT_VERSION < 0x040000 -/*! - \brief Constructor - \param parent Parent widget - \param name Object name - - Create a dial widget with no scale and no needle. - The default origin is 90.0 with no valid value. It accepts - mouse and keyboard inputs and has no step size. The default mode - is QwtDial::RotateNeedle. + The default mode is QwtDial::RotateNeedle. */ -QwtDial::QwtDial(QWidget* parent, const char *name): - QwtAbstractSlider(Qt::Horizontal, parent) -{ - setName(name); - initDial(); -} -#endif - -void QwtDial::initDial() +QwtDial::QwtDial( QWidget* parent ): + QwtAbstractSlider( parent ) { d_data = new PrivateData; -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#endif - -#if QT_VERSION >= 0x040000 - using namespace Qt; -#endif - setFocusPolicy(TabFocus); + setFocusPolicy( Qt::TabFocus ); QPalette p = palette(); - for ( int i = 0; i < QPalette::NColorGroups; i++ ) { - const QPalette::ColorGroup cg = (QPalette::ColorGroup)i; + for ( int i = 0; i < QPalette::NColorGroups; i++ ) + { + const QPalette::ColorGroup colorGroup = + static_cast<QPalette::ColorGroup>( i ); // Base: background color of the circle inside the frame. - // Foreground: background color of the circle inside the scale - -#if QT_VERSION < 0x040000 - p.setColor(cg, QColorGroup::Foreground, - p.color(cg, QColorGroup::Base)); -#else - p.setColor(cg, QPalette::Foreground, - p.color(cg, QPalette::Base)); -#endif + // WindowText: background color of the circle inside the scale + + p.setColor( colorGroup, QPalette::WindowText, + p.color( colorGroup, QPalette::Base ) ); } - setPalette(p); + setPalette( p ); - d_data->scaleDraw = new QwtDialScaleDraw(this); - d_data->scaleDraw->setRadius(0); + QwtRoundScaleDraw* scaleDraw = new QwtRoundScaleDraw(); + scaleDraw->setRadius( 0 ); - setScaleArc(0.0, 360.0); // scale as a full circle - setRange(0.0, 360.0, 1.0, 10); // degrees as deafult -} + setScaleDraw( scaleDraw ); -//! Destructor -QwtDial::~QwtDial() -{ - delete d_data; -} + setScaleArc( 0.0, 360.0 ); // scale as a full circle -/*! - Show/Hide the area outside of the frame - \param show Show if true, hide if false + setScaleMaxMajor( 10 ); + setScaleMaxMinor( 5 ); - \sa hasVisibleBackground(), setMask() - \warning When QwtDial is a toplevel widget the window - border might disappear too. -*/ -void QwtDial::showBackground(bool show) -{ - if ( d_data->visibleBackground != show ) { - d_data->visibleBackground = show; - updateMask(); - } + setValue( 0.0 ); } -/*! - true when the area outside of the frame is visible - - \sa showBackground(), setMask() -*/ -bool QwtDial::hasVisibleBackground() const +//! Destructor +QwtDial::~QwtDial() { - return d_data->visibleBackground; + delete d_data; } /*! Sets the frame shadow value from the frame style. + \param shadow Frame shadow \sa setLineWidth(), QFrame::setFrameShadow() */ -void QwtDial::setFrameShadow(Shadow shadow) +void QwtDial::setFrameShadow( Shadow shadow ) { - if ( shadow != d_data->frameShadow ) { + if ( shadow != d_data->frameShadow ) + { + invalidateCache(); + d_data->frameShadow = shadow; if ( lineWidth() > 0 ) update(); @@ -234,7 +184,7 @@ void QwtDial::setFrameShadow(Shadow shadow) /*! \return Frame shadow - /sa setFrameShadow(), lineWidth(), QFrame::frameShadow + /sa setFrameShadow(), lineWidth(), QFrame::frameShadow() */ QwtDial::Shadow QwtDial::frameShadow() const { @@ -242,17 +192,20 @@ QwtDial::Shadow QwtDial::frameShadow() const } /*! - Sets the line width + Sets the line width of the frame \param lineWidth Line width \sa setFrameShadow() */ -void QwtDial::setLineWidth(int lineWidth) +void QwtDial::setLineWidth( int lineWidth ) { if ( lineWidth < 0 ) lineWidth = 0; - if ( d_data->lineWidth != lineWidth ) { + if ( d_data->lineWidth != lineWidth ) + { + invalidateCache(); + d_data->lineWidth = lineWidth; update(); } @@ -268,65 +221,56 @@ int QwtDial::lineWidth() const } /*! - \return bounding rect of the circle inside the frame - \sa setLineWidth(), scaleContentsRect(), boundingRect() + \return bounding rectangle of the circle inside the frame + \sa setLineWidth(), scaleInnerRect(), boundingRect() */ -QRect QwtDial::contentsRect() const +QRect QwtDial::innerRect() const { const int lw = lineWidth(); - - QRect r = boundingRect(); - if ( lw > 0 ) { - r.setRect(r.x() + lw, r.y() + lw, - r.width() - 2 * lw, r.height() - 2 * lw); - } - return r; + return boundingRect().adjusted( lw, lw, -lw, -lw ); } /*! - \return bounding rect of the dial including the frame - \sa setLineWidth(), scaleContentsRect(), contentsRect() + \return bounding rectangle of the dial including the frame + \sa setLineWidth(), scaleInnerRect(), innerRect() */ QRect QwtDial::boundingRect() const { - const int radius = qwtMin(width(), height()) / 2; + const QRect cr = contentsRect(); + + const double dim = qMin( cr.width(), cr.height() ); + + QRect inner( 0, 0, dim, dim ); + inner.moveCenter( cr.center() ); - QRect r(0, 0, 2 * radius, 2 * radius); - r.moveCenter(rect().center()); - return r; + return inner; } /*! - \return rect inside the scale - \sa setLineWidth(), boundingRect(), contentsRect() + \return rectangle inside the scale + \sa setLineWidth(), boundingRect(), innerRect() */ -QRect QwtDial::scaleContentsRect() const +QRect QwtDial::scaleInnerRect() const { -#if QT_VERSION < 0x040000 - const QPen scalePen(colorGroup().text(), 0, Qt::NoPen); -#else - const QPen scalePen(palette().text(), 0, Qt::NoPen); -#endif - - int scaleDist = 0; - if ( d_data->scaleDraw ) { - scaleDist = d_data->scaleDraw->extent(scalePen, font()); + QRect rect = innerRect(); + + const QwtAbstractScaleDraw *sd = scaleDraw(); + if ( sd ) + { + int scaleDist = qCeil( sd->extent( font() ) ); scaleDist++; // margin + + rect.adjust( scaleDist, scaleDist, -scaleDist, -scaleDist ); } - const QRect rect = contentsRect(); - return QRect(rect.x() + scaleDist, rect.y() + scaleDist, - rect.width() - 2 * scaleDist, rect.height() - 2 * scaleDist); + return rect; } /*! - \brief Change the mode of the meter. + \brief Change the mode of the dial. \param mode New mode - The value of the meter is indicated by the difference - between north of the scale and the direction of the needle. - In case of QwtDial::RotateNeedle north is pointing - to the origin() and the needle is rotating, in case of + In case of QwtDial::RotateNeedle the needle is rotating, in case of QwtDial::RotateScale, the needle points to origin() and the scale is rotating. @@ -334,26 +278,19 @@ QRect QwtDial::scaleContentsRect() const \sa mode(), setValue(), setOrigin() */ -void QwtDial::setMode(Mode mode) +void QwtDial::setMode( Mode mode ) { - if ( mode != d_data->mode ) { + if ( mode != d_data->mode ) + { + invalidateCache(); + d_data->mode = mode; - update(); + sliderChange(); } } /*! - \return mode of the dial. - - The value of the dial is indicated by the difference - between the origin and the direction of the needle. - In case of QwtDial::RotateNeedle the scale arc is fixed - to the origin() and the needle is rotating, in case of - QwtDial::RotateScale, the needle points to origin() - and the scale is rotating. - - The default mode is QwtDial::RotateNeedle. - + \return Mode of the dial. \sa setMode(), origin(), setScaleArc(), value() */ QwtDial::Mode QwtDial::mode() const @@ -362,115 +299,72 @@ QwtDial::Mode QwtDial::mode() const } /*! - Sets whether it is possible to step the value from the highest value to - the lowest value and vice versa to on. - - \param wrapping en/disables wrapping - - \sa wrapping(), QwtDoubleRange::periodic() - \note The meaning of wrapping is like the wrapping property of QSpinBox, - but not like it is used in QDial. -*/ -void QwtDial::setWrapping(bool wrapping) + Invalidate the internal caches used to speed up repainting + */ +void QwtDial::invalidateCache() { - setPeriodic(wrapping); + d_data->pixmapCache = QPixmap(); } /*! - wrapping() holds whether it is possible to step the value from the - highest value to the lowest value and vice versa. - - \sa setWrapping(), QwtDoubleRange::setPeriodic() - \note The meaning of wrapping is like the wrapping property of QSpinBox, - but not like it is used in QDial. + Paint the dial + \param event Paint event */ -bool QwtDial::wrapping() const +void QwtDial::paintEvent( QPaintEvent *event ) { - return periodic(); -} + QPainter painter( this ); + painter.setClipRegion( event->region() ); -/*! - Resize the dial widget - \param e Resize event -*/ -void QwtDial::resizeEvent(QResizeEvent *e) -{ - QWidget::resizeEvent(e); + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); - if ( !hasVisibleBackground() ) - updateMask(); -} + if ( d_data->mode == QwtDial::RotateScale ) + { + painter.save(); + painter.setRenderHint( QPainter::Antialiasing, true ); -/*! - Paint the dial - \param e Paint event -*/ -void QwtDial::paintEvent(QPaintEvent *e) -{ - const QRect &ur = e->rect(); - if ( ur.isValid() ) { -#if QT_VERSION < 0x040000 - QwtPaintBuffer paintBuffer(this, ur); - QPainter &painter = *paintBuffer.painter(); -#else - QPainter painter(this); - painter.setRenderHint(QPainter::Antialiasing, true); -#endif + drawContents( &painter ); - painter.save(); - drawContents(&painter); painter.restore(); + } - painter.save(); - drawFrame(&painter); - painter.restore(); + const QRect r = contentsRect(); + if ( r.size() != d_data->pixmapCache.size() ) + { + d_data->pixmapCache = QwtPainter::backingStore( this, r.size() ); + d_data->pixmapCache.fill( Qt::transparent ); + + QPainter p( &d_data->pixmapCache ); + p.setRenderHint( QPainter::Antialiasing, true ); + p.translate( -r.topLeft() ); + + if ( d_data->mode != QwtDial::RotateScale ) + drawContents( &p ); - if ( hasFocus() ) - drawFocusIndicator(&painter); + if ( lineWidth() > 0 ) + drawFrame( &p ); + + if ( d_data->mode != QwtDial::RotateNeedle ) + drawNeedle( &p ); } + + painter.drawPixmap( r.topLeft(), d_data->pixmapCache ); + + if ( d_data->mode == QwtDial::RotateNeedle ) + drawNeedle( &painter ); + + if ( hasFocus() ) + drawFocusIndicator( &painter ); } /*! - Draw a dotted round circle, if !isReadOnly() - + Draw the focus indicator \param painter Painter */ -void QwtDial::drawFocusIndicator(QPainter *painter) const +void QwtDial::drawFocusIndicator( QPainter *painter ) const { - if ( !isReadOnly() ) { - QRect focusRect = contentsRect(); - - const int margin = 2; - focusRect.setRect( - focusRect.x() + margin, - focusRect.y() + margin, - focusRect.width() - 2 * margin, - focusRect.height() - 2 * margin); - -#if QT_VERSION < 0x040000 - QColor color = colorGroup().color(QColorGroup::Base); -#else - QColor color = palette().color(QPalette::Base); -#endif - if (color.isValid()) { - const QColor gray(Qt::gray); - - int h, s, v; -#if QT_VERSION < 0x040000 - color.hsv(&h, &s, &v); -#else - color.getHsv(&h, &s, &v); -#endif - color = (v > 128) ? gray.dark(120) : gray.light(120); - } else - color = Qt::darkGray; - - painter->save(); - painter->setBrush(Qt::NoBrush); - painter->setPen(QPen(color, 0, Qt::DotLine)); - painter->drawEllipse(focusRect); - painter->restore(); - } + QwtPainter::drawFocusRect( painter, this, boundingRect() ); } /*! @@ -479,160 +373,60 @@ void QwtDial::drawFocusIndicator(QPainter *painter) const \param painter Painter \sa lineWidth(), frameShadow() */ -void QwtDial::drawFrame(QPainter *painter) +void QwtDial::drawFrame( QPainter *painter ) { - const int lw = lineWidth(); - const int off = (lw + 1) % 2; - - QRect r = boundingRect(); - r.setRect(r.x() + lw / 2 - off, r.y() + lw / 2 - off, - r.width() - lw + off + 1, r.height() - lw + off + 1); -#if QT_VERSION >= 0x040000 -#ifdef __GNUC__ -#endif - r.setX(r.x() + 1); - r.setY(r.y() + 1); - r.setWidth(r.width() - 2); - r.setHeight(r.height() - 2); -#endif - - if ( lw > 0 ) { - switch(d_data->frameShadow) { - case QwtDial::Raised: -#if QT_VERSION < 0x040000 - QwtPainter::drawRoundFrame(painter, r, - lw, colorGroup(), false); -#else - QwtPainter::drawRoundFrame(painter, r, - lw, palette(), false); -#endif - break; - case QwtDial::Sunken: -#if QT_VERSION < 0x040000 - QwtPainter::drawRoundFrame(painter, r, - lw, colorGroup(), true); -#else - QwtPainter::drawRoundFrame(painter, r, - lw, palette(), true); -#endif - break; - default: { // Plain - painter->save(); - painter->setPen(QPen(Qt::black, lw)); - painter->setBrush(Qt::NoBrush); - painter->drawEllipse(r); - painter->restore(); - } - } - } + QwtPainter::drawRoundFrame( painter, boundingRect(), + palette(), lineWidth(), d_data->frameShadow ); } /*! \brief Draw the contents inside the frame - QColorGroup::Background is the background color outside of the frame. - QColorGroup::Base is the background color inside the frame. - QColorGroup::Foreground is the background color inside the scale. + QPalette::Window is the background color outside of the frame. + QPalette::Base is the background color inside the frame. + QPalette::WindowText is the background color inside the scale. \param painter Painter - \sa boundingRect(), contentsRect(), - scaleContentsRect(), QWidget::setPalette + + \sa boundingRect(), innerRect(), + scaleInnerRect(), QWidget::setPalette() */ -void QwtDial::drawContents(QPainter *painter) const +void QwtDial::drawContents( QPainter *painter ) const { -#if QT_VERSION < 0x040000 - if ( backgroundMode() == Qt::NoBackground || - colorGroup().brush(QColorGroup::Base) != - colorGroup().brush(QColorGroup::Background) ) -#else - if ( testAttribute(Qt::WA_NoSystemBackground) || - palette().brush(QPalette::Base) != - palette().brush(QPalette::Background) ) -#endif + if ( testAttribute( Qt::WA_NoSystemBackground ) || + palette().brush( QPalette::Base ) != + palette().brush( QPalette::Window ) ) { - - const QRect br = boundingRect(); + const QRectF br = boundingRect(); painter->save(); - painter->setPen(Qt::NoPen); - -#if QT_VERSION < 0x040000 - painter->setBrush(colorGroup().brush(QColorGroup::Base)); -#else - painter->setBrush(palette().brush(QPalette::Base)); -#endif - - painter->drawEllipse(br); + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().brush( QPalette::Base ) ); + painter->drawEllipse( br ); painter->restore(); } - - const QRect insideScaleRect = scaleContentsRect(); -#if QT_VERSION < 0x040000 - if ( colorGroup().brush(QColorGroup::Foreground) != - colorGroup().brush(QColorGroup::Base) ) -#else - if ( palette().brush(QPalette::Foreground) != - palette().brush(QPalette::Base) ) -#endif + const QRectF insideScaleRect = scaleInnerRect(); + if ( palette().brush( QPalette::WindowText ) != + palette().brush( QPalette::Base ) ) { painter->save(); - painter->setPen(Qt::NoPen); - -#if QT_VERSION < 0x040000 - painter->setBrush(colorGroup().brush(QColorGroup::Foreground)); -#else - painter->setBrush(palette().brush(QPalette::Foreground)); -#endif - - painter->drawEllipse(insideScaleRect.x() - 1, insideScaleRect.y() - 1, - insideScaleRect.width(), insideScaleRect.height() ); - + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().brush( QPalette::WindowText ) ); + painter->drawEllipse( insideScaleRect ); painter->restore(); } - const QPoint center = insideScaleRect.center(); - const int radius = insideScaleRect.width() / 2; + const QPointF center = insideScaleRect.center(); + const double radius = 0.5 * insideScaleRect.width(); painter->save(); - drawScaleContents(painter, center, radius); + drawScale( painter, center, radius ); painter->restore(); - double direction = d_data->origin; - - if (isValid()) { - direction = d_data->origin + d_data->minScaleArc; - if ( maxValue() > minValue() && d_data->maxScaleArc > d_data->minScaleArc ) { - const double ratio = - (value() - minValue()) / (maxValue() - minValue()); - direction += ratio * (d_data->maxScaleArc - d_data->minScaleArc); - } - - if ( direction >= 360.0 ) - direction -= 360.0; - } - - double origin = d_data->origin; - if ( mode() == RotateScale ) { - origin -= direction - d_data->origin; - direction = d_data->origin; - } - painter->save(); - drawScale(painter, center, radius, origin, d_data->minScaleArc, d_data->maxScaleArc); + drawScaleContents( painter, center, radius ); painter->restore(); - - if ( isValid() ) { - QPalette::ColorGroup cg; - if ( isEnabled() ) - cg = hasFocus() ? QPalette::Active : QPalette::Inactive; - else - cg = QPalette::Disabled; - - painter->save(); - drawNeedle(painter, center, radius, direction, cg); - painter->restore(); - } } /*! @@ -642,98 +436,96 @@ void QwtDial::drawContents(QPainter *painter) const \param center Center of the dial \param radius Length for the needle \param direction Direction of the needle in degrees, counter clockwise - \param cg ColorGroup + \param colorGroup ColorGroup */ -void QwtDial::drawNeedle(QPainter *painter, const QPoint ¢er, - int radius, double direction, QPalette::ColorGroup cg) const +void QwtDial::drawNeedle( QPainter *painter, const QPointF ¢er, + double radius, double direction, QPalette::ColorGroup colorGroup ) const { - if ( d_data->needle ) { + if ( d_data->needle ) + { direction = 360.0 - direction; // counter clockwise - d_data->needle->draw(painter, center, radius, direction, cg); + d_data->needle->draw( painter, center, radius, direction, colorGroup ); } } +void QwtDial::drawNeedle( QPainter *painter ) const +{ + if ( !isValid() ) + return; + + QPalette::ColorGroup colorGroup; + if ( isEnabled() ) + colorGroup = hasFocus() ? QPalette::Active : QPalette::Inactive; + else + colorGroup = QPalette::Disabled; + + const QRectF sr = scaleInnerRect(); + + painter->save(); + painter->setRenderHint( QPainter::Antialiasing, true ); + drawNeedle( painter, sr.center(), 0.5 * sr.width(), + transform( value() ) + 270.0, colorGroup ); + painter->restore(); +} + /*! Draw the scale \param painter Painter \param center Center of the dial \param radius Radius of the scale - \param origin Origin of the scale - \param minArc Minimum of the arc - \param maxArc Minimum of the arc - - \sa QwtAbstractScaleDraw::setAngleRange */ -void QwtDial::drawScale(QPainter *painter, const QPoint ¢er, - int radius, double origin, double minArc, double maxArc) const +void QwtDial::drawScale( QPainter *painter, + const QPointF ¢er, double radius ) const { - if ( d_data->scaleDraw == NULL ) + QwtRoundScaleDraw *sd = const_cast<QwtRoundScaleDraw *>( scaleDraw() ); + if ( sd == NULL ) return; - origin -= 270.0; // hardcoded origin of QwtScaleDraw - - double angle = maxArc - minArc; - if ( angle > 360.0 ) - angle = fmod(angle, 360.0); - - minArc += origin; - if ( minArc < -360.0 ) - minArc = fmod(minArc, 360.0); + sd->setRadius( radius ); + sd->moveCenter( center ); - maxArc = minArc + angle; - if ( maxArc > 360.0 ) { - // QwtAbstractScaleDraw::setAngleRange accepts only values - // in the range [-360.0..360.0] - minArc -= 360.0; - maxArc -= 360.0; - } - - painter->setFont(font()); - - d_data->scaleDraw->setAngleRange(minArc, maxArc); - d_data->scaleDraw->setRadius(radius); - d_data->scaleDraw->moveCenter(center); - -#if QT_VERSION < 0x040000 - QColorGroup cg = colorGroup(); - - const QColor textColor = cg.color(QColorGroup::Text); - cg.setColor(QColorGroup::Foreground, textColor); - painter->setPen(QPen(textColor, d_data->scaleDraw->penWidth())); - - d_data->scaleDraw->draw(painter, cg); -#else QPalette pal = palette(); - const QColor textColor = pal.color(QPalette::Text); - pal.setColor(QPalette::Foreground, textColor); //ticks, backbone + const QColor textColor = pal.color( QPalette::Text ); + pal.setColor( QPalette::WindowText, textColor ); // ticks, backbone - painter->setPen(QPen(textColor, d_data->scaleDraw->penWidth())); + painter->setFont( font() ); + painter->setPen( QPen( textColor, sd->penWidth() ) ); - d_data->scaleDraw->draw(painter, pal); -#endif + painter->setBrush( Qt::red ); + sd->draw( painter, pal ); } -void QwtDial::drawScaleContents(QPainter *, - const QPoint &, int) const +/*! + Draw the contents inside the scale + + Paints nothing. + + \param painter Painter + \param center Center of the contents circle + \param radius Radius of the contents circle +*/ +void QwtDial::drawScaleContents( QPainter *painter, + const QPointF ¢er, double radius ) const { - // empty default implementation + Q_UNUSED(painter); + Q_UNUSED(center); + Q_UNUSED(radius); } /*! Set a needle for the dial - Qwt is missing a set of good looking needles. - Contributions are very welcome. - \param needle Needle + \warning The needle will be deleted, when a different needle is - set or in ~QwtDial() + set or in ~QwtDial() */ -void QwtDial::setNeedle(QwtDialNeedle *needle) +void QwtDial::setNeedle( QwtDialNeedle *needle ) { - if ( needle != d_data->needle ) { + if ( needle != d_data->needle ) + { if ( d_data->needle ) delete d_data->needle; @@ -760,142 +552,101 @@ QwtDialNeedle *QwtDial::needle() return d_data->needle; } -//! QwtDoubleRange update hook -void QwtDial::rangeChange() +//! \return the scale draw +QwtRoundScaleDraw *QwtDial::scaleDraw() { - updateScale(); + return static_cast<QwtRoundScaleDraw *>( abstractScaleDraw() ); } -/*! - Update the scale with the current attributes - \sa setScale() -*/ -void QwtDial::updateScale() +//! \return the scale draw +const QwtRoundScaleDraw *QwtDial::scaleDraw() const { - if ( d_data->scaleDraw ) { - QwtLinearScaleEngine scaleEngine; - - const QwtScaleDiv scaleDiv = scaleEngine.divideScale( - minValue(), maxValue(), - d_data->maxMajIntv, d_data->maxMinIntv, d_data->scaleStep); - - d_data->scaleDraw->setTransformation(scaleEngine.transformation()); - d_data->scaleDraw->setScaleDiv(scaleDiv); - } -} - -//! Return the scale draw -QwtDialScaleDraw *QwtDial::scaleDraw() -{ - return d_data->scaleDraw; -} - -//! Return the scale draw -const QwtDialScaleDraw *QwtDial::scaleDraw() const -{ - return d_data->scaleDraw; + return static_cast<const QwtRoundScaleDraw *>( abstractScaleDraw() ); } /*! Set an individual scale draw + The motivation for setting a scale draw is often + to overload QwtRoundScaleDraw::label() to return + individual tick labels. + \param scaleDraw Scale draw \warning The previous scale draw is deleted */ -void QwtDial::setScaleDraw(QwtDialScaleDraw *scaleDraw) +void QwtDial::setScaleDraw( QwtRoundScaleDraw *scaleDraw ) { - if ( scaleDraw != d_data->scaleDraw ) { - if ( d_data->scaleDraw ) - delete d_data->scaleDraw; - - d_data->scaleDraw = scaleDraw; - updateScale(); - update(); - } + setAbstractScaleDraw( scaleDraw ); + sliderChange(); } /*! - Change the intervals of the scale - \sa QwtAbstractScaleDraw::setScale -*/ -void QwtDial::setScale(int maxMajIntv, int maxMinIntv, double step) -{ - d_data->maxMajIntv = maxMajIntv; - d_data->maxMinIntv = maxMinIntv; - d_data->scaleStep = step; + Change the arc of the scale - updateScale(); -} + \param minArc Lower limit + \param maxArc Upper limit -/*! - A wrapper method for accessing the scale draw. - - - options == 0\n - No visible scale: setScaleDraw(NULL) - - options & ScaleBackbone\n - En/disable the backbone of the scale. - - options & ScaleTicks\n - En/disable the ticks of the scale. - - options & ScaleLabel\n - En/disable scale labels - - \sa QwtAbstractScaleDraw::enableComponent + \sa minScaleArc(), maxScaleArc() */ -void QwtDial::setScaleOptions(int options) +void QwtDial::setScaleArc( double minArc, double maxArc ) { - if ( options == 0 ) - setScaleDraw(NULL); - - QwtDialScaleDraw *sd = d_data->scaleDraw; - if ( sd == NULL ) - return; + if ( minArc != 360.0 && minArc != -360.0 ) + minArc = ::fmod( minArc, 360.0 ); + if ( maxArc != 360.0 && maxArc != -360.0 ) + maxArc = ::fmod( maxArc, 360.0 ); - sd->enableComponent(QwtAbstractScaleDraw::Backbone, - options & ScaleBackbone); + double minScaleArc = qMin( minArc, maxArc ); + double maxScaleArc = qMax( minArc, maxArc ); - sd->enableComponent(QwtAbstractScaleDraw::Ticks, - options & ScaleTicks); + if ( maxScaleArc - minScaleArc > 360.0 ) + maxScaleArc = minScaleArc + 360.0; - sd->enableComponent(QwtAbstractScaleDraw::Labels, - options & ScaleLabel); -} + if ( ( minScaleArc != d_data->minScaleArc ) || + ( maxScaleArc != d_data->maxScaleArc ) ) + { + d_data->minScaleArc = minScaleArc; + d_data->maxScaleArc = maxScaleArc; -//! See: QwtAbstractScaleDraw::setTickLength, QwtDialScaleDraw::setPenWidth -void QwtDial::setScaleTicks(int minLen, int medLen, - int majLen, int penWidth) -{ - QwtDialScaleDraw *sd = d_data->scaleDraw; - if ( sd ) { - sd->setTickLength(QwtScaleDiv::MinorTick, minLen); - sd->setTickLength(QwtScaleDiv::MediumTick, medLen); - sd->setTickLength(QwtScaleDiv::MajorTick, majLen); - sd->setPenWidth(penWidth); + invalidateCache(); + sliderChange(); } } -/*! - Find the label for a value +/*! + Set the lower limit for the scale arc - \param value Value - \return label -*/ -QwtText QwtDial::scaleLabel(double value) const + \param min Lower limit of the scale arc + \sa setScaleArc(), setMaxScaleArc() + */ +void QwtDial::setMinScaleArc( double min ) { -#if 1 - if ( value == -0 ) - value = 0; -#endif - - return QString::number(value); + setScaleArc( min, d_data->maxScaleArc ); } -//! \return Lower limit of the scale arc +/*! + \return Lower limit of the scale arc + \sa setScaleArc() +*/ double QwtDial::minScaleArc() const { return d_data->minScaleArc; } -//! \return Upper limit of the scale arc +/*! + Set the upper limit for the scale arc + + \param max Upper limit of the scale arc + \sa setScaleArc(), setMinScaleArc() + */ +void QwtDial::setMaxScaleArc( double max ) +{ + setScaleArc( d_data->minScaleArc, max ); +} + +/*! + \return Upper limit of the scale arc + \sa setScaleArc() +*/ double QwtDial::maxScaleArc() const { return d_data->maxScaleArc; @@ -909,10 +660,12 @@ double QwtDial::maxScaleArc() const \param origin New origin \sa origin() */ -void QwtDial::setOrigin(double origin) +void QwtDial::setOrigin( double origin ) { + invalidateCache(); + d_data->origin = origin; - update(); + sliderChange(); } /*! @@ -926,266 +679,194 @@ double QwtDial::origin() const return d_data->origin; } -/*! - Change the arc of the scale - - \param minArc Lower limit - \param maxArc Upper limit -*/ -void QwtDial::setScaleArc(double minArc, double maxArc) -{ - if ( minArc != 360.0 && minArc != -360.0 ) - minArc = fmod(minArc, 360.0); - if ( maxArc != 360.0 && maxArc != -360.0 ) - maxArc = fmod(maxArc, 360.0); - - d_data->minScaleArc = qwtMin(minArc, maxArc); - d_data->maxScaleArc = qwtMax(minArc, maxArc); - if ( d_data->maxScaleArc - d_data->minScaleArc > 360.0 ) - d_data->maxScaleArc = d_data->minScaleArc + 360.0; - - update(); -} - -//! QwtDoubleRange update hook -void QwtDial::valueChange() -{ - update(); - QwtAbstractSlider::valueChange(); -} - /*! \return Size hint + \sa minimumSizeHint() */ QSize QwtDial::sizeHint() const { int sh = 0; - if ( d_data->scaleDraw ) - sh = d_data->scaleDraw->extent( QPen(), font() ); + if ( scaleDraw() ) + sh = qCeil( scaleDraw()->extent( font() ) ); const int d = 6 * sh + 2 * lineWidth(); - return QSize( d, d ); + QSize hint( d, d ); + if ( !isReadOnly() ) + hint = hint.expandedTo( QApplication::globalStrut() ); + + return hint; } /*! - \brief Return a minimum size hint - \warning The return value of QwtDial::minimumSizeHint() depends on the - font and the scale. + \return Minimum size hint + \sa sizeHint() */ QSize QwtDial::minimumSizeHint() const { int sh = 0; - if ( d_data->scaleDraw ) - sh = d_data->scaleDraw->extent(QPen(), font() ); + if ( scaleDraw() ) + sh = qCeil( scaleDraw()->extent( font() ) ); const int d = 3 * sh + 2 * lineWidth(); return QSize( d, d ); } -static double line2Radians(const QPoint &p1, const QPoint &p2) +/*! + \brief Determine what to do when the user presses a mouse button. + + \param pos Mouse position + + \retval True, when the inner circle contains pos + \sa scrolledTo() +*/ +bool QwtDial::isScrollPosition( const QPoint &pos ) const { - const QPoint p = p2 - p1; - - double angle; - if ( p.x() == 0 ) - angle = ( p.y() <= 0 ) ? M_PI_2 : 3 * M_PI_2; - else { - angle = atan(double(-p.y()) / double(p.x())); - if ( p.x() < 0 ) - angle += M_PI; - if ( angle < 0.0 ) - angle += 2 * M_PI; + const QRegion region( innerRect(), QRegion::Ellipse ); + if ( region.contains( pos ) && ( pos != innerRect().center() ) ) + { + double angle = QLineF( rect().center(), pos ).angle(); + if ( d_data->mode == QwtDial::RotateScale ) + angle = 360.0 - angle; + + double valueAngle = + qwtNormalizeDegrees( 90.0 - transform( value() ) ); + + d_data->mouseOffset = qwtNormalizeDegrees( angle - valueAngle ); + d_data->arcOffset = scaleMap().p1(); + + return true; } - return 360.0 - angle * 180.0 / M_PI; + + return false; } /*! - Find the value for a given position + \brief Determine the value for a new position of the + slider handle. + + \param pos Mouse position - \param pos Position - \return Value + \return Value for the mouse position + \sa isScrollPosition() */ -double QwtDial::getValue(const QPoint &pos) +double QwtDial::scrolledTo( const QPoint &pos ) const { - if ( d_data->maxScaleArc == d_data->minScaleArc || maxValue() == minValue() ) - return minValue(); + double angle = QLineF( rect().center(), pos ).angle(); + if ( d_data->mode == QwtDial::RotateScale ) + { + angle += scaleMap().p1() - d_data->arcOffset; + angle = 360.0 - angle; + } - double dir = line2Radians(rect().center(), pos) - d_data->origin; - if ( dir < 0.0 ) - dir += 360.0; + angle = qwtNormalizeDegrees( angle - d_data->mouseOffset ); + angle = qwtNormalizeDegrees( 90.0 - angle ); - if ( mode() == RotateScale ) - dir = 360.0 - dir; - - // The position might be in the area that is outside the scale arc. - // We need the range of the scale if it was a complete circle. - - const double completeCircle = 360.0 / (d_data->maxScaleArc - d_data->minScaleArc) - * (maxValue() - minValue()); - - double posValue = minValue() + completeCircle * dir / 360.0; - - if ( scrollMode() == ScrMouse ) { - if ( d_data->previousDir >= 0.0 ) { // valid direction - // We have to find out whether the mouse is moving - // clock or counter clockwise - - bool clockWise = false; - - const double angle = dir - d_data->previousDir; - if ( (angle >= 0.0 && angle <= 180.0) || angle < -180.0 ) - clockWise = true; - - if ( clockWise ) { - if ( dir < d_data->previousDir && mouseOffset() > 0.0 ) { - // We passed 360 -> 0 - setMouseOffset(mouseOffset() - completeCircle); - } - - if ( wrapping() ) { - if ( posValue - mouseOffset() > maxValue() ) { - // We passed maxValue and the value will be set - // to minValue. We have to adjust the mouseOffset. - - setMouseOffset(posValue - minValue()); - } - } else { - if ( posValue - mouseOffset() > maxValue() || - value() == maxValue() ) { - // We fix the value at maxValue by adjusting - // the mouse offset. - - setMouseOffset(posValue - maxValue()); - } - } - } else { - if ( dir > d_data->previousDir && mouseOffset() < 0.0 ) { - // We passed 0 -> 360 - setMouseOffset(mouseOffset() + completeCircle); - } - - if ( wrapping() ) { - if ( posValue - mouseOffset() < minValue() ) { - // We passed minValue and the value will be set - // to maxValue. We have to adjust the mouseOffset. - - setMouseOffset(posValue - maxValue()); - } - } else { - if ( posValue - mouseOffset() < minValue() || - value() == minValue() ) { - // We fix the value at minValue by adjusting - // the mouse offset. - - setMouseOffset(posValue - minValue()); - } - } + if ( scaleMap().pDist() >= 360.0 ) + { + if ( angle < scaleMap().p1() ) + angle += 360.0; + + if ( !wrapping() ) + { + double boundedAngle = angle; + + const double arc = angle - transform( value() ); + if ( qAbs( arc ) > 180.0 ) + { + boundedAngle = ( arc > 0 ) + ? scaleMap().p1() : scaleMap().p2(); } + + d_data->mouseOffset += ( boundedAngle - angle ); + + angle = boundedAngle; } - d_data->previousDir = dir; + } + else + { + const double boundedAngle = + qwtBoundedAngle( scaleMap().p1(), angle, scaleMap().p2() ); + + if ( !wrapping() ) + d_data->mouseOffset += ( boundedAngle - angle ); + + angle = boundedAngle; } - return posValue; + return invTransform( angle ); } /*! - \sa QwtAbstractSlider::getScrollMode + Change Event handler + \param event Change event + + Invalidates internal paint caches if necessary */ -void QwtDial::getScrollMode(const QPoint &p, int &scrollMode, int &direction) +void QwtDial::changeEvent( QEvent *event ) { - direction = 0; - scrollMode = ScrNone; - - const QRegion region(contentsRect(), QRegion::Ellipse); - if ( region.contains(p) && p != rect().center() ) { - scrollMode = ScrMouse; - d_data->previousDir = -1.0; + switch( event->type() ) + { + case QEvent::EnabledChange: + case QEvent::FontChange: + case QEvent::StyleChange: + case QEvent::PaletteChange: + case QEvent::LanguageChange: + case QEvent::LocaleChange: + { + invalidateCache(); + break; + } + default: + break; } + + QwtAbstractSlider::changeEvent( event ); } /*! - Handles key events - - - Key_Down, KeyLeft\n - Decrement by 1 - - Key_Prior\n - Decrement by pageSize() - - Key_Home\n - Set the value to minValue() - - - Key_Up, KeyRight\n - Increment by 1 - - Key_Next\n - Increment by pageSize() - - Key_End\n - Set the value to maxValue() - - \sa isReadOnly() + Wheel Event handler + \param event Wheel event */ -void QwtDial::keyPressEvent(QKeyEvent *e) +void QwtDial::wheelEvent( QWheelEvent *event ) { - if ( isReadOnly() ) { - e->ignore(); - return; - } - - if ( !isValid() ) - return; + const QRegion region( innerRect(), QRegion::Ellipse ); + if ( region.contains( event->pos() ) ) + QwtAbstractSlider::wheelEvent( event ); +} - double previous = prevValue(); - switch ( e->key() ) { - case Qt::Key_Down: - case Qt::Key_Left: - QwtDoubleRange::incValue(-1); - break; -#if QT_VERSION < 0x040000 - case Qt::Key_Prior: -#else - case Qt::Key_PageUp: -#endif - QwtDoubleRange::incValue(-pageSize()); - break; - case Qt::Key_Home: - setValue(minValue()); - break; - - case Qt::Key_Up: - case Qt::Key_Right: - QwtDoubleRange::incValue(1); - break; -#if QT_VERSION < 0x040000 - case Qt::Key_Next: -#else - case Qt::Key_PageDown: -#endif - QwtDoubleRange::incValue(pageSize()); - break; - case Qt::Key_End: - setValue(maxValue()); - break; - default: - ; - e->ignore(); +void QwtDial::setAngleRange( double angle, double span ) +{ + QwtRoundScaleDraw *sd = const_cast<QwtRoundScaleDraw *>( scaleDraw() ); + if ( sd ) + { + angle = qwtNormalizeDegrees( angle - 270.0 ); + sd->setAngleRange( angle, angle + span ); } - - if (value() != previous) - emit sliderMoved(value()); } /*! - \brief Update the mask of the dial - - In case of "hasVisibleBackground() == false", the backgound is - transparent by a mask. + Invalidate the internal caches and call + QwtAbstractSlider::scaleChange() + */ +void QwtDial::scaleChange() +{ + invalidateCache(); + QwtAbstractSlider::scaleChange(); +} - \sa showBackground(), hasVisibleBackground() -*/ -void QwtDial::updateMask() +void QwtDial::sliderChange() { - if ( d_data->visibleBackground ) - clearMask(); - else - setMask(QRegion(boundingRect(), QRegion::Ellipse)); + setAngleRange( d_data->origin + d_data->minScaleArc, + d_data->maxScaleArc - d_data->minScaleArc ); + + if ( mode() == RotateScale ) + { + const double arc = transform( value() ) - scaleMap().p1(); + setAngleRange( d_data->origin - arc, + d_data->maxScaleArc - d_data->minScaleArc ); + } + + QwtAbstractSlider::sliderChange(); } diff --git a/libs/qwt/qwt_dial.h b/libs/qwt/qwt_dial.h index 37e5e783fe..a409b4be60 100644 --- a/libs/qwt/qwt_dial.h +++ b/libs/qwt/qwt_dial.h @@ -7,38 +7,17 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_DIAL_H #define QWT_DIAL_H 1 -#include <qframe.h> -#include <qpalette.h> #include "qwt_global.h" #include "qwt_abstract_slider.h" -#include "qwt_round_scale_draw.h" +#include "qwt_abstract_scale_draw.h" +#include <qframe.h> +#include <qpalette.h> class QwtDialNeedle; -class QwtDial; - -/*! - \brief A special scale draw made for QwtDial - - \sa QwtDial, QwtCompass -*/ -class QWT_EXPORT QwtDialScaleDraw: public QwtRoundScaleDraw -{ -public: - explicit QwtDialScaleDraw(QwtDial *); - virtual QwtText label(double value) const; - - void setPenWidth(uint); - uint penWidth() const; - -private: - QwtDial *d_parent; - int d_penWidth; -}; +class QwtRoundScaleDraw; /*! \brief QwtDial class provides a rounded range control. @@ -52,33 +31,34 @@ private: of the dial. Depending on Mode one of them is fixed and the other is rotating. If not isReadOnly() the dial can be rotated by dragging the mouse or using keyboard inputs - (see keyPressEvent()). A dial might be wrapping, what means + (see QwtAbstractSlider::keyPressEvent()). A dial might be wrapping, what means a rotation below/above one limit continues on the other limit (f.e compass). The scale might cover any arc of the dial, its values are related to the origin() of the dial. - Qwt is missing a set of good looking needles (QwtDialNeedle). - Contributions are very welcome. + Often dials have to be updated very often according to values from external + devices. For these high refresh rates QwtDial caches as much as possible. + For derived classes it might be necessary to clear these caches manually + according to attribute changes using invalidateCache(). \sa QwtCompass, QwtAnalogClock, QwtDialNeedle - \note The examples/dials example shows different types of dials. + \note The controls and dials examples shows different types of dials. + \note QDial is more similar to QwtKnob than to QwtDial */ class QWT_EXPORT QwtDial: public QwtAbstractSlider { Q_OBJECT - Q_ENUMS(Shadow) - Q_ENUMS(Mode) + Q_ENUMS( Shadow Mode Direction ) - Q_PROPERTY(bool visibleBackground READ hasVisibleBackground WRITE showBackground) - Q_PROPERTY(int lineWidth READ lineWidth WRITE setLineWidth) - Q_PROPERTY(Shadow frameShadow READ frameShadow WRITE setFrameShadow) - Q_PROPERTY(Mode mode READ mode WRITE setMode) - Q_PROPERTY(double origin READ origin WRITE setOrigin) - Q_PROPERTY(bool wrapping READ wrapping WRITE setWrapping) + Q_PROPERTY( int lineWidth READ lineWidth WRITE setLineWidth ) + Q_PROPERTY( Shadow frameShadow READ frameShadow WRITE setFrameShadow ) + Q_PROPERTY( Mode mode READ mode WRITE setMode ) + Q_PROPERTY( double origin READ origin WRITE setOrigin ) + Q_PROPERTY( double minScaleArc READ minScaleArc WRITE setMinScaleArc ) + Q_PROPERTY( double maxScaleArc READ maxScaleArc WRITE setMaxScaleArc ) - friend class QwtDialScaleDraw; public: /*! @@ -89,120 +69,97 @@ public: The following enum is made for the designer only. It is safe to use QFrame::Shadow instead. */ - enum Shadow { + enum Shadow + { + //! QFrame::Plain Plain = QFrame::Plain, + + //! QFrame::Raised Raised = QFrame::Raised, - Sunken = QFrame::Sunken - }; - //! see QwtDial::setScaleOptions - enum ScaleOptions { - ScaleBackbone = 1, - ScaleTicks = 2, - ScaleLabel = 4 + //! QFrame::Sunken + Sunken = QFrame::Sunken }; - /*! - In case of RotateNeedle the needle is rotating, in case of - RotateScale, the needle points to origin() - and the scale is rotating. - */ - enum Mode { + //! Mode controlling whether the needle or the scale is rotating + enum Mode + { + //! The needle is rotating RotateNeedle, + + //! The needle is fixed, the scales are rotating RotateScale }; - explicit QwtDial( QWidget *parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtDial( QWidget *parent, const char *name); -#endif - + explicit QwtDial( QWidget *parent = NULL ); virtual ~QwtDial(); - void setFrameShadow(Shadow); + void setFrameShadow( Shadow ); Shadow frameShadow() const; - bool hasVisibleBackground() const; - void showBackground(bool); - - void setLineWidth(int); + void setLineWidth( int ); int lineWidth() const; - void setMode(Mode); + void setMode( Mode ); Mode mode() const; - virtual void setWrapping(bool); - bool wrapping() const; - - virtual void setScale(int maxMajIntv, int maxMinIntv, double step = 0.0); - - void setScaleArc(double min, double max); - void setScaleOptions(int); - void setScaleTicks(int minLen, int medLen, int majLen, int penWidth = 1); + void setScaleArc( double min, double max ); + void setMinScaleArc( double min ); double minScaleArc() const; + + void setMaxScaleArc( double min ); double maxScaleArc() const; - virtual void setOrigin(double); + virtual void setOrigin( double ); double origin() const; - virtual void setNeedle(QwtDialNeedle *); + void setNeedle( QwtDialNeedle * ); const QwtDialNeedle *needle() const; QwtDialNeedle *needle(); QRect boundingRect() const; - QRect contentsRect() const; - virtual QRect scaleContentsRect() const; + QRect innerRect() const; + + virtual QRect scaleInnerRect() const; virtual QSize sizeHint() const; virtual QSize minimumSizeHint() const; - virtual void setScaleDraw(QwtDialScaleDraw *); + void setScaleDraw( QwtRoundScaleDraw * ); - QwtDialScaleDraw *scaleDraw(); - const QwtDialScaleDraw *scaleDraw() const; + QwtRoundScaleDraw *scaleDraw(); + const QwtRoundScaleDraw *scaleDraw() const; protected: - virtual void paintEvent(QPaintEvent *); - virtual void resizeEvent(QResizeEvent *); - virtual void keyPressEvent(QKeyEvent *); + virtual void wheelEvent( QWheelEvent * ); + virtual void paintEvent( QPaintEvent * ); + virtual void changeEvent( QEvent * ); - virtual void updateMask(); - - virtual void drawFrame(QPainter *p); - virtual void drawContents(QPainter *) const; - virtual void drawFocusIndicator(QPainter *) const; - - virtual void drawScale(QPainter *, const QPoint ¢er, - int radius, double origin, double arcMin, double arcMax) const; - - /*! - Draw the contents inside the scale + virtual void drawFrame( QPainter *p ); + virtual void drawContents( QPainter * ) const; + virtual void drawFocusIndicator( QPainter * ) const; - Paints nothing. + void invalidateCache(); - \param painter Painter - \param center Center of the contents circle - \param radius Radius of the contents circle - */ - virtual void drawScaleContents(QPainter *painter, const QPoint ¢er, - int radius) const; + virtual void drawScale( QPainter *, + const QPointF ¢er, double radius ) const; - virtual void drawNeedle(QPainter *, const QPoint &, - int radius, double direction, QPalette::ColorGroup) const; + virtual void drawScaleContents( QPainter *painter, + const QPointF ¢er, double radius ) const; - virtual QwtText scaleLabel(double) const; - void updateScale(); + virtual void drawNeedle( QPainter *, const QPointF &, + double radius, double direction, QPalette::ColorGroup ) const; - virtual void rangeChange(); - virtual void valueChange(); + virtual double scrolledTo( const QPoint & ) const; + virtual bool isScrollPosition( const QPoint & ) const; - virtual double getValue(const QPoint &); - virtual void getScrollMode(const QPoint &, - int &scrollMode, int &direction); + virtual void sliderChange(); + virtual void scaleChange(); private: - void initDial(); + void setAngleRange( double angle, double span ); + void drawNeedle( QPainter * ) const; class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_dial_needle.cpp b/libs/qwt/qwt_dial_needle.cpp index d403b18dc7..1b53a3d5b3 100644 --- a/libs/qwt/qwt_dial_needle.cpp +++ b/libs/qwt/qwt_dial_needle.cpp @@ -7,559 +7,434 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <math.h> -#include <qapplication.h> -#include <qpainter.h> +#include "qwt_dial_needle.h" +#include "qwt_global.h" #include "qwt_math.h" #include "qwt_painter.h" -#include "qwt_polygon.h" -#include "qwt_dial_needle.h" +#include <qapplication.h> +#include <qpainter.h> -#if QT_VERSION < 0x040000 -typedef QColorGroup QwtPalette; -#else -typedef QPalette QwtPalette; +#if QT_VERSION < 0x040601 +#define qFastSin(x) qSin(x) +#define qFastCos(x) qCos(x) #endif -//! Constructor -QwtDialNeedle::QwtDialNeedle(): - d_palette(QApplication::palette()) +static void qwtDrawStyle1Needle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, + double length ) { -} + const double r[] = { 0.4, 0.3, 1, 0.8, 1, 0.3, 0.4 }; + const double a[] = { -45, -20, -15, 0, 15, 20, 45 }; -//! Destructor -QwtDialNeedle::~QwtDialNeedle() -{ -} + QPainterPath path; + for ( int i = 0; i < 7; i++ ) + { + const double angle = a[i] / 180.0 * M_PI; + const double radius = r[i] * length; -/*! - Sets the palette for the needle. + const double x = radius * qFastCos( angle ); + const double y = radius * qFastSin( angle ); - \param palette New Palette -*/ -void QwtDialNeedle::setPalette(const QPalette &palette) -{ - d_palette = palette; -} + path.lineTo( x, -y ); + } -/*! - \return the palette of the needle. -*/ -const QPalette &QwtDialNeedle::palette() const -{ - return d_palette; + painter->setPen( Qt::NoPen ); + painter->setBrush( palette.brush( colorGroup, QPalette::Light ) ); + painter->drawPath( path ); } -//! Draw the knob -void QwtDialNeedle::drawKnob(QPainter *painter, - const QPoint &pos, int width, const QBrush &brush, bool sunken) +static void qwtDrawStyle2Needle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, double length ) { - painter->save(); + const double ratioX = 0.7; + const double ratioY = 0.3; - QRect rect(0, 0, width, width); - rect.moveCenter(pos); + QPainterPath path1; + path1.lineTo( ratioX * length, 0.0 ); + path1.lineTo( length, ratioY * length ); - painter->setPen(Qt::NoPen); - painter->setBrush(brush); - painter->drawEllipse(rect); + QPainterPath path2; + path2.lineTo( ratioX * length, 0.0 ); + path2.lineTo( length, -ratioY * length ); - painter->setBrush(Qt::NoBrush); + painter->setPen( Qt::NoPen ); - const int colorOffset = 20; + painter->setBrush( palette.brush( colorGroup, QPalette::Light ) ); + painter->drawPath( path1 ); - int startAngle = 45; - if ( sunken ) - startAngle += 180; + painter->setBrush( palette.brush( colorGroup, QPalette::Dark ) ); + painter->drawPath( path2 ); +} - QPen pen; - pen.setWidth(1); +static void qwtDrawShadedPointer( QPainter *painter, + const QColor &lightColor, const QColor &darkColor, + double length, double width ) +{ + const double peak = qMax( length / 10.0, 5.0 ); - pen.setColor(brush.color().dark(100 - colorOffset)); - painter->setPen(pen); - painter->drawArc(rect, startAngle * 16, 180 * 16); + const double knobWidth = width + 8; + QRectF knobRect( 0, 0, knobWidth, knobWidth ); + knobRect.moveCenter( QPointF(0, 0) ); - pen.setColor(brush.color().dark(100 + colorOffset)); - painter->setPen(pen); - painter->drawArc(rect, (startAngle + 180) * 16, 180 * 16); + QPainterPath path1; + path1.lineTo( 0.0, 0.5 * width ); + path1.lineTo( length - peak, 0.5 * width ); + path1.lineTo( length, 0.0 ); + path1.lineTo( 0.0, 0.0 ); - painter->restore(); -} + QPainterPath arcPath1; + arcPath1.arcTo( knobRect, 0.0, -90.0 ); -/*! - Constructor -*/ -QwtDialSimpleNeedle::QwtDialSimpleNeedle(Style style, bool hasKnob, - const QColor &mid, const QColor &base): - d_style(style), - d_hasKnob(hasKnob), - d_width(-1) -{ - QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) { - palette.setColor((QPalette::ColorGroup)i, - QwtPalette::Mid, mid); - palette.setColor((QPalette::ColorGroup)i, - QwtPalette::Base, base); - } + path1 = path1.united( arcPath1 ); - setPalette(palette); -} + QPainterPath path2; + path2.lineTo( 0.0, -0.5 * width ); + path2.lineTo( length - peak, -0.5 * width ); + path2.lineTo( length, 0.0 ); + path2.lineTo( 0.0, 0.0 ); -//! Set the width of the needle -void QwtDialSimpleNeedle::setWidth(int width) -{ - d_width = width; -} + QPainterPath arcPath2; + arcPath2.arcTo( knobRect, 0.0, 90.0 ); -/*! - \return the width of the needle -*/ -int QwtDialSimpleNeedle::width() const -{ - return d_width; -} + path2 = path2.united( arcPath2 ); -/*! - Draw the needle + painter->setPen( Qt::NoPen ); - \param painter Painter - \param center Center of the dial, start position for the needle - \param length Length of the needle - \param direction Direction of the needle, in degrees counter clockwise - \param colorGroup Color group, used for painting -*/ -void QwtDialSimpleNeedle::draw(QPainter *painter, const QPoint ¢er, - int length, double direction, QPalette::ColorGroup colorGroup) const -{ - if ( d_style == Arrow ) { - drawArrowNeedle(painter, palette(), colorGroup, - center, length, d_width, direction, d_hasKnob); - } else { - drawRayNeedle(painter, palette(), colorGroup, - center, length, d_width, direction, d_hasKnob); - } + painter->setBrush( lightColor ); + painter->drawPath( path1 ); + + painter->setBrush( darkColor ); + painter->drawPath( path2 ); } -/*! - Draw a needle looking like a ray -*/ -void QwtDialSimpleNeedle::drawRayNeedle(QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - const QPoint ¢er, int length, int width, double direction, - bool hasKnob) +static void qwtDrawArrowNeedle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, + double length, double width ) { if ( width <= 0 ) - width = 5; + width = qMax( length * 0.06, 9.0 ); - direction *= M_PI / 180.0; + const double peak = qMax( 2.0, 0.4 * width ); - painter->save(); + QPainterPath path; + path.moveTo( 0.0, 0.5 * width ); + path.lineTo( length - peak, 0.3 * width ); + path.lineTo( length, 0.0 ); + path.lineTo( length - peak, -0.3 * width ); + path.lineTo( 0.0, -0.5 * width ); - const QPoint p1(center.x() + 1, center.y() + 2); - const QPoint p2 = qwtPolar2Pos(p1, length, direction); - - if ( width == 1 ) { - const QColor midColor = - palette.color(colorGroup, QwtPalette::Mid); - - painter->setPen(QPen(midColor, 1)); - painter->drawLine(p1, p2); - } else { - QwtPolygon pa(4); - pa.setPoint(0, qwtPolar2Pos(p1, width / 2, direction + M_PI_2)); - pa.setPoint(1, qwtPolar2Pos(p2, width / 2, direction + M_PI_2)); - pa.setPoint(2, qwtPolar2Pos(p2, width / 2, direction - M_PI_2)); - pa.setPoint(3, qwtPolar2Pos(p1, width / 2, direction - M_PI_2)); - - painter->setPen(Qt::NoPen); - painter->setBrush(palette.brush(colorGroup, QwtPalette::Mid)); - painter->drawPolygon(pa); - } - if ( hasKnob ) { - int knobWidth = qwtMax(qRound(width * 0.7), 5); - if ( knobWidth % 2 == 0 ) - knobWidth++; - - drawKnob(painter, center, knobWidth, - palette.brush(colorGroup, QwtPalette::Base), - false); - } + QRectF br = path.boundingRect(); - painter->restore(); -} + QPalette pal( palette.color( QPalette::Mid ) ); + QColor c1 = pal.color( QPalette::Light ); + QColor c2 = pal.color( QPalette::Dark ); -/*! - Draw a needle looking like an arrow -*/ -void QwtDialSimpleNeedle::drawArrowNeedle(QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - const QPoint ¢er, int length, int width, - double direction, bool hasKnob) -{ - direction *= M_PI / 180.0; + QLinearGradient gradient( br.topLeft(), br.bottomLeft() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 0.5, c1 ); + gradient.setColorAt( 0.5001, c2 ); + gradient.setColorAt( 1.0, c2 ); - painter->save(); + QPen pen( gradient, 1 ); + pen.setJoinStyle( Qt::MiterJoin ); - if ( width <= 0 ) { - width = (int)qwtMax(length * 0.06, 9.0); - if ( width % 2 == 0 ) - width++; - } + painter->setPen( pen ); + painter->setBrush( palette.brush( colorGroup, QPalette::Mid ) ); + + painter->drawPath( path ); +} - const int peak = 3; - const QPoint p1(center.x() + 1, center.y() + 1); - const QPoint p2 = qwtPolar2Pos(p1, length - peak, direction); - const QPoint p3 = qwtPolar2Pos(p1, length, direction); +static void qwtDrawTriangleNeedle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, + double length ) +{ + const double width = qRound( length / 3.0 ); - QwtPolygon pa(5); - pa.setPoint(0, qwtPolar2Pos(p1, width / 2, direction - M_PI_2)); - pa.setPoint(1, qwtPolar2Pos(p2, 1, direction - M_PI_2)); - pa.setPoint(2, p3); - pa.setPoint(3, qwtPolar2Pos(p2, 1, direction + M_PI_2)); - pa.setPoint(4, qwtPolar2Pos(p1, width / 2, direction + M_PI_2)); + QPainterPath path[4]; - painter->setPen(Qt::NoPen); - painter->setBrush(palette.brush(colorGroup, QwtPalette::Mid)); - painter->drawPolygon(pa); + path[0].lineTo( length, 0.0 ); + path[0].lineTo( 0.0, width / 2 ); - QwtPolygon shadowPa(3); + path[1].lineTo( length, 0.0 ); + path[1].lineTo( 0.0, -width / 2 ); - const int colorOffset = 10; + path[2].lineTo( -length, 0.0 ); + path[2].lineTo( 0.0, width / 2 ); - int i; - for ( i = 0; i < 3; i++ ) - shadowPa.setPoint(i, pa[i]); + path[3].lineTo( -length, 0.0 ); + path[3].lineTo( 0.0, -width / 2 ); - const QColor midColor = palette.color(colorGroup, QwtPalette::Mid); - painter->setPen(midColor.dark(100 + colorOffset)); - painter->drawPolyline(shadowPa); + const int colorOffset = 10; + const QColor darkColor = palette.color( colorGroup, QPalette::Dark ); + const QColor lightColor = palette.color( colorGroup, QPalette::Light ); - for ( i = 0; i < 3; i++ ) - shadowPa.setPoint(i, pa[i + 2]); + QColor color[4]; + color[0] = darkColor.light( 100 + colorOffset ); + color[1] = darkColor.dark( 100 + colorOffset ); + color[2] = lightColor.light( 100 + colorOffset ); + color[3] = lightColor.dark( 100 + colorOffset ); - painter->setPen(midColor.dark(100 - colorOffset)); - painter->drawPolyline(shadowPa); + painter->setPen( Qt::NoPen ); - if ( hasKnob ) { - drawKnob(painter, center, qRound(width * 1.3), - palette.brush(colorGroup, QwtPalette::Base), - false); + for ( int i = 0; i < 4; i++ ) + { + painter->setBrush( color[i] ); + painter->drawPath( path[i] ); } - - painter->restore(); } //! Constructor - -QwtCompassMagnetNeedle::QwtCompassMagnetNeedle(Style style, - const QColor &light, const QColor &dark): - d_style(style) +QwtDialNeedle::QwtDialNeedle(): + d_palette( QApplication::palette() ) { - QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) { - palette.setColor((QPalette::ColorGroup)i, - QwtPalette::Light, light); - palette.setColor((QPalette::ColorGroup)i, - QwtPalette::Dark, dark); - palette.setColor((QPalette::ColorGroup)i, - QwtPalette::Base, Qt::darkGray); - } +} - setPalette(palette); +//! Destructor +QwtDialNeedle::~QwtDialNeedle() +{ } /*! - Draw the needle + Sets the palette for the needle. - \param painter Painter - \param center Center of the dial, start position for the needle - \param length Length of the needle - \param direction Direction of the needle, in degrees counter clockwise - \param colorGroup Color group, used for painting + \param palette New Palette */ -void QwtCompassMagnetNeedle::draw(QPainter *painter, const QPoint ¢er, - int length, double direction, QPalette::ColorGroup colorGroup) const +void QwtDialNeedle::setPalette( const QPalette &palette ) { - if ( d_style == ThinStyle ) { - drawThinNeedle(painter, palette(), colorGroup, - center, length, direction); - } else { - drawTriangleNeedle(painter, palette(), colorGroup, - center, length, direction); - } + d_palette = palette; } /*! - Draw a compass needle - - \param painter Painter - \param palette Palette - \param colorGroup Color group - \param center Center, where the needle starts - \param length Length of the needle - \param direction Direction + \return the palette of the needle. */ -void QwtCompassMagnetNeedle::drawTriangleNeedle(QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - const QPoint ¢er, int length, double direction) +const QPalette &QwtDialNeedle::palette() const { - const QBrush darkBrush = palette.brush(colorGroup, QwtPalette::Dark); - const QBrush lightBrush = palette.brush(colorGroup, QwtPalette::Light); - - QBrush brush; - - const int width = qRound(length / 3.0); - const int colorOffset = 10; - - painter->save(); - painter->setPen(Qt::NoPen); - - const QPoint arrowCenter(center.x() + 1, center.y() + 1); - - QwtPolygon pa(3); - pa.setPoint(0, arrowCenter); - pa.setPoint(1, qwtDegree2Pos(arrowCenter, length, direction)); - - pa.setPoint(2, qwtDegree2Pos(arrowCenter, width / 2, direction + 90.0)); - - brush = darkBrush; - brush.setColor(brush.color().dark(100 + colorOffset)); - painter->setBrush(brush); - painter->drawPolygon(pa); - - pa.setPoint(2, qwtDegree2Pos(arrowCenter, width / 2, direction - 90.0)); - - brush = darkBrush; - brush.setColor(brush.color().dark(100 - colorOffset)); - painter->setBrush(brush); - painter->drawPolygon(pa); - - // -- - - pa.setPoint(1, qwtDegree2Pos(arrowCenter, length, direction + 180.0)); - - pa.setPoint(2, qwtDegree2Pos(arrowCenter, width / 2, direction + 90.0)); - - brush = lightBrush; - brush.setColor(brush.color().dark(100 + colorOffset)); - painter->setBrush(brush); - painter->drawPolygon(pa); - - pa.setPoint(2, qwtDegree2Pos(arrowCenter, width / 2, direction - 90.0)); - - brush = lightBrush; - brush.setColor(brush.color().dark(100 - colorOffset)); - painter->setBrush(brush); - painter->drawPolygon(pa); - - painter->restore(); + return d_palette; } /*! - Draw a compass needle + Draw the needle \param painter Painter - \param palette Palette - \param colorGroup Color group - \param center Center, where the needle starts + \param center Center of the dial, start position for the needle \param length Length of the needle - \param direction Direction + \param direction Direction of the needle, in degrees counter clockwise + \param colorGroup Color group, used for painting */ -void QwtCompassMagnetNeedle::drawThinNeedle(QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - const QPoint ¢er, int length, double direction) +void QwtDialNeedle::draw( QPainter *painter, + const QPointF ¢er, double length, double direction, + QPalette::ColorGroup colorGroup ) const { - const QBrush darkBrush = palette.brush(colorGroup, QwtPalette::Dark); - const QBrush lightBrush = palette.brush(colorGroup, QwtPalette::Light); - const QBrush baseBrush = palette.brush(colorGroup, QwtPalette::Base); - - const int colorOffset = 10; - const int width = qwtMax(qRound(length / 6.0), 3); - painter->save(); - const QPoint arrowCenter(center.x() + 1, center.y() + 1); + painter->translate( center ); + painter->rotate( -direction ); - drawPointer(painter, darkBrush, colorOffset, - arrowCenter, length, width, direction); - drawPointer(painter, lightBrush, -colorOffset, - arrowCenter, length, width, direction + 180.0); - - drawKnob(painter, arrowCenter, width, baseBrush, true); + drawNeedle( painter, length, colorGroup ); painter->restore(); } -/*! - Draw a compass needle - - \param painter Painter - \param brush Brush - \param colorOffset Color offset - \param center Center, where the needle starts - \param length Length of the needle - \param width Width of the needle - \param direction Direction -*/ -void QwtCompassMagnetNeedle::drawPointer( - QPainter *painter, const QBrush &brush, - int colorOffset, const QPoint ¢er, int length, - int width, double direction) +//! Draw the knob +void QwtDialNeedle::drawKnob( QPainter *painter, + double width, const QBrush &brush, bool sunken ) const { - painter->save(); - - const int peak = qwtMax(qRound(length / 10.0), 5); + QPalette palette( brush.color() ); - const int knobWidth = width + 8; - QRect knobRect(0, 0, knobWidth, knobWidth); - knobRect.moveCenter(center); + QColor c1 = palette.color( QPalette::Light ); + QColor c2 = palette.color( QPalette::Dark ); - QwtPolygon pa(5); + if ( sunken ) + qSwap( c1, c2 ); - pa.setPoint(0, qwtDegree2Pos(center, width / 2, direction + 90.0)); - pa.setPoint(1, center); - pa.setPoint(2, qwtDegree2Pos(pa.point(1), length - peak, direction)); - pa.setPoint(3, qwtDegree2Pos(center, length, direction)); - pa.setPoint(4, qwtDegree2Pos(pa.point(0), length - peak, direction)); + QRectF rect( 0.0, 0.0, width, width ); + rect.moveCenter( painter->combinedTransform().map( QPointF() ) ); - painter->setPen(Qt::NoPen); + QLinearGradient gradient( rect.topLeft(), rect.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 0.3, c1 ); + gradient.setColorAt( 0.7, c2 ); + gradient.setColorAt( 1.0, c2 ); - QBrush darkBrush = brush; - darkBrush.setColor(darkBrush.color().dark(100 + colorOffset)); - painter->setBrush(darkBrush); - painter->drawPolygon(pa); - painter->drawPie(knobRect, qRound(direction * 16), 90 * 16); + painter->save(); - pa.setPoint(0, qwtDegree2Pos(center, width / 2, direction - 90.0)); - pa.setPoint(4, qwtDegree2Pos(pa.point(0), length - peak, direction)); + painter->resetTransform(); - QBrush lightBrush = brush; - lightBrush.setColor(lightBrush.color().dark(100 - colorOffset)); - painter->setBrush(lightBrush); - painter->drawPolygon(pa); - painter->drawPie(knobRect, qRound(direction * 16), -90 * 16); + painter->setPen( QPen( gradient, 1 ) ); + painter->setBrush( brush ); + painter->drawEllipse( rect ); painter->restore(); } /*! - Constructor + Constructor - \param style Arrow style - \param light Light color - \param dark Dark color + \param style Style + \param hasKnob With/Without knob + \param mid Middle color + \param base Base color */ -QwtCompassWindArrow::QwtCompassWindArrow(Style style, - const QColor &light, const QColor &dark): - d_style(style) +QwtDialSimpleNeedle::QwtDialSimpleNeedle( Style style, bool hasKnob, + const QColor &mid, const QColor &base ): + d_style( style ), + d_hasKnob( hasKnob ), + d_width( -1 ) { QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) { - palette.setColor((QPalette::ColorGroup)i, - QwtPalette::Light, light); - palette.setColor((QPalette::ColorGroup)i, - QwtPalette::Dark, dark); - } + palette.setColor( QPalette::Mid, mid ); + palette.setColor( QPalette::Base, base ); - setPalette(palette); + setPalette( palette ); } /*! - Draw the needle + Set the width of the needle + \param width Width + \sa width() +*/ +void QwtDialSimpleNeedle::setWidth( double width ) +{ + d_width = width; +} - \param painter Painter - \param center Center of the dial, start position for the needle - \param length Length of the needle - \param direction Direction of the needle, in degrees counter clockwise - \param colorGroup Color group, used for painting +/*! + \return the width of the needle + \sa setWidth() */ -void QwtCompassWindArrow::draw(QPainter *painter, const QPoint ¢er, - int length, double direction, QPalette::ColorGroup colorGroup) const +double QwtDialSimpleNeedle::width() const { - if ( d_style == Style1 ) { - drawStyle1Needle(painter, palette(), colorGroup, - center, length, direction); - } else { - drawStyle2Needle(painter, palette(), colorGroup, - center, length, direction); - } + return d_width; } /*! - Draw a compass needle + Draw the needle \param painter Painter - \param palette Palette - \param colorGroup colorGroup - \param center Center of the dial, start position for the needle \param length Length of the needle - \param direction Direction of the needle, in degrees counter clockwise + \param colorGroup Color group, used for painting */ -void QwtCompassWindArrow::drawStyle1Needle(QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - const QPoint ¢er, int length, double direction) +void QwtDialSimpleNeedle::drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const { - const QBrush lightBrush = palette.brush(colorGroup, QwtPalette::Light); + double knobWidth = 0.0; + double width = d_width; - const double AR1[] = {0, 0.4, 0.3, 1, 0.8, 1, 0.3, 0.4}; - const double AW1[] = {0, -45, -20, -15, 0, 15, 20, 45}; + if ( d_style == Arrow ) + { + if ( width <= 0.0 ) + width = qMax(length * 0.06, 6.0); - const QPoint arrowCenter(center.x() + 1, center.y() + 1); + qwtDrawArrowNeedle( painter, + palette(), colorGroup, length, width ); - QwtPolygon pa(8); - pa.setPoint(0, arrowCenter); - for (int i=1; i<8; i++) { - const QPoint p = qwtDegree2Pos(center, - AR1[i] * length, direction + AW1[i]); - pa.setPoint(i, p); + knobWidth = qMin( width * 2.0, 0.2 * length ); + } + else + { + if ( width <= 0.0 ) + width = 5.0; + + QPen pen ( palette().brush( colorGroup, QPalette::Mid ), width ); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + painter->drawLine( QPointF( 0.0, 0.0 ), QPointF( length, 0.0 ) ); + + knobWidth = qMax( width * 3.0, 5.0 ); } - painter->save(); - painter->setPen(Qt::NoPen); - painter->setBrush(lightBrush); - painter->drawPolygon(pa); - painter->restore(); + if ( d_hasKnob && knobWidth > 0.0 ) + { + drawKnob( painter, knobWidth, + palette().brush( colorGroup, QPalette::Base ), false ); + } } -/*! - Draw a compass needle - - \param painter Painter - \param palette Palette - \param colorGroup colorGroup - \param center Center of the dial, start position for the needle - \param length Length of the needle - \param direction Direction of the needle, in degrees counter clockwise -*/ -void QwtCompassWindArrow::drawStyle2Needle(QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - const QPoint ¢er, int length, double direction) +//! Constructor +QwtCompassMagnetNeedle::QwtCompassMagnetNeedle( Style style, + const QColor &light, const QColor &dark ): + d_style( style ) { - const QBrush lightBrush = palette.brush(colorGroup, QwtPalette::Light); - const QBrush darkBrush = palette.brush(colorGroup, QwtPalette::Dark); + QPalette palette; + palette.setColor( QPalette::Light, light ); + palette.setColor( QPalette::Dark, dark ); + palette.setColor( QPalette::Base, Qt::gray ); - painter->save(); - painter->setPen(Qt::NoPen); + setPalette( palette ); +} - const double angle = 12.0; - const double ratio = 0.7; +/*! + Draw the needle - const QPoint arrowCenter(center.x() + 1, center.y() + 1); + \param painter Painter + \param length Length of the needle + \param colorGroup Color group, used for painting +*/ +void QwtCompassMagnetNeedle::drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const +{ + if ( d_style == ThinStyle ) + { + const double width = qMax( length / 6.0, 3.0 ); + + const int colorOffset = 10; + + const QColor light = palette().color( colorGroup, QPalette::Light ); + const QColor dark = palette().color( colorGroup, QPalette::Dark ); + + qwtDrawShadedPointer( painter, + dark.light( 100 + colorOffset ), + dark.dark( 100 + colorOffset ), + length, width ); + + painter->rotate( 180.0 ); + + qwtDrawShadedPointer( painter, + light.light( 100 + colorOffset ), + light.dark( 100 + colorOffset ), + length, width ); + + const QBrush baseBrush = palette().brush( colorGroup, QPalette::Base ); + drawKnob( painter, width, baseBrush, true ); + } + else + { + qwtDrawTriangleNeedle( painter, palette(), colorGroup, length ); + } +} - QwtPolygon pa(3); +/*! + Constructor - pa.setPoint(0, center); - pa.setPoint(2, qwtDegree2Pos(arrowCenter, ratio * length, direction)); + \param style Arrow style + \param light Light color + \param dark Dark color +*/ +QwtCompassWindArrow::QwtCompassWindArrow( Style style, + const QColor &light, const QColor &dark ): + d_style( style ) +{ + QPalette palette; + palette.setColor( QPalette::Light, light ); + palette.setColor( QPalette::Dark, dark ); - pa.setPoint(1, qwtDegree2Pos(arrowCenter, length, direction + angle)); - painter->setBrush(darkBrush); - painter->drawPolygon(pa); + setPalette( palette ); +} - pa.setPoint(1, qwtDegree2Pos(arrowCenter, length, direction - angle)); - painter->setBrush(lightBrush); - painter->drawPolygon(pa); +/*! + Draw the needle - painter->restore(); + \param painter Painter + \param length Length of the needle + \param colorGroup Color group, used for painting +*/ +void QwtCompassWindArrow::drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const +{ + if ( d_style == Style1 ) + qwtDrawStyle1Needle( painter, palette(), colorGroup, length ); + else + qwtDrawStyle2Needle( painter, palette(), colorGroup, length ); } - diff --git a/libs/qwt/qwt_dial_needle.h b/libs/qwt/qwt_dial_needle.h index e17d01bfd7..d84384a0fd 100644 --- a/libs/qwt/qwt_dial_needle.h +++ b/libs/qwt/qwt_dial_needle.h @@ -10,8 +10,8 @@ #ifndef QWT_DIAL_NEEDLE_H #define QWT_DIAL_NEEDLE_H 1 -#include <qpalette.h> #include "qwt_global.h" +#include <qpalette.h> class QPainter; class QPoint; @@ -22,9 +22,6 @@ class QPoint; QwtDialNeedle is a pointer that indicates a value by pointing to a specific direction. - Qwt is missing a set of good looking needles. - Contributions are very welcome. - \sa QwtDial, QwtCompass */ @@ -34,25 +31,34 @@ public: QwtDialNeedle(); virtual ~QwtDialNeedle(); + virtual void setPalette( const QPalette & ); + const QPalette &palette() const; + + virtual void draw( QPainter *painter, const QPointF ¢er, + double length, double direction, + QPalette::ColorGroup = QPalette::Active ) const; + +protected: /*! - Draw the needle + \brief Draw the needle - \param painter Painter - \param center Center of the dial, start position for the needle - \param length Length of the needle - \param direction Direction of the needle, in degrees counter clockwise - \param cg Color group, used for painting - */ - virtual void draw(QPainter *painter, const QPoint ¢er, - int length, double direction, - QPalette::ColorGroup cg = QPalette::Active) const = 0; + The origin of the needle is at position (0.0, 0.0 ) + pointing in direction 0.0 ( = east ). - virtual void setPalette(const QPalette &); - const QPalette &palette() const; + The painter is already initialized with translation and + rotation. -protected: - static void drawKnob(QPainter *, const QPoint &pos, - int width, const QBrush &, bool sunken); + \param painter Painter + \param length Length of the needle + \param colorGroup Color group, used for painting + + \sa setPalette(), palette() + */ + virtual void drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const = 0; + + virtual void drawKnob( QPainter *, double width, + const QBrush &, bool sunken ) const; private: QPalette d_palette; @@ -62,9 +68,10 @@ private: \brief A needle for dial widgets The following colors are used: - - QColorGroup::Mid\n + + - QPalette::Mid\n Pointer - - QColorGroup::base\n + - QPalette::Base\n Knob \sa QwtDial, QwtCompass @@ -74,34 +81,29 @@ class QWT_EXPORT QwtDialSimpleNeedle: public QwtDialNeedle { public: //! Style of the needle - enum Style { + enum Style + { + //! Arrow Arrow, + + //! A straight line from the center Ray }; - QwtDialSimpleNeedle(Style, bool hasKnob = true, - const QColor &mid = Qt::gray, const QColor &base = Qt::darkGray); - - virtual void draw(QPainter *, const QPoint &, int length, - double direction, QPalette::ColorGroup = QPalette::Active) const; + QwtDialSimpleNeedle( Style, bool hasKnob = true, + const QColor &mid = Qt::gray, const QColor &base = Qt::darkGray ); - static void drawArrowNeedle(QPainter *, - const QPalette&, QPalette::ColorGroup, - const QPoint &, int length, int width, double direction, - bool hasKnob); + void setWidth( double width ); + double width() const; - static void drawRayNeedle(QPainter *, - const QPalette&, QPalette::ColorGroup, - const QPoint &, int length, int width, double direction, - bool hasKnob); - - void setWidth(int width); - int width() const; +protected: + virtual void drawNeedle( QPainter *, double length, + QPalette::ColorGroup ) const; private: Style d_style; bool d_hasKnob; - int d_width; + double d_width; }; /*! @@ -111,11 +113,11 @@ private: north and south. The following colors are used: - - QColorGroup::Light\n + - QPalette::Light\n Used for pointing south - - QColorGroup::Dark\n + - QPalette::Dark\n Used for pointing north - - QColorGroup::Base\n + - QPalette::Base\n Knob (ThinStyle only) \sa QwtDial, QwtCompass @@ -125,28 +127,21 @@ class QWT_EXPORT QwtCompassMagnetNeedle: public QwtDialNeedle { public: //! Style of the needle - enum Style { + enum Style + { + //! A needle with a triangular shape TriangleStyle, + + //! A thin needle ThinStyle }; - QwtCompassMagnetNeedle(Style = TriangleStyle, - const QColor &light = Qt::white, const QColor &dark = Qt::red); - virtual void draw(QPainter *, const QPoint &, int length, - double direction, QPalette::ColorGroup = QPalette::Active) const; - - static void drawTriangleNeedle(QPainter *, - const QPalette &, QPalette::ColorGroup, - const QPoint &, int length, double direction); - - static void drawThinNeedle(QPainter *, - const QPalette &, QPalette::ColorGroup, - const QPoint &, int length, double direction); + QwtCompassMagnetNeedle( Style = TriangleStyle, + const QColor &light = Qt::white, const QColor &dark = Qt::red ); protected: - static void drawPointer(QPainter *painter, const QBrush &brush, - int colorOffset, const QPoint ¢er, - int length, int width, double direction); + virtual void drawNeedle( QPainter *, + double length, QPalette::ColorGroup ) const; private: Style d_style; @@ -157,9 +152,9 @@ private: QwtCompassWindArrow shows the direction where the wind comes from. - - QColorGroup::Light\n + - QPalette::Light\n Used for Style1, or the light half of Style2 - - QColorGroup::Dark\n + - QPalette::Dark\n Used for the dark half of Style2 \sa QwtDial, QwtCompass @@ -169,27 +164,24 @@ class QWT_EXPORT QwtCompassWindArrow: public QwtDialNeedle { public: //! Style of the arrow - enum Style { + enum Style + { + //! A needle pointing to the center Style1, + + //! A needle pointing to the center Style2 }; - QwtCompassWindArrow(Style, const QColor &light = Qt::white, - const QColor &dark = Qt::gray); + QwtCompassWindArrow( Style, const QColor &light = Qt::white, + const QColor &dark = Qt::gray ); - virtual void draw(QPainter *, const QPoint &, int length, - double direction, QPalette::ColorGroup = QPalette::Active) const; - - static void drawStyle1Needle(QPainter *, - const QPalette &, QPalette::ColorGroup, - const QPoint &, int length, double direction); - - static void drawStyle2Needle(QPainter *, - const QPalette &, QPalette::ColorGroup, - const QPoint &, int length, double direction); +protected: + virtual void drawNeedle( QPainter *, + double length, QPalette::ColorGroup ) const; private: Style d_style; }; -#endif // QWT_DIAL_NEEDLE_H +#endif diff --git a/libs/qwt/qwt_dyngrid_layout.cpp b/libs/qwt/qwt_dyngrid_layout.cpp index ac98ad1c03..9e0fa2851f 100644 --- a/libs/qwt/qwt_dyngrid_layout.cpp +++ b/libs/qwt/qwt_dyngrid_layout.cpp @@ -7,128 +7,72 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qwidget.h> #include "qwt_dyngrid_layout.h" #include "qwt_math.h" - -#if QT_VERSION < 0x040000 -#include <qvaluelist.h> -#else +#include <qvector.h> #include <qlist.h> -#endif class QwtDynGridLayout::PrivateData { public: - -#if QT_VERSION < 0x040000 - class LayoutIterator: public QGLayoutIterator - { - public: - LayoutIterator(PrivateData *data): - d_data(data) { - d_iterator = d_data->itemList.begin(); - } - - virtual QLayoutItem *current() { - if (d_iterator == d_data->itemList.end()) - return NULL; - - return *d_iterator; - } - - virtual QLayoutItem *next() { - if (d_iterator == d_data->itemList.end()) - return NULL; - - d_iterator++; - if (d_iterator == d_data->itemList.end()) - return NULL; - - return *d_iterator; - } - - virtual QLayoutItem *takeCurrent() { - if ( d_iterator == d_data->itemList.end() ) - return NULL; - - QLayoutItem *item = *d_iterator; - - d_data->isDirty = true; - d_iterator = d_data->itemList.remove(d_iterator); - return item; - } - - private: - - QValueListIterator<QLayoutItem*> d_iterator; - QwtDynGridLayout::PrivateData *d_data; - }; -#endif - PrivateData(): - isDirty(true) { + isDirty( true ) + { } -#if QT_VERSION < 0x040000 - typedef QValueList<QLayoutItem*> LayoutItemList; -#else - typedef QList<QLayoutItem*> LayoutItemList; -#endif + void updateLayoutCache(); - mutable LayoutItemList itemList; + mutable QList<QLayoutItem*> itemList; - uint maxCols; + uint maxColumns; uint numRows; - uint numCols; + uint numColumns; -#if QT_VERSION < 0x040000 - QSizePolicy::ExpandData expanding; -#else Qt::Orientations expanding; -#endif bool isDirty; - QwtArray<QSize> itemSizeHints; + QVector<QSize> itemSizeHints; }; +void QwtDynGridLayout::PrivateData::updateLayoutCache() +{ + itemSizeHints.resize( itemList.count() ); -/*! - \param parent Parent widget - \param margin Margin - \param spacing Spacing -*/ + int index = 0; -QwtDynGridLayout::QwtDynGridLayout(QWidget *parent, - int margin, int spacing): - QLayout(parent) -{ - init(); + for ( QList<QLayoutItem*>::iterator it = itemList.begin(); + it != itemList.end(); ++it, index++ ) + { + itemSizeHints[ index ] = ( *it )->sizeHint(); + } - setSpacing(spacing); - setMargin(margin); + isDirty = false; } -#if QT_VERSION < 0x040000 /*! \param parent Parent widget + \param margin Margin \param spacing Spacing */ -QwtDynGridLayout::QwtDynGridLayout(QLayout *parent, int spacing): - QLayout(parent, spacing) + +QwtDynGridLayout::QwtDynGridLayout( QWidget *parent, + int margin, int spacing ): + QLayout( parent ) { init(); + + setSpacing( spacing ); + setMargin( margin ); } -#endif /*! \param spacing Spacing */ -QwtDynGridLayout::QwtDynGridLayout(int spacing) +QwtDynGridLayout::QwtDynGridLayout( int spacing ) { init(); - setSpacing(spacing); + setSpacing( spacing ); } /*! @@ -137,82 +81,63 @@ QwtDynGridLayout::QwtDynGridLayout(int spacing) void QwtDynGridLayout::init() { d_data = new QwtDynGridLayout::PrivateData; - d_data->maxCols = d_data->numRows - = d_data->numCols = 0; - -#if QT_VERSION < 0x040000 - d_data->expanding = QSizePolicy::NoDirection; - setSupportsMargin(true); -#else + d_data->maxColumns = d_data->numRows = d_data->numColumns = 0; d_data->expanding = 0; -#endif } //! Destructor QwtDynGridLayout::~QwtDynGridLayout() { -#if QT_VERSION < 0x040000 - deleteAllItems(); -#endif + for ( int i = 0; i < d_data->itemList.size(); i++ ) + delete d_data->itemList[i]; delete d_data; } +//! Invalidate all internal caches void QwtDynGridLayout::invalidate() { d_data->isDirty = true; QLayout::invalidate(); } -void QwtDynGridLayout::updateLayoutCache() -{ - d_data->itemSizeHints.resize(itemCount()); - - int index = 0; - - for (PrivateData::LayoutItemList::iterator it = d_data->itemList.begin(); - it != d_data->itemList.end(); ++it, index++) { - d_data->itemSizeHints[int(index)] = (*it)->sizeHint(); - } - - d_data->isDirty = false; -} - /*! Limit the number of columns. - \param maxCols upper limit, 0 means unlimited - \sa QwtDynGridLayout::maxCols() + \param maxColumns upper limit, 0 means unlimited + \sa maxColumns() */ - -void QwtDynGridLayout::setMaxCols(uint maxCols) +void QwtDynGridLayout::setMaxColumns( uint maxColumns ) { - d_data->maxCols = maxCols; + d_data->maxColumns = maxColumns; } /*! - Return the upper limit for the number of columns. + \brief Return the upper limit for the number of columns. + 0 means unlimited, what is the default. - \sa QwtDynGridLayout::setMaxCols() -*/ -uint QwtDynGridLayout::maxCols() const + \return Upper limit for the number of columns + \sa setMaxColumns() +*/ +uint QwtDynGridLayout::maxColumns() const { - return d_data->maxCols; + return d_data->maxColumns; } -//! Adds item to the next free position. - -void QwtDynGridLayout::addItem(QLayoutItem *item) +/*! + \brief Add an item to the next free position. + \param item Layout item + */ +void QwtDynGridLayout::addItem( QLayoutItem *item ) { - d_data->itemList.append(item); + d_data->itemList.append( item ); invalidate(); } /*! \return true if this layout is empty. */ - bool QwtDynGridLayout::isEmpty() const { return d_data->itemList.isEmpty(); @@ -221,140 +146,134 @@ bool QwtDynGridLayout::isEmpty() const /*! \return number of layout items */ - uint QwtDynGridLayout::itemCount() const { return d_data->itemList.count(); } -#if QT_VERSION < 0x040000 /*! - \return An iterator over the children of this layout. -*/ - -QLayoutIterator QwtDynGridLayout::iterator() -{ - return QLayoutIterator( - new QwtDynGridLayout::PrivateData::LayoutIterator(d_data) ); -} + Find the item at a specific index -/*! - Set whether this layout can make use of more space than sizeHint(). - A value of Vertical or Horizontal means that it wants to grow in only - one dimension, while BothDirections means that it wants to grow in - both dimensions. The default value is NoDirection. - \sa QwtDynGridLayout::expanding() + \param index Index + \return Item at a specific index + \sa takeAt() */ - -void QwtDynGridLayout::setExpanding(QSizePolicy::ExpandData expanding) -{ - d_data->expanding = expanding; -} - -/*! - Returns whether this layout can make use of more space than sizeHint(). - A value of Vertical or Horizontal means that it wants to grow in only - one dimension, while BothDirections means that it wants to grow in - both dimensions. - \sa QwtDynGridLayout::setExpanding() -*/ - -QSizePolicy::ExpandData QwtDynGridLayout::expanding() const -{ - return d_data->expanding; -} - -#else // QT_VERSION >= 0x040000 - QLayoutItem *QwtDynGridLayout::itemAt( int index ) const { if ( index < 0 || index >= d_data->itemList.count() ) return NULL; - return d_data->itemList.at(index); + return d_data->itemList.at( index ); } +/*! + Find the item at a specific index and remove it from the layout + + \param index Index + \return Layout item, removed from the layout + \sa itemAt() +*/ QLayoutItem *QwtDynGridLayout::takeAt( int index ) { if ( index < 0 || index >= d_data->itemList.count() ) return NULL; d_data->isDirty = true; - return d_data->itemList.takeAt(index); + return d_data->itemList.takeAt( index ); } +//! \return Number of items in the layout int QwtDynGridLayout::count() const { return d_data->itemList.count(); } -void QwtDynGridLayout::setExpandingDirections(Qt::Orientations expanding) +/*! + Set whether this layout can make use of more space than sizeHint(). + A value of Qt::Vertical or Qt::Horizontal means that it wants to grow in only + one dimension, while Qt::Vertical | Qt::Horizontal means that it wants + to grow in both dimensions. The default value is 0. + + \param expanding Or'd orientations + \sa expandingDirections() +*/ +void QwtDynGridLayout::setExpandingDirections( Qt::Orientations expanding ) { d_data->expanding = expanding; } +/*! + \brief Returns whether this layout can make use of more space than sizeHint(). + + A value of Qt::Vertical or Qt::Horizontal means that it wants to grow in only + one dimension, while Qt::Vertical | Qt::Horizontal means that it wants + to grow in both dimensions. + + \return Orientations, where the layout expands + \sa setExpandingDirections() +*/ Qt::Orientations QwtDynGridLayout::expandingDirections() const { return d_data->expanding; } -#endif - /*! - Reorganizes columns and rows and resizes managed widgets within - the rectangle rect. -*/ + Reorganizes columns and rows and resizes managed items within + a rectangle. -void QwtDynGridLayout::setGeometry(const QRect &rect) + \param rect Layout geometry +*/ +void QwtDynGridLayout::setGeometry( const QRect &rect ) { - QLayout::setGeometry(rect); + QLayout::setGeometry( rect ); if ( isEmpty() ) return; - d_data->numCols = columnsForWidth(rect.width()); - d_data->numRows = itemCount() / d_data->numCols; - if ( itemCount() % d_data->numCols ) + d_data->numColumns = columnsForWidth( rect.width() ); + d_data->numRows = itemCount() / d_data->numColumns; + if ( itemCount() % d_data->numColumns ) d_data->numRows++; -#if QT_VERSION < 0x040000 - QValueList<QRect> itemGeometries = layoutItems(rect, d_data->numCols); -#else - QList<QRect> itemGeometries = layoutItems(rect, d_data->numCols); -#endif + QList<QRect> itemGeometries = layoutItems( rect, d_data->numColumns ); int index = 0; - for (PrivateData::LayoutItemList::iterator it = d_data->itemList.begin(); - it != d_data->itemList.end(); ++it) { - QWidget *w = (*it)->widget(); - if ( w ) { - w->setGeometry(itemGeometries[index]); - index++; - } + for ( QList<QLayoutItem*>::iterator it = d_data->itemList.begin(); + it != d_data->itemList.end(); ++it ) + { + ( *it )->setGeometry( itemGeometries[index] ); + index++; } } /*! - Calculate the number of columns for a given width. It tries to - use as many columns as possible (limited by maxCols()) + \brief Calculate the number of columns for a given width. + + The calculation tries to use as many columns as possible + ( limited by maxColumns() ) \param width Available width for all columns - \sa QwtDynGridLayout::maxCols(), QwtDynGridLayout::setMaxCols() -*/ + \return Number of columns for a given width -uint QwtDynGridLayout::columnsForWidth(int width) const + \sa maxColumns(), setMaxColumns() +*/ +uint QwtDynGridLayout::columnsForWidth( int width ) const { if ( isEmpty() ) return 0; - const int maxCols = (d_data->maxCols > 0) ? d_data->maxCols : itemCount(); - if ( maxRowWidth(maxCols) <= width ) - return maxCols; + uint maxColumns = itemCount(); + if ( d_data->maxColumns > 0 ) + maxColumns = qMin( d_data->maxColumns, maxColumns ); + + if ( maxRowWidth( maxColumns ) <= width ) + return maxColumns; - for (int numCols = 2; numCols <= maxCols; numCols++ ) { - const int rowWidth = maxRowWidth(numCols); + for ( uint numColumns = 2; numColumns <= maxColumns; numColumns++ ) + { + const int rowWidth = maxRowWidth( numColumns ); if ( rowWidth > width ) - return numCols - 1; + return numColumns - 1; } return 1; // At least 1 column @@ -364,29 +283,30 @@ uint QwtDynGridLayout::columnsForWidth(int width) const Calculate the width of a layout for a given number of columns. - \param numCols Given number of columns + \param numColumns Given number of columns \param itemWidth Array of the width hints for all items */ -int QwtDynGridLayout::maxRowWidth(int numCols) const +int QwtDynGridLayout::maxRowWidth( int numColumns ) const { int col; - QwtArray<int> colWidth(numCols); - for ( col = 0; col < (int)numCols; col++ ) + QVector<int> colWidth( numColumns ); + for ( col = 0; col < numColumns; col++ ) colWidth[col] = 0; if ( d_data->isDirty ) - ((QwtDynGridLayout*)this)->updateLayoutCache(); + d_data->updateLayoutCache(); - for ( uint index = 0; - index < (uint)d_data->itemSizeHints.count(); index++ ) { - col = index % numCols; - colWidth[col] = qwtMax(colWidth[col], - d_data->itemSizeHints[int(index)].width()); + for ( int index = 0; + index < d_data->itemSizeHints.count(); index++ ) + { + col = index % numColumns; + colWidth[col] = qMax( colWidth[col], + d_data->itemSizeHints[int( index )].width() ); } - int rowWidth = 2 * margin() + (numCols - 1) * spacing(); - for ( col = 0; col < (int)numCols; col++ ) + int rowWidth = 2 * margin() + ( numColumns - 1 ) * spacing(); + for ( col = 0; col < numColumns; col++ ) rowWidth += colWidth[col]; return rowWidth; @@ -395,18 +315,18 @@ int QwtDynGridLayout::maxRowWidth(int numCols) const /*! \return the maximum width of all layout items */ - int QwtDynGridLayout::maxItemWidth() const { if ( isEmpty() ) return 0; if ( d_data->isDirty ) - ((QwtDynGridLayout*)this)->updateLayoutCache(); + d_data->updateLayoutCache(); int w = 0; - for ( uint i = 0; i < (uint)d_data->itemSizeHints.count(); i++ ) { - const int itemW = d_data->itemSizeHints[int(i)].width(); + for ( int i = 0; i < d_data->itemSizeHints.count(); i++ ) + { + const int itemW = d_data->itemSizeHints[i].width(); if ( itemW > w ) w = itemW; } @@ -416,79 +336,69 @@ int QwtDynGridLayout::maxItemWidth() const /*! Calculate the geometries of the layout items for a layout - with numCols columns and a given rect. + with numColumns columns and a given rectangle. + \param rect Rect where to place the items - \param numCols Number of columns + \param numColumns Number of columns \return item geometries */ -#if QT_VERSION < 0x040000 -QValueList<QRect> QwtDynGridLayout::layoutItems(const QRect &rect, - uint numCols) const -#else -QList<QRect> QwtDynGridLayout::layoutItems(const QRect &rect, - uint numCols) const -#endif +QList<QRect> QwtDynGridLayout::layoutItems( const QRect &rect, + uint numColumns ) const { -#if QT_VERSION < 0x040000 - QValueList<QRect> itemGeometries; -#else QList<QRect> itemGeometries; -#endif - if ( numCols == 0 || isEmpty() ) + if ( numColumns == 0 || isEmpty() ) return itemGeometries; - uint numRows = itemCount() / numCols; - if ( numRows % itemCount() ) + uint numRows = itemCount() / numColumns; + if ( numColumns % itemCount() ) numRows++; - QwtArray<int> rowHeight(numRows); - QwtArray<int> colWidth(numCols); + if ( numRows == 0 ) + return itemGeometries; + + QVector<int> rowHeight( numRows ); + QVector<int> colWidth( numColumns ); - layoutGrid(numCols, rowHeight, colWidth); + layoutGrid( numColumns, rowHeight, colWidth ); bool expandH, expandV; -#if QT_VERSION >= 0x040000 expandH = expandingDirections() & Qt::Horizontal; expandV = expandingDirections() & Qt::Vertical; -#else - expandH = expanding() & QSizePolicy::Horizontally; - expandV = expanding() & QSizePolicy::Vertically; -#endif if ( expandH || expandV ) - stretchGrid(rect, numCols, rowHeight, colWidth); + stretchGrid( rect, numColumns, rowHeight, colWidth ); - QwtDynGridLayout *that = (QwtDynGridLayout *)this; - const int maxCols = d_data->maxCols; - that->d_data->maxCols = numCols; - const QRect alignedRect = alignmentRect(rect); - that->d_data->maxCols = maxCols; + const int maxColumns = d_data->maxColumns; + d_data->maxColumns = numColumns; + const QRect alignedRect = alignmentRect( rect ); + d_data->maxColumns = maxColumns; const int xOffset = expandH ? 0 : alignedRect.x(); const int yOffset = expandV ? 0 : alignedRect.y(); - QwtArray<int> colX(numCols); - QwtArray<int> rowY(numRows); + QVector<int> colX( numColumns ); + QVector<int> rowY( numRows ); const int xySpace = spacing(); rowY[0] = yOffset + margin(); - for ( int r = 1; r < (int)numRows; r++ ) + for ( uint r = 1; r < numRows; r++ ) rowY[r] = rowY[r-1] + rowHeight[r-1] + xySpace; colX[0] = xOffset + margin(); - for ( int c = 1; c < (int)numCols; c++ ) + for ( uint c = 1; c < numColumns; c++ ) colX[c] = colX[c-1] + colWidth[c-1] + xySpace; const int itemCount = d_data->itemList.size(); - for ( int i = 0; i < itemCount; i++ ) { - const int row = i / numCols; - const int col = i % numCols; + for ( int i = 0; i < itemCount; i++ ) + { + const int row = i / numColumns; + const int col = i % numColumns; - QRect itemGeometry(colX[col], rowY[row], - colWidth[col], rowHeight[row]); - itemGeometries.append(itemGeometry); + QRect itemGeometry( colX[col], rowY[row], + colWidth[col], rowHeight[row] ); + itemGeometries.append( itemGeometry ); } return itemGeometries; @@ -497,67 +407,66 @@ QList<QRect> QwtDynGridLayout::layoutItems(const QRect &rect, /*! Calculate the dimensions for the columns and rows for a grid - of numCols columns. - \param numCols Number of columns. + of numColumns columns. + + \param numColumns Number of columns. \param rowHeight Array where to fill in the calculated row heights. \param colWidth Array where to fill in the calculated column widths. */ -void QwtDynGridLayout::layoutGrid(uint numCols, - QwtArray<int>& rowHeight, QwtArray<int>& colWidth) const +void QwtDynGridLayout::layoutGrid( uint numColumns, + QVector<int>& rowHeight, QVector<int>& colWidth ) const { - if ( numCols <= 0 ) + if ( numColumns <= 0 ) return; if ( d_data->isDirty ) - ((QwtDynGridLayout*)this)->updateLayoutCache(); + d_data->updateLayoutCache(); - for ( uint index = 0; - index < (uint)d_data->itemSizeHints.count(); index++ ) { - const int row = index / numCols; - const int col = index % numCols; + for ( int index = 0; index < d_data->itemSizeHints.count(); index++ ) + { + const int row = index / numColumns; + const int col = index % numColumns; - const QSize &size = d_data->itemSizeHints[int(index)]; + const QSize &size = d_data->itemSizeHints[int( index )]; - rowHeight[row] = (col == 0) - ? size.height() : qwtMax(rowHeight[row], size.height()); - colWidth[col] = (row == 0) - ? size.width() : qwtMax(colWidth[col], size.width()); + rowHeight[row] = ( col == 0 ) + ? size.height() : qMax( rowHeight[row], size.height() ); + colWidth[col] = ( row == 0 ) + ? size.width() : qMax( colWidth[col], size.width() ); } } /*! - \return true: QwtDynGridLayout implements heightForWidth. - \sa QwtDynGridLayout::heightForWidth() + \return true: QwtDynGridLayout implements heightForWidth(). + \sa heightForWidth() */ - bool QwtDynGridLayout::hasHeightForWidth() const { return true; } /*! - \return The preferred height for this layout, given the width w. - \sa QwtDynGridLayout::hasHeightForWidth() + \return The preferred height for this layout, given a width. + \sa hasHeightForWidth() */ - -int QwtDynGridLayout::heightForWidth(int width) const +int QwtDynGridLayout::heightForWidth( int width ) const { if ( isEmpty() ) return 0; - const uint numCols = columnsForWidth(width); - uint numRows = itemCount() / numCols; - if ( itemCount() % numCols ) + const uint numColumns = columnsForWidth( width ); + uint numRows = itemCount() / numColumns; + if ( itemCount() % numColumns ) numRows++; - QwtArray<int> rowHeight(numRows); - QwtArray<int> colWidth(numCols); + QVector<int> rowHeight( numRows ); + QVector<int> colWidth( numColumns ); - layoutGrid(numCols, rowHeight, colWidth); + layoutGrid( numColumns, rowHeight, colWidth ); - int h = 2 * margin() + (numRows - 1) * spacing(); - for ( int row = 0; row < (int)numRows; row++ ) + int h = 2 * margin() + ( numRows - 1 ) * spacing(); + for ( uint row = 0; row < numRows; row++ ) h += rowHeight[row]; return h; @@ -567,50 +476,56 @@ int QwtDynGridLayout::heightForWidth(int width) const Stretch columns in case of expanding() & QSizePolicy::Horizontal and rows in case of expanding() & QSizePolicy::Vertical to fill the entire rect. Rows and columns are stretched with the same factor. - \sa QwtDynGridLayout::setExpanding(), QwtDynGridLayout::expanding() -*/ -void QwtDynGridLayout::stretchGrid(const QRect &rect, - uint numCols, QwtArray<int>& rowHeight, QwtArray<int>& colWidth) const + \param rect Bounding rectangle + \param numColumns Number of columns + \param rowHeight Array to be filled with the calculated row heights + \param colWidth Array to be filled with the calculated column widths + + \sa setExpanding(), expanding() +*/ +void QwtDynGridLayout::stretchGrid( const QRect &rect, + uint numColumns, QVector<int>& rowHeight, QVector<int>& colWidth ) const { - if ( numCols == 0 || isEmpty() ) + if ( numColumns == 0 || isEmpty() ) return; bool expandH, expandV; -#if QT_VERSION >= 0x040000 expandH = expandingDirections() & Qt::Horizontal; expandV = expandingDirections() & Qt::Vertical; -#else - expandH = expanding() & QSizePolicy::Horizontally; - expandV = expanding() & QSizePolicy::Vertically; -#endif - - if ( expandH ) { - int xDelta = rect.width() - 2 * margin() - (numCols - 1) * spacing(); - for ( int col = 0; col < (int)numCols; col++ ) + + if ( expandH ) + { + int xDelta = rect.width() - 2 * margin() - ( numColumns - 1 ) * spacing(); + for ( uint col = 0; col < numColumns; col++ ) xDelta -= colWidth[col]; - if ( xDelta > 0 ) { - for ( int col = 0; col < (int)numCols; col++ ) { - const int space = xDelta / (numCols - col); + if ( xDelta > 0 ) + { + for ( uint col = 0; col < numColumns; col++ ) + { + const int space = xDelta / ( numColumns - col ); colWidth[col] += space; xDelta -= space; } } } - if ( expandV ) { - uint numRows = itemCount() / numCols; - if ( itemCount() % numCols ) + if ( expandV ) + { + uint numRows = itemCount() / numColumns; + if ( itemCount() % numColumns ) numRows++; - int yDelta = rect.height() - 2 * margin() - (numRows - 1) * spacing(); - for ( int row = 0; row < (int)numRows; row++ ) + int yDelta = rect.height() - 2 * margin() - ( numRows - 1 ) * spacing(); + for ( uint row = 0; row < numRows; row++ ) yDelta -= rowHeight[row]; - if ( yDelta > 0 ) { - for ( int row = 0; row < (int)numRows; row++ ) { - const int space = yDelta / (numRows - row); + if ( yDelta > 0 ) + { + for ( uint row = 0; row < numRows; row++ ) + { + const int space = yDelta / ( numRows - row ); rowHeight[row] += space; yDelta -= space; } @@ -619,41 +534,45 @@ void QwtDynGridLayout::stretchGrid(const QRect &rect, } /*! - Return the size hint. If maxCols() > 0 it is the size for - a grid with maxCols() columns, otherwise it is the size for + Return the size hint. If maxColumns() > 0 it is the size for + a grid with maxColumns() columns, otherwise it is the size for a grid with only one row. - \sa QwtDynGridLayout::maxCols(), QwtDynGridLayout::setMaxCols() -*/ + \return Size hint + \sa maxColumns(), setMaxColumns() +*/ QSize QwtDynGridLayout::sizeHint() const { if ( isEmpty() ) return QSize(); - const uint numCols = (d_data->maxCols > 0 ) ? d_data->maxCols : itemCount(); - uint numRows = itemCount() / numCols; - if ( itemCount() % numCols ) + uint numColumns = itemCount(); + if ( d_data->maxColumns > 0 ) + numColumns = qMin( d_data->maxColumns, numColumns ); + + uint numRows = itemCount() / numColumns; + if ( itemCount() % numColumns ) numRows++; - QwtArray<int> rowHeight(numRows); - QwtArray<int> colWidth(numCols); + QVector<int> rowHeight( numRows ); + QVector<int> colWidth( numColumns ); - layoutGrid(numCols, rowHeight, colWidth); + layoutGrid( numColumns, rowHeight, colWidth ); - int h = 2 * margin() + (numRows - 1) * spacing(); - for ( int row = 0; row < (int)numRows; row++ ) + int h = 2 * margin() + ( numRows - 1 ) * spacing(); + for ( uint row = 0; row < numRows; row++ ) h += rowHeight[row]; - int w = 2 * margin() + (numCols - 1) * spacing(); - for ( int col = 0; col < (int)numCols; col++ ) + int w = 2 * margin() + ( numColumns - 1 ) * spacing(); + for ( uint col = 0; col < numColumns; col++ ) w += colWidth[col]; - return QSize(w, h); + return QSize( w, h ); } /*! \return Number of rows of the current layout. - \sa QwtDynGridLayout::numCols + \sa numColumns() \warning The number of rows might change whenever the geometry changes */ uint QwtDynGridLayout::numRows() const @@ -663,10 +582,10 @@ uint QwtDynGridLayout::numRows() const /*! \return Number of columns of the current layout. - \sa QwtDynGridLayout::numRows + \sa numRows() \warning The number of columns might change whenever the geometry changes */ -uint QwtDynGridLayout::numCols() const +uint QwtDynGridLayout::numColumns() const { - return d_data->numCols; + return d_data->numColumns; } diff --git a/libs/qwt/qwt_dyngrid_layout.h b/libs/qwt/qwt_dyngrid_layout.h index a59e4e719d..dd20266124 100644 --- a/libs/qwt/qwt_dyngrid_layout.h +++ b/libs/qwt/qwt_dyngrid_layout.h @@ -10,15 +10,10 @@ #ifndef QWT_DYNGRID_LAYOUT_H #define QWT_DYNGRID_LAYOUT_H +#include "qwt_global.h" #include <qlayout.h> #include <qsize.h> -#if QT_VERSION >= 0x040000 #include <qlist.h> -#else -#include <qvaluelist.h> -#endif -#include "qwt_global.h" -#include "qwt_array.h" /*! \brief The QwtDynGridLayout class lays out widgets in a grid, @@ -26,81 +21,62 @@ QwtDynGridLayout takes the space it gets, divides it up into rows and columns, and puts each of the widgets it manages into the correct cell(s). - It lays out as many number of columns as possible (limited by maxCols()). + It lays out as many number of columns as possible (limited by maxColumns()). */ class QWT_EXPORT QwtDynGridLayout : public QLayout { Q_OBJECT public: - explicit QwtDynGridLayout(QWidget *, int margin = 0, int space = -1); -#if QT_VERSION < 0x040000 - explicit QwtDynGridLayout(QLayout *, int space = -1); -#endif - explicit QwtDynGridLayout(int space = -1); + explicit QwtDynGridLayout( QWidget *, int margin = 0, int space = -1 ); + explicit QwtDynGridLayout( int space = -1 ); virtual ~QwtDynGridLayout(); virtual void invalidate(); - void setMaxCols(uint maxCols); - uint maxCols() const; + void setMaxColumns( uint maxCols ); + uint maxColumns() const; uint numRows () const; - uint numCols () const; + uint numColumns () const; - virtual void addItem(QLayoutItem *); + virtual void addItem( QLayoutItem * ); -#if QT_VERSION >= 0x040000 virtual QLayoutItem *itemAt( int index ) const; virtual QLayoutItem *takeAt( int index ); virtual int count() const; - void setExpandingDirections(Qt::Orientations); + void setExpandingDirections( Qt::Orientations ); virtual Qt::Orientations expandingDirections() const; - QList<QRect> layoutItems(const QRect &, uint numCols) const; -#else - virtual QLayoutIterator iterator(); - - void setExpanding(QSizePolicy::ExpandData); - virtual QSizePolicy::ExpandData expanding() const; - QValueList<QRect> layoutItems(const QRect &, uint numCols) const; -#endif + QList<QRect> layoutItems( const QRect &, uint numCols ) const; virtual int maxItemWidth() const; - virtual void setGeometry(const QRect &rect); + virtual void setGeometry( const QRect &rect ); virtual bool hasHeightForWidth() const; - virtual int heightForWidth(int) const; + virtual int heightForWidth( int ) const; virtual QSize sizeHint() const; virtual bool isEmpty() const; uint itemCount() const; - virtual uint columnsForWidth(int width) const; + virtual uint columnsForWidth( int width ) const; protected: - void layoutGrid(uint numCols, - QwtArray<int>& rowHeight, QwtArray<int>& colWidth) const; - void stretchGrid(const QRect &rect, uint numCols, - QwtArray<int>& rowHeight, QwtArray<int>& colWidth) const; - + void layoutGrid( uint numCols, + QVector<int>& rowHeight, QVector<int>& colWidth ) const; + void stretchGrid( const QRect &rect, uint numCols, + QVector<int>& rowHeight, QVector<int>& colWidth ) const; private: void init(); - int maxRowWidth(int numCols) const; - void updateLayoutCache(); + int maxRowWidth( int numCols ) const; -#if QT_VERSION < 0x040000 -// xlC 5.1, the IBM/AIX C++ compiler, needs it to be public -public: -#endif class PrivateData; - -private: PrivateData *d_data; }; diff --git a/libs/qwt/qwt_event_pattern.cpp b/libs/qwt/qwt_event_pattern.cpp index 56ece45b41..463774362e 100644 --- a/libs/qwt/qwt_event_pattern.cpp +++ b/libs/qwt/qwt_event_pattern.cpp @@ -7,8 +7,8 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qevent.h> #include "qwt_event_pattern.h" +#include <qevent.h> /*! Constructor @@ -17,11 +17,11 @@ */ QwtEventPattern::QwtEventPattern(): - d_mousePattern(MousePatternCount), - d_keyPattern(KeyPatternCount) + d_mousePattern( MousePatternCount ), + d_keyPattern( KeyPatternCount ) { initKeyPattern(); - initMousePattern(3); + initMousePattern( 3 ); } //! Destructor @@ -35,44 +35,42 @@ QwtEventPattern::~QwtEventPattern() \param numButtons Number of mouse buttons ( <= 3 ) \sa MousePatternCode */ -void QwtEventPattern::initMousePattern(int numButtons) +void QwtEventPattern::initMousePattern( int numButtons ) { -#if QT_VERSION < 0x040000 - const int altButton = Qt::AltButton; - const int controlButton = Qt::ControlButton; - const int shiftButton = Qt::ShiftButton; -#else - const int altButton = Qt::AltModifier; - const int controlButton = Qt::ControlModifier; - const int shiftButton = Qt::ShiftModifier; -#endif - - d_mousePattern.resize(MousePatternCount); - - switch(numButtons) { - case 1: { - setMousePattern(MouseSelect1, Qt::LeftButton); - setMousePattern(MouseSelect2, Qt::LeftButton, controlButton); - setMousePattern(MouseSelect3, Qt::LeftButton, altButton); - break; - } - case 2: { - setMousePattern(MouseSelect1, Qt::LeftButton); - setMousePattern(MouseSelect2, Qt::RightButton); - setMousePattern(MouseSelect3, Qt::LeftButton, altButton); - break; - } - default: { - setMousePattern(MouseSelect1, Qt::LeftButton); - setMousePattern(MouseSelect2, Qt::RightButton); - setMousePattern(MouseSelect3, Qt::MidButton); - } - } - for ( int i = 0; i < 3; i++ ) { - setMousePattern(MouseSelect4 + i, - d_mousePattern[MouseSelect1 + i].button, - d_mousePattern[MouseSelect1 + i].state | shiftButton); + d_mousePattern.resize( MousePatternCount ); + + switch ( numButtons ) + { + case 1: + { + setMousePattern( MouseSelect1, Qt::LeftButton ); + setMousePattern( MouseSelect2, Qt::LeftButton, Qt::ControlModifier ); + setMousePattern( MouseSelect3, Qt::LeftButton, Qt::AltModifier ); + break; + } + case 2: + { + setMousePattern( MouseSelect1, Qt::LeftButton ); + setMousePattern( MouseSelect2, Qt::RightButton ); + setMousePattern( MouseSelect3, Qt::LeftButton, Qt::AltModifier ); + break; + } + default: + { + setMousePattern( MouseSelect1, Qt::LeftButton ); + setMousePattern( MouseSelect2, Qt::RightButton ); + setMousePattern( MouseSelect3, Qt::MidButton ); + } } + + setMousePattern( MouseSelect4, d_mousePattern[MouseSelect1].button, + d_mousePattern[MouseSelect1].modifiers | Qt::ShiftModifier ); + + setMousePattern( MouseSelect5, d_mousePattern[MouseSelect2].button, + d_mousePattern[MouseSelect2].modifiers | Qt::ShiftModifier ); + + setMousePattern( MouseSelect6, d_mousePattern[MouseSelect3].button, + d_mousePattern[MouseSelect3].modifiers | Qt::ShiftModifier ); } /*! @@ -82,20 +80,20 @@ void QwtEventPattern::initMousePattern(int numButtons) */ void QwtEventPattern::initKeyPattern() { - d_keyPattern.resize(KeyPatternCount); + d_keyPattern.resize( KeyPatternCount ); - setKeyPattern(KeySelect1, Qt::Key_Return); - setKeyPattern(KeySelect2, Qt::Key_Space); - setKeyPattern(KeyAbort, Qt::Key_Escape); + setKeyPattern( KeySelect1, Qt::Key_Return ); + setKeyPattern( KeySelect2, Qt::Key_Space ); + setKeyPattern( KeyAbort, Qt::Key_Escape ); - setKeyPattern(KeyLeft, Qt::Key_Left); - setKeyPattern(KeyRight, Qt::Key_Right); - setKeyPattern(KeyUp, Qt::Key_Up); - setKeyPattern(KeyDown, Qt::Key_Down); + setKeyPattern( KeyLeft, Qt::Key_Left ); + setKeyPattern( KeyRight, Qt::Key_Right ); + setKeyPattern( KeyUp, Qt::Key_Up ); + setKeyPattern( KeyDown, Qt::Key_Down ); - setKeyPattern(KeyRedo, Qt::Key_Plus); - setKeyPattern(KeyUndo, Qt::Key_Minus); - setKeyPattern(KeyHome, Qt::Key_Escape); + setKeyPattern( KeyRedo, Qt::Key_Plus ); + setKeyPattern( KeyUndo, Qt::Key_Minus ); + setKeyPattern( KeyHome, Qt::Key_Escape ); } /*! @@ -103,15 +101,17 @@ void QwtEventPattern::initKeyPattern() \param pattern Index of the pattern \param button Button - \param state State + \param modifiers Keyboard modifiers \sa QMouseEvent */ -void QwtEventPattern::setMousePattern(uint pattern, int button, int state) +void QwtEventPattern::setMousePattern( MousePatternCode pattern, + Qt::MouseButton button, Qt::KeyboardModifiers modifiers ) { - if ( pattern < (uint)d_mousePattern.count() ) { - d_mousePattern[int(pattern)].button = button; - d_mousePattern[int(pattern)].state = state; + if ( pattern >= 0 && pattern < MousePatternCount ) + { + d_mousePattern[ pattern ].button = button; + d_mousePattern[ pattern ].modifiers = modifiers; } } @@ -120,52 +120,54 @@ void QwtEventPattern::setMousePattern(uint pattern, int button, int state) \param pattern Index of the pattern \param key Key - \param state State + \param modifiers Keyboard modifiers \sa QKeyEvent */ -void QwtEventPattern::setKeyPattern(uint pattern, int key, int state) +void QwtEventPattern::setKeyPattern( KeyPatternCode pattern, + int key, Qt::KeyboardModifiers modifiers ) { - if ( pattern < (uint)d_keyPattern.count() ) { - d_keyPattern[int(pattern)].key = key; - d_keyPattern[int(pattern)].state = state; + if ( pattern >= 0 && pattern < KeyPatternCount ) + { + d_keyPattern[ pattern ].key = key; + d_keyPattern[ pattern ].modifiers = modifiers; } } //! Change the mouse event patterns -void QwtEventPattern::setMousePattern(const QwtArray<MousePattern> &pattern) +void QwtEventPattern::setMousePattern( const QVector<MousePattern> &pattern ) { d_mousePattern = pattern; } //! Change the key event patterns -void QwtEventPattern::setKeyPattern(const QwtArray<KeyPattern> &pattern) +void QwtEventPattern::setKeyPattern( const QVector<KeyPattern> &pattern ) { d_keyPattern = pattern; } -//! Return mouse patterns -const QwtArray<QwtEventPattern::MousePattern> & +//! \return Mouse pattern +const QVector<QwtEventPattern::MousePattern> & QwtEventPattern::mousePattern() const { return d_mousePattern; } -//! Return key patterns -const QwtArray<QwtEventPattern::KeyPattern> & +//! \return Key pattern +const QVector<QwtEventPattern::KeyPattern> & QwtEventPattern::keyPattern() const { return d_keyPattern; } -//! Return ,ouse patterns -QwtArray<QwtEventPattern::MousePattern> &QwtEventPattern::mousePattern() +//! \return Mouse pattern +QVector<QwtEventPattern::MousePattern> &QwtEventPattern::mousePattern() { return d_mousePattern; } -//! Return Key patterns -QwtArray<QwtEventPattern::KeyPattern> &QwtEventPattern::keyPattern() +//! \return Key pattern +QVector<QwtEventPattern::KeyPattern> &QwtEventPattern::keyPattern() { return d_keyPattern; } @@ -177,20 +179,19 @@ QwtArray<QwtEventPattern::KeyPattern> &QwtEventPattern::keyPattern() value and in the state value the same key flags(Qt::KeyButtonMask) are set. - \param pattern Index of the event pattern - \param e Mouse event + \param code Index of the event pattern + \param event Mouse event \return true if matches \sa keyMatch() */ -bool QwtEventPattern::mouseMatch(uint pattern, const QMouseEvent *e) const +bool QwtEventPattern::mouseMatch( MousePatternCode code, + const QMouseEvent *event ) const { - bool ok = false; - - if ( e && pattern < (uint)d_mousePattern.count() ) - ok = mouseMatch(d_mousePattern[int(pattern)], e); + if ( code >= 0 && code < MousePatternCount ) + return mouseMatch( d_mousePattern[ code ], event ); - return ok; + return false; } /*! @@ -201,28 +202,20 @@ bool QwtEventPattern::mouseMatch(uint pattern, const QMouseEvent *e) const are set. \param pattern Mouse event pattern - \param e Mouse event + \param event Mouse event \return true if matches \sa keyMatch() */ -bool QwtEventPattern::mouseMatch(const MousePattern &pattern, - const QMouseEvent *e) const +bool QwtEventPattern::mouseMatch( const MousePattern &pattern, + const QMouseEvent *event ) const { - if ( e->button() != pattern.button ) + if ( event == NULL ) return false; - const bool matched = -#if QT_VERSION < 0x040000 - (e->state() & Qt::KeyButtonMask) == - (pattern.state & Qt::KeyButtonMask); -#else - (e->modifiers() & Qt::KeyboardModifierMask) == - (int)(pattern.state & Qt::KeyboardModifierMask); -#endif - - return matched; + const MousePattern mousePattern( event->button(), event->modifiers() ); + return mousePattern == pattern; } /*! @@ -232,20 +225,19 @@ bool QwtEventPattern::mouseMatch(const MousePattern &pattern, value and in the state value the same key flags (Qt::KeyButtonMask) are set. - \param pattern Index of the event pattern - \param e Key event + \param code Index of the event pattern + \param event Key event \return true if matches \sa mouseMatch() */ -bool QwtEventPattern::keyMatch(uint pattern, const QKeyEvent *e) const +bool QwtEventPattern::keyMatch( KeyPatternCode code, + const QKeyEvent *event ) const { - bool ok = false; - - if ( e && pattern < (uint)d_keyPattern.count() ) - ok = keyMatch(d_keyPattern[int(pattern)], e); + if ( code >= 0 && code < KeyPatternCount ) + return keyMatch( d_keyPattern[ code ], event ); - return ok; + return false; } /*! @@ -256,26 +248,18 @@ bool QwtEventPattern::keyMatch(uint pattern, const QKeyEvent *e) const are set. \param pattern Key event pattern - \param e Key event + \param event Key event \return true if matches \sa mouseMatch() */ bool QwtEventPattern::keyMatch( - const KeyPattern &pattern, const QKeyEvent *e) const + const KeyPattern &pattern, const QKeyEvent *event ) const { - if ( e->key() != pattern.key) + if ( event == NULL ) return false; - const bool matched = -#if QT_VERSION < 0x040000 - (e->state() & Qt::KeyButtonMask) == - (pattern.state & Qt::KeyButtonMask); -#else - (e->modifiers() & Qt::KeyboardModifierMask) == - (int)(pattern.state & Qt::KeyboardModifierMask); -#endif - - return matched; + const KeyPattern keyPattern( event->key(), event->modifiers() ); + return keyPattern == pattern; } diff --git a/libs/qwt/qwt_event_pattern.h b/libs/qwt/qwt_event_pattern.h index e4455b12a0..7c5d1a37f6 100644 --- a/libs/qwt/qwt_event_pattern.h +++ b/libs/qwt/qwt_event_pattern.h @@ -10,8 +10,9 @@ #ifndef QWT_EVENT_PATTERN #define QWT_EVENT_PATTERN 1 +#include "qwt_global.h" #include <qnamespace.h> -#include "qwt_array.h" +#include <qvector.h> class QMouseEvent; class QKeyEvent; @@ -31,103 +32,115 @@ public: /*! \brief Symbolic mouse input codes - The default initialization for 3 button mice is: - - MouseSelect1\n - Qt::LeftButton - - MouseSelect2\n - Qt::RightButton - - MouseSelect3\n - Qt::MidButton - - MouseSelect4\n - Qt::LeftButton + Qt::ShiftButton - - MouseSelect5\n - Qt::RightButton + Qt::ShiftButton - - MouseSelect6\n - Qt::MidButton + Qt::ShiftButton - - The default initialization for 2 button mice is: - - MouseSelect1\n - Qt::LeftButton - - MouseSelect2\n - Qt::RightButton - - MouseSelect3\n - Qt::LeftButton + Qt::AltButton - - MouseSelect4\n - Qt::LeftButton + Qt::ShiftButton - - MouseSelect5\n - Qt::RightButton + Qt::ShiftButton - - MouseSelect6\n - Qt::LeftButton + Qt::AltButton + Qt::ShiftButton - - The default initialization for 1 button mice is: - - MouseSelect1\n - Qt::LeftButton - - MouseSelect2\n - Qt::LeftButton + Qt::ControlButton - - MouseSelect3\n - Qt::LeftButton + Qt::AltButton - - MouseSelect4\n - Qt::LeftButton + Qt::ShiftButton - - MouseSelect5\n - Qt::LeftButton + Qt::ControlButton + Qt::ShiftButton - - MouseSelect6\n - Qt::LeftButton + Qt::AltButton + Qt::ShiftButton - - \sa initMousePattern() + QwtEventPattern implements 3 different settings for + mice with 1, 2, or 3 buttons that can be activated + using initMousePattern(). The default setting is for + 3 button mice. + + Individual settings can be configured using setMousePattern(). + + \sa initMousePattern(), setMousePattern(), setKeyPattern() */ + enum MousePatternCode + { + /*! + The default setting for 1, 2 and 3 button mice is: - enum MousePatternCode { + - Qt::LeftButton + - Qt::LeftButton + - Qt::LeftButton + */ MouseSelect1, + + /*! + The default setting for 1, 2 and 3 button mice is: + + - Qt::LeftButton + Qt::ControlModifier + - Qt::RightButton + - Qt::RightButton + */ MouseSelect2, + + /*! + The default setting for 1, 2 and 3 button mice is: + + - Qt::LeftButton + Qt::AltModifier + - Qt::LeftButton + Qt::AltModifier + - Qt::MidButton + */ MouseSelect3, + + /*! + The default setting for 1, 2 and 3 button mice is: + + - Qt::LeftButton + Qt::ShiftModifier + - Qt::LeftButton + Qt::ShiftModifier + - Qt::LeftButton + Qt::ShiftModifier + */ MouseSelect4, + + /*! + The default setting for 1, 2 and 3 button mice is: + + - Qt::LeftButton + Qt::ControlButton | Qt::ShiftModifier + - Qt::RightButton + Qt::ShiftModifier + - Qt::RightButton + Qt::ShiftModifier + */ MouseSelect5, + + /*! + The default setting for 1, 2 and 3 button mice is: + + - Qt::LeftButton + Qt::AltModifier + Qt::ShiftModifier + - Qt::LeftButton + Qt::AltModifier | Qt::ShiftModifier + - Qt::MidButton + Qt::ShiftModifier + */ MouseSelect6, + //! Number of mouse patterns MousePatternCount }; /*! \brief Symbolic keyboard input codes - Default initialization: - - KeySelect1\n - Qt::Key_Return - - KeySelect2\n - Qt::Key_Space - - KeyAbort\n - Qt::Key_Escape - - - KeyLeft\n - Qt::Key_Left - - KeyRight\n - Qt::Key_Right - - KeyUp\n - Qt::Key_Up - - KeyDown\n - Qt::Key_Down - - - KeyUndo\n - Qt::Key_Minus - - KeyRedo\n - Qt::Key_Plus - - KeyHome\n - Qt::Key_Escape + Individual settings can be configured using setKeyPattern() + + \sa setKeyPattern(), setMousePattern() */ - enum KeyPatternCode { + enum KeyPatternCode + { + //! Qt::Key_Return KeySelect1, + + //! Qt::Key_Space KeySelect2, + + //! Qt::Key_Escape KeyAbort, + //! Qt::Key_Left KeyLeft, + + //! Qt::Key_Right KeyRight, + + //! Qt::Key_Up KeyUp, + + //! Qt::Key_Down KeyDown, + //! Qt::Key_Plus KeyRedo, + + //! Qt::Key_Minus KeyUndo, + + //! Qt::Key_Escape KeyHome, + //! Number of key patterns KeyPatternCount }; @@ -135,52 +148,67 @@ public: class MousePattern { public: - MousePattern(int btn = Qt::NoButton, int st = Qt::NoButton) { - button = btn; - state = st; + //! Constructor + MousePattern( Qt::MouseButton btn = Qt::NoButton, + Qt::KeyboardModifiers modifierCodes = Qt::NoModifier ): + button( btn ), + modifiers( modifierCodes ) + { } - int button; - int state; + //! Button + Qt::MouseButton button; + + //! Keyboard modifier + Qt::KeyboardModifiers modifiers; }; //! A pattern for key events class KeyPattern { public: - KeyPattern(int k = 0, int st = Qt::NoButton) { - key = k; - state = st; + //! Constructor + KeyPattern( int keyCode = Qt::Key_unknown, + Qt::KeyboardModifiers modifierCodes = Qt::NoModifier ): + key( keyCode ), + modifiers( modifierCodes ) + { } + //! Key code int key; - int state; + + //! Modifiers + Qt::KeyboardModifiers modifiers; }; QwtEventPattern(); virtual ~QwtEventPattern(); - void initMousePattern(int numButtons); + void initMousePattern( int numButtons ); void initKeyPattern(); - void setMousePattern(uint pattern, int button, int state = Qt::NoButton); - void setKeyPattern(uint pattern, int key, int state = Qt::NoButton); + void setMousePattern( MousePatternCode, Qt::MouseButton button, + Qt::KeyboardModifiers = Qt::NoModifier ); - void setMousePattern(const QwtArray<MousePattern> &); - void setKeyPattern(const QwtArray<KeyPattern> &); + void setKeyPattern( KeyPatternCode, int keyCode, + Qt::KeyboardModifiers modifierCodes = Qt::NoModifier ); - const QwtArray<MousePattern> &mousePattern() const; - const QwtArray<KeyPattern> &keyPattern() const; + void setMousePattern( const QVector<MousePattern> & ); + void setKeyPattern( const QVector<KeyPattern> & ); - QwtArray<MousePattern> &mousePattern(); - QwtArray<KeyPattern> &keyPattern(); + const QVector<MousePattern> &mousePattern() const; + const QVector<KeyPattern> &keyPattern() const; - bool mouseMatch(uint pattern, const QMouseEvent *) const; - bool keyMatch(uint pattern, const QKeyEvent *) const; + QVector<MousePattern> &mousePattern(); + QVector<KeyPattern> &keyPattern(); + + bool mouseMatch( MousePatternCode, const QMouseEvent * ) const; + bool keyMatch( KeyPatternCode, const QKeyEvent * ) const; protected: - virtual bool mouseMatch(const MousePattern &, const QMouseEvent *) const; - virtual bool keyMatch(const KeyPattern &, const QKeyEvent *) const; + virtual bool mouseMatch( const MousePattern &, const QMouseEvent * ) const; + virtual bool keyMatch( const KeyPattern &, const QKeyEvent * ) const; private: @@ -188,30 +216,25 @@ private: #pragma warning(push) #pragma warning(disable: 4251) #endif - QwtArray<MousePattern> d_mousePattern; - QwtArray<KeyPattern> d_keyPattern; + QVector<MousePattern> d_mousePattern; + QVector<KeyPattern> d_keyPattern; #if defined(_MSC_VER) #pragma warning(pop) #endif }; -inline bool operator==(QwtEventPattern::MousePattern b1, - QwtEventPattern::MousePattern b2) +//! Compare operator +inline bool operator==( QwtEventPattern::MousePattern b1, + QwtEventPattern::MousePattern b2 ) { - return b1.button == b2.button && b1.state == b2.state; + return b1.button == b2.button && b1.modifiers == b2.modifiers; } -inline bool operator==(QwtEventPattern::KeyPattern b1, - QwtEventPattern::KeyPattern b2) +//! Compare operator +inline bool operator==( QwtEventPattern::KeyPattern b1, + QwtEventPattern::KeyPattern b2 ) { - return b1.key == b2.key && b1.state == b2.state; + return b1.key == b2.key && b1.modifiers == b2.modifiers; } -#if defined(QWT_TEMPLATEDLL) -// MOC_SKIP_BEGIN -template class QWT_EXPORT QwtArray<QwtEventPattern::MousePattern>; -template class QWT_EXPORT QwtArray<QwtEventPattern::KeyPattern>; -// MOC_SKIP_END -#endif - #endif diff --git a/libs/qwt/qwt_global.h b/libs/qwt/qwt_global.h index d8c96e5898..3833077c59 100644 --- a/libs/qwt/qwt_global.h +++ b/libs/qwt/qwt_global.h @@ -7,45 +7,35 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_GLOBAL_H #define QWT_GLOBAL_H #include <qglobal.h> -#if QT_VERSION < 0x040000 -#include <qmodules.h> -#endif // QWT_VERSION is (major << 16) + (minor << 8) + patch. -#define QWT_VERSION 0x050102 -#define QWT_VERSION_STR "5.1.2" - -#if defined(Q_WS_WIN) +#define QWT_VERSION 0x060101 +#define QWT_VERSION_STR "6.1.1" #if defined(_MSC_VER) /* MSVC Compiler */ /* template-class specialization 'identifier' is already instantiated */ #pragma warning(disable: 4660) +/* inherits via dominance */ +#pragma warning(disable: 4250) #endif // _MSC_VER #ifdef QWT_DLL #if defined(QWT_MAKEDLL) // create a Qwt DLL library -#define QWT_EXPORT __declspec(dllexport) -#define QWT_TEMPLATEDLL +#define QWT_EXPORT Q_DECL_EXPORT #else // use a Qwt DLL library -#define QWT_EXPORT __declspec(dllimport) +#define QWT_EXPORT Q_DECL_IMPORT #endif #endif // QWT_DLL -#endif // Q_WS_WIN - #ifndef QWT_EXPORT #define QWT_EXPORT #endif -// #define QWT_NO_COMPAT 1 // disable withdrawn functionality - -#endif // QWT_GLOBAL_H +#endif diff --git a/libs/qwt/qwt_graphic.cpp b/libs/qwt/qwt_graphic.cpp new file mode 100644 index 0000000000..d67bcea0e0 --- /dev/null +++ b/libs/qwt/qwt_graphic.cpp @@ -0,0 +1,986 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_graphic.h" +#include "qwt_painter_command.h" +#include <qvector.h> +#include <qpainter.h> +#include <qpaintengine.h> +#include <qimage.h> +#include <qpixmap.h> +#include <qpainterpath.h> +#include <qmath.h> + +static bool qwtHasScalablePen( const QPainter *painter ) +{ + const QPen pen = painter->pen(); + + bool scalablePen = false; + + if ( pen.style() != Qt::NoPen && pen.brush().style() != Qt::NoBrush ) + { + scalablePen = !pen.isCosmetic(); + if ( !scalablePen && pen.widthF() == 0.0 ) + { + const QPainter::RenderHints hints = painter->renderHints(); + if ( hints.testFlag( QPainter::NonCosmeticDefaultPen ) ) + scalablePen = true; + } + } + + return scalablePen; +} + +static QRectF qwtStrokedPathRect( + const QPainter *painter, const QPainterPath &path ) +{ + QPainterPathStroker stroker; + stroker.setWidth( painter->pen().widthF() ); + stroker.setCapStyle( painter->pen().capStyle() ); + stroker.setJoinStyle( painter->pen().joinStyle() ); + stroker.setMiterLimit( painter->pen().miterLimit() ); + + QRectF rect; + if ( qwtHasScalablePen( painter ) ) + { + QPainterPath stroke = stroker.createStroke(path); + rect = painter->transform().map(stroke).boundingRect(); + } + else + { + QPainterPath mappedPath = painter->transform().map(path); + mappedPath = stroker.createStroke( mappedPath ); + + rect = mappedPath.boundingRect(); + } + + return rect; +} + +static inline void qwtExecCommand( + QPainter *painter, const QwtPainterCommand &cmd, + QwtGraphic::RenderHints renderHints, + const QTransform &transform ) +{ + switch( cmd.type() ) + { + case QwtPainterCommand::Path: + { + bool doMap = false; + + if ( renderHints.testFlag( QwtGraphic::RenderPensUnscaled ) + && painter->transform().isScaling() ) + { + bool isCosmetic = painter->pen().isCosmetic(); + if ( isCosmetic && painter->pen().widthF() == 0.0 ) + { + QPainter::RenderHints hints = painter->renderHints(); + if ( hints.testFlag( QPainter::NonCosmeticDefaultPen ) ) + isCosmetic = false; + } + + doMap = !isCosmetic; + } + + if ( doMap ) + { + const QTransform transform = painter->transform(); + + painter->resetTransform(); + painter->drawPath( transform.map( *cmd.path() ) ); + + painter->setTransform( transform ); + } + else + { + painter->drawPath( *cmd.path() ); + } + break; + } + case QwtPainterCommand::Pixmap: + { + const QwtPainterCommand::PixmapData *data = cmd.pixmapData(); + painter->drawPixmap( data->rect, data->pixmap, data->subRect ); + break; + } + case QwtPainterCommand::Image: + { + const QwtPainterCommand::ImageData *data = cmd.imageData(); + painter->drawImage( data->rect, data->image, + data->subRect, data->flags ); + break; + } + case QwtPainterCommand::State: + { + const QwtPainterCommand::StateData *data = cmd.stateData(); + + if ( data->flags & QPaintEngine::DirtyPen ) + painter->setPen( data->pen ); + + if ( data->flags & QPaintEngine::DirtyBrush ) + painter->setBrush( data->brush ); + + if ( data->flags & QPaintEngine::DirtyBrushOrigin ) + painter->setBrushOrigin( data->brushOrigin ); + + if ( data->flags & QPaintEngine::DirtyFont ) + painter->setFont( data->font ); + + if ( data->flags & QPaintEngine::DirtyBackground ) + { + painter->setBackgroundMode( data->backgroundMode ); + painter->setBackground( data->backgroundBrush ); + } + + if ( data->flags & QPaintEngine::DirtyTransform ) + { + painter->setTransform( data->transform * transform ); + } + + if ( data->flags & QPaintEngine::DirtyClipEnabled ) + painter->setClipping( data->isClipEnabled ); + + if ( data->flags & QPaintEngine::DirtyClipRegion) + { + painter->setClipRegion( data->clipRegion, + data->clipOperation ); + } + + if ( data->flags & QPaintEngine::DirtyClipPath ) + { + painter->setClipPath( data->clipPath, data->clipOperation ); + } + + if ( data->flags & QPaintEngine::DirtyHints) + { + const QPainter::RenderHints hints = data->renderHints; + + painter->setRenderHint( QPainter::Antialiasing, + hints.testFlag( QPainter::Antialiasing ) ); + + painter->setRenderHint( QPainter::TextAntialiasing, + hints.testFlag( QPainter::TextAntialiasing ) ); + + painter->setRenderHint( QPainter::SmoothPixmapTransform, + hints.testFlag( QPainter::SmoothPixmapTransform ) ); + + painter->setRenderHint( QPainter::HighQualityAntialiasing, + hints.testFlag( QPainter::HighQualityAntialiasing ) ); + + painter->setRenderHint( QPainter::NonCosmeticDefaultPen, + hints.testFlag( QPainter::NonCosmeticDefaultPen ) ); + } + + if ( data->flags & QPaintEngine::DirtyCompositionMode) + painter->setCompositionMode( data->compositionMode ); + + if ( data->flags & QPaintEngine::DirtyOpacity) + painter->setOpacity( data->opacity ); + + break; + } + default: + break; + } + +} + +class QwtGraphic::PathInfo +{ +public: + PathInfo(): + d_scalablePen( false ) + { + // QVector needs a default constructor + } + + PathInfo( const QRectF &pointRect, + const QRectF &boundingRect, bool scalablePen ): + d_pointRect( pointRect ), + d_boundingRect( boundingRect ), + d_scalablePen( scalablePen ) + { + } + + inline QRectF scaledBoundingRect( double sx, double sy, + bool scalePens ) const + { + if ( sx == 1.0 && sy == 1.0 ) + return d_boundingRect; + + QTransform transform; + transform.scale( sx, sy ); + + QRectF rect; + if ( scalePens && d_scalablePen ) + { + rect = transform.mapRect( d_boundingRect ); + } + else + { + rect = transform.mapRect( d_pointRect ); + + const double l = qAbs( d_pointRect.left() - d_boundingRect.left() ); + const double r = qAbs( d_pointRect.right() - d_boundingRect.right() ); + const double t = qAbs( d_pointRect.top() - d_boundingRect.top() ); + const double b = qAbs( d_pointRect.bottom() - d_boundingRect.bottom() ); + + rect.adjust( -l, -t, r, b ); + } + + return rect; + } + + inline double scaleFactorX( const QRectF& pathRect, + const QRectF &targetRect, bool scalePens ) const + { + if ( pathRect.width() <= 0.0 ) + return 0.0; + + const QPointF p0 = d_pointRect.center(); + + const double l = qAbs( pathRect.left() - p0.x() ); + const double r = qAbs( pathRect.right() - p0.x() ); + + const double w = 2.0 * qMin( l, r ) + * targetRect.width() / pathRect.width(); + + double sx; + if ( scalePens && d_scalablePen ) + { + sx = w / d_boundingRect.width(); + } + else + { + const double pw = qMax( + qAbs( d_boundingRect.left() - d_pointRect.left() ), + qAbs( d_boundingRect.right() - d_pointRect.right() ) ); + + sx = ( w - 2 * pw ) / d_pointRect.width(); + } + + return sx; + } + + inline double scaleFactorY( const QRectF& pathRect, + const QRectF &targetRect, bool scalePens ) const + { + if ( pathRect.height() <= 0.0 ) + return 0.0; + + const QPointF p0 = d_pointRect.center(); + + const double t = qAbs( pathRect.top() - p0.y() ); + const double b = qAbs( pathRect.bottom() - p0.y() ); + + const double h = 2.0 * qMin( t, b ) + * targetRect.height() / pathRect.height(); + + double sy; + if ( scalePens && d_scalablePen ) + { + sy = h / d_boundingRect.height(); + } + else + { + const double pw = + qMax( qAbs( d_boundingRect.top() - d_pointRect.top() ), + qAbs( d_boundingRect.bottom() - d_pointRect.bottom() ) ); + + sy = ( h - 2 * pw ) / d_pointRect.height(); + } + + return sy; + } + +private: + QRectF d_pointRect; + QRectF d_boundingRect; + bool d_scalablePen; +}; + +class QwtGraphic::PrivateData +{ +public: + PrivateData(): + boundingRect( 0.0, 0.0, -1.0, -1.0 ), + pointRect( 0.0, 0.0, -1.0, -1.0 ) + { + } + + QSizeF defaultSize; + QVector<QwtPainterCommand> commands; + QVector<QwtGraphic::PathInfo> pathInfos; + + QRectF boundingRect; + QRectF pointRect; + + QwtGraphic::RenderHints renderHints; +}; + +/*! + \brief Constructor + + Initializes a null graphic + \sa isNull() + */ +QwtGraphic::QwtGraphic(): + QwtNullPaintDevice() +{ + setMode( QwtNullPaintDevice::PathMode ); + d_data = new PrivateData; +} + +/*! + \brief Copy constructor + + \param other Source + \sa operator=() + */ +QwtGraphic::QwtGraphic( const QwtGraphic &other ): + QwtNullPaintDevice() +{ + setMode( other.mode() ); + d_data = new PrivateData( *other.d_data ); +} + +//! Destructor +QwtGraphic::~QwtGraphic() +{ + delete d_data; +} + +/*! + \brief Assignment operator + + \param other Source + \return A reference of this object + */ +QwtGraphic& QwtGraphic::operator=(const QwtGraphic &other) +{ + setMode( other.mode() ); + *d_data = *other.d_data; + + return *this; +} + +/*! + \brief Clear all stored commands + \sa isNull() + */ +void QwtGraphic::reset() +{ + d_data->commands.clear(); + d_data->pathInfos.clear(); + + d_data->boundingRect = QRectF( 0.0, 0.0, -1.0, -1.0 ); + d_data->pointRect = QRectF( 0.0, 0.0, -1.0, -1.0 ); + d_data->defaultSize = QSizeF(); + +} + +/*! + \return True, when no painter commands have been stored + \sa isEmpty(), commands() +*/ +bool QwtGraphic::isNull() const +{ + return d_data->commands.isEmpty(); +} + +/*! + \return True, when the bounding rectangle is empty + \sa boundingRect(), isNull() +*/ +bool QwtGraphic::isEmpty() const +{ + return d_data->boundingRect.isEmpty(); +} + +/*! + Toggle an render hint + + \param hint Render hint + \param on true/false + + \sa testRenderHint(), RenderHint +*/ +void QwtGraphic::setRenderHint( RenderHint hint, bool on ) +{ + if ( on ) + d_data->renderHints |= hint; + else + d_data->renderHints &= ~hint; +} + +/*! + Test a render hint + + \param hint Render hint + \return true/false + \sa setRenderHint(), RenderHint +*/ +bool QwtGraphic::testRenderHint( RenderHint hint ) const +{ + return d_data->renderHints.testFlag( hint ); +} + +/*! + The bounding rectangle is the controlPointRect() + extended by the areas needed for rendering the outlines + with unscaled pens. + + \return Bounding rectangle of the graphic + \sa controlPointRect(), scaledBoundingRect() + */ +QRectF QwtGraphic::boundingRect() const +{ + if ( d_data->boundingRect.width() < 0 ) + return QRectF(); + + return d_data->boundingRect; +} + +/*! + The control point rectangle is the bounding rectangle + of all control points of the paths and the target + rectangles of the images/pixmaps. + + \return Control point rectangle + \sa boundingRect(), scaledBoundingRect() + */ +QRectF QwtGraphic::controlPointRect() const +{ + if ( d_data->pointRect.width() < 0 ) + return QRectF(); + + return d_data->pointRect; +} + +/*! + \brief Calculate the target rectangle for scaling the graphic + + \param sx Horizontal scaling factor + \param sy Vertical scaling factor + + \note In case of paths that are painted with a cosmetic pen + ( see QPen::isCosmetic() ) the target rectangle is different to + multiplying the bounding rectangle. + + \return Scaled bounding rectangle + \sa boundingRect(), controlPointRect() + */ +QRectF QwtGraphic::scaledBoundingRect( double sx, double sy ) const +{ + if ( sx == 1.0 && sy == 1.0 ) + return d_data->boundingRect; + + QTransform transform; + transform.scale( sx, sy ); + + QRectF rect = transform.mapRect( d_data->pointRect ); + + for ( int i = 0; i < d_data->pathInfos.size(); i++ ) + { + rect |= d_data->pathInfos[i].scaledBoundingRect( sx, sy, + !d_data->renderHints.testFlag( RenderPensUnscaled ) ); + } + + return rect; +} + +//! \return Ceiled defaultSize() +QSize QwtGraphic::sizeMetrics() const +{ + const QSizeF sz = defaultSize(); + return QSize( qCeil( sz.width() ), qCeil( sz.height() ) ); +} + +/*! + \brief Set a default size + + The default size is used in all methods rendering the graphic, + where no size is explicitly specified. Assigning an empty size + means, that the default size will be calculated from the bounding + rectangle. + + The default setting is an empty size. + + \param size Default size + + \sa defaultSize(), boundingRect() + */ +void QwtGraphic::setDefaultSize( const QSizeF &size ) +{ + const double w = qMax( qreal( 0.0 ), size.width() ); + const double h = qMax( qreal( 0.0 ), size.height() ); + + d_data->defaultSize = QSizeF( w, h ); +} + +/*! + \brief Default size + + When a non empty size has been assigned by setDefaultSize() this + size will be returned. Otherwise the default size is the size + of the bounding rectangle. + + The default size is used in all methods rendering the graphic, + where no size is explicitly specified. + + \return Default size + \sa setDefaultSize(), boundingRect() + */ +QSizeF QwtGraphic::defaultSize() const +{ + if ( !d_data->defaultSize.isEmpty() ) + return d_data->defaultSize; + + return boundingRect().size(); +} + +/*! + \brief Replay all recorded painter commands + \param painter Qt painter + */ +void QwtGraphic::render( QPainter *painter ) const +{ + if ( isNull() ) + return; + + const int numCommands = d_data->commands.size(); + const QwtPainterCommand *commands = d_data->commands.constData(); + + const QTransform transform = painter->transform(); + + painter->save(); + + for ( int i = 0; i < numCommands; i++ ) + { + qwtExecCommand( painter, commands[i], + d_data->renderHints, transform ); + } + + painter->restore(); +} + +/*! + \brief Replay all recorded painter commands + + The graphic is scaled to fit into the rectangle + of the given size starting at ( 0, 0 ). + + \param painter Qt painter + \param size Size for the scaled graphic + \param aspectRatioMode Mode how to scale - See Qt::AspectRatioMode + */ +void QwtGraphic::render( QPainter *painter, const QSizeF &size, + Qt::AspectRatioMode aspectRatioMode ) const +{ + const QRectF r( 0.0, 0.0, size.width(), size.height() ); + render( painter, r, aspectRatioMode ); +} + +/*! + \brief Replay all recorded painter commands + + The graphic is scaled to fit into the given rectangle + + \param painter Qt painter + \param rect Rectangle for the scaled graphic + \param aspectRatioMode Mode how to scale - See Qt::AspectRatioMode + */ +void QwtGraphic::render( QPainter *painter, const QRectF &rect, + Qt::AspectRatioMode aspectRatioMode ) const +{ + if ( isEmpty() || rect.isEmpty() ) + return; + + double sx = 1.0; + double sy = 1.0; + + if ( d_data->pointRect.width() > 0.0 ) + sx = rect.width() / d_data->pointRect.width(); + + if ( d_data->pointRect.height() > 0.0 ) + sy = rect.height() / d_data->pointRect.height(); + + const bool scalePens = + !d_data->renderHints.testFlag( RenderPensUnscaled ); + + for ( int i = 0; i < d_data->pathInfos.size(); i++ ) + { + const PathInfo info = d_data->pathInfos[i]; + + const double ssx = info.scaleFactorX( + d_data->pointRect, rect, scalePens ); + + if ( ssx > 0.0 ) + sx = qMin( sx, ssx ); + + const double ssy = info.scaleFactorY( + d_data->pointRect, rect, scalePens ); + + if ( ssy > 0.0 ) + sy = qMin( sy, ssy ); + } + + if ( aspectRatioMode == Qt::KeepAspectRatio ) + { + const double s = qMin( sx, sy ); + sx = s; + sy = s; + } + else if ( aspectRatioMode == Qt::KeepAspectRatioByExpanding ) + { + const double s = qMax( sx, sy ); + sx = s; + sy = s; + } + + QTransform tr; + tr.translate( rect.center().x() - 0.5 * sx * d_data->pointRect.width(), + rect.center().y() - 0.5 * sy * d_data->pointRect.height() ); + tr.scale( sx, sy ); + tr.translate( -d_data->pointRect.x(), -d_data->pointRect.y() ); + + const QTransform transform = painter->transform(); + + painter->setTransform( tr, true ); + render( painter ); + + painter->setTransform( transform ); +} + +/*! + \brief Replay all recorded painter commands + + The graphic is scaled to the defaultSize() and aligned + to a position. + + \param painter Qt painter + \param pos Reference point, where to render + \param alignment Flags how to align the target rectangle + to pos. + */ +void QwtGraphic::render( QPainter *painter, + const QPointF &pos, Qt::Alignment alignment ) const +{ + QRectF r( pos, defaultSize() ); + + if ( alignment & Qt::AlignLeft ) + { + r.moveLeft( pos.x() ); + } + else if ( alignment & Qt::AlignHCenter ) + { + r.moveCenter( QPointF( pos.x(), r.center().y() ) ); + } + else if ( alignment & Qt::AlignRight ) + { + r.moveRight( pos.x() ); + } + + if ( alignment & Qt::AlignTop ) + { + r.moveTop( pos.y() ); + } + else if ( alignment & Qt::AlignVCenter ) + { + r.moveCenter( QPointF( r.center().x(), pos.y() ) ); + } + else if ( alignment & Qt::AlignBottom ) + { + r.moveBottom( pos.y() ); + } + + render( painter, r ); +} + +/*! + \brief Convert the graphic to a QPixmap + + All pixels of the pixmap get initialized by Qt::transparent + before the graphic is scaled and rendered on it. + + The size of the pixmap is the default size ( ceiled to integers ) + of the graphic. + + \return The graphic as pixmap in default size + \sa defaultSize(), toImage(), render() + */ +QPixmap QwtGraphic::toPixmap() const +{ + if ( isNull() ) + return QPixmap(); + + const QSizeF sz = defaultSize(); + + const int w = qCeil( sz.width() ); + const int h = qCeil( sz.height() ); + + QPixmap pixmap( w, h ); + pixmap.fill( Qt::transparent ); + + const QRectF r( 0.0, 0.0, sz.width(), sz.height() ); + + QPainter painter( &pixmap ); + render( &painter, r, Qt::KeepAspectRatio ); + painter.end(); + + return pixmap; +} + +/*! + \brief Convert the graphic to a QPixmap + + All pixels of the pixmap get initialized by Qt::transparent + before the graphic is scaled and rendered on it. + + \param size Size of the image + \param aspectRatioMode Aspect ratio how to scale the graphic + + \return The graphic as pixmap + \sa toImage(), render() + */ +QPixmap QwtGraphic::toPixmap( const QSize &size, + Qt::AspectRatioMode aspectRatioMode ) const +{ + QPixmap pixmap( size ); + pixmap.fill( Qt::transparent ); + + const QRect r( 0, 0, size.width(), size.height() ); + + QPainter painter( &pixmap ); + render( &painter, r, aspectRatioMode ); + painter.end(); + + return pixmap; +} + +/*! + \brief Convert the graphic to a QImage + + All pixels of the image get initialized by 0 ( transparent ) + before the graphic is scaled and rendered on it. + + The format of the image is QImage::Format_ARGB32_Premultiplied. + + \param size Size of the image + \param aspectRatioMode Aspect ratio how to scale the graphic + + \return The graphic as image + \sa toPixmap(), render() + */ +QImage QwtGraphic::toImage( const QSize &size, + Qt::AspectRatioMode aspectRatioMode ) const +{ + QImage image( size, QImage::Format_ARGB32_Premultiplied ); + image.fill( 0 ); + + const QRect r( 0, 0, size.width(), size.height() ); + + QPainter painter( &image ); + render( &painter, r, aspectRatioMode ); + painter.end(); + + return image; +} + +/*! + \brief Convert the graphic to a QImage + + All pixels of the image get initialized by 0 ( transparent ) + before the graphic is scaled and rendered on it. + + The format of the image is QImage::Format_ARGB32_Premultiplied. + + The size of the image is the default size ( ceiled to integers ) + of the graphic. + + \return The graphic as image in default size + \sa defaultSize(), toPixmap(), render() + */ +QImage QwtGraphic::toImage() const +{ + if ( isNull() ) + return QImage(); + + const QSizeF sz = defaultSize(); + + const int w = qCeil( sz.width() ); + const int h = qCeil( sz.height() ); + + QImage image( w, h, QImage::Format_ARGB32 ); + image.fill( 0 ); + + const QRect r( 0, 0, sz.width(), sz.height() ); + + QPainter painter( &image ); + render( &painter, r, Qt::KeepAspectRatio ); + painter.end(); + + return image; +} + +/*! + Store a path command in the command list + + \param path Painter path + \sa QPaintEngine::drawPath() +*/ +void QwtGraphic::drawPath( const QPainterPath &path ) +{ + const QPainter *painter = paintEngine()->painter(); + if ( painter == NULL ) + return; + + d_data->commands += QwtPainterCommand( path ); + + if ( !path.isEmpty() ) + { + const QPainterPath scaledPath = painter->transform().map( path ); + + QRectF pointRect = scaledPath.boundingRect(); + QRectF boundingRect = pointRect; + + if ( painter->pen().style() != Qt::NoPen + && painter->pen().brush().style() != Qt::NoBrush ) + { + boundingRect = qwtStrokedPathRect( painter, path ); + } + + updateControlPointRect( pointRect ); + updateBoundingRect( boundingRect ); + + d_data->pathInfos += PathInfo( pointRect, + boundingRect, qwtHasScalablePen( painter ) ); + } +} + +/*! + \brief Store a pixmap command in the command list + + \param rect target rectangle + \param pixmap Pixmap to be painted + \param subRect Reactangle of the pixmap to be painted + + \sa QPaintEngine::drawPixmap() +*/ +void QwtGraphic::drawPixmap( const QRectF &rect, + const QPixmap &pixmap, const QRectF &subRect ) +{ + const QPainter *painter = paintEngine()->painter(); + if ( painter == NULL ) + return; + + d_data->commands += QwtPainterCommand( rect, pixmap, subRect ); + + const QRectF r = painter->transform().mapRect( rect ); + updateControlPointRect( r ); + updateBoundingRect( r ); +} + +/*! + \brief Store a image command in the command list + + \param rect traget rectangle + \param image Image to be painted + \param subRect Reactangle of the pixmap to be painted + \param flags Image conversion flags + + \sa QPaintEngine::drawImage() + */ +void QwtGraphic::drawImage( const QRectF &rect, const QImage &image, + const QRectF &subRect, Qt::ImageConversionFlags flags) +{ + const QPainter *painter = paintEngine()->painter(); + if ( painter == NULL ) + return; + + d_data->commands += QwtPainterCommand( rect, image, subRect, flags ); + + const QRectF r = painter->transform().mapRect( rect ); + + updateControlPointRect( r ); + updateBoundingRect( r ); +} + +/*! + \brief Store a state command in the command list + + \param state State to be stored + \sa QPaintEngine::updateState() + */ +void QwtGraphic::updateState( const QPaintEngineState &state) +{ + d_data->commands += QwtPainterCommand( state ); +} + +void QwtGraphic::updateBoundingRect( const QRectF &rect ) +{ + QRectF br = rect; + + const QPainter *painter = paintEngine()->painter(); + if ( painter && painter->hasClipping() ) + { + QRectF cr = painter->clipRegion().boundingRect(); + cr = painter->transform().mapRect( br ); + + br &= cr; + } + + if ( d_data->boundingRect.width() < 0 ) + d_data->boundingRect = br; + else + d_data->boundingRect |= br; +} + +void QwtGraphic::updateControlPointRect( const QRectF &rect ) +{ + if ( d_data->pointRect.width() < 0.0 ) + d_data->pointRect = rect; + else + d_data->pointRect |= rect; +} + +/*! + \return List of recorded paint commands + \sa setCommands() + */ +const QVector< QwtPainterCommand > &QwtGraphic::commands() const +{ + return d_data->commands; +} + +/*! + \brief Append paint commands + + \param commands Paint commands + \sa commands() + */ +void QwtGraphic::setCommands( QVector< QwtPainterCommand > &commands ) +{ + reset(); + + const int numCommands = commands.size(); + if ( numCommands <= 0 ) + return; + + // to calculate a proper bounding rectangle we don't simply copy + // the commands. + + const QwtPainterCommand *cmds = commands.constData(); + + QPainter painter( this ); + for ( int i = 0; i < numCommands; i++ ) + qwtExecCommand( &painter, cmds[i], RenderHints(), QTransform() ); + + painter.end(); +} diff --git a/libs/qwt/qwt_graphic.h b/libs/qwt/qwt_graphic.h new file mode 100644 index 0000000000..a1ce1e8a2a --- /dev/null +++ b/libs/qwt/qwt_graphic.h @@ -0,0 +1,172 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_GRAPHIC_H +#define QWT_GRAPHIC_H + +#include "qwt_global.h" +#include "qwt_null_paintdevice.h" +#include <qmetatype.h> +#include <qimage.h> +#include <qpixmap.h> + +class QwtPainterCommand; + +/*! + \brief A paint device for scalable graphics + + QwtGraphic is the representation of a graphic that is tailored for + scalability. Like QPicture it will be initialized by QPainter + operations and can be replayed later to any target paint device. + + While the usual image representations QImage and QPixmap are not + scalable Qt offers two paint devices, that might be candidates + for representing a vector graphic: + + - QPicture\n + Unfortunately QPicture had been forgotten, when Qt4 + introduced floating point based render engines. Its API + is still on integers, what make it unusable for proper scaling. + + - QSvgRenderer/QSvgGenerator\n + Unfortunately QSvgRenderer hides to much information about + its nodes in internal APIs, that are necessary for proper + layout calculations. Also it is derived from QObject and + can't be copied like QImage/QPixmap. + + QwtGraphic maps all scalable drawing primitives to a QPainterPath + and stores them together with the painter state changes + ( pen, brush, transformation ... ) in a list of QwtPaintCommands. + For being a complete QPaintDevice it also stores pixmaps or images, + what is somehow against the idea of the class, because these objects + can't be scaled without a loss in quality. + + The main issue about scaling a QwtGraphic object are the pens used for + drawing the outlines of the painter paths. While non cosmetic pens + ( QPen::isCosmetic() ) are scaled with the same ratio as the path, + cosmetic pens have a fixed width. A graphic might have paths with + different pens - cosmetic and non-cosmetic. + + QwtGraphic caches 2 different rectangles: + + - control point rectangle\n + The control point rectangle is the bounding rectangle of all + control point rectangles of the painter paths, or the target + rectangle of the pixmaps/images. + + - bounding rectangle\n + The bounding rectangle extends the control point rectangle by + what is needed for rendering the outline with an unscaled pen. + + Because the offset for drawing the outline depends on the shape + of the painter path ( the peak of a triangle is different than the flat side ) + scaling with a fixed aspect ratio always needs to be calculated from the + control point rectangle. + + \sa QwtPainterCommand + */ +class QWT_EXPORT QwtGraphic: public QwtNullPaintDevice +{ +public: + /*! + Hint how to render a graphic + \sa setRenderHint(), testRenderHint() + */ + enum RenderHint + { + /*! + When RenderPensUnscaled is set non cosmetic pens are + painted unscaled - like cosmetic pens. The difference to + using cosmetic pens is, when the graphic is rendered + to a document in a scalable vector format ( PDF, SVG ): + the width of non cosmetic pens will be scaled by the + document viewer. + */ + RenderPensUnscaled = 0x1 + }; + + /*! + \brief Render hints + + The default setting is to disable all hints + */ + typedef QFlags<RenderHint> RenderHints; + + QwtGraphic(); + QwtGraphic( const QwtGraphic & ); + + virtual ~QwtGraphic(); + + QwtGraphic& operator=( const QwtGraphic & ); + + void reset(); + + bool isNull() const; + bool isEmpty() const; + + void render( QPainter * ) const; + + void render( QPainter *, const QSizeF &, + Qt::AspectRatioMode = Qt::IgnoreAspectRatio ) const; + + void render( QPainter *, const QRectF &, + Qt::AspectRatioMode = Qt::IgnoreAspectRatio ) const; + + void render( QPainter *, const QPointF &, + Qt::Alignment = Qt::AlignTop | Qt::AlignLeft ) const; + + QPixmap toPixmap() const; + QPixmap toPixmap( const QSize &, + Qt::AspectRatioMode = Qt::IgnoreAspectRatio ) const; + + QImage toImage() const; + QImage toImage( const QSize &, + Qt::AspectRatioMode = Qt::IgnoreAspectRatio ) const; + + QRectF scaledBoundingRect( double sx, double sy ) const; + + QRectF boundingRect() const; + QRectF controlPointRect() const; + + const QVector< QwtPainterCommand > &commands() const; + void setCommands( QVector< QwtPainterCommand > & ); + + void setDefaultSize( const QSizeF & ); + QSizeF defaultSize() const; + + void setRenderHint( RenderHint, bool on = true ); + bool testRenderHint( RenderHint ) const; + +protected: + virtual QSize sizeMetrics() const; + + virtual void drawPath( const QPainterPath & ); + + virtual void drawPixmap( const QRectF &, + const QPixmap &, const QRectF & ); + + virtual void drawImage( const QRectF &, + const QImage &, const QRectF &, Qt::ImageConversionFlags ); + + virtual void updateState( const QPaintEngineState &state ); + +private: + void updateBoundingRect( const QRectF & ); + void updateControlPointRect( const QRectF & ); + + class PathInfo; + + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtGraphic::RenderHints ) +Q_DECLARE_METATYPE( QwtGraphic ) + +#endif diff --git a/libs/qwt/qwt_interval.cpp b/libs/qwt/qwt_interval.cpp new file mode 100644 index 0000000000..b7c6ee9920 --- /dev/null +++ b/libs/qwt/qwt_interval.cpp @@ -0,0 +1,354 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_interval.h" +#include "qwt_math.h" +#include <qalgorithms.h> + +/*! + \brief Normalize the limits of the interval + + If maxValue() < minValue() the limits will be inverted. + \return Normalized interval + + \sa isValid(), inverted() +*/ +QwtInterval QwtInterval::normalized() const +{ + if ( d_minValue > d_maxValue ) + { + return inverted(); + } + if ( d_minValue == d_maxValue && d_borderFlags == ExcludeMinimum ) + { + return inverted(); + } + + return *this; +} + +/*! + Invert the limits of the interval + \return Inverted interval + \sa normalized() +*/ +QwtInterval QwtInterval::inverted() const +{ + BorderFlags borderFlags = IncludeBorders; + if ( d_borderFlags & ExcludeMinimum ) + borderFlags |= ExcludeMaximum; + if ( d_borderFlags & ExcludeMaximum ) + borderFlags |= ExcludeMinimum; + + return QwtInterval( d_maxValue, d_minValue, borderFlags ); +} + +/*! + Test if a value is inside an interval + + \param value Value + \return true, if value >= minValue() && value <= maxValue() +*/ +bool QwtInterval::contains( double value ) const +{ + if ( !isValid() ) + return false; + + if ( value < d_minValue || value > d_maxValue ) + return false; + + if ( value == d_minValue && d_borderFlags & ExcludeMinimum ) + return false; + + if ( value == d_maxValue && d_borderFlags & ExcludeMaximum ) + return false; + + return true; +} + +//! Unite 2 intervals +QwtInterval QwtInterval::unite( const QwtInterval &other ) const +{ + /* + If one of the intervals is invalid return the other one. + If both are invalid return an invalid default interval + */ + if ( !isValid() ) + { + if ( !other.isValid() ) + return QwtInterval(); + else + return other; + } + if ( !other.isValid() ) + return *this; + + QwtInterval united; + BorderFlags flags = IncludeBorders; + + // minimum + if ( d_minValue < other.minValue() ) + { + united.setMinValue( d_minValue ); + flags &= d_borderFlags & ExcludeMinimum; + } + else if ( other.minValue() < d_minValue ) + { + united.setMinValue( other.minValue() ); + flags &= other.borderFlags() & ExcludeMinimum; + } + else // d_minValue == other.minValue() + { + united.setMinValue( d_minValue ); + flags &= ( d_borderFlags & other.borderFlags() ) & ExcludeMinimum; + } + + // maximum + if ( d_maxValue > other.maxValue() ) + { + united.setMaxValue( d_maxValue ); + flags &= d_borderFlags & ExcludeMaximum; + } + else if ( other.maxValue() > d_maxValue ) + { + united.setMaxValue( other.maxValue() ); + flags &= other.borderFlags() & ExcludeMaximum; + } + else // d_maxValue == other.maxValue() ) + { + united.setMaxValue( d_maxValue ); + flags &= d_borderFlags & other.borderFlags() & ExcludeMaximum; + } + + united.setBorderFlags( flags ); + return united; +} + +/*! + \brief Intersect 2 intervals + + \param other Interval to be intersect with + \return Intersection + */ +QwtInterval QwtInterval::intersect( const QwtInterval &other ) const +{ + if ( !other.isValid() || !isValid() ) + return QwtInterval(); + + QwtInterval i1 = *this; + QwtInterval i2 = other; + + // swap i1/i2, so that the minimum of i1 + // is smaller then the minimum of i2 + + if ( i1.minValue() > i2.minValue() ) + { + qSwap( i1, i2 ); + } + else if ( i1.minValue() == i2.minValue() ) + { + if ( i1.borderFlags() & ExcludeMinimum ) + qSwap( i1, i2 ); + } + + if ( i1.maxValue() < i2.minValue() ) + { + return QwtInterval(); + } + + if ( i1.maxValue() == i2.minValue() ) + { + if ( i1.borderFlags() & ExcludeMaximum || + i2.borderFlags() & ExcludeMinimum ) + { + return QwtInterval(); + } + } + + QwtInterval intersected; + BorderFlags flags = IncludeBorders; + + intersected.setMinValue( i2.minValue() ); + flags |= i2.borderFlags() & ExcludeMinimum; + + if ( i1.maxValue() < i2.maxValue() ) + { + intersected.setMaxValue( i1.maxValue() ); + flags |= i1.borderFlags() & ExcludeMaximum; + } + else if ( i2.maxValue() < i1.maxValue() ) + { + intersected.setMaxValue( i2.maxValue() ); + flags |= i2.borderFlags() & ExcludeMaximum; + } + else // i1.maxValue() == i2.maxValue() + { + intersected.setMaxValue( i1.maxValue() ); + flags |= i1.borderFlags() & i2.borderFlags() & ExcludeMaximum; + } + + intersected.setBorderFlags( flags ); + return intersected; +} + +/*! + \brief Unite this interval with the given interval. + + \param other Interval to be united with + \return This interval + */ +QwtInterval& QwtInterval::operator|=( const QwtInterval &other ) +{ + *this = *this | other; + return *this; +} + +/*! + \brief Intersect this interval with the given interval. + + \param other Interval to be intersected with + \return This interval + */ +QwtInterval& QwtInterval::operator&=( const QwtInterval &other ) +{ + *this = *this & other; + return *this; +} + +/*! + \brief Test if two intervals overlap + + \param other Interval + \return True, when the intervals are intersecting +*/ +bool QwtInterval::intersects( const QwtInterval &other ) const +{ + if ( !isValid() || !other.isValid() ) + return false; + + QwtInterval i1 = *this; + QwtInterval i2 = other; + + // swap i1/i2, so that the minimum of i1 + // is smaller then the minimum of i2 + + if ( i1.minValue() > i2.minValue() ) + { + qSwap( i1, i2 ); + } + else if ( i1.minValue() == i2.minValue() && + i1.borderFlags() & ExcludeMinimum ) + { + qSwap( i1, i2 ); + } + + if ( i1.maxValue() > i2.minValue() ) + { + return true; + } + if ( i1.maxValue() == i2.minValue() ) + { + return !( ( i1.borderFlags() & ExcludeMaximum ) || + ( i2.borderFlags() & ExcludeMinimum ) ); + } + return false; +} + +/*! + Adjust the limit that is closer to value, so that value becomes + the center of the interval. + + \param value Center + \return Interval with value as center +*/ +QwtInterval QwtInterval::symmetrize( double value ) const +{ + if ( !isValid() ) + return *this; + + const double delta = + qMax( qAbs( value - d_maxValue ), qAbs( value - d_minValue ) ); + + return QwtInterval( value - delta, value + delta ); +} + +/*! + Limit the interval, keeping the border modes + + \param lowerBound Lower limit + \param upperBound Upper limit + + \return Limited interval +*/ +QwtInterval QwtInterval::limited( double lowerBound, double upperBound ) const +{ + if ( !isValid() || lowerBound > upperBound ) + return QwtInterval(); + + double minValue = qMax( d_minValue, lowerBound ); + minValue = qMin( minValue, upperBound ); + + double maxValue = qMax( d_maxValue, lowerBound ); + maxValue = qMin( maxValue, upperBound ); + + return QwtInterval( minValue, maxValue, d_borderFlags ); +} + +/*! + \brief Extend the interval + + If value is below minValue(), value becomes the lower limit. + If value is above maxValue(), value becomes the upper limit. + + extend() has no effect for invalid intervals + + \param value Value + \return extended interval + + \sa isValid() +*/ +QwtInterval QwtInterval::extend( double value ) const +{ + if ( !isValid() ) + return *this; + + return QwtInterval( qMin( value, d_minValue ), + qMax( value, d_maxValue ), d_borderFlags ); +} + +/*! + Extend an interval + + \param value Value + \return Reference of the extended interval + + \sa extend() +*/ +QwtInterval& QwtInterval::operator|=( double value ) +{ + *this = *this | value; + return *this; +} + +#ifndef QT_NO_DEBUG_STREAM + +QDebug operator<<( QDebug debug, const QwtInterval &interval ) +{ + const int flags = interval.borderFlags(); + + debug.nospace() << "QwtInterval(" + << ( ( flags & QwtInterval::ExcludeMinimum ) ? "]" : "[" ) + << interval.minValue() << "," << interval.maxValue() + << ( ( flags & QwtInterval::ExcludeMaximum ) ? "[" : "]" ) + << ")"; + + return debug.space(); +} + +#endif diff --git a/libs/qwt/qwt_interval.h b/libs/qwt/qwt_interval.h new file mode 100644 index 0000000000..68841e00b3 --- /dev/null +++ b/libs/qwt/qwt_interval.h @@ -0,0 +1,320 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_INTERVAL_H +#define QWT_INTERVAL_H + +#include "qwt_global.h" +#include <qmetatype.h> + +#ifndef QT_NO_DEBUG_STREAM +#include <qdebug.h> +#endif + +/*! + \brief A class representing an interval + + The interval is represented by 2 doubles, the lower and the upper limit. +*/ + +class QWT_EXPORT QwtInterval +{ +public: + /*! + Flag indicating if a border is included or excluded + \sa setBorderFlags(), borderFlags() + */ + enum BorderFlag + { + //! Min/Max values are inside the interval + IncludeBorders = 0x00, + + //! Min value is not included in the interval + ExcludeMinimum = 0x01, + + //! Max value is not included in the interval + ExcludeMaximum = 0x02, + + //! Min/Max values are not included in the interval + ExcludeBorders = ExcludeMinimum | ExcludeMaximum + }; + + //! Border flags + typedef QFlags<BorderFlag> BorderFlags; + + QwtInterval(); + QwtInterval( double minValue, double maxValue, + BorderFlags = IncludeBorders ); + + void setInterval( double minValue, double maxValue, + BorderFlags = IncludeBorders ); + + QwtInterval normalized() const; + QwtInterval inverted() const; + QwtInterval limited( double minValue, double maxValue ) const; + + bool operator==( const QwtInterval & ) const; + bool operator!=( const QwtInterval & ) const; + + void setBorderFlags( BorderFlags ); + BorderFlags borderFlags() const; + + double minValue() const; + double maxValue() const; + + double width() const; + + void setMinValue( double ); + void setMaxValue( double ); + + bool contains( double value ) const; + + bool intersects( const QwtInterval & ) const; + QwtInterval intersect( const QwtInterval & ) const; + QwtInterval unite( const QwtInterval & ) const; + + QwtInterval operator|( const QwtInterval & ) const; + QwtInterval operator&( const QwtInterval & ) const; + + QwtInterval &operator|=( const QwtInterval & ); + QwtInterval &operator&=( const QwtInterval & ); + + QwtInterval extend( double value ) const; + QwtInterval operator|( double ) const; + QwtInterval &operator|=( double ); + + bool isValid() const; + bool isNull() const; + void invalidate(); + + QwtInterval symmetrize( double value ) const; + +private: + double d_minValue; + double d_maxValue; + BorderFlags d_borderFlags; +}; + +Q_DECLARE_TYPEINFO(QwtInterval, Q_MOVABLE_TYPE); + +/*! + \brief Default Constructor + + Creates an invalid interval [0.0, -1.0] + \sa setInterval(), isValid() +*/ +inline QwtInterval::QwtInterval(): + d_minValue( 0.0 ), + d_maxValue( -1.0 ), + d_borderFlags( IncludeBorders ) +{ +} + +/*! + Constructor + + Build an interval with from min/max values + + \param minValue Minimum value + \param maxValue Maximum value + \param borderFlags Include/Exclude borders +*/ +inline QwtInterval::QwtInterval( + double minValue, double maxValue, BorderFlags borderFlags ): + d_minValue( minValue ), + d_maxValue( maxValue ), + d_borderFlags( borderFlags ) +{ +} + +/*! + Assign the limits of the interval + + \param minValue Minimum value + \param maxValue Maximum value + \param borderFlags Include/Exclude borders +*/ +inline void QwtInterval::setInterval( + double minValue, double maxValue, BorderFlags borderFlags ) +{ + d_minValue = minValue; + d_maxValue = maxValue; + d_borderFlags = borderFlags; +} + +/*! + Change the border flags + + \param borderFlags Or'd BorderMode flags + \sa borderFlags() +*/ +inline void QwtInterval::setBorderFlags( BorderFlags borderFlags ) +{ + d_borderFlags = borderFlags; +} + +/*! + \return Border flags + \sa setBorderFlags() +*/ +inline QwtInterval::BorderFlags QwtInterval::borderFlags() const +{ + return d_borderFlags; +} + +/*! + Assign the lower limit of the interval + + \param minValue Minimum value +*/ +inline void QwtInterval::setMinValue( double minValue ) +{ + d_minValue = minValue; +} + +/*! + Assign the upper limit of the interval + + \param maxValue Maximum value +*/ +inline void QwtInterval::setMaxValue( double maxValue ) +{ + d_maxValue = maxValue; +} + +//! \return Lower limit of the interval +inline double QwtInterval::minValue() const +{ + return d_minValue; +} + +//! \return Upper limit of the interval +inline double QwtInterval::maxValue() const +{ + return d_maxValue; +} + +/*! + A interval is valid when minValue() <= maxValue(). + In case of QwtInterval::ExcludeBorders it is true + when minValue() < maxValue() + + \return True, when the interval is valid +*/ +inline bool QwtInterval::isValid() const +{ + if ( ( d_borderFlags & ExcludeBorders ) == 0 ) + return d_minValue <= d_maxValue; + else + return d_minValue < d_maxValue; +} + +/*! + \brief Return the width of an interval + + The width of invalid intervals is 0.0, otherwise the result is + maxValue() - minValue(). + + \return Interval width + \sa isValid() +*/ +inline double QwtInterval::width() const +{ + return isValid() ? ( d_maxValue - d_minValue ) : 0.0; +} + +/*! + \brief Intersection of two intervals + + \param other Interval to intersect with + \return Intersection of this and other + + \sa intersect() +*/ +inline QwtInterval QwtInterval::operator&( + const QwtInterval &other ) const +{ + return intersect( other ); +} + +/*! + Union of two intervals + + \param other Interval to unite with + \return Union of this and other + + \sa unite() +*/ +inline QwtInterval QwtInterval::operator|( + const QwtInterval &other ) const +{ + return unite( other ); +} + +/*! + \brief Compare two intervals + + \param other Interval to compare with + \return True, when this and other are equal +*/ +inline bool QwtInterval::operator==( const QwtInterval &other ) const +{ + return ( d_minValue == other.d_minValue ) && + ( d_maxValue == other.d_maxValue ) && + ( d_borderFlags == other.d_borderFlags ); +} +/*! + \brief Compare two intervals + + \param other Interval to compare with + \return True, when this and other are not equal +*/ +inline bool QwtInterval::operator!=( const QwtInterval &other ) const +{ + return ( !( *this == other ) ); +} + +/*! + Extend an interval + + \param value Value + \return Extended interval + \sa extend() +*/ +inline QwtInterval QwtInterval::operator|( double value ) const +{ + return extend( value ); +} + +//! \return true, if isValid() && (minValue() >= maxValue()) +inline bool QwtInterval::isNull() const +{ + return isValid() && d_minValue >= d_maxValue; +} + +/*! + Invalidate the interval + + The limits are set to interval [0.0, -1.0] + \sa isValid() +*/ +inline void QwtInterval::invalidate() +{ + d_minValue = 0.0; + d_maxValue = -1.0; +} + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtInterval::BorderFlags ) +Q_DECLARE_METATYPE( QwtInterval ) + +#ifndef QT_NO_DEBUG_STREAM +QWT_EXPORT QDebug operator<<( QDebug, const QwtInterval & ); +#endif + +#endif diff --git a/libs/qwt/qwt_interval_symbol.cpp b/libs/qwt/qwt_interval_symbol.cpp new file mode 100644 index 0000000000..83c842d984 --- /dev/null +++ b/libs/qwt/qwt_interval_symbol.cpp @@ -0,0 +1,319 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_interval_symbol.h" +#include "qwt_painter.h" +#include "qwt_math.h" +#include <qpainter.h> + +#if QT_VERSION < 0x040601 +#define qAtan2(y, x) ::atan2(y, x) +#define qFastSin(x) qSin(x) +#define qFastCos(x) qCos(x) +#endif + +class QwtIntervalSymbol::PrivateData +{ +public: + PrivateData(): + style( QwtIntervalSymbol::NoSymbol ), + width( 6 ) + { + } + + bool operator==( const PrivateData &other ) const + { + return ( style == other.style ) + && ( width == other.width ) + && ( brush == other.brush ) + && ( pen == other.pen ); + } + + QwtIntervalSymbol::Style style; + int width; + + QPen pen; + QBrush brush; +}; + +/*! + Constructor + + \param style Style of the symbol + \sa setStyle(), style(), Style +*/ +QwtIntervalSymbol::QwtIntervalSymbol( Style style ) +{ + d_data = new PrivateData(); + d_data->style = style; +} + +//! Copy constructor +QwtIntervalSymbol::QwtIntervalSymbol( const QwtIntervalSymbol &other ) +{ + d_data = new PrivateData(); + *d_data = *other.d_data; +} + +//! Destructor +QwtIntervalSymbol::~QwtIntervalSymbol() +{ + delete d_data; +} + +//! \brief Assignment operator +QwtIntervalSymbol &QwtIntervalSymbol::operator=( + const QwtIntervalSymbol &other ) +{ + *d_data = *other.d_data; + return *this; +} + +//! \brief Compare two symbols +bool QwtIntervalSymbol::operator==( + const QwtIntervalSymbol &other ) const +{ + return *d_data == *other.d_data; +} + +//! \brief Compare two symbols +bool QwtIntervalSymbol::operator!=( + const QwtIntervalSymbol &other ) const +{ + return !( *d_data == *other.d_data ); +} + +/*! + Specify the symbol style + + \param style Style + \sa style(), Style +*/ +void QwtIntervalSymbol::setStyle( Style style ) +{ + d_data->style = style; +} + +/*! + \return Current symbol style + \sa setStyle() +*/ +QwtIntervalSymbol::Style QwtIntervalSymbol::style() const +{ + return d_data->style; +} + +/*! + Specify the width of the symbol + It is used depending on the style. + + \param width Width + \sa width(), setStyle() +*/ +void QwtIntervalSymbol::setWidth( int width ) +{ + d_data->width = width; +} + +/*! + \return Width of the symbol. + \sa setWidth(), setStyle() +*/ +int QwtIntervalSymbol::width() const +{ + return d_data->width; +} + +/*! + \brief Assign a brush + + The brush is used for the Box style. + + \param brush Brush + \sa brush() +*/ +void QwtIntervalSymbol::setBrush( const QBrush &brush ) +{ + d_data->brush = brush; +} + +/*! + \return Brush + \sa setBrush() +*/ +const QBrush& QwtIntervalSymbol::brush() const +{ + return d_data->brush; +} + +/*! + Build and assign a pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtIntervalSymbol::setPen( const QColor &color, + qreal width, Qt::PenStyle style ) +{ + setPen( QPen( color, width, style ) ); +} + +/*! + Assign a pen + + \param pen Pen + \sa pen(), setBrush() +*/ +void QwtIntervalSymbol::setPen( const QPen &pen ) +{ + d_data->pen = pen; +} + +/*! + \return Pen + \sa setPen(), brush() +*/ +const QPen& QwtIntervalSymbol::pen() const +{ + return d_data->pen; +} + +/*! + Draw a symbol depending on its style + + \param painter Painter + \param orientation Orientation + \param from Start point of the interval in target device coordinates + \param to End point of the interval in target device coordinates + + \sa setStyle() +*/ +void QwtIntervalSymbol::draw( QPainter *painter, Qt::Orientation orientation, + const QPointF &from, const QPointF &to ) const +{ + const qreal pw = qMax( painter->pen().widthF(), qreal( 1.0 ) ); + + QPointF p1 = from; + QPointF p2 = to; + if ( QwtPainter::roundingAlignment( painter ) ) + { + p1 = p1.toPoint(); + p2 = p2.toPoint(); + } + + switch ( d_data->style ) + { + case QwtIntervalSymbol::Bar: + { + QwtPainter::drawLine( painter, p1, p2 ); + if ( d_data->width > pw ) + { + if ( ( orientation == Qt::Horizontal ) + && ( p1.y() == p2.y() ) ) + { + const double sw = d_data->width; + + const double y = p1.y() - sw / 2; + QwtPainter::drawLine( painter, + p1.x(), y, p1.x(), y + sw ); + QwtPainter::drawLine( painter, + p2.x(), y, p2.x(), y + sw ); + } + else if ( ( orientation == Qt::Vertical ) + && ( p1.x() == p2.x() ) ) + { + const double sw = d_data->width; + + const double x = p1.x() - sw / 2; + QwtPainter::drawLine( painter, + x, p1.y(), x + sw, p1.y() ); + QwtPainter::drawLine( painter, + x, p2.y(), x + sw, p2.y() ); + } + else + { + const double sw = d_data->width; + + const double dx = p2.x() - p1.x(); + const double dy = p2.y() - p1.y(); + const double angle = qAtan2( dy, dx ) + M_PI_2; + double dw2 = sw / 2.0; + + const double cx = qFastCos( angle ) * dw2; + const double sy = qFastSin( angle ) * dw2; + + QwtPainter::drawLine( painter, + p1.x() - cx, p1.y() - sy, + p1.x() + cx, p1.y() + sy ); + QwtPainter::drawLine( painter, + p2.x() - cx, p2.y() - sy, + p2.x() + cx, p2.y() + sy ); + } + } + break; + } + case QwtIntervalSymbol::Box: + { + if ( d_data->width <= pw ) + { + QwtPainter::drawLine( painter, p1, p2 ); + } + else + { + if ( ( orientation == Qt::Horizontal ) + && ( p1.y() == p2.y() ) ) + { + const double sw = d_data->width; + + const double y = p1.y() - d_data->width / 2; + QwtPainter::drawRect( painter, + p1.x(), y, p2.x() - p1.x(), sw ); + } + else if ( ( orientation == Qt::Vertical ) + && ( p1.x() == p2.x() ) ) + { + const double sw = d_data->width; + + const double x = p1.x() - d_data->width / 2; + QwtPainter::drawRect( painter, + x, p1.y(), sw, p2.y() - p1.y() ); + } + else + { + const double sw = d_data->width; + + const double dx = p2.x() - p1.x(); + const double dy = p2.y() - p1.y(); + const double angle = qAtan2( dy, dx ) + M_PI_2; + double dw2 = sw / 2.0; + + const double cx = qFastCos( angle ) * dw2; + const double sy = qFastSin( angle ) * dw2; + + QPolygonF polygon; + polygon += QPointF( p1.x() - cx, p1.y() - sy ); + polygon += QPointF( p1.x() + cx, p1.y() + sy ); + polygon += QPointF( p2.x() + cx, p2.y() + sy ); + polygon += QPointF( p2.x() - cx, p2.y() - sy ); + + QwtPainter::drawPolygon( painter, polygon ); + } + } + break; + } + default:; + } +} diff --git a/libs/qwt/qwt_interval_symbol.h b/libs/qwt/qwt_interval_symbol.h new file mode 100644 index 0000000000..f32e1c41dc --- /dev/null +++ b/libs/qwt/qwt_interval_symbol.h @@ -0,0 +1,87 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_INTERVAL_SYMBOL_H +#define QWT_INTERVAL_SYMBOL_H + +#include "qwt_global.h" +#include <qpen.h> +#include <qsize.h> + +class QPainter; +class QRect; +class QPointF; + +/*! + \brief A drawing primitive for displaying an interval like an error bar + + \sa QwtPlotIntervalCurve +*/ +class QWT_EXPORT QwtIntervalSymbol +{ +public: + //! Symbol style + enum Style + { + //! No Style. The symbol cannot be drawn. + NoSymbol = -1, + + /*! + The symbol displays a line with caps at the beginning/end. + The size of the caps depends on the symbol width(). + */ + Bar, + + /*! + The symbol displays a plain rectangle using pen() and brush(). + The size of the rectangle depends on the translated interval and + the width(), + */ + Box, + + /*! + Styles >= UserSymbol are reserved for derived + classes of QwtIntervalSymbol that overload draw() with + additional application specific symbol types. + */ + UserSymbol = 1000 + }; + +public: + QwtIntervalSymbol( Style = NoSymbol ); + QwtIntervalSymbol( const QwtIntervalSymbol & ); + virtual ~QwtIntervalSymbol(); + + QwtIntervalSymbol &operator=( const QwtIntervalSymbol & ); + bool operator==( const QwtIntervalSymbol & ) const; + bool operator!=( const QwtIntervalSymbol & ) const; + + void setWidth( int ); + int width() const; + + void setBrush( const QBrush& b ); + const QBrush& brush() const; + + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); + const QPen& pen() const; + + void setStyle( Style ); + Style style() const; + + virtual void draw( QPainter *, Qt::Orientation, + const QPointF& from, const QPointF& to ) const; + +private: + + class PrivateData; + PrivateData* d_data; +}; + +#endif diff --git a/libs/qwt/qwt_knob.cpp b/libs/qwt/qwt_knob.cpp index 9ce3b84b2a..5860e42c47 100644 --- a/libs/qwt/qwt_knob.cpp +++ b/libs/qwt/qwt_knob.cpp @@ -7,88 +7,120 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_knob.h" +#include "qwt_round_scale_draw.h" +#include "qwt_math.h" +#include "qwt_painter.h" +#include "qwt_scale_map.h" #include <qpainter.h> #include <qpalette.h> #include <qstyle.h> +#include <qstyleoption.h> #include <qevent.h> -#include "qwt_round_scale_draw.h" -#include "qwt_knob.h" -#include "qwt_math.h" -#include "qwt_painter.h" -#include "qwt_paint_buffer.h" +#include <qmath.h> +#include <qapplication.h> + +#if QT_VERSION < 0x040601 +#define qAtan2(y, x) ::atan2(y, x) +#define qFabs(x) ::fabs(x) +#define qFastCos(x) qCos(x) +#define qFastSin(x) qSin(x) +#endif + +static QSize qwtKnobSizeHint( const QwtKnob *knob, int min ) +{ + int knobWidth = knob->knobWidth(); + if ( knobWidth <= 0 ) + knobWidth = qMax( 3 * knob->markerSize(), min ); + + // Add the scale radial thickness to the knobWidth + const int extent = qCeil( knob->scaleDraw()->extent( knob->font() ) ); + const int d = 2 * ( extent + 4 ) + knobWidth; + + int left, right, top, bottom; + knob->getContentsMargins( &left, &top, &right, &bottom ); + + return QSize( d + left + right, d + top + bottom ); +} + +static inline double qwtToScaleAngle( double angle ) +{ + // the map is counter clockwise with the origin + // at 90° using angles from -180° -> 180° + + double a = 90.0 - angle; + if ( a <= -180.0 ) + a += 360.0; + else if ( a >= 180.0 ) + a -= 360.0; + + return a; +} + +static double qwtToDegrees( double value ) +{ + return qwtNormalizeDegrees( 90.0 - value ); +} class QwtKnob::PrivateData { public: - PrivateData() { - angle = 0.0; - nTurns = 0.0; - borderWidth = 2; - borderDist = 4; - totalAngle = 270.0; - scaleDist = 4; - symbol = Line; - maxScaleTicks = 11; - knobWidth = 50; - dotWidth = 8; + PrivateData(): + knobStyle( QwtKnob::Raised ), + markerStyle( QwtKnob::Notch ), + borderWidth( 2 ), + borderDist( 4 ), + scaleDist( 4 ), + maxScaleTicks( 11 ), + knobWidth( 0 ), + alignment( Qt::AlignCenter ), + markerSize( 8 ), + totalAngle( 270.0 ), + mouseOffset( 0.0 ) + { } + QwtKnob::KnobStyle knobStyle; + QwtKnob::MarkerStyle markerStyle; + int borderWidth; int borderDist; int scaleDist; int maxScaleTicks; int knobWidth; - int dotWidth; + Qt::Alignment alignment; + int markerSize; - Symbol symbol; - double angle; double totalAngle; - double nTurns; - QRect knobRect; // bounding rect of the knob without scale + double mouseOffset; }; /*! - Constructor - \param parent Parent widget -*/ -QwtKnob::QwtKnob(QWidget* parent): - QwtAbstractSlider(Qt::Horizontal, parent) -{ - initKnob(); -} + \brief Constructor + + Construct a knob with an angle of 270°. The style is + QwtKnob::Raised and the marker style is QwtKnob::Notch. + The width of the knob is set to 50 pixels. -#if QT_VERSION < 0x040000 -/*! - Constructor \param parent Parent widget - \param name Object name -*/ -QwtKnob::QwtKnob(QWidget* parent, const char *name): - QwtAbstractSlider(Qt::Horizontal, parent) -{ - setName(name); - initKnob(); -} -#endif -void QwtKnob::initKnob() + \sa setTotalAngle() +*/ +QwtKnob::QwtKnob( QWidget* parent ): + QwtAbstractSlider( parent ) { -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#endif - d_data = new PrivateData; - setScaleDraw(new QwtRoundScaleDraw()); + setScaleDraw( new QwtRoundScaleDraw() ); - setUpdateTime(50); setTotalAngle( 270.0 ); - recalcAngle(); - setSizePolicy(QSizePolicy(QSizePolicy::Minimum, QSizePolicy::Minimum)); - setRange(0.0, 10.0, 1.0); - setValue(0.0); + setScale( 0.0, 10.0 ); + setValue( 0.0 ); + + setSizePolicy( QSizePolicy::MinimumExpanding, + QSizePolicy::MinimumExpanding ); } //! Destructor @@ -98,52 +130,130 @@ QwtKnob::~QwtKnob() } /*! - \brief Set the symbol of the knob - \sa symbol() + \brief Set the knob type + + \param knobStyle Knob type + \sa knobStyle(), setBorderWidth() +*/ +void QwtKnob::setKnobStyle( KnobStyle knobStyle ) +{ + if ( d_data->knobStyle != knobStyle ) + { + d_data->knobStyle = knobStyle; + update(); + } +} + +/*! + \return Marker type of the knob + \sa setKnobStyle(), setBorderWidth() +*/ +QwtKnob::KnobStyle QwtKnob::knobStyle() const +{ + return d_data->knobStyle; +} + +/*! + \brief Set the marker type of the knob + + \param markerStyle Marker type + \sa markerStyle(), setMarkerSize() */ -void QwtKnob::setSymbol(QwtKnob::Symbol s) +void QwtKnob::setMarkerStyle( MarkerStyle markerStyle ) { - if ( d_data->symbol != s ) { - d_data->symbol = s; + if ( d_data->markerStyle != markerStyle ) + { + d_data->markerStyle = markerStyle; update(); } } /*! - \return symbol of the knob - \sa setSymbol() + \return Marker type of the knob + \sa setMarkerStyle(), setMarkerSize() */ -QwtKnob::Symbol QwtKnob::symbol() const +QwtKnob::MarkerStyle QwtKnob::markerStyle() const { - return d_data->symbol; + return d_data->markerStyle; } /*! \brief Set the total angle by which the knob can be turned \param angle Angle in degrees. - The default angle is 270 degrees. It is possible to specify - an angle of more than 360 degrees so that the knob can be - turned several times around its axis. + The angle has to be between [10, 360] degrees. Angles above + 360 ( so that the knob can be turned several times around its axis ) + have to be set using setNumTurns(). + + The default angle is 270 degrees. + + \sa totalAngle(), setNumTurns() */ -void QwtKnob::setTotalAngle (double angle) +void QwtKnob::setTotalAngle ( double angle ) { - if (angle < 10.0) - d_data->totalAngle = 10.0; - else + angle = qBound( 10.0, angle, 360.0 ); + + if ( angle != d_data->totalAngle ) + { d_data->totalAngle = angle; - scaleDraw()->setAngleRange( -0.5 * d_data->totalAngle, - 0.5 * d_data->totalAngle); - layoutKnob(); + scaleDraw()->setAngleRange( -0.5 * d_data->totalAngle, + 0.5 * d_data->totalAngle ); + + updateGeometry(); + update(); + } } -//! Return the total angle +/*! + \return the total angle + \sa setTotalAngle(), setNumTurns(), numTurns() + */ double QwtKnob::totalAngle() const { return d_data->totalAngle; } +/*! + \brief Set the number of turns + + When numTurns > 1 the knob can be turned several times around its axis + - otherwise the total angle is floored to 360°. + + \sa numTurns(), totalAngle(), setTotalAngle() +*/ + +void QwtKnob::setNumTurns( int numTurns ) +{ + numTurns = qMax( numTurns, 1 ); + + if ( numTurns == 1 && d_data->totalAngle <= 360.0 ) + return; + + const double angle = numTurns * 360.0; + if ( angle != d_data->totalAngle ) + { + d_data->totalAngle = angle; + + scaleDraw()->setAngleRange( -0.5 * d_data->totalAngle, + 0.5 * d_data->totalAngle ); + + updateGeometry(); + update(); + } +} + +/*! + \return Number of turns. + + When the total angle is below 360° numTurns() is ceiled to 1. + \sa setNumTurns(), setTotalAngle(), totalAngle() + */ +int QwtKnob::numTurns() const +{ + return qCeil( d_data->totalAngle / 360.0 ); +} + /*! Change the scale draw of the knob @@ -153,10 +263,10 @@ double QwtKnob::totalAngle() const \sa scaleDraw() */ -void QwtKnob::setScaleDraw(QwtRoundScaleDraw *scaleDraw) +void QwtKnob::setScaleDraw( QwtRoundScaleDraw *scaleDraw ) { - setAbstractScaleDraw(scaleDraw); - setTotalAngle(d_data->totalAngle); + setAbstractScaleDraw( scaleDraw ); + setTotalAngle( d_data->totalAngle ); } /*! @@ -165,7 +275,7 @@ void QwtKnob::setScaleDraw(QwtRoundScaleDraw *scaleDraw) */ const QwtRoundScaleDraw *QwtKnob::scaleDraw() const { - return (QwtRoundScaleDraw *)abstractScaleDraw(); + return static_cast<const QwtRoundScaleDraw *>( abstractScaleDraw() ); } /*! @@ -174,270 +284,495 @@ const QwtRoundScaleDraw *QwtKnob::scaleDraw() const */ QwtRoundScaleDraw *QwtKnob::scaleDraw() { - return (QwtRoundScaleDraw *)abstractScaleDraw(); + return static_cast<QwtRoundScaleDraw *>( abstractScaleDraw() ); } /*! - \brief Draw the knob - \param painter painter - \param r Bounding rectangle of the knob (without scale) -*/ -void QwtKnob::drawKnob(QPainter *painter, const QRect &r) -{ -#if QT_VERSION < 0x040000 - const QBrush buttonBrush = colorGroup().brush(QColorGroup::Button); - const QColor buttonTextColor = colorGroup().buttonText(); - const QColor lightColor = colorGroup().light(); - const QColor darkColor = colorGroup().dark(); -#else - const QBrush buttonBrush = palette().brush(QPalette::Button); - const QColor buttonTextColor = palette().color(QPalette::ButtonText); - const QColor lightColor = palette().color(QPalette::Light); - const QColor darkColor = palette().color(QPalette::Dark); -#endif + Calculate the bounding rectangle of the knob without the scale - const int bw2 = d_data->borderWidth / 2; + \return Bounding rectangle of the knob + \sa knobWidth(), alignment(), QWidget::contentsRect() + */ +QRect QwtKnob::knobRect() const +{ + const QRect cr = contentsRect(); - const int radius = (qwtMin(r.width(), r.height()) - bw2) / 2; + const int extent = qCeil( scaleDraw()->extent( font() ) ); + const int d = extent + d_data->scaleDist; - const QRect aRect( - r.center().x() - radius, r.center().y() - radius, - 2 * radius, 2 * radius); + int w = d_data->knobWidth; + if ( w <= 0 ) + { + const int dim = qMin( cr.width(), cr.height() ); - // - // draw button face - // - painter->setBrush(buttonBrush); - painter->drawEllipse(aRect); + w = dim - 2 * ( d ); + w = qMax( 0, w ); + } - // - // draw button shades - // - QPen pn; - pn.setWidth(d_data->borderWidth); + QRect r( 0, 0, w, w ); - pn.setColor(lightColor); - painter->setPen(pn); - painter->drawArc(aRect, 45*16, 180*16); + if ( d_data->alignment & Qt::AlignLeft ) + { + r.moveLeft( cr.left() + d ); + } + else if ( d_data->alignment & Qt::AlignRight ) + { + r.moveRight( cr.right() - d ); + } + else + { + r.moveCenter( QPoint( cr.center().x(), r.center().y() ) ); + } - pn.setColor(darkColor); - painter->setPen(pn); - painter->drawArc(aRect, 225*16, 180*16); + if ( d_data->alignment & Qt::AlignTop ) + { + r.moveTop( cr.top() + d ); + } + else if ( d_data->alignment & Qt::AlignBottom ) + { + r.moveBottom( cr.bottom() - d ); + } + else + { + r.moveCenter( QPoint( r.center().x(), cr.center().y() ) ); + } - // - // draw marker - // - if ( isValid() ) - drawMarker(painter, d_data->angle, buttonTextColor); + return r; } /*! - \brief Notify change of value + \brief Determine what to do when the user presses a mouse button. + + \param pos Mouse position - Sets the knob's value to the nearest multiple - of the step size. + \retval True, when pos is inside the circle of the knob. + \sa scrolledTo() */ -void QwtKnob::valueChange() +bool QwtKnob::isScrollPosition( const QPoint &pos ) const { - recalcAngle(); - update(); - QwtAbstractSlider::valueChange(); + const QRect kr = knobRect(); + + const QRegion region( kr, QRegion::Ellipse ); + if ( region.contains( pos ) && ( pos != kr.center() ) ) + { + const double angle = QLineF( kr.center(), pos ).angle(); + const double valueAngle = qwtToDegrees( transform( value() ) ); + + d_data->mouseOffset = qwtNormalizeDegrees( angle - valueAngle ); + + return true; + } + + return false; } /*! - \brief Determine the value corresponding to a specified position + \brief Determine the value for a new position of the mouse - Called by QwtAbstractSlider - \param p point + \param pos Mouse position + + \return Value for the mouse position + \sa isScrollPosition() */ -double QwtKnob::getValue(const QPoint &p) +double QwtKnob::scrolledTo( const QPoint &pos ) const { - const double dx = double((rect().x() + rect().width() / 2) - p.x() ); - const double dy = double((rect().y() + rect().height() / 2) - p.y() ); + double angle = QLineF( rect().center(), pos ).angle(); + angle = qwtNormalizeDegrees( angle - d_data->mouseOffset ); - const double arc = atan2(-dx,dy) * 180.0 / M_PI; + if ( scaleMap().pDist() > 360.0 ) + { + angle = qwtToDegrees( angle ); - double newValue = 0.5 * (minValue() + maxValue()) - + (arc + d_data->nTurns * 360.0) * (maxValue() - minValue()) - / d_data->totalAngle; + const double v = transform( value() ); - const double oneTurn = fabs(maxValue() - minValue()) * 360.0 / d_data->totalAngle; - const double eqValue = value() + mouseOffset(); + int numTurns = qFloor( ( v - scaleMap().p1() ) / 360.0 ); - if (fabs(newValue - eqValue) > 0.5 * oneTurn) { - if (newValue < eqValue) - newValue += oneTurn; - else - newValue -= oneTurn; - } + double valueAngle = qwtNormalizeDegrees( v ); + if ( qAbs( valueAngle - angle ) > 180.0 ) + { + numTurns += ( angle > valueAngle ) ? -1 : 1; + } - return newValue; -} + angle += scaleMap().p1() + numTurns * 360.0; -/*! - \brief Set the scrolling mode and direction + if ( !wrapping() ) + { + const double boundedAngle = + qBound( scaleMap().p1(), angle, scaleMap().p2() ); - Called by QwtAbstractSlider - \param p Point in question -*/ -void QwtKnob::getScrollMode(const QPoint &p, int &scrollMode, int &direction) -{ - const int r = d_data->knobRect.width() / 2; - - const int dx = d_data->knobRect.x() + r - p.x(); - const int dy = d_data->knobRect.y() + r - p.y(); - - if ( (dx * dx) + (dy * dy) <= (r * r)) { // point is inside the knob - scrollMode = ScrMouse; - direction = 0; - } else { // point lies outside - scrollMode = ScrTimer; - double arc = atan2(double(-dx),double(dy)) * 180.0 / M_PI; - if ( arc < d_data->angle) - direction = -1; - else if (arc > d_data->angle) - direction = 1; - else - direction = 0; + d_data->mouseOffset += ( boundedAngle - angle ); + angle = boundedAngle; + } } -} + else + { + angle = qwtToScaleAngle( angle ); + const double boundedAngle = + qBound( scaleMap().p1(), angle, scaleMap().p2() ); -/*! - \brief Notify a change of the range + if ( !wrapping() ) + d_data->mouseOffset += ( boundedAngle - angle ); - Called by QwtAbstractSlider -*/ -void QwtKnob::rangeChange() -{ - if (autoScale()) - rescale(minValue(), maxValue()); + angle = boundedAngle; + } - layoutKnob(); - recalcAngle(); + return invTransform( angle ); } -/*! - \brief Qt Resize Event +/*! + Handle QEvent::StyleChange and QEvent::FontChange; + \param event Change event */ -void QwtKnob::resizeEvent(QResizeEvent *) +void QwtKnob::changeEvent( QEvent *event ) { - layoutKnob( false ); + switch( event->type() ) + { + case QEvent::StyleChange: + case QEvent::FontChange: + { + updateGeometry(); + update(); + break; + } + default: + break; + } } -//! Recalculate the knob's geometry and layout based on -// the current rect and fonts. -// \param update_geometry notify the layout system and call update -// to redraw the scale -void QwtKnob::layoutKnob( bool update_geometry ) +/*! + Repaint the knob + \param event Paint event +*/ +void QwtKnob::paintEvent( QPaintEvent *event ) { - const QRect r = rect(); - const int radius = d_data->knobWidth / 2; + const QRectF knobRect = this->knobRect(); - d_data->knobRect.setWidth(2 * radius); - d_data->knobRect.setHeight(2 * radius); - d_data->knobRect.moveCenter(r.center()); + QPainter painter( this ); + painter.setClipRegion( event->region() ); - scaleDraw()->setRadius(radius + d_data->scaleDist); - scaleDraw()->moveCenter(r.center()); + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); - if ( update_geometry ) { - updateGeometry(); - update(); - } -} + painter.setRenderHint( QPainter::Antialiasing, true ); -/*! - \brief Repaint the knob -*/ -void QwtKnob::paintEvent(QPaintEvent *e) -{ - const QRect &ur = e->rect(); - if ( ur.isValid() ) { -#if QT_VERSION < 0x040000 - QwtPaintBuffer paintBuffer(this, ur); - draw(paintBuffer.painter(), ur); -#else - QPainter painter(this); - painter.setRenderHint(QPainter::Antialiasing); - draw(&painter, ur); -#endif + if ( !knobRect.contains( event->region().boundingRect() ) ) + { + scaleDraw()->setRadius( 0.5 * knobRect.width() + d_data->scaleDist ); + scaleDraw()->moveCenter( knobRect.center() ); + + scaleDraw()->draw( &painter, palette() ); } + + drawKnob( &painter, knobRect ); + + drawMarker( &painter, knobRect, + qwtNormalizeDegrees( transform( value() ) ) ); + + painter.setRenderHint( QPainter::Antialiasing, false ); + + if ( hasFocus() ) + drawFocusIndicator( &painter ); } /*! - \brief Repaint the knob + \brief Draw the knob + + \param painter painter + \param knobRect Bounding rectangle of the knob (without scale) */ -void QwtKnob::draw(QPainter *painter, const QRect& ur) +void QwtKnob::drawKnob( QPainter *painter, const QRectF &knobRect ) const { - if ( !d_data->knobRect.contains( ur ) ) { // event from valueChange() -#if QT_VERSION < 0x040000 - scaleDraw()->draw( painter, colorGroup() ); -#else - scaleDraw()->draw( painter, palette() ); -#endif + double dim = qMin( knobRect.width(), knobRect.height() ); + dim -= d_data->borderWidth * 0.5; + + QRectF aRect( 0, 0, dim, dim ); + aRect.moveCenter( knobRect.center() ); + + QPen pen( Qt::NoPen ); + if ( d_data->borderWidth > 0 ) + { + QColor c1 = palette().color( QPalette::Light ); + QColor c2 = palette().color( QPalette::Dark ); + + QLinearGradient gradient( aRect.topLeft(), aRect.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 0.3, c1 ); + gradient.setColorAt( 0.7, c2 ); + gradient.setColorAt( 1.0, c2 ); + + pen = QPen( gradient, d_data->borderWidth ); } - drawKnob( painter, d_data->knobRect ); + QBrush brush; + switch( d_data->knobStyle ) + { + case QwtKnob::Raised: + { + double off = 0.3 * knobRect.width(); + QRadialGradient gradient( knobRect.center(), + knobRect.width(), knobRect.topLeft() + QPointF( off, off ) ); + + gradient.setColorAt( 0.0, palette().color( QPalette::Midlight ) ); + gradient.setColorAt( 1.0, palette().color( QPalette::Button ) ); + + brush = QBrush( gradient ); + + break; + } + case QwtKnob::Styled: + { + QRadialGradient gradient(knobRect.center().x() - knobRect.width() / 3, + knobRect.center().y() - knobRect.height() / 2, + knobRect.width() * 1.3, + knobRect.center().x(), + knobRect.center().y() - knobRect.height() / 2); + + const QColor c = palette().color( QPalette::Button ); + gradient.setColorAt(0, c.lighter(110)); + gradient.setColorAt(qreal(0.5), c); + gradient.setColorAt(qreal(0.501), c.darker(102)); + gradient.setColorAt(1, c.darker(115)); + + brush = QBrush( gradient ); + + break; + } + case QwtKnob::Sunken: + { + QLinearGradient gradient( + knobRect.topLeft(), knobRect.bottomRight() ); + gradient.setColorAt( 0.0, palette().color( QPalette::Mid ) ); + gradient.setColorAt( 0.5, palette().color( QPalette::Button ) ); + gradient.setColorAt( 1.0, palette().color( QPalette::Midlight ) ); + brush = QBrush( gradient ); + + break; + } + case QwtKnob::Flat: + default: + brush = palette().brush( QPalette::Button ); + } - if ( hasFocus() ) - QwtPainter::drawFocusRect(painter, this); + painter->setPen( pen ); + painter->setBrush( brush ); + painter->drawEllipse( aRect ); } + /*! \brief Draw the marker at the knob's front - \param p Painter - \param arc Angle of the marker - \param c Marker color + + \param painter Painter + \param rect Bounding rectangle of the knob without scale + \param angle Angle of the marker in degrees + ( clockwise, 0 at the 12 o'clock position ) */ -void QwtKnob::drawMarker(QPainter *p, double arc, const QColor &c) +void QwtKnob::drawMarker( QPainter *painter, + const QRectF &rect, double angle ) const { - const double rarc = arc * M_PI / 180.0; - const double ca = cos(rarc); - const double sa = - sin(rarc); + if ( d_data->markerStyle == NoMarker || !isValid() ) + return; + + const double radians = qwtRadians( angle ); + const double sinA = -qFastSin( radians ); + const double cosA = qFastCos( radians ); + + const double xm = rect.center().x(); + const double ym = rect.center().y(); + const double margin = 4.0; + + double radius = 0.5 * ( rect.width() - d_data->borderWidth ) - margin; + if ( radius < 1.0 ) + radius = 1.0; + + int markerSize = d_data->markerSize; + if ( markerSize <= 0 ) + markerSize = qRound( 0.4 * radius ); + + switch ( d_data->markerStyle ) + { + case Notch: + case Nub: + { + const double dotWidth = + qMin( double( markerSize ), radius); + + const double dotCenterDist = radius - 0.5 * dotWidth; + if ( dotCenterDist > 0.0 ) + { + const QPointF center( xm - sinA * dotCenterDist, + ym - cosA * dotCenterDist ); + + QRectF ellipse( 0.0, 0.0, dotWidth, dotWidth ); + ellipse.moveCenter( center ); + + QColor c1 = palette().color( QPalette::Light ); + QColor c2 = palette().color( QPalette::Mid ); + + if ( d_data->markerStyle == Notch ) + qSwap( c1, c2 ); + + QLinearGradient gradient( + ellipse.topLeft(), ellipse.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 1.0, c2 ); + + painter->setPen( Qt::NoPen ); + painter->setBrush( gradient ); + + painter->drawEllipse( ellipse ); + } + break; + } + case Dot: + { + const double dotWidth = + qMin( double( markerSize ), radius); + + const double dotCenterDist = radius - 0.5 * dotWidth; + if ( dotCenterDist > 0.0 ) + { + const QPointF center( xm - sinA * dotCenterDist, + ym - cosA * dotCenterDist ); + + QRectF ellipse( 0.0, 0.0, dotWidth, dotWidth ); + ellipse.moveCenter( center ); + + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().color( QPalette::ButtonText ) ); + painter->drawEllipse( ellipse ); + } + + break; + } + case Tick: + { + const double rb = qMax( radius - markerSize, 1.0 ); + const double re = radius; + + const QLineF line( xm - sinA * rb, ym - cosA * rb, + xm - sinA * re, ym - cosA * re ); + + QPen pen( palette().color( QPalette::ButtonText ), 0 ); + pen.setCapStyle( Qt::FlatCap ); + painter->setPen( pen ); + painter->drawLine ( line ); + + break; + } + case Triangle: + { + const double rb = qMax( radius - markerSize, 1.0 ); + const double re = radius; + + painter->translate( rect.center() ); + painter->rotate( angle - 90.0 ); + + QPolygonF polygon; + polygon += QPointF( re, 0.0 ); + polygon += QPointF( rb, 0.5 * ( re - rb ) ); + polygon += QPointF( rb, -0.5 * ( re - rb ) ); + + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().color( QPalette::ButtonText ) ); + painter->drawPolygon( polygon ); + + painter->resetTransform(); + + break; + } + default: + break; + } +} - int radius = d_data->knobRect.width() / 2 - d_data->borderWidth; - if (radius < 3) - radius = 3; +/*! + Draw the focus indicator + \param painter Painter +*/ +void QwtKnob::drawFocusIndicator( QPainter *painter ) const +{ + const QRect cr = contentsRect(); + + int w = d_data->knobWidth; + if ( w <= 0 ) + { + w = qMin( cr.width(), cr.height() ); + } + else + { + const int extent = qCeil( scaleDraw()->extent( font() ) ); + w += 2 * ( extent + d_data->scaleDist ); + } - const int ym = d_data->knobRect.y() + radius + d_data->borderWidth; - const int xm = d_data->knobRect.x() + radius + d_data->borderWidth; + QRect focusRect( 0, 0, w, w ); + focusRect.moveCenter( cr.center() ); - switch (d_data->symbol) { - case Dot: { - p->setBrush(c); - p->setPen(Qt::NoPen); + QwtPainter::drawFocusRect( painter, this, focusRect ); +} - const double rb = double(qwtMax(radius - 4 - d_data->dotWidth / 2, 0)); - p->drawEllipse(xm - qRound(sa * rb) - d_data->dotWidth / 2, - ym - qRound(ca * rb) - d_data->dotWidth / 2, - d_data->dotWidth, d_data->dotWidth); - break; - } - case Line: { - p->setPen(QPen(c, 2)); +/*! + \brief Set the alignment of the knob - const double rb = qwtMax(double((radius - 4) / 3.0), 0.0); - const double re = qwtMax(double(radius - 4), 0.0); + Similar to a QLabel::alignment() the flags decide how + to align the knob inside of contentsRect(). - p->drawLine ( xm - qRound(sa * rb), ym - qRound(ca * rb), - xm - qRound(sa * re), ym - qRound(ca * re)); + The default setting is Qt::AlignCenter - break; - } + \param alignment Or'd alignment flags + + \sa alignment(), setKnobWidth(), knobRect() + */ +void QwtKnob::setAlignment( Qt::Alignment alignment ) +{ + if ( d_data->alignment != alignment ) + { + d_data->alignment = alignment; + update(); } } +/*! + \return Alignment of the knob inside of contentsRect() + \sa setAlignment(), knobWidth(), knobRect() + */ +Qt::Alignment QwtKnob::alignment() const +{ + return d_data->alignment; +} + /*! \brief Change the knob's width. - The specified width must be >= 5, or it will be clipped. - \param w New width + Setting a fixed value for the diameter of the knob + is helpful for aligning several knobs in a row. + + \param width New width + + \sa knobWidth(), setAlignment() + \note Modifies the sizePolicy() */ -void QwtKnob::setKnobWidth(int w) +void QwtKnob::setKnobWidth( int width ) { - d_data->knobWidth = qwtMax(w,5); - layoutKnob(); + width = qMax( width, 0 ); + + if ( width != d_data->knobWidth ) + { + QSizePolicy::Policy policy; + if ( width > 0 ) + policy = QSizePolicy::Minimum; + else + policy = QSizePolicy::MinimumExpanding; + + setSizePolicy( policy, policy ); + + d_data->knobWidth = width; + + updateGeometry(); + update(); + } } //! Return the width of the knob @@ -448,12 +783,15 @@ int QwtKnob::knobWidth() const /*! \brief Set the knob's border width - \param bw new border width + \param borderWidth new border width */ -void QwtKnob::setBorderWidth(int bw) +void QwtKnob::setBorderWidth( int borderWidth ) { - d_data->borderWidth = qwtMax(bw, 0); - layoutKnob(); + d_data->borderWidth = qMax( borderWidth, 0 ); + + updateGeometry(); + update(); + } //! Return the border width @@ -463,63 +801,45 @@ int QwtKnob::borderWidth() const } /*! - \brief Recalculate the marker angle corresponding to the - current value -*/ -void QwtKnob::recalcAngle() -{ - // - // calculate the angle corresponding to the value - // - if (maxValue() == minValue()) { - d_data->angle = 0; - d_data->nTurns = 0; - } else { - d_data->angle = (value() - 0.5 * (minValue() + maxValue())) - / (maxValue() - minValue()) * d_data->totalAngle; - d_data->nTurns = floor((d_data->angle + 180.0) / 360.0); - d_data->angle = d_data->angle - d_data->nTurns * 360.0; - } -} + \brief Set the size of the marker + When setting a size <= 0 the marker will + automatically scaled to 40% of the radius of the knob. -/*! - Recalculates the layout - \sa layoutKnob() + \sa markerSize(), markerStyle() */ -void QwtKnob::scaleChange() +void QwtKnob::setMarkerSize( int size ) { - layoutKnob(); + if ( d_data->markerSize != size ) + { + d_data->markerSize = size; + update(); + } } -/*! - Recalculates the layout - \sa layoutKnob() -*/ -void QwtKnob::fontChange(const QFont &f) +/*! + \return Marker size + \sa setMarkerSize() + */ +int QwtKnob::markerSize() const { - QwtAbstractSlider::fontChange( f ); - layoutKnob(); + return d_data->markerSize; } /*! - \return minimumSizeHint() + \return sizeHint() */ QSize QwtKnob::sizeHint() const { - return minimumSizeHint(); + const QSize hint = qwtKnobSizeHint( this, 50 ); + return hint.expandedTo( QApplication::globalStrut() ); } /*! - \brief Return a minimum size hint - \warning The return value of QwtKnob::minimumSizeHint() depends on the - font and the scale. + \return Minimum size hint + \sa sizeHint() */ QSize QwtKnob::minimumSizeHint() const { - // Add the scale radial thickness to the knobWidth - const int sh = scaleDraw()->extent( QPen(), font() ); - const int d = 2 * sh + 2 * d_data->scaleDist + d_data->knobWidth; - - return QSize( d, d ); + return qwtKnobSizeHint( this, 20 ); } diff --git a/libs/qwt/qwt_knob.h b/libs/qwt/qwt_knob.h index ee43aa71b4..852374c02b 100644 --- a/libs/qwt/qwt_knob.h +++ b/libs/qwt/qwt_knob.h @@ -12,87 +12,165 @@ #include "qwt_global.h" #include "qwt_abstract_slider.h" -#include "qwt_abstract_scale.h" class QwtRoundScaleDraw; /*! \brief The Knob Widget - The QwtKnob widget imitates look and behaviour of a volume knob on a radio. - It contains a scale around the knob which is set up automatically or can - be configured manually (see QwtAbstractScale). - Automatic scrolling is enabled when the user presses a mouse - button on the scale. For a description of signals, slots and other - members, see QwtAbstractSlider. + The QwtKnob widget imitates look and behavior of a volume knob on a radio. + It looks similar to QDial - not to QwtDial. + The value range of a knob might be divided into several turns. + + The layout of the knob depends on the knobWidth(). + + - width > 0 + The diameter of the knob is fixed and the knob is aligned + according to the alignment() flags inside of the contentsRect(). + + - width <= 0 + The knob is extended to the minimum of width/height of the contentsRect() + and aligned in the other direction according to alignment(). + + Setting a fixed knobWidth() is helpful to align several knobs with different + scale labels. + \image html knob.png - \sa QwtAbstractSlider and QwtAbstractScale for the descriptions - of the inherited members. */ -class QWT_EXPORT QwtKnob : public QwtAbstractSlider, public QwtAbstractScale +class QWT_EXPORT QwtKnob: public QwtAbstractSlider { Q_OBJECT - Q_ENUMS (Symbol) + + Q_ENUMS ( KnobStyle MarkerStyle ) + + Q_PROPERTY( KnobStyle knobStyle READ knobStyle WRITE setKnobStyle ) Q_PROPERTY( int knobWidth READ knobWidth WRITE setKnobWidth ) - Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) + Q_PROPERTY( Qt::Alignment alignment READ alignment WRITE setAlignment ) Q_PROPERTY( double totalAngle READ totalAngle WRITE setTotalAngle ) - Q_PROPERTY( Symbol symbol READ symbol WRITE setSymbol ) + Q_PROPERTY( int numTurns READ numTurns WRITE setNumTurns ) + Q_PROPERTY( MarkerStyle markerStyle READ markerStyle WRITE setMarkerStyle ) + Q_PROPERTY( int markerSize READ markerSize WRITE setMarkerSize ) + Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) public: - /*! - Symbol - \sa QwtKnob::QwtKnob() - */ + /*! + \brief Style of the knob surface + + Depending on the KnobStyle the surface of the knob is + filled from the brushes of the widget palette(). + + \sa setKnobStyle(), knobStyle() + */ + enum KnobStyle + { + //! Fill the knob with a brush from QPalette::Button. + Flat, + + //! Build a gradient from QPalette::Midlight and QPalette::Button + Raised, + + /*! + Build a gradient from QPalette::Midlight, QPalette::Button + and QPalette::Midlight + */ + Sunken, + + /*! + Build a radial gradient from QPalette::Button + like it is used for QDial in various Qt styles. + */ + Styled + }; - enum Symbol { Line, Dot }; + /*! + \brief Marker type + + The marker indicates the current value on the knob + The default setting is a Notch marker. - explicit QwtKnob(QWidget* parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtKnob(QWidget* parent, const char *name); -#endif + \sa setMarkerStyle(), setMarkerSize() + */ + enum MarkerStyle + { + //! Don't paint any marker + NoMarker = -1, + + //! Paint a single tick in QPalette::ButtonText color + Tick, + + //! Paint a triangle in QPalette::ButtonText color + Triangle, + + //! Paint a circle in QPalette::ButtonText color + Dot, + + /*! + Draw a raised ellipse with a gradient build from + QPalette::Light and QPalette::Mid + */ + Nub, + + /*! + Draw a sunken ellipse with a gradient build from + QPalette::Light and QPalette::Mid + */ + Notch + }; + + explicit QwtKnob( QWidget* parent = NULL ); virtual ~QwtKnob(); - void setKnobWidth(int w); + void setAlignment( Qt::Alignment ); + Qt::Alignment alignment() const; + + void setKnobWidth( int ); int knobWidth() const; - void setTotalAngle (double angle); + void setNumTurns( int ); + int numTurns() const; + + void setTotalAngle ( double angle ); double totalAngle() const; - void setBorderWidth(int bw); + void setKnobStyle( KnobStyle ); + KnobStyle knobStyle() const; + + void setBorderWidth( int bw ); int borderWidth() const; - void setSymbol(Symbol); - Symbol symbol() const; + void setMarkerStyle( MarkerStyle ); + MarkerStyle markerStyle() const; + + void setMarkerSize( int ); + int markerSize() const; virtual QSize sizeHint() const; virtual QSize minimumSizeHint() const; - void setScaleDraw(QwtRoundScaleDraw *); + void setScaleDraw( QwtRoundScaleDraw * ); + const QwtRoundScaleDraw *scaleDraw() const; QwtRoundScaleDraw *scaleDraw(); + QRect knobRect() const; + protected: - virtual void paintEvent(QPaintEvent *e); - virtual void resizeEvent(QResizeEvent *e); + virtual void paintEvent( QPaintEvent * ); + virtual void changeEvent( QEvent * ); - void draw(QPainter *p, const QRect& ur); - void drawKnob(QPainter *p, const QRect &r); - void drawMarker(QPainter *p, double arc, const QColor &c); + virtual void drawKnob( QPainter *, const QRectF & ) const; -private: - void initKnob(); - void layoutKnob( bool update = true ); - double getValue(const QPoint &p); - void getScrollMode( const QPoint &p, int &scrollMode, int &direction ); - void recalcAngle(); + virtual void drawFocusIndicator( QPainter * ) const; - virtual void valueChange(); - virtual void rangeChange(); - virtual void scaleChange(); - virtual void fontChange(const QFont &oldFont); + virtual void drawMarker( QPainter *, + const QRectF &, double arc ) const; + virtual double scrolledTo( const QPoint & ) const; + virtual bool isScrollPosition( const QPoint & ) const; + +private: class PrivateData; PrivateData *d_data; }; diff --git a/libs/qwt/qwt_legend.cpp b/libs/qwt/qwt_legend.cpp index c06236471f..25916ad4c7 100644 --- a/libs/qwt/qwt_legend.cpp +++ b/libs/qwt/qwt_legend.cpp @@ -7,116 +7,198 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_legend.h" +#include "qwt_legend_label.h" +#include "qwt_dyngrid_layout.h" +#include "qwt_math.h" +#include "qwt_plot_item.h" +#include "qwt_painter.h" #include <qapplication.h> -#include <qmap.h> -#if QT_VERSION >= 0x040000 #include <qscrollbar.h> -#endif -#include "qwt_math.h" -#include "qwt_dyngrid_layout.h" -#include "qwt_legend_itemmanager.h" -#include "qwt_legend_item.h" -#include "qwt_legend.h" +#include <qscrollarea.h> +#include <qpainter.h> +#include <qstyle.h> +#include <qstyleoption.h> -class QwtLegend::PrivateData +class QwtLegendMap { public: - class LegendMap + inline bool isEmpty() const { return d_entries.isEmpty(); } + + void insert( const QVariant &, const QList<QWidget *> & ); + void remove( const QVariant & ); + + void removeWidget( const QWidget * ); + + QList<QWidget *> legendWidgets( const QVariant & ) const; + QVariant itemInfo( const QWidget * ) const; + +private: + // we don't know anything about itemInfo and therefore don't have + // any key that can be used for a map or hashtab. + // But a simple linear list is o.k. here, as we will never have + // more than a few entries. + + class Entry { public: - void insert(const QwtLegendItemManager *, QWidget *); + QVariant itemInfo; + QList<QWidget *> widgets; + }; - void remove(const QwtLegendItemManager *); - void remove(QWidget *); + QList< Entry > d_entries; +}; - void clear(); +void QwtLegendMap::insert( const QVariant &itemInfo, + const QList<QWidget *> &widgets ) +{ + for ( int i = 0; i < d_entries.size(); i++ ) + { + Entry &entry = d_entries[i]; + if ( entry.itemInfo == itemInfo ) + { + entry.widgets = widgets; + return; + } + } - uint count() const; + Entry newEntry; + newEntry.itemInfo = itemInfo; + newEntry.widgets = widgets; - inline const QWidget *find(const QwtLegendItemManager *) const; - inline QWidget *find(const QwtLegendItemManager *); + d_entries += newEntry; +} - inline const QwtLegendItemManager *find(const QWidget *) const; - inline QwtLegendItemManager *find(const QWidget *); +void QwtLegendMap::remove( const QVariant &itemInfo ) +{ + for ( int i = 0; i < d_entries.size(); i++ ) + { + Entry &entry = d_entries[i]; + if ( entry.itemInfo == itemInfo ) + { + d_entries.removeAt( i ); + return; + } + } +} - const QMap<QWidget *, const QwtLegendItemManager *> &widgetMap() const; - QMap<QWidget *, const QwtLegendItemManager *> &widgetMap(); +void QwtLegendMap::removeWidget( const QWidget *widget ) +{ + QWidget *w = const_cast<QWidget *>( widget ); - private: - QMap<QWidget *, const QwtLegendItemManager *> d_widgetMap; - QMap<const QwtLegendItemManager *, QWidget *> d_itemMap; - }; + for ( int i = 0; i < d_entries.size(); i++ ) + d_entries[ i ].widgets.removeAll( w ); +} - QwtLegend::LegendItemMode itemMode; - QwtLegend::LegendDisplayPolicy displayPolicy; - int identifierMode; +QVariant QwtLegendMap::itemInfo( const QWidget *widget ) const +{ + if ( widget != NULL ) + { + QWidget *w = const_cast<QWidget *>( widget ); - LegendMap map; + for ( int i = 0; i < d_entries.size(); i++ ) + { + const Entry &entry = d_entries[i]; + if ( entry.widgets.indexOf( w ) >= 0 ) + return entry.itemInfo; + } + } - class LegendView; - LegendView *view; -}; + return QVariant(); +} + +QList<QWidget *> QwtLegendMap::legendWidgets( const QVariant &itemInfo ) const +{ + if ( itemInfo.isValid() ) + { + for ( int i = 0; i < d_entries.size(); i++ ) + { + const Entry &entry = d_entries[i]; + if ( entry.itemInfo == itemInfo ) + return entry.widgets; + } + } -#if QT_VERSION < 0x040000 -#include <qscrollview.h> + return QList<QWidget *>(); +} -class QwtLegend::PrivateData::LegendView: public QScrollView +class QwtLegend::PrivateData { public: - LegendView(QWidget *parent): - QScrollView(parent) { - setResizePolicy(Manual); + PrivateData(): + itemMode( QwtLegendData::ReadOnly ), + view( NULL ) + { + } - viewport()->setBackgroundMode(Qt::NoBackground); // Avoid flicker + QwtLegendData::Mode itemMode; + QwtLegendMap itemMap; - contentsWidget = new QWidget(viewport()); + class LegendView; + LegendView *view; +}; - addChild(contentsWidget); - } +class QwtLegend::PrivateData::LegendView: public QScrollArea +{ +public: + LegendView( QWidget *parent ): + QScrollArea( parent ) + { + contentsWidget = new QWidget( this ); + contentsWidget->setObjectName( "QwtLegendViewContents" ); - void viewportResizeEvent(QResizeEvent *e) { - QScrollView::viewportResizeEvent(e); + setWidget( contentsWidget ); + setWidgetResizable( false ); - // It's not safe to update the layout now, because - // we are in an internal update of the scrollview framework. - // So we delay the update by posting a LayoutHint. + viewport()->setObjectName( "QwtLegendViewport" ); - QApplication::postEvent(contentsWidget, - new QEvent(QEvent::LayoutHint)); + // QScrollArea::setWidget internally sets autoFillBackground to true + // But we don't want a background. + contentsWidget->setAutoFillBackground( false ); + viewport()->setAutoFillBackground( false ); } - QWidget *contentsWidget; -}; + virtual bool event( QEvent *event ) + { + if ( event->type() == QEvent::PolishRequest ) + { + setFocusPolicy( Qt::NoFocus ); + } -#else // QT_VERSION >= 0x040000 + if ( event->type() == QEvent::Resize ) + { + // adjust the size to en/disable the scrollbars + // before QScrollArea adjusts the viewport size -#include <qscrollarea.h> + const QRect cr = contentsRect(); -class QwtLegend::PrivateData::LegendView: public QScrollArea -{ -public: - LegendView(QWidget *parent): - QScrollArea(parent) { - contentsWidget = new QWidget(this); + int w = cr.width(); + int h = contentsWidget->heightForWidth( cr.width() ); + if ( h > w ) + { + w -= verticalScrollBar()->sizeHint().width(); + h = contentsWidget->heightForWidth( w ); + } + + contentsWidget->resize( w, h ); + } - setWidget(contentsWidget); - setWidgetResizable(false); - setFocusPolicy(Qt::NoFocus); + return QScrollArea::event( event ); } - virtual bool viewportEvent(QEvent *e) { - bool ok = QScrollArea::viewportEvent(e); + virtual bool viewportEvent( QEvent *event ) + { + bool ok = QScrollArea::viewportEvent( event ); - if ( e->type() == QEvent::Resize ) { - QEvent event(QEvent::LayoutRequest); - QApplication::sendEvent(contentsWidget, &event); + if ( event->type() == QEvent::Resize ) + { + layoutContents(); } return ok; } - QSize viewportSize(int w, int h) const { + QSize viewportSize( int w, int h ) const + { const int sbHeight = horizontalScrollBar()->sizeHint().height(); const int sbWidth = verticalScrollBar()->sizeHint().width(); @@ -129,509 +211,591 @@ public: if ( w > vw ) vh -= sbHeight; - if ( h > vh ) { + if ( h > vh ) + { vw -= sbWidth; if ( w > vw && vh == ch ) vh -= sbHeight; } - return QSize(vw, vh); + return QSize( vw, vh ); } - QWidget *contentsWidget; -}; - -#endif - - -void QwtLegend::PrivateData::LegendMap::insert( - const QwtLegendItemManager *item, QWidget *widget) -{ - d_itemMap.insert(item, widget); - d_widgetMap.insert(widget, item); -} - -void QwtLegend::PrivateData::LegendMap::remove(const QwtLegendItemManager *item) -{ - QWidget *widget = d_itemMap[item]; - d_itemMap.remove(item); - d_widgetMap.remove(widget); -} - -void QwtLegend::PrivateData::LegendMap::remove(QWidget *widget) -{ - const QwtLegendItemManager *item = d_widgetMap[widget]; - d_itemMap.remove(item); - d_widgetMap.remove(widget); -} - -void QwtLegend::PrivateData::LegendMap::clear() -{ + void layoutContents() + { + const QwtDynGridLayout *tl = qobject_cast<QwtDynGridLayout *>( + contentsWidget->layout() ); + if ( tl == NULL ) + return; - /* - We can't delete the widgets in the following loop, because - we would get ChildRemoved events, changing d_itemMap, while - we are iterating. - */ + const QSize visibleSize = viewport()->contentsRect().size(); -#if QT_VERSION < 0x040000 - QValueList<QWidget *> widgets; + const int minW = int( tl->maxItemWidth() ) + 2 * tl->margin(); - QMap<const QwtLegendItemManager *, QWidget *>::const_iterator it; - for ( it = d_itemMap.begin(); it != d_itemMap.end(); ++it ) - widgets.append(it.data()); -#else - QList<QWidget *> widgets; + int w = qMax( visibleSize.width(), minW ); + int h = qMax( tl->heightForWidth( w ), visibleSize.height() ); - QMap<const QwtLegendItemManager *, QWidget *>::const_iterator it; - for ( it = d_itemMap.begin(); it != d_itemMap.end(); ++it ) - widgets.append(it.value()); -#endif + const int vpWidth = viewportSize( w, h ).width(); + if ( w > vpWidth ) + { + w = qMax( vpWidth, minW ); + h = qMax( tl->heightForWidth( w ), visibleSize.height() ); + } - d_itemMap.clear(); - d_widgetMap.clear(); + contentsWidget->resize( w, h ); + } - for ( int i = 0; i < (int)widgets.size(); i++ ) - delete widgets[i]; -} + QWidget *contentsWidget; +}; -uint QwtLegend::PrivateData::LegendMap::count() const +/*! + Constructor + \param parent Parent widget +*/ +QwtLegend::QwtLegend( QWidget *parent ): + QwtAbstractLegend( parent ) { - return d_itemMap.count(); -} + setFrameStyle( NoFrame ); -inline const QWidget *QwtLegend::PrivateData::LegendMap::find(const QwtLegendItemManager *item) const -{ - if ( !d_itemMap.contains((QwtLegendItemManager *)item) ) - return NULL; + d_data = new QwtLegend::PrivateData; - return d_itemMap[(QwtLegendItemManager *)item]; -} + d_data->view = new QwtLegend::PrivateData::LegendView( this ); + d_data->view->setObjectName( "QwtLegendView" ); + d_data->view->setFrameStyle( NoFrame ); -inline QWidget *QwtLegend::PrivateData::LegendMap::find(const QwtLegendItemManager *item) -{ - if ( !d_itemMap.contains((QwtLegendItemManager *)item) ) - return NULL; + QwtDynGridLayout *gridLayout = new QwtDynGridLayout( + d_data->view->contentsWidget ); + gridLayout->setAlignment( Qt::AlignHCenter | Qt::AlignTop ); + + d_data->view->contentsWidget->installEventFilter( this ); - return d_itemMap[(QwtLegendItemManager *)item]; + QVBoxLayout *layout = new QVBoxLayout( this ); + layout->setContentsMargins( 0, 0, 0, 0 ); + layout->addWidget( d_data->view ); } -inline const QwtLegendItemManager *QwtLegend::PrivateData::LegendMap::find( - const QWidget *widget) const +//! Destructor +QwtLegend::~QwtLegend() { - if ( !d_widgetMap.contains((QWidget *)widget) ) - return NULL; - - return d_widgetMap[(QWidget *)widget]; + delete d_data; } -inline QwtLegendItemManager *QwtLegend::PrivateData::LegendMap::find( - const QWidget *widget) -{ - if ( !d_widgetMap.contains((QWidget *)widget) ) - return NULL; +/*! + \brief Set the maximum number of entries in a row - return (QwtLegendItemManager *)d_widgetMap[(QWidget *)widget]; -} + F.e when the maximum is set to 1 all items are aligned + vertically. 0 means unlimited -inline const QMap<QWidget *, const QwtLegendItemManager *> & -QwtLegend::PrivateData::LegendMap::widgetMap() const -{ - return d_widgetMap; -} + \param numColums Maximum number of entries in a row -inline QMap<QWidget *, const QwtLegendItemManager *> & -QwtLegend::PrivateData::LegendMap::widgetMap() + \sa maxColumns(), QwtDynGridLayout::setMaxColumns() + */ +void QwtLegend::setMaxColumns( uint numColums ) { - return d_widgetMap; + QwtDynGridLayout *tl = qobject_cast<QwtDynGridLayout *>( + d_data->view->contentsWidget->layout() ); + if ( tl ) + tl->setMaxColumns( numColums ); } /*! - \param parent Parent widget -*/ -QwtLegend::QwtLegend(QWidget *parent): - QFrame(parent) + \return Maximum number of entries in a row + \sa setMaxColumns(), QwtDynGridLayout::maxColumns() + */ +uint QwtLegend::maxColumns() const { - setFrameStyle(NoFrame); + uint maxCols = 0; - d_data = new QwtLegend::PrivateData; - d_data->itemMode = QwtLegend::ReadOnlyItem; - d_data->displayPolicy = QwtLegend::AutoIdentifier; - d_data->identifierMode = QwtLegendItem::ShowLine | - QwtLegendItem::ShowSymbol | QwtLegendItem::ShowText; - - d_data->view = new QwtLegend::PrivateData::LegendView(this); - d_data->view->setFrameStyle(NoFrame); - - QwtDynGridLayout *layout = new QwtDynGridLayout( - d_data->view->contentsWidget); -#if QT_VERSION < 0x040000 - layout->setAutoAdd(true); -#endif - layout->setAlignment(Qt::AlignHCenter | Qt::AlignTop); - - d_data->view->contentsWidget->installEventFilter(this); -} + const QwtDynGridLayout *tl = qobject_cast<const QwtDynGridLayout *>( + d_data->view->contentsWidget->layout() ); + if ( tl ) + maxCols = tl->maxColumns(); -//! Destructor -QwtLegend::~QwtLegend() -{ - delete d_data; + return maxCols; } /*! - Set the legend display policy to: - - \param policy Legend display policy - \param mode Identifier mode (or'd ShowLine, ShowSymbol, ShowText) - - \sa displayPolicy, LegendDisplayPolicy -*/ -void QwtLegend::setDisplayPolicy(LegendDisplayPolicy policy, int mode) -{ - d_data->displayPolicy = policy; - if (-1 != mode) - d_data->identifierMode = mode; - - QMap<QWidget *, const QwtLegendItemManager *> &map = - d_data->map.widgetMap(); - - QMap<QWidget *, const QwtLegendItemManager *>::iterator it; - for ( it = map.begin(); it != map.end(); ++it ) { -#if QT_VERSION < 0x040000 - QwtLegendItemManager *item = (QwtLegendItemManager *)it.data(); -#else - QwtLegendItemManager *item = (QwtLegendItemManager *)it.value(); -#endif - if ( item ) - item->updateLegend(this); - } -} + \brief Set the default mode for legend labels -/*! - \return the legend display policy. - Default is LegendDisplayPolicy::Auto. - \sa setDisplayPolicy, LegendDisplayPolicy -*/ + Legend labels will be constructed according to the + attributes in a QwtLegendData object. When it doesn't + contain a value for the QwtLegendData::ModeRole the + label will be initialized with the default mode of the legend. -QwtLegend::LegendDisplayPolicy QwtLegend::displayPolicy() const -{ - return d_data->displayPolicy; -} + \param mode Default item mode -void QwtLegend::setItemMode(LegendItemMode mode) + \sa itemMode(), QwtLegendData::value(), QwtPlotItem::legendData() + \note Changing the mode doesn't have any effect on existing labels. + */ +void QwtLegend::setDefaultItemMode( QwtLegendData::Mode mode ) { d_data->itemMode = mode; } -QwtLegend::LegendItemMode QwtLegend::itemMode() const -{ - return d_data->itemMode; -} - /*! - \return the IdentifierMode to be used in combination with - LegendDisplayPolicy::Fixed. - - Default is ShowLine | ShowSymbol | ShowText. + \return Default item mode + \sa setDefaultItemMode() */ - -int QwtLegend::identifierMode() const +QwtLegendData::Mode QwtLegend::defaultItemMode() const { - return d_data->identifierMode; + return d_data->itemMode; } /*! - The contents widget is the only child of the viewport() and - the parent widget of all legend items. + The contents widget is the only child of the viewport of + the internal QScrollArea and the parent widget of all legend items. + + \return Container widget of the legend items */ QWidget *QwtLegend::contentsWidget() { return d_data->view->contentsWidget; } +/*! + \return Horizontal scrollbar + \sa verticalScrollBar() +*/ QScrollBar *QwtLegend::horizontalScrollBar() const { return d_data->view->horizontalScrollBar(); } +/*! + \return Vertical scrollbar + \sa horizontalScrollBar() +*/ QScrollBar *QwtLegend::verticalScrollBar() const { return d_data->view->verticalScrollBar(); } /*! - The contents widget is the only child of the viewport() and - the parent widget of all legend items. -*/ + The contents widget is the only child of the viewport of + the internal QScrollArea and the parent widget of all legend items. + \return Container widget of the legend items + +*/ const QWidget *QwtLegend::contentsWidget() const { return d_data->view->contentsWidget; } /*! - Insert a new item for a plot item - \param plotItem Plot item - \param legendItem New legend item - \note The parent of item will be changed to QwtLegend::contentsWidget() -*/ -void QwtLegend::insert(const QwtLegendItemManager *plotItem, QWidget *legendItem) + \brief Update the entries for an item + + \param itemInfo Info for an item + \param data List of legend entry attributes for the item + */ +void QwtLegend::updateLegend( const QVariant &itemInfo, + const QList<QwtLegendData> &data ) { - if ( legendItem == NULL || plotItem == NULL ) - return; + QList<QWidget *> widgetList = legendWidgets( itemInfo ); - QWidget *contentsWidget = d_data->view->contentsWidget; + if ( widgetList.size() != data.size() ) + { + QLayout *contentsLayout = d_data->view->contentsWidget->layout(); - if ( legendItem->parent() != contentsWidget ) { -#if QT_VERSION >= 0x040000 - legendItem->setParent(contentsWidget); -#else - legendItem->reparent(contentsWidget, QPoint(0, 0)); -#endif - } + while ( widgetList.size() > data.size() ) + { + QWidget *w = widgetList.takeLast(); - legendItem->show(); + contentsLayout->removeWidget( w ); - d_data->map.insert(plotItem, legendItem); + // updates might be triggered by signals from the legend widget + // itself. So we better don't delete it here. - layoutContents(); + w->hide(); + w->deleteLater(); + } - if ( contentsWidget->layout() ) { -#if QT_VERSION >= 0x040000 - contentsWidget->layout()->addWidget(legendItem); -#endif + for ( int i = widgetList.size(); i < data.size(); i++ ) + { + QWidget *widget = createWidget( data[i] ); - // set tab focus chain + if ( contentsLayout ) + contentsLayout->addWidget( widget ); - QWidget *w = NULL; + widgetList += widget; + } -#if QT_VERSION < 0x040000 - QLayoutIterator layoutIterator = - contentsWidget->layout()->iterator(); - for ( QLayoutItem *item = layoutIterator.current(); - item != 0; item = ++layoutIterator) { -#else - for (int i = 0; i < contentsWidget->layout()->count(); i++) { - QLayoutItem *item = contentsWidget->layout()->itemAt(i); -#endif - if ( w && item->widget() ) { - QWidget::setTabOrder(w, item->widget()); - w = item->widget(); - } + if ( widgetList.isEmpty() ) + { + d_data->itemMap.remove( itemInfo ); } + else + { + d_data->itemMap.insert( itemInfo, widgetList ); + } + + updateTabOrder(); } - if ( parentWidget() && parentWidget()->layout() == NULL ) { - /* - updateGeometry() doesn't post LayoutRequest in certain - situations, like when we are hidden. But we want the - parent widget notified, so it can show/hide the legend - depending on its items. - */ -#if QT_VERSION < 0x040000 - QApplication::postEvent(parentWidget(), - new QEvent(QEvent::LayoutHint)); -#else - QApplication::postEvent(parentWidget(), - new QEvent(QEvent::LayoutRequest)); -#endif - } + + for ( int i = 0; i < data.size(); i++ ) + updateWidget( widgetList[i], data[i] ); } /*! - Find the widget that represents a plot item + \brief Create a widget to be inserted into the legend - \param plotItem Plot item - \return Widget on the legend, or NULL -*/ -QWidget *QwtLegend::find(const QwtLegendItemManager *plotItem) const + The default implementation returns a QwtLegendLabel. + + \param data Attributes of the legend entry + \return Widget representing data on the legend + + \note updateWidget() will called soon after createWidget() + with the same attributes. + */ +QWidget *QwtLegend::createWidget( const QwtLegendData &data ) const { - return d_data->map.find(plotItem); -} + Q_UNUSED( data ); -/*! - Find the widget that represents a plot item + QwtLegendLabel *label = new QwtLegendLabel(); + label->setItemMode( defaultItemMode() ); - \param plotItem Plot item - \return Widget on the legend, or NULL -*/ -QwtLegendItemManager *QwtLegend::find(const QWidget *legendItem) const -{ - return d_data->map.find(legendItem); + connect( label, SIGNAL( clicked() ), SLOT( itemClicked() ) ); + connect( label, SIGNAL( checked( bool ) ), SLOT( itemChecked( bool ) ) ); + + return label; } /*! - Find the corresponding item for a plotItem and remove it - from the item list. + \brief Update the widget - \param plotItem Plot item -*/ -void QwtLegend::remove(const QwtLegendItemManager *plotItem) + \param widget Usually a QwtLegendLabel + \param data Attributes to be displayed + + \sa createWidget() + \note When widget is no QwtLegendLabel updateWidget() does nothing. + */ +void QwtLegend::updateWidget( QWidget *widget, const QwtLegendData &data ) { - QWidget *legendItem = d_data->map.find(plotItem); - d_data->map.remove(legendItem); - delete legendItem; + QwtLegendLabel *label = qobject_cast<QwtLegendLabel *>( widget ); + if ( label ) + { + label->setData( data ); + if ( !data.value( QwtLegendData::ModeRole ).isValid() ) + { + // use the default mode, when there is no specific + // hint from the legend data + + label->setItemMode( defaultItemMode() ); + } + } } -//! Remove all items. -void QwtLegend::clear() +void QwtLegend::updateTabOrder() { -#if QT_VERSION < 0x040000 - bool doUpdate = isUpdatesEnabled(); -#else - bool doUpdate = updatesEnabled(); -#endif - setUpdatesEnabled(false); + QLayout *contentsLayout = d_data->view->contentsWidget->layout(); + if ( contentsLayout ) + { + // set tab focus chain - d_data->map.clear(); + QWidget *w = NULL; + + for ( int i = 0; i < contentsLayout->count(); i++ ) + { + QLayoutItem *item = contentsLayout->itemAt( i ); + if ( w && item->widget() ) + QWidget::setTabOrder( w, item->widget() ); - setUpdatesEnabled(doUpdate); - update(); + w = item->widget(); + } + } } //! Return a size hint. QSize QwtLegend::sizeHint() const { QSize hint = d_data->view->contentsWidget->sizeHint(); - hint += QSize(2 * frameWidth(), 2 * frameWidth()); + hint += QSize( 2 * frameWidth(), 2 * frameWidth() ); return hint; } /*! - \return The preferred height, for the width w. + \return The preferred height, for a width. \param width Width */ -int QwtLegend::heightForWidth(int width) const +int QwtLegend::heightForWidth( int width ) const { width -= 2 * frameWidth(); - int h = d_data->view->contentsWidget->heightForWidth(width); -#if QT_VERSION < 0x040000 - - // Asking the layout is the default implementation in Qt4 - - if ( h <= 0 ) { - QLayout *l = d_data->view->contentsWidget->layout(); - if ( l && l->hasHeightForWidth() ) - h = l->heightForWidth(width); - } -#endif + int h = d_data->view->contentsWidget->heightForWidth( width ); if ( h >= 0 ) h += 2 * frameWidth(); return h; } + /*! - Adjust contents widget and item layout to the size of the viewport(). -*/ -void QwtLegend::layoutContents() -{ - const QSize visibleSize = d_data->view->viewport()->size(); + Handle QEvent::ChildRemoved andQEvent::LayoutRequest events + for the contentsWidget(). - const QLayout *l = d_data->view->contentsWidget->layout(); - if ( l && l->inherits("QwtDynGridLayout") ) { - const QwtDynGridLayout *tl = (const QwtDynGridLayout *)l; + \param object Object to be filtered + \param event Event - const int minW = int(tl->maxItemWidth()) + 2 * tl->margin(); + \return Forwarded to QwtAbstractLegend::eventFilter() +*/ +bool QwtLegend::eventFilter( QObject *object, QEvent *event ) +{ + if ( object == d_data->view->contentsWidget ) + { + switch ( event->type() ) + { + case QEvent::ChildRemoved: + { + const QChildEvent *ce = + static_cast<const QChildEvent *>(event); + if ( ce->child()->isWidgetType() ) + { + QWidget *w = static_cast< QWidget * >( ce->child() ); + d_data->itemMap.removeWidget( w ); + } + break; + } + case QEvent::LayoutRequest: + { + d_data->view->layoutContents(); + + if ( parentWidget() && parentWidget()->layout() == NULL ) + { + /* + We want the parent widget ( usually QwtPlot ) to recalculate + its layout, when the contentsWidget has changed. But + because of the scroll view we have to forward the LayoutRequest + event manually. + + We don't use updateGeometry() because it doesn't post LayoutRequest + events when the legend is hidden. But we want the + parent widget notified, so it can show/hide the legend + depending on its items. + */ + QApplication::postEvent( parentWidget(), + new QEvent( QEvent::LayoutRequest ) ); + } + break; + } + default: + break; + } + } - int w = qwtMax(visibleSize.width(), minW); - int h = qwtMax(tl->heightForWidth(w), visibleSize.height()); + return QwtAbstractLegend::eventFilter( object, event ); +} - const int vpWidth = d_data->view->viewportSize(w, h).width(); - if ( w > vpWidth ) { - w = qwtMax(vpWidth, minW); - h = qwtMax(tl->heightForWidth(w), visibleSize.height()); +/*! + Called internally when the legend has been clicked on. + Emits a clicked() signal. +*/ +void QwtLegend::itemClicked() +{ + QWidget *w = qobject_cast<QWidget *>( sender() ); + if ( w ) + { + const QVariant itemInfo = d_data->itemMap.itemInfo( w ); + if ( itemInfo.isValid() ) + { + const QList<QWidget *> widgetList = + d_data->itemMap.legendWidgets( itemInfo ); + + const int index = widgetList.indexOf( w ); + if ( index >= 0 ) + Q_EMIT clicked( itemInfo, index ); } + } +} - d_data->view->contentsWidget->resize(w, h); -#if QT_VERSION < 0x040000 - d_data->view->resizeContents(w, h); -#endif +/*! + Called internally when the legend has been checked + Emits a checked() signal. +*/ +void QwtLegend::itemChecked( bool on ) +{ + QWidget *w = qobject_cast<QWidget *>( sender() ); + if ( w ) + { + const QVariant itemInfo = d_data->itemMap.itemInfo( w ); + if ( itemInfo.isValid() ) + { + const QList<QWidget *> widgetList = + d_data->itemMap.legendWidgets( itemInfo ); + + const int index = widgetList.indexOf( w ); + if ( index >= 0 ) + Q_EMIT checked( itemInfo, on, index ); + } } } -/* - Filter layout related events of QwtLegend::contentsWidget(). +/*! + Render the legend into a given rectangle. - \param o Object to be filtered - \param e Event -*/ + \param painter Painter + \param rect Bounding rectangle + \param fillBackground When true, fill rect with the widget background -bool QwtLegend::eventFilter(QObject *o, QEvent *e) + \sa renderLegend() is used by QwtPlotRenderer - not by QwtLegend itself +*/ +void QwtLegend::renderLegend( QPainter *painter, + const QRectF &rect, bool fillBackground ) const { - if ( o == d_data->view->contentsWidget ) { - switch(e->type()) { - case QEvent::ChildRemoved: { - const QChildEvent *ce = (const QChildEvent *)e; - if ( ce->child()->isWidgetType() ) - d_data->map.remove((QWidget *)ce->child()); - break; - } -#if QT_VERSION < 0x040000 - case QEvent::LayoutHint: -#else - case QEvent::LayoutRequest: -#endif - { - layoutContents(); - break; - } -#if QT_VERSION < 0x040000 - case QEvent::Resize: { - updateGeometry(); - break; - } -#endif - default: - break; + if ( d_data->itemMap.isEmpty() ) + return; + + if ( fillBackground ) + { + if ( autoFillBackground() || + testAttribute( Qt::WA_StyledBackground ) ) + { + QwtPainter::drawBackgound( painter, rect, this ); } } - return QFrame::eventFilter(o, e); + const QwtDynGridLayout *legendLayout = + qobject_cast<QwtDynGridLayout *>( contentsWidget()->layout() ); + if ( legendLayout == NULL ) + return; + + int left, right, top, bottom; + getContentsMargins( &left, &top, &right, &bottom ); + + QRect layoutRect; + layoutRect.setLeft( qCeil( rect.left() ) + left ); + layoutRect.setTop( qCeil( rect.top() ) + top ); + layoutRect.setRight( qFloor( rect.right() ) - right ); + layoutRect.setBottom( qFloor( rect.bottom() ) - bottom ); + + uint numCols = legendLayout->columnsForWidth( layoutRect.width() ); + QList<QRect> itemRects = + legendLayout->layoutItems( layoutRect, numCols ); + + int index = 0; + + for ( int i = 0; i < legendLayout->count(); i++ ) + { + QLayoutItem *item = legendLayout->itemAt( i ); + QWidget *w = item->widget(); + if ( w ) + { + painter->save(); + + painter->setClipRect( itemRects[index], Qt::IntersectClip ); + renderItem( painter, w, itemRects[index], fillBackground ); + + index++; + painter->restore(); + } + } } +/*! + Render a legend entry into a given rectangle. -//! Return true, if there are no legend items. -bool QwtLegend::isEmpty() const + \param painter Painter + \param widget Widget representing a legend entry + \param rect Bounding rectangle + \param fillBackground When true, fill rect with the widget background + + \note When widget is not derived from QwtLegendLabel renderItem + does nothing beside the background +*/ +void QwtLegend::renderItem( QPainter *painter, + const QWidget *widget, const QRectF &rect, bool fillBackground ) const { - return d_data->map.count() == 0; + if ( fillBackground ) + { + if ( widget->autoFillBackground() || + widget->testAttribute( Qt::WA_StyledBackground ) ) + { + QwtPainter::drawBackgound( painter, rect, widget ); + } + } + + const QwtLegendLabel *label = qobject_cast<const QwtLegendLabel *>( widget ); + if ( label ) + { + // icon + + const QwtGraphic &icon = label->data().icon(); + const QSizeF sz = icon.defaultSize(); + + const QRectF iconRect( rect.x() + label->margin(), + rect.center().y() - 0.5 * sz.height(), + sz.width(), sz.height() ); + + icon.render( painter, iconRect, Qt::KeepAspectRatio ); + + // title + + QRectF titleRect = rect; + titleRect.setX( iconRect.right() + 2 * label->spacing() ); + + painter->setFont( label->font() ); + painter->setPen( label->palette().color( QPalette::Text ) ); + const_cast< QwtLegendLabel *>( label )->drawText( painter, titleRect ); + } } -//! Return the number of legend items. -uint QwtLegend::itemCount() const +/*! + \return List of widgets associated to a item + \param itemInfo Info about an item + \sa legendWidget(), itemInfo(), QwtPlot::itemToInfo() + */ +QList<QWidget *> QwtLegend::legendWidgets( const QVariant &itemInfo ) const { - return d_data->map.count(); + return d_data->itemMap.legendWidgets( itemInfo ); } -#if QT_VERSION < 0x040000 -QValueList<QWidget *> QwtLegend::legendItems() const -#else -QList<QWidget *> QwtLegend::legendItems() const -#endif +/*! + \return First widget in the list of widgets associated to an item + \param itemInfo Info about an item + \sa itemInfo(), QwtPlot::itemToInfo() + \note Almost all types of items have only one widget +*/ +QWidget *QwtLegend::legendWidget( const QVariant &itemInfo ) const { - const QMap<QWidget *, const QwtLegendItemManager *> &map = - d_data->map.widgetMap(); + const QList<QWidget *> list = d_data->itemMap.legendWidgets( itemInfo ); + if ( list.isEmpty() ) + return NULL; -#if QT_VERSION < 0x040000 - QValueList<QWidget *> list; -#else - QList<QWidget *> list; -#endif + return list[0]; +} + +/*! + Find the item that is associated to a widget - QMap<QWidget *, const QwtLegendItemManager *>::const_iterator it; - for ( it = map.begin(); it != map.end(); ++it ) - list += it.key(); + \param widget Widget on the legend + \return Associated item info + \sa legendWidget() + */ +QVariant QwtLegend::itemInfo( const QWidget *widget ) const +{ + return d_data->itemMap.itemInfo( widget ); +} - return list; +//! \return True, when no item is inserted +bool QwtLegend::isEmpty() const +{ + return d_data->itemMap.isEmpty(); } /*! - Resize event - \param e Event -*/ -void QwtLegend::resizeEvent(QResizeEvent *e) + Return the extent, that is needed for the scrollbars + + \param orientation Orientation ( + \return The width of the vertical scrollbar for Qt::Horizontal and v.v. + */ +int QwtLegend::scrollExtent( Qt::Orientation orientation ) const { - QFrame::resizeEvent(e); - d_data->view->setGeometry(contentsRect()); + int extent = 0; + + if ( orientation == Qt::Horizontal ) + extent = verticalScrollBar()->sizeHint().width(); + else + extent = horizontalScrollBar()->sizeHint().height(); + + return extent; } + diff --git a/libs/qwt/qwt_legend.h b/libs/qwt/qwt_legend.h index 4d73069921..3d8fca67a3 100644 --- a/libs/qwt/qwt_legend.h +++ b/libs/qwt/qwt_legend.h @@ -7,117 +7,111 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_LEGEND_H #define QWT_LEGEND_H -#include <qframe.h> #include "qwt_global.h" -#if QT_VERSION < 0x040000 -#include <qvaluelist.h> -#else -#include <qlist.h> -#endif +#include "qwt_abstract_legend.h" +#include <qvariant.h> class QScrollBar; -class QwtLegendItemManager; /*! \brief The legend widget The QwtLegend widget is a tabular arrangement of legend items. Legend items might be any type of widget, but in general they will be - a QwtLegendItem. + a QwtLegendLabel. - \sa QwtLegendItem, QwtLegendItemManager QwtPlot + \sa QwtLegendLabel, QwtPlotItem, QwtPlot */ -class QWT_EXPORT QwtLegend : public QFrame +class QWT_EXPORT QwtLegend : public QwtAbstractLegend { Q_OBJECT public: - /*! - \brief Display policy + explicit QwtLegend( QWidget *parent = NULL ); + virtual ~QwtLegend(); - - NoIdentifier\n - The client code is responsible how to display of each legend item. - The Qwt library will not interfere. + void setMaxColumns( uint numColums ); + uint maxColumns() const; - - FixedIdentifier\n - All legend items are displayed with the QwtLegendItem::IdentifierMode - to be passed in 'mode'. + void setDefaultItemMode( QwtLegendData::Mode ); + QwtLegendData::Mode defaultItemMode() const; - - AutoIdentifier\n - Each legend item is displayed with a mode that is a bitwise or of - - QwtLegendItem::ShowLine (if its curve is drawn with a line) and - - QwtLegendItem::ShowSymbol (if its curve is drawn with symbols) and - - QwtLegendItem::ShowText (if the has a title). + QWidget *contentsWidget(); + const QWidget *contentsWidget() const; - Default is AutoIdentifier. - \sa setDisplayPolicy(), displayPolicy(), QwtLegendItem::IdentifierMode - */ + QWidget *legendWidget( const QVariant & ) const; + QList<QWidget *> legendWidgets( const QVariant & ) const; - enum LegendDisplayPolicy { - NoIdentifier = 0, - FixedIdentifier = 1, - AutoIdentifier = 2 - }; + QVariant itemInfo( const QWidget * ) const; - //! Interaction mode for the legend items - enum LegendItemMode { - ReadOnlyItem, - ClickableItem, - CheckableItem - }; + virtual bool eventFilter( QObject *, QEvent * ); - explicit QwtLegend(QWidget *parent = NULL); - virtual ~QwtLegend(); + virtual QSize sizeHint() const; + virtual int heightForWidth( int w ) const; - void setDisplayPolicy(LegendDisplayPolicy policy, int mode); - LegendDisplayPolicy displayPolicy() const; + QScrollBar *horizontalScrollBar() const; + QScrollBar *verticalScrollBar() const; - void setItemMode(LegendItemMode); - LegendItemMode itemMode() const; + virtual void renderLegend( QPainter *, + const QRectF &, bool fillBackground ) const; - int identifierMode() const; + virtual void renderItem( QPainter *, + const QWidget *, const QRectF &, bool fillBackground ) const; - QWidget *contentsWidget(); - const QWidget *contentsWidget() const; + virtual bool isEmpty() const; + virtual int scrollExtent( Qt::Orientation ) const; - void insert(const QwtLegendItemManager *, QWidget *); - void remove(const QwtLegendItemManager *); +Q_SIGNALS: + /*! + A signal which is emitted when the user has clicked on + a legend label, which is in QwtLegendData::Clickable mode. - QWidget *find(const QwtLegendItemManager *) const; - QwtLegendItemManager *find(const QWidget *) const; + \param itemInfo Info for the item item of the + selected legend item + \param index Index of the legend label in the list of widgets + that are associated with the plot item -#if QT_VERSION < 0x040000 - virtual QValueList<QWidget *> legendItems() const; -#else - virtual QList<QWidget *> legendItems() const; -#endif + \note clicks are disabled as default + \sa setDefaultItemMode(), defaultItemMode(), QwtPlot::itemToInfo() + */ + void clicked( const QVariant &itemInfo, int index ); - void clear(); + /*! + A signal which is emitted when the user has clicked on + a legend label, which is in QwtLegendData::Checkable mode - bool isEmpty() const; - uint itemCount() const; + \param itemInfo Info for the item of the + selected legend label + \param index Index of the legend label in the list of widgets + that are associated with the plot item + \param on True when the legend label is checked - virtual bool eventFilter(QObject *, QEvent *); + \note clicks are disabled as default + \sa setDefaultItemMode(), defaultItemMode(), QwtPlot::itemToInfo() + */ + void checked( const QVariant &itemInfo, bool on, int index ); - virtual QSize sizeHint() const; - virtual int heightForWidth(int w) const; +public Q_SLOTS: + virtual void updateLegend( const QVariant &, + const QList<QwtLegendData> & ); - QScrollBar *horizontalScrollBar() const; - QScrollBar *verticalScrollBar() const; +protected Q_SLOTS: + void itemClicked(); + void itemChecked( bool ); protected: - virtual void resizeEvent(QResizeEvent *); - virtual void layoutContents(); + virtual QWidget *createWidget( const QwtLegendData & ) const; + virtual void updateWidget( QWidget *widget, const QwtLegendData &data ); private: + void updateTabOrder(); + class PrivateData; PrivateData *d_data; }; -#endif // QWT_LEGEND_H +#endif diff --git a/libs/qwt/qwt_legend_data.cpp b/libs/qwt/qwt_legend_data.cpp new file mode 100644 index 0000000000..cf0cb2ce36 --- /dev/null +++ b/libs/qwt/qwt_legend_data.cpp @@ -0,0 +1,129 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_legend_data.h" + +//! Constructor +QwtLegendData::QwtLegendData() +{ +} + +//! Destructor +QwtLegendData::~QwtLegendData() +{ +} + +/*! + Set the legend attributes + + QwtLegendData actually is a QMap<int, QVariant> with some + convenience interfaces + + \param map Values + \sa values() + */ +void QwtLegendData::setValues( const QMap<int, QVariant> &map ) +{ + d_map = map; +} + +/*! + \return Legend attributes + \sa setValues() + */ +const QMap<int, QVariant> &QwtLegendData::values() const +{ + return d_map; +} + +/*! + \param role Attribute role + \return True, when the internal map has an entry for role + */ +bool QwtLegendData::hasRole( int role ) const +{ + return d_map.contains( role ); +} + +/*! + Set an attribute value + + \param role Attribute role + \param data Attribute value + + \sa value() + */ +void QwtLegendData::setValue( int role, const QVariant &data ) +{ + d_map[role] = data; +} + +/*! + \param role Attribute role + \return Attribute value for a specific role + */ +QVariant QwtLegendData::value( int role ) const +{ + if ( !d_map.contains( role ) ) + return QVariant(); + + return d_map[role]; +} + +//! \return True, when the internal map is empty +bool QwtLegendData::isValid() const +{ + return !d_map.isEmpty(); +} + +//! \return Value of the TitleRole attribute +QwtText QwtLegendData::title() const +{ + QwtText text; + + const QVariant titleValue = value( QwtLegendData::TitleRole ); + if ( titleValue.canConvert<QwtText>() ) + { + text = qvariant_cast<QwtText>( titleValue ); + } + else if ( titleValue.canConvert<QString>() ) + { + text.setText( qvariant_cast<QString>( titleValue ) ); + } + + return text; +} + +//! \return Value of the IconRole attribute +QwtGraphic QwtLegendData::icon() const +{ + const QVariant iconValue = value( QwtLegendData::IconRole ); + + QwtGraphic graphic; + if ( iconValue.canConvert<QwtGraphic>() ) + { + graphic = qvariant_cast<QwtGraphic>( iconValue ); + } + + return graphic; +} + +//! \return Value of the ModeRole attribute +QwtLegendData::Mode QwtLegendData::mode() const +{ + const QVariant modeValue = value( QwtLegendData::ModeRole ); + if ( modeValue.canConvert<int>() ) + { + const int mode = qvariant_cast<int>( modeValue ); + return static_cast<QwtLegendData::Mode>( mode ); + } + + return QwtLegendData::ReadOnly; +} + diff --git a/libs/qwt/qwt_legend_data.h b/libs/qwt/qwt_legend_data.h new file mode 100644 index 0000000000..d83e13264f --- /dev/null +++ b/libs/qwt/qwt_legend_data.h @@ -0,0 +1,87 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_LEGEND_DATA_H +#define QWT_LEGEND_DATA_H + +#include "qwt_global.h" +#include "qwt_text.h" +#include "qwt_graphic.h" +#include <qvariant.h> +#include <qpixmap.h> +#include <qmap.h> + +/*! + \brief Attributes of an entry on a legend + + QwtLegendData is an abstract container ( like QAbstractModel ) + to exchange attributes, that are only known between to + the plot item and the legend. + + By overloading QwtPlotItem::legendData() any other set of attributes + could be used, that can be handled by a modified ( or completely + different ) implementation of a legend. + + \sa QwtLegend, QwtPlotLegendItem + \note The stockchart example implements a legend as a tree + with checkable items + */ +class QWT_EXPORT QwtLegendData +{ +public: + //! Mode defining how a legend entry interacts + enum Mode + { + //! The legend item is not interactive, like a label + ReadOnly, + + //! The legend item is clickable, like a push button + Clickable, + + //! The legend item is checkable, like a checkable button + Checkable + }; + + //! Identifier how to interprete a QVariant + enum Role + { + // The value is a Mode + ModeRole, + + // The value is a title + TitleRole, + + // The value is an icon + IconRole, + + // Values < UserRole are reserved for internal use + UserRole = 32 + }; + + QwtLegendData(); + ~QwtLegendData(); + + void setValues( const QMap<int, QVariant> & ); + const QMap<int, QVariant> &values() const; + + void setValue( int role, const QVariant & ); + QVariant value( int role ) const; + + bool hasRole( int role ) const; + bool isValid() const; + + QwtGraphic icon() const; + QwtText title() const; + Mode mode() const; + +private: + QMap<int, QVariant> d_map; +}; + +#endif diff --git a/libs/qwt/qwt_legend_label.cpp b/libs/qwt/qwt_legend_label.cpp new file mode 100644 index 0000000000..19a7eb9578 --- /dev/null +++ b/libs/qwt/qwt_legend_label.cpp @@ -0,0 +1,421 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_legend_label.h" +#include "qwt_legend_data.h" +#include "qwt_math.h" +#include "qwt_painter.h" +#include "qwt_symbol.h" +#include "qwt_graphic.h" +#include <qpainter.h> +#include <qdrawutil.h> +#include <qstyle.h> +#include <qpen.h> +#include <qevent.h> +#include <qstyleoption.h> +#include <qapplication.h> + +static const int ButtonFrame = 2; +static const int Margin = 2; + +static QSize buttonShift( const QwtLegendLabel *w ) +{ + QStyleOption option; + option.init( w ); + + const int ph = w->style()->pixelMetric( + QStyle::PM_ButtonShiftHorizontal, &option, w ); + const int pv = w->style()->pixelMetric( + QStyle::PM_ButtonShiftVertical, &option, w ); + return QSize( ph, pv ); +} + +class QwtLegendLabel::PrivateData +{ +public: + PrivateData(): + itemMode( QwtLegendData::ReadOnly ), + isDown( false ), + spacing( Margin ) + { + } + + QwtLegendData::Mode itemMode; + QwtLegendData legendData; + bool isDown; + + QPixmap icon; + + int spacing; +}; + +/*! + Set the attributes of the legend label + + \param legendData Attributes of the label + \sa data() + */ +void QwtLegendLabel::setData( const QwtLegendData &legendData ) +{ + d_data->legendData = legendData; + + const bool doUpdate = updatesEnabled(); + setUpdatesEnabled( false ); + + setText( legendData.title() ); + setIcon( legendData.icon().toPixmap() ); + + if ( legendData.hasRole( QwtLegendData::ModeRole ) ) + setItemMode( legendData.mode() ); + + if ( doUpdate ) + { + setUpdatesEnabled( true ); + update(); + } +} + +/*! + \return Attributes of the label + \sa setData(), QwtPlotItem::legendData() + */ +const QwtLegendData &QwtLegendLabel::data() const +{ + return d_data->legendData; +} + +/*! + \param parent Parent widget +*/ +QwtLegendLabel::QwtLegendLabel( QWidget *parent ): + QwtTextLabel( parent ) +{ + d_data = new PrivateData; + setMargin( Margin ); + setIndent( Margin ); +} + +//! Destructor +QwtLegendLabel::~QwtLegendLabel() +{ + delete d_data; + d_data = NULL; +} + +/*! + Set the text to the legend item + + \param text Text label + \sa QwtTextLabel::text() +*/ +void QwtLegendLabel::setText( const QwtText &text ) +{ + const int flags = Qt::AlignLeft | Qt::AlignVCenter + | Qt::TextExpandTabs | Qt::TextWordWrap; + + QwtText txt = text; + txt.setRenderFlags( flags ); + + QwtTextLabel::setText( txt ); +} + +/*! + Set the item mode + The default is QwtLegendData::ReadOnly + + \param mode Item mode + \sa itemMode() +*/ +void QwtLegendLabel::setItemMode( QwtLegendData::Mode mode ) +{ + if ( mode != d_data->itemMode ) + { + d_data->itemMode = mode; + d_data->isDown = false; + + setFocusPolicy( ( mode != QwtLegendData::ReadOnly ) + ? Qt::TabFocus : Qt::NoFocus ); + setMargin( ButtonFrame + Margin ); + + updateGeometry(); + } +} + +/*! + \return Item mode + \sa setItemMode() +*/ +QwtLegendData::Mode QwtLegendLabel::itemMode() const +{ + return d_data->itemMode; +} + +/*! + Assign the icon + + \param icon Pixmap representing a plot item + + \sa icon(), QwtPlotItem::legendIcon() +*/ +void QwtLegendLabel::setIcon( const QPixmap &icon ) +{ + d_data->icon = icon; + + int indent = margin() + d_data->spacing; + if ( icon.width() > 0 ) + indent += icon.width() + d_data->spacing; + + setIndent( indent ); +} + +/*! + \return Pixmap representing a plot item + \sa setIcon() +*/ +QPixmap QwtLegendLabel::icon() const +{ + return d_data->icon; +} + +/*! + \brief Change the spacing between icon and text + + \param spacing Spacing + \sa spacing(), QwtTextLabel::margin() +*/ +void QwtLegendLabel::setSpacing( int spacing ) +{ + spacing = qMax( spacing, 0 ); + if ( spacing != d_data->spacing ) + { + d_data->spacing = spacing; + + int indent = margin() + d_data->spacing; + if ( d_data->icon.width() > 0 ) + indent += d_data->icon.width() + d_data->spacing; + + setIndent( indent ); + } +} + +/*! + \return Spacing between icon and text + \sa setSpacing(), QwtTextLabel::margin() +*/ +int QwtLegendLabel::spacing() const +{ + return d_data->spacing; +} + +/*! + Check/Uncheck a the item + + \param on check/uncheck + \sa setItemMode() +*/ +void QwtLegendLabel::setChecked( bool on ) +{ + if ( d_data->itemMode == QwtLegendData::Checkable ) + { + const bool isBlocked = signalsBlocked(); + blockSignals( true ); + + setDown( on ); + + blockSignals( isBlocked ); + } +} + +//! Return true, if the item is checked +bool QwtLegendLabel::isChecked() const +{ + return d_data->itemMode == QwtLegendData::Checkable && isDown(); +} + +//! Set the item being down +void QwtLegendLabel::setDown( bool down ) +{ + if ( down == d_data->isDown ) + return; + + d_data->isDown = down; + update(); + + if ( d_data->itemMode == QwtLegendData::Clickable ) + { + if ( d_data->isDown ) + Q_EMIT pressed(); + else + { + Q_EMIT released(); + Q_EMIT clicked(); + } + } + + if ( d_data->itemMode == QwtLegendData::Checkable ) + Q_EMIT checked( d_data->isDown ); +} + +//! Return true, if the item is down +bool QwtLegendLabel::isDown() const +{ + return d_data->isDown; +} + +//! Return a size hint +QSize QwtLegendLabel::sizeHint() const +{ + QSize sz = QwtTextLabel::sizeHint(); + sz.setHeight( qMax( sz.height(), d_data->icon.height() + 4 ) ); + + if ( d_data->itemMode != QwtLegendData::ReadOnly ) + { + sz += buttonShift( this ); + sz = sz.expandedTo( QApplication::globalStrut() ); + } + + return sz; +} + +//! Paint event +void QwtLegendLabel::paintEvent( QPaintEvent *e ) +{ + const QRect cr = contentsRect(); + + QPainter painter( this ); + painter.setClipRegion( e->region() ); + + if ( d_data->isDown ) + { + qDrawWinButton( &painter, 0, 0, width(), height(), + palette(), true ); + } + + painter.save(); + + if ( d_data->isDown ) + { + const QSize shiftSize = buttonShift( this ); + painter.translate( shiftSize.width(), shiftSize.height() ); + } + + painter.setClipRect( cr ); + + drawContents( &painter ); + + if ( !d_data->icon.isNull() ) + { + QRect iconRect = cr; + iconRect.setX( iconRect.x() + margin() ); + if ( d_data->itemMode != QwtLegendData::ReadOnly ) + iconRect.setX( iconRect.x() + ButtonFrame ); + + iconRect.setSize( d_data->icon.size() ); + iconRect.moveCenter( QPoint( iconRect.center().x(), cr.center().y() ) ); + + painter.drawPixmap( iconRect, d_data->icon ); + } + + painter.restore(); +} + +//! Handle mouse press events +void QwtLegendLabel::mousePressEvent( QMouseEvent *e ) +{ + if ( e->button() == Qt::LeftButton ) + { + switch ( d_data->itemMode ) + { + case QwtLegendData::Clickable: + { + setDown( true ); + return; + } + case QwtLegendData::Checkable: + { + setDown( !isDown() ); + return; + } + default:; + } + } + QwtTextLabel::mousePressEvent( e ); +} + +//! Handle mouse release events +void QwtLegendLabel::mouseReleaseEvent( QMouseEvent *e ) +{ + if ( e->button() == Qt::LeftButton ) + { + switch ( d_data->itemMode ) + { + case QwtLegendData::Clickable: + { + setDown( false ); + return; + } + case QwtLegendData::Checkable: + { + return; // do nothing, but accept + } + default:; + } + } + QwtTextLabel::mouseReleaseEvent( e ); +} + +//! Handle key press events +void QwtLegendLabel::keyPressEvent( QKeyEvent *e ) +{ + if ( e->key() == Qt::Key_Space ) + { + switch ( d_data->itemMode ) + { + case QwtLegendData::Clickable: + { + if ( !e->isAutoRepeat() ) + setDown( true ); + return; + } + case QwtLegendData::Checkable: + { + if ( !e->isAutoRepeat() ) + setDown( !isDown() ); + return; + } + default:; + } + } + + QwtTextLabel::keyPressEvent( e ); +} + +//! Handle key release events +void QwtLegendLabel::keyReleaseEvent( QKeyEvent *e ) +{ + if ( e->key() == Qt::Key_Space ) + { + switch ( d_data->itemMode ) + { + case QwtLegendData::Clickable: + { + if ( !e->isAutoRepeat() ) + setDown( false ); + return; + } + case QwtLegendData::Checkable: + { + return; // do nothing, but accept + } + default:; + } + } + + QwtTextLabel::keyReleaseEvent( e ); +} diff --git a/libs/qwt/qwt_legend_label.h b/libs/qwt/qwt_legend_label.h new file mode 100644 index 0000000000..f0a1584af3 --- /dev/null +++ b/libs/qwt/qwt_legend_label.h @@ -0,0 +1,80 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_LEGEND_LABEL_H +#define QWT_LEGEND_LABEL_H + +#include "qwt_global.h" +#include "qwt_legend_data.h" +#include "qwt_text.h" +#include "qwt_text_label.h" +#include <qpixmap.h> + +class QwtLegendData; + +/*! + \brief A widget representing something on a QwtLegend. +*/ +class QWT_EXPORT QwtLegendLabel: public QwtTextLabel +{ + Q_OBJECT +public: + explicit QwtLegendLabel( QWidget *parent = 0 ); + virtual ~QwtLegendLabel(); + + void setData( const QwtLegendData & ); + const QwtLegendData &data() const; + + void setItemMode( QwtLegendData::Mode ); + QwtLegendData::Mode itemMode() const; + + void setSpacing( int spacing ); + int spacing() const; + + virtual void setText( const QwtText & ); + + void setIcon( const QPixmap & ); + QPixmap icon() const; + + virtual QSize sizeHint() const; + + bool isChecked() const; + +public Q_SLOTS: + void setChecked( bool on ); + +Q_SIGNALS: + //! Signal, when the legend item has been clicked + void clicked(); + + //! Signal, when the legend item has been pressed + void pressed(); + + //! Signal, when the legend item has been released + void released(); + + //! Signal, when the legend item has been toggled + void checked( bool ); + +protected: + void setDown( bool ); + bool isDown() const; + + virtual void paintEvent( QPaintEvent * ); + virtual void mousePressEvent( QMouseEvent * ); + virtual void mouseReleaseEvent( QMouseEvent * ); + virtual void keyPressEvent( QKeyEvent * ); + virtual void keyReleaseEvent( QKeyEvent * ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_magnifier.cpp b/libs/qwt/qwt_magnifier.cpp index 61b0d8ee16..55e7bb5eb7 100644 --- a/libs/qwt/qwt_magnifier.cpp +++ b/libs/qwt/qwt_magnifier.cpp @@ -7,51 +7,47 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <math.h> +#include "qwt_magnifier.h" +#include "qwt_math.h" #include <qevent.h> #include <qwidget.h> -#include "qwt_math.h" -#include "qwt_magnifier.h" class QwtMagnifier::PrivateData { public: PrivateData(): - isEnabled(false), - wheelFactor(0.9), - wheelButtonState(Qt::NoButton), - mouseFactor(0.95), - mouseButton(Qt::RightButton), - mouseButtonState(Qt::NoButton), - keyFactor(0.9), - zoomInKey(Qt::Key_Plus), - zoomOutKey(Qt::Key_Minus), -#if QT_VERSION < 0x040000 - zoomInKeyModifiers(Qt::NoButton), - zoomOutKeyModifiers(Qt::NoButton), -#else - zoomInKeyModifiers(Qt::NoModifier), - zoomOutKeyModifiers(Qt::NoModifier), -#endif - mousePressed(false) { + isEnabled( false ), + wheelFactor( 0.9 ), + wheelModifiers( Qt::NoModifier ), + mouseFactor( 0.95 ), + mouseButton( Qt::RightButton ), + mouseButtonModifiers( Qt::NoModifier ), + keyFactor( 0.9 ), + zoomInKey( Qt::Key_Plus ), + zoomInKeyModifiers( Qt::NoModifier ), + zoomOutKey( Qt::Key_Minus ), + zoomOutKeyModifiers( Qt::NoModifier ), + mousePressed( false ) + { } bool isEnabled; double wheelFactor; - int wheelButtonState; + Qt::KeyboardModifiers wheelModifiers; double mouseFactor; - int mouseButton; - int mouseButtonState; + + Qt::MouseButton mouseButton; + Qt::KeyboardModifiers mouseButtonModifiers; double keyFactor; + int zoomInKey; + Qt::KeyboardModifiers zoomInKeyModifiers; + int zoomOutKey; - int zoomInKeyModifiers; - int zoomOutKeyModifiers; + Qt::KeyboardModifiers zoomOutKeyModifiers; bool mousePressed; bool hasMouseTracking; @@ -62,11 +58,11 @@ public: Constructor \param parent Widget to be magnified */ -QwtMagnifier::QwtMagnifier(QWidget *parent): - QObject(parent) +QwtMagnifier::QwtMagnifier( QWidget *parent ): + QObject( parent ) { d_data = new PrivateData(); - setEnabled(true); + setEnabled( true ); } //! Destructor @@ -84,24 +80,26 @@ QwtMagnifier::~QwtMagnifier() \param on true or false \sa isEnabled(), eventFilter() */ -void QwtMagnifier::setEnabled(bool on) +void QwtMagnifier::setEnabled( bool on ) { - if ( d_data->isEnabled != on ) { + if ( d_data->isEnabled != on ) + { d_data->isEnabled = on; QObject *o = parent(); - if ( o ) { + if ( o ) + { if ( d_data->isEnabled ) - o->installEventFilter(this); + o->installEventFilter( this ); else - o->removeEventFilter(this); + o->removeEventFilter( this ); } } } /*! \return true when enabled, false otherwise - \sa setEnabled, eventFilter() + \sa setEnabled(), eventFilter() */ bool QwtMagnifier::isEnabled() const { @@ -113,13 +111,18 @@ bool QwtMagnifier::isEnabled() const The wheel factor defines the ratio between the current range on the parent widget and the zoomed range for each step of the wheel. + + Use values > 1 for magnification (i.e. 2.0) and values < 1 for + scaling down (i.e. 1/2.0 = 0.5). You can use this feature for + inverting the direction of the wheel. + The default value is 0.9. \param factor Wheel factor \sa wheelFactor(), setWheelButtonState(), setMouseFactor(), setKeyFactor() */ -void QwtMagnifier::setWheelFactor(double factor) +void QwtMagnifier::setWheelFactor( double factor ) { d_data->wheelFactor = factor; } @@ -134,24 +137,24 @@ double QwtMagnifier::wheelFactor() const } /*! - Assign a mandatory button state for zooming in/out using the wheel. - The default button state is Qt::NoButton. + Assign keyboard modifiers for zooming in/out using the wheel. + The default modifiers are Qt::NoModifiers. - \param buttonState Button state - \sa wheelButtonState + \param modifiers Keyboard modifiers + \sa wheelModifiers() */ -void QwtMagnifier::setWheelButtonState(int buttonState) +void QwtMagnifier::setWheelModifiers( Qt::KeyboardModifiers modifiers ) { - d_data->wheelButtonState = buttonState; + d_data->wheelModifiers = modifiers; } /*! - \return Wheel button state - \sa setWheelButtonState + \return Wheel modifiers + \sa setWheelModifiers() */ -int QwtMagnifier::wheelButtonState() const +Qt::KeyboardModifiers QwtMagnifier::wheelModifiers() const { - return d_data->wheelButtonState; + return d_data->wheelModifiers; } /*! @@ -164,7 +167,7 @@ int QwtMagnifier::wheelButtonState() const \param factor Wheel factor \sa mouseFactor(), setMouseButton(), setWheelFactor(), setKeyFactor() */ -void QwtMagnifier::setMouseFactor(double factor) +void QwtMagnifier::setMouseFactor( double factor ) { d_data->mouseFactor = factor; } @@ -183,21 +186,23 @@ double QwtMagnifier::mouseFactor() const The default value is Qt::RightButton. \param button Button - \param buttonState Button state - \sa getMouseButton + \param modifiers Keyboard modifiers + + \sa getMouseButton() */ -void QwtMagnifier::setMouseButton(int button, int buttonState) +void QwtMagnifier::setMouseButton( + Qt::MouseButton button, Qt::KeyboardModifiers modifiers ) { d_data->mouseButton = button; - d_data->mouseButtonState = buttonState; + d_data->mouseButtonModifiers = modifiers; } -//! \sa setMouseButton +//! \sa setMouseButton() void QwtMagnifier::getMouseButton( - int &button, int &buttonState) const + Qt::MouseButton &button, Qt::KeyboardModifiers &modifiers ) const { button = d_data->mouseButton; - buttonState = d_data->mouseButtonState; + modifiers = d_data->mouseButtonModifiers; } /*! @@ -211,7 +216,7 @@ void QwtMagnifier::getMouseButton( \sa keyFactor(), setZoomInKey(), setZoomOutKey(), setWheelFactor, setMouseFactor() */ -void QwtMagnifier::setKeyFactor(double factor) +void QwtMagnifier::setKeyFactor( double factor ) { d_data->keyFactor = factor; } @@ -233,14 +238,23 @@ double QwtMagnifier::keyFactor() const \param modifiers \sa getZoomInKey(), setZoomOutKey() */ -void QwtMagnifier::setZoomInKey(int key, int modifiers) +void QwtMagnifier::setZoomInKey( int key, + Qt::KeyboardModifiers modifiers ) { d_data->zoomInKey = key; d_data->zoomInKeyModifiers = modifiers; } -//! \sa setZoomInKey -void QwtMagnifier::getZoomInKey(int &key, int &modifiers) const +/*! + \brief Retrieve the settings of the zoom in key + + \param key Key code, see Qt::Key + \param modifiers Keyboard modifiers + + \sa setZoomInKey() +*/ +void QwtMagnifier::getZoomInKey( int &key, + Qt::KeyboardModifiers &modifiers ) const { key = d_data->zoomInKey; modifiers = d_data->zoomInKeyModifiers; @@ -254,14 +268,23 @@ void QwtMagnifier::getZoomInKey(int &key, int &modifiers) const \param modifiers \sa getZoomOutKey(), setZoomOutKey() */ -void QwtMagnifier::setZoomOutKey(int key, int modifiers) +void QwtMagnifier::setZoomOutKey( int key, + Qt::KeyboardModifiers modifiers ) { d_data->zoomOutKey = key; d_data->zoomOutKeyModifiers = modifiers; } -//! \sa setZoomOutKey -void QwtMagnifier::getZoomOutKey(int &key, int &modifiers) const +/*! + \brief Retrieve the settings of the zoom out key + + \param key Key code, see Qt::Key + \param modifiers Keyboard modifiers + + \sa setZoomOutKey() +*/ +void QwtMagnifier::getZoomOutKey( int &key, + Qt::KeyboardModifiers &modifiers ) const { key = d_data->zoomOutKey; modifiers = d_data->zoomOutKeyModifiers; @@ -270,130 +293,141 @@ void QwtMagnifier::getZoomOutKey(int &key, int &modifiers) const /*! \brief Event filter - When isEnabled() the mouse events of the observed widget are filtered. + When isEnabled() is true, the mouse events of the + observed widget are filtered. + + \param object Object to be filtered + \param event Event + + \return Forwarded to QObject::eventFilter() \sa widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyPressEvent() widgetKeyReleaseEvent() */ -bool QwtMagnifier::eventFilter(QObject *o, QEvent *e) +bool QwtMagnifier::eventFilter( QObject *object, QEvent *event ) { - if ( o && o == parent() ) { - switch(e->type() ) { - case QEvent::MouseButtonPress: { - widgetMousePressEvent((QMouseEvent *)e); - break; - } - case QEvent::MouseMove: { - widgetMouseMoveEvent((QMouseEvent *)e); - break; - } - case QEvent::MouseButtonRelease: { - widgetMouseReleaseEvent((QMouseEvent *)e); - break; - } - case QEvent::Wheel: { - widgetWheelEvent((QWheelEvent *)e); - break; - } - case QEvent::KeyPress: { - widgetKeyPressEvent((QKeyEvent *)e); - break; - } - case QEvent::KeyRelease: { - widgetKeyReleaseEvent((QKeyEvent *)e); - break; - } - default: - ; + if ( object && object == parent() ) + { + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + widgetMousePressEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::MouseMove: + { + widgetMouseMoveEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::MouseButtonRelease: + { + widgetMouseReleaseEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::Wheel: + { + widgetWheelEvent( static_cast<QWheelEvent *>( event ) ); + break; + } + case QEvent::KeyPress: + { + widgetKeyPressEvent( static_cast<QKeyEvent *>( event ) ); + break; + } + case QEvent::KeyRelease: + { + widgetKeyReleaseEvent( static_cast<QKeyEvent *>( event ) ); + break; + } + default:; } } - return QObject::eventFilter(o, e); + return QObject::eventFilter( object, event ); } /*! Handle a mouse press event for the observed widget. - \param me Mouse event + \param mouseEvent Mouse event \sa eventFilter(), widgetMouseReleaseEvent(), widgetMouseMoveEvent() */ -void QwtMagnifier::widgetMousePressEvent(QMouseEvent *me) +void QwtMagnifier::widgetMousePressEvent( QMouseEvent *mouseEvent ) { - if ( me->button() != d_data->mouseButton || parentWidget() == NULL ) + if ( parentWidget() == NULL ) return; -#if QT_VERSION < 0x040000 - if ( (me->state() & Qt::KeyButtonMask) != - (d_data->mouseButtonState & Qt::KeyButtonMask) ) -#else - if ( (me->modifiers() & Qt::KeyboardModifierMask) != - (int)(d_data->mouseButtonState & Qt::KeyboardModifierMask) ) -#endif + if ( ( mouseEvent->button() != d_data->mouseButton ) || + ( mouseEvent->modifiers() != d_data->mouseButtonModifiers ) ) { return; } d_data->hasMouseTracking = parentWidget()->hasMouseTracking(); - parentWidget()->setMouseTracking(true); - d_data->mousePos = me->pos(); + + parentWidget()->setMouseTracking( true ); + d_data->mousePos = mouseEvent->pos(); d_data->mousePressed = true; } /*! Handle a mouse release event for the observed widget. + + \param mouseEvent Mouse event + \sa eventFilter(), widgetMousePressEvent(), widgetMouseMoveEvent(), */ -void QwtMagnifier::widgetMouseReleaseEvent(QMouseEvent *) +void QwtMagnifier::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) { - if ( d_data->mousePressed && parentWidget() ) { + Q_UNUSED( mouseEvent ); + + if ( d_data->mousePressed && parentWidget() ) + { d_data->mousePressed = false; - parentWidget()->setMouseTracking(d_data->hasMouseTracking); + parentWidget()->setMouseTracking( d_data->hasMouseTracking ); } } /*! Handle a mouse move event for the observed widget. - \param me Mouse event + \param mouseEvent Mouse event \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), */ -void QwtMagnifier::widgetMouseMoveEvent(QMouseEvent *me) +void QwtMagnifier::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) { if ( !d_data->mousePressed ) return; - const int dy = me->pos().y() - d_data->mousePos.y(); - if ( dy != 0 ) { + const int dy = mouseEvent->pos().y() - d_data->mousePos.y(); + if ( dy != 0 ) + { double f = d_data->mouseFactor; if ( dy < 0 ) f = 1 / f; - rescale(f); + rescale( f ); } - d_data->mousePos = me->pos(); + d_data->mousePos = mouseEvent->pos(); } /*! Handle a wheel event for the observed widget. - \param we Wheel event + \param wheelEvent Wheel event \sa eventFilter() */ -void QwtMagnifier::widgetWheelEvent(QWheelEvent *we) +void QwtMagnifier::widgetWheelEvent( QWheelEvent *wheelEvent ) { -#if QT_VERSION < 0x040000 - if ( (we->state() & Qt::KeyButtonMask) != - (d_data->wheelButtonState & Qt::KeyButtonMask) ) -#else - if ( (we->modifiers() & Qt::KeyboardModifierMask) != - (int)(d_data->wheelButtonState & Qt::KeyboardModifierMask) ) -#endif + if ( wheelEvent->modifiers() != d_data->wheelModifiers ) { return; } - if ( d_data->wheelFactor != 0.0 ) { + if ( d_data->wheelFactor != 0.0 ) + { /* A positive delta indicates that the wheel was rotated forwards away from the user; a negative @@ -403,62 +437,56 @@ void QwtMagnifier::widgetWheelEvent(QWheelEvent *we) in which case the delta value is a multiple of 120 (== 15 * 8). */ - double f = ::pow(d_data->wheelFactor, - qwtAbs(we->delta() / 120)); - if ( we->delta() > 0 ) + double f = qPow( d_data->wheelFactor, + qAbs( wheelEvent->delta() / 120.0 ) ); + + if ( wheelEvent->delta() > 0 ) f = 1 / f; - rescale(f); + rescale( f ); } } /*! Handle a key press event for the observed widget. - \param ke Key event + \param keyEvent Key event \sa eventFilter(), widgetKeyReleaseEvent() */ -void QwtMagnifier::widgetKeyPressEvent(QKeyEvent *ke) +void QwtMagnifier::widgetKeyPressEvent( QKeyEvent *keyEvent ) { - const int key = ke->key(); -#if QT_VERSION < 0x040000 - const int state = ke->state(); -#else - const int state = ke->modifiers(); -#endif - - if ( key == d_data->zoomInKey && - state == d_data->zoomInKeyModifiers ) { - rescale(d_data->keyFactor); - } else if ( key == d_data->zoomOutKey && - state == d_data->zoomOutKeyModifiers ) { - rescale(1.0 / d_data->keyFactor); + if ( keyEvent->key() == d_data->zoomInKey && + keyEvent->modifiers() == d_data->zoomInKeyModifiers ) + { + rescale( d_data->keyFactor ); + } + else if ( keyEvent->key() == d_data->zoomOutKey && + keyEvent->modifiers() == d_data->zoomOutKeyModifiers ) + { + rescale( 1.0 / d_data->keyFactor ); } } /*! Handle a key release event for the observed widget. - \param ke Key event + \param keyEvent Key event \sa eventFilter(), widgetKeyReleaseEvent() */ -void QwtMagnifier::widgetKeyReleaseEvent(QKeyEvent *) +void QwtMagnifier::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) { + Q_UNUSED( keyEvent ); } +//! \return Parent widget, where the rescaling happens QWidget *QwtMagnifier::parentWidget() { - if ( parent()->inherits("QWidget") ) - return (QWidget *)parent(); - - return NULL; + return qobject_cast<QWidget *>( parent() ); } +//! \return Parent widget, where the rescaling happens const QWidget *QwtMagnifier::parentWidget() const { - if ( parent()->inherits("QWidget") ) - return (const QWidget *)parent(); - - return NULL; + return qobject_cast<const QWidget *>( parent() ); } diff --git a/libs/qwt/qwt_magnifier.h b/libs/qwt/qwt_magnifier.h index 973a208103..48e8ed8c41 100644 --- a/libs/qwt/qwt_magnifier.h +++ b/libs/qwt/qwt_magnifier.h @@ -29,50 +29,54 @@ class QWT_EXPORT QwtMagnifier: public QObject Q_OBJECT public: - explicit QwtMagnifier(QWidget *); + explicit QwtMagnifier( QWidget * ); virtual ~QwtMagnifier(); QWidget *parentWidget(); const QWidget *parentWidget() const; - void setEnabled(bool); + void setEnabled( bool ); bool isEnabled() const; // mouse - void setMouseFactor(double); + void setMouseFactor( double ); double mouseFactor() const; - void setMouseButton(int button, int buttonState = Qt::NoButton); - void getMouseButton(int &button, int &buttonState) const; + void setMouseButton( Qt::MouseButton, Qt::KeyboardModifiers = Qt::NoModifier ); + void getMouseButton( Qt::MouseButton &, Qt::KeyboardModifiers & ) const; // mouse wheel - void setWheelFactor(double); + void setWheelFactor( double ); double wheelFactor() const; - void setWheelButtonState(int buttonState); - int wheelButtonState() const; + void setWheelModifiers( Qt::KeyboardModifiers ); + Qt::KeyboardModifiers wheelModifiers() const; // keyboard - void setKeyFactor(double); + void setKeyFactor( double ); double keyFactor() const; - void setZoomInKey(int key, int modifiers); - void getZoomInKey(int &key, int &modifiers) const; + void setZoomInKey( int key, Qt::KeyboardModifiers = Qt::NoModifier ); + void getZoomInKey( int &key, Qt::KeyboardModifiers & ) const; - void setZoomOutKey(int key, int modifiers); - void getZoomOutKey(int &key, int &modifiers) const; + void setZoomOutKey( int key, Qt::KeyboardModifiers = Qt::NoModifier ); + void getZoomOutKey( int &key, Qt::KeyboardModifiers & ) const; - virtual bool eventFilter(QObject *, QEvent *); + virtual bool eventFilter( QObject *, QEvent * ); protected: - virtual void rescale(double factor) = 0; - - virtual void widgetMousePressEvent(QMouseEvent *); - virtual void widgetMouseReleaseEvent(QMouseEvent *); - virtual void widgetMouseMoveEvent(QMouseEvent *); - virtual void widgetWheelEvent(QWheelEvent *); - virtual void widgetKeyPressEvent(QKeyEvent *); - virtual void widgetKeyReleaseEvent(QKeyEvent *); + /*! + Rescale the parent widget + \param factor Scale factor + */ + virtual void rescale( double factor ) = 0; + + virtual void widgetMousePressEvent( QMouseEvent * ); + virtual void widgetMouseReleaseEvent( QMouseEvent * ); + virtual void widgetMouseMoveEvent( QMouseEvent * ); + virtual void widgetWheelEvent( QWheelEvent * ); + virtual void widgetKeyPressEvent( QKeyEvent * ); + virtual void widgetKeyReleaseEvent( QKeyEvent * ); private: class PrivateData; diff --git a/libs/qwt/qwt_math.cpp b/libs/qwt/qwt_math.cpp index e99f67eed6..9e898c1051 100644 --- a/libs/qwt/qwt_math.cpp +++ b/libs/qwt/qwt_math.cpp @@ -7,8 +7,6 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #include "qwt_math.h" /*! @@ -16,14 +14,14 @@ \param array Pointer to an array \param size Array size */ -double qwtGetMin(const double *array, int size) +double qwtGetMin( const double *array, int size ) { - if (size <= 0) + if ( size <= 0 ) return 0.0; double rv = array[0]; - for (int i = 1; i < size; i++) - rv = qwtMin(rv, array[i]); + for ( int i = 1; i < size; i++ ) + rv = qMin( rv, array[i] ); return rv; } @@ -34,14 +32,43 @@ double qwtGetMin(const double *array, int size) \param array Pointer to an array \param size Array size */ -double qwtGetMax(const double *array, int size) +double qwtGetMax( const double *array, int size ) { - if (size <= 0) + if ( size <= 0 ) return 0.0; double rv = array[0]; - for (int i = 1; i < size; i++) - rv = qwtMax(rv, array[i]); + for ( int i = 1; i < size; i++ ) + rv = qMax( rv, array[i] ); return rv; } + +/*! + \brief Normalize an angle to be int the range [0.0, 2 * PI[ + \param radians Angle in radians + \return Normalized angle in radians +*/ +double qwtNormalizeRadians( double radians ) +{ + double a = ::fmod( radians, 2.0 * M_PI ); + if ( a < 0.0 ) + a += 2.0 * M_PI; + + return a; + +} + +/*! + \brief Normalize an angle to be int the range [0.0, 360.0[ + \param radians Angle in degrees + \return Normalized angle in degrees +*/ +double qwtNormalizeDegrees( double degrees ) +{ + double a = ::fmod( degrees, 360.0 ); + if ( a < 0.0 ) + a += 360.0; + + return a; +} diff --git a/libs/qwt/qwt_math.h b/libs/qwt/qwt_math.h index 305b220a61..23ad205601 100644 --- a/libs/qwt/qwt_math.h +++ b/libs/qwt/qwt_math.h @@ -10,43 +10,30 @@ #ifndef QWT_MATH_H #define QWT_MATH_H -#include <math.h> -#include <qpoint.h> #include "qwt_global.h" -#include "qwt_double_rect.h" -#if QT_VERSION < 0x040000 +#if defined(_MSC_VER) +/* + Microsoft says: -#define qwtMax QMAX -#define qwtMin QMIN -#define qwtAbs QABS - -#else // QT_VERSION >= 0x040000 - -#define qwtMax(x,y) qMax(qreal(x),qreal(y)) -#define qwtMin(x,y) qMin(qreal(x),qreal(y)) -#define qwtAbs qAbs - -#endif - -#ifndef LOG10_2 -#define LOG10_2 0.30102999566398119802 /* log10(2) */ -#endif - -#ifndef LOG10_3 -#define LOG10_3 0.47712125471966243540 /* log10(3) */ + Define _USE_MATH_DEFINES before including math.h to expose these macro + definitions for common math constants. These are placed under an #ifdef + since these commonly-defined names are not part of the C/C++ standards. +*/ +#define _USE_MATH_DEFINES 1 #endif -#ifndef LOG10_5 -#define LOG10_5 0.69897000433601885749 /* log10(5) */ -#endif +#include <qmath.h> +#include "qwt_global.h" -#ifndef M_2PI -#define M_2PI 6.28318530717958623200 /* 2 pi */ +#ifndef M_PI_2 +// For Qt <= 4.8.4 M_PI_2 is not known by MinGW-w64 +// when compiling with -std=c++11 +#define M_PI_2 (1.57079632679489661923) #endif #ifndef LOG_MIN -//! Mininum value for logarithmic scales +//! Minimum value for logarithmic scales #define LOG_MIN 1.0e-100 #endif @@ -55,138 +42,108 @@ #define LOG_MAX 1.0e100 #endif -#ifndef M_E -#define M_E 2.7182818284590452354 /* e */ -#endif +QWT_EXPORT double qwtGetMin( const double *array, int size ); +QWT_EXPORT double qwtGetMax( const double *array, int size ); -#ifndef M_LOG2E -#define M_LOG2E 1.4426950408889634074 /* log_2 e */ -#endif - -#ifndef M_LOG10E -#define M_LOG10E 0.43429448190325182765 /* log_10 e */ -#endif +QWT_EXPORT double qwtNormalizeRadians( double radians ); +QWT_EXPORT double qwtNormalizeDegrees( double degrees ); -#ifndef M_LN2 -#define M_LN2 0.69314718055994530942 /* log_e 2 */ -#endif - -#ifndef M_LN10 -#define M_LN10 2.30258509299404568402 /* log_e 10 */ -#endif +/*! + \brief Compare 2 values, relative to an interval -#ifndef M_PI -#define M_PI 3.14159265358979323846 /* pi */ -#endif + Values are "equal", when : + \f$\cdot value2 - value1 <= abs(intervalSize * 10e^{-6})\f$ -#ifndef M_PI_2 -#define M_PI_2 1.57079632679489661923 /* pi/2 */ -#endif + \param value1 First value to compare + \param value2 Second value to compare + \param intervalSize interval size -#ifndef M_PI_4 -#define M_PI_4 0.78539816339744830962 /* pi/4 */ -#endif - -#ifndef M_1_PI -#define M_1_PI 0.31830988618379067154 /* 1/pi */ -#endif + \return 0: if equal, -1: if value2 > value1, 1: if value1 > value2 +*/ +inline int qwtFuzzyCompare( double value1, double value2, double intervalSize ) +{ + const double eps = qAbs( 1.0e-6 * intervalSize ); -#ifndef M_2_PI -#define M_2_PI 0.63661977236758134308 /* 2/pi */ -#endif + if ( value2 - value1 > eps ) + return -1; -#ifndef M_2_SQRTPI -#define M_2_SQRTPI 1.12837916709551257390 /* 2/sqrt(pi) */ -#endif + if ( value1 - value2 > eps ) + return 1; -#ifndef M_SQRT2 -#define M_SQRT2 1.41421356237309504880 /* sqrt(2) */ -#endif + return 0; +} -#ifndef M_SQRT1_2 -#define M_SQRT1_2 0.70710678118654752440 /* 1/sqrt(2) */ -#endif -QWT_EXPORT double qwtGetMin(const double *array, int size); -QWT_EXPORT double qwtGetMax(const double *array, int size); +inline bool qwtFuzzyGreaterOrEqual( double d1, double d2 ) +{ + return ( d1 >= d2 ) || qFuzzyCompare( d1, d2 ); +} +inline bool qwtFuzzyLessOrEqual( double d1, double d2 ) +{ + return ( d1 <= d2 ) || qFuzzyCompare( d1, d2 ); +} //! Return the sign -inline int qwtSign(double x) +inline int qwtSign( double x ) { - if (x > 0.0) + if ( x > 0.0 ) return 1; - else if (x < 0.0) - return (-1); + else if ( x < 0.0 ) + return ( -1 ); else return 0; } //! Return the square of a number -inline double qwtSqr(const double x) +inline double qwtSqr( double x ) { - return x*x; + return x * x; } -/*! - \brief Limit a value to fit into a specified interval - \param x Input value - \param x1 First interval boundary - \param x2 Second interval boundary -*/ -template <class T> -T qwtLim(const T& x, const T& x1, const T& x2) +//! Approximation of arc tangent ( error below 0,005 radians ) +inline double qwtFastAtan( double x ) { - T rv; - T xmin, xmax; + if ( x < -1.0 ) + return -M_PI_2 - x / ( x * x + 0.28 ); - xmin = qwtMin(x1, x2); - xmax = qwtMax(x1, x2); + if ( x > 1.0 ) + return M_PI_2 - x / ( x * x + 0.28 ); - if ( x < xmin ) - rv = xmin; - else if ( x > xmax ) - rv = xmax; - else - rv = x; - - return rv; + return x / ( 1.0 + x * x * 0.28 ); } -inline QPoint qwtPolar2Pos(const QPoint &pole, - double radius, double angle) +//! Approximation of arc tangent ( error below 0,005 radians ) +inline double qwtFastAtan2( double y, double x ) { - const double x = pole.x() + radius * ::cos(angle); - const double y = pole.y() - radius * ::sin(angle); + if ( x > 0 ) + return qwtFastAtan( y / x ); - return QPoint(qRound(x), qRound(y)); -} + if ( x < 0 ) + { + const double d = qwtFastAtan( y / x ); + return ( y >= 0 ) ? d + M_PI : d - M_PI; + } -inline QPoint qwtDegree2Pos(const QPoint &pole, - double radius, double angle) -{ - return qwtPolar2Pos(pole, radius, angle / 180.0 * M_PI); -} + if ( y < 0.0 ) + return -M_PI_2; -inline QwtDoublePoint qwtPolar2Pos(const QwtDoublePoint &pole, - double radius, double angle) -{ - const double x = pole.x() + radius * ::cos(angle); - const double y = pole.y() - radius * ::sin(angle); + if ( y > 0.0 ) + return M_PI_2; - return QPoint(qRound(x), qRound(y)); + return 0.0; } -inline QwtDoublePoint qwtDegree2Pos(const QwtDoublePoint &pole, - double radius, double angle) +// Translate degrees into radians +inline double qwtRadians( double degrees ) { - return qwtPolar2Pos(pole, radius, angle / 180.0 * M_PI); + return degrees * M_PI / 180.0; } -//! Rounding of doubles, like qRound for integers -inline double qwtRound(double value) +// Translate radians into degrees +inline double qwtDegrees( double degrees ) { - return ::floor(value + 0.5); // MSVC has no ::round(). + return degrees * 180.0 / M_PI; } #endif diff --git a/libs/qwt/qwt_matrix_raster_data.cpp b/libs/qwt/qwt_matrix_raster_data.cpp new file mode 100644 index 0000000000..69355adb34 --- /dev/null +++ b/libs/qwt/qwt_matrix_raster_data.cpp @@ -0,0 +1,298 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_matrix_raster_data.h" +#include <qnumeric.h> +#include <qmath.h> + +class QwtMatrixRasterData::PrivateData +{ +public: + PrivateData(): + resampleMode(QwtMatrixRasterData::NearestNeighbour), + numColumns(0) + { + } + + inline double value(int row, int col) const + { + return values.data()[ row * numColumns + col ]; + } + + QwtMatrixRasterData::ResampleMode resampleMode; + + QVector<double> values; + int numColumns; + int numRows; + + double dx; + double dy; +}; + +//! Constructor +QwtMatrixRasterData::QwtMatrixRasterData() +{ + d_data = new PrivateData(); + update(); +} + +//! Destructor +QwtMatrixRasterData::~QwtMatrixRasterData() +{ + delete d_data; +} + +/*! + \brief Set the resampling algorithm + + \param mode Resampling mode + \sa resampleMode(), value() +*/ +void QwtMatrixRasterData::setResampleMode( ResampleMode mode ) +{ + d_data->resampleMode = mode; +} + +/*! + \return resampling algorithm + \sa setResampleMode(), value() +*/ +QwtMatrixRasterData::ResampleMode QwtMatrixRasterData::resampleMode() const +{ + return d_data->resampleMode; +} + +/*! + \brief Assign the bounding interval for an axis + + Setting the bounding intervals for the X/Y axis is mandatory + to define the positions for the values of the value matrix. + The interval in Z direction defines the possible range for + the values in the matrix, what is f.e used by QwtPlotSpectrogram + to map values to colors. The Z-interval might be the bounding + interval of the values in the matrix, but usually it isn't. + ( f.e a interval of 0.0-100.0 for values in percentage ) + + \param axis X, Y or Z axis + \param interval Interval + + \sa QwtRasterData::interval(), setValueMatrix() +*/ +void QwtMatrixRasterData::setInterval( + Qt::Axis axis, const QwtInterval &interval ) +{ + QwtRasterData::setInterval( axis, interval ); + update(); +} + +/*! + \brief Assign a value matrix + + The positions of the values are calculated by dividing + the bounding rectangle of the X/Y intervals into equidistant + rectangles ( pixels ). Each value corresponds to the center of + a pixel. + + \param values Vector of values + \param numColumns Number of columns + + \sa valueMatrix(), numColumns(), numRows(), setInterval()() +*/ +void QwtMatrixRasterData::setValueMatrix( + const QVector<double> &values, int numColumns ) +{ + d_data->values = values; + d_data->numColumns = qMax( numColumns, 0 ); + update(); +} + +/*! + \return Value matrix + \sa setValueMatrix(), numColumns(), numRows(), setInterval() +*/ +const QVector<double> QwtMatrixRasterData::valueMatrix() const +{ + return d_data->values; +} + +/*! + \brief Change a single value in the matrix + + \param row Row index + \param col Column index + \param value New value + + \sa value(), setValueMatrix() +*/ +void QwtMatrixRasterData::setValue( int row, int col, double value ) +{ + if ( row >= 0 && row < d_data->numRows && + col >= 0 && col < d_data->numColumns ) + { + const int index = row * d_data->numColumns + col; + d_data->values.data()[ index ] = value; + } +} + +/*! + \return Number of columns of the value matrix + \sa valueMatrix(), numRows(), setValueMatrix() +*/ +int QwtMatrixRasterData::numColumns() const +{ + return d_data->numColumns; +} + +/*! + \return Number of rows of the value matrix + \sa valueMatrix(), numColumns(), setValueMatrix() +*/ +int QwtMatrixRasterData::numRows() const +{ + return d_data->numRows; +} + +/*! + \brief Calculate the pixel hint + + pixelHint() returns the geometry of a pixel, that can be used + to calculate the resolution and alignment of the plot item, that is + representing the data. + + - NearestNeighbour\n + pixelHint() returns the surrounding pixel of the top left value + in the matrix. + + - BilinearInterpolation\n + Returns an empty rectangle recommending + to render in target device ( f.e. screen ) resolution. + + \param area Requested area, ignored + \return Calculated hint + + \sa ResampleMode, setMatrix(), setInterval() +*/ +QRectF QwtMatrixRasterData::pixelHint( const QRectF &area ) const +{ + Q_UNUSED( area ) + + QRectF rect; + if ( d_data->resampleMode == NearestNeighbour ) + { + const QwtInterval intervalX = interval( Qt::XAxis ); + const QwtInterval intervalY = interval( Qt::YAxis ); + if ( intervalX.isValid() && intervalY.isValid() ) + { + rect = QRectF( intervalX.minValue(), intervalY.minValue(), + d_data->dx, d_data->dy ); + } + } + + return rect; +} + +/*! + \return the value at a raster position + + \param x X value in plot coordinates + \param y Y value in plot coordinates + + \sa ResampleMode +*/ +double QwtMatrixRasterData::value( double x, double y ) const +{ + const QwtInterval xInterval = interval( Qt::XAxis ); + const QwtInterval yInterval = interval( Qt::YAxis ); + + if ( !( xInterval.contains(x) && yInterval.contains(y) ) ) + return qQNaN(); + + double value; + + switch( d_data->resampleMode ) + { + case BilinearInterpolation: + { + int col1 = qRound( (x - xInterval.minValue() ) / d_data->dx ) - 1; + int row1 = qRound( (y - yInterval.minValue() ) / d_data->dy ) - 1; + int col2 = col1 + 1; + int row2 = row1 + 1; + + if ( col1 < 0 ) + col1 = col2; + else if ( col2 >= static_cast<int>( d_data->numColumns ) ) + col2 = col1; + + if ( row1 < 0 ) + row1 = row2; + else if ( row2 >= static_cast<int>( d_data->numRows ) ) + row2 = row1; + + const double v11 = d_data->value( row1, col1 ); + const double v21 = d_data->value( row1, col2 ); + const double v12 = d_data->value( row2, col1 ); + const double v22 = d_data->value( row2, col2 ); + + const double x2 = xInterval.minValue() + + ( col2 + 0.5 ) * d_data->dx; + const double y2 = yInterval.minValue() + + ( row2 + 0.5 ) * d_data->dy; + + const double rx = ( x2 - x ) / d_data->dx; + const double ry = ( y2 - y ) / d_data->dy; + + const double vr1 = rx * v11 + ( 1.0 - rx ) * v21; + const double vr2 = rx * v12 + ( 1.0 - rx ) * v22; + + value = ry * vr1 + ( 1.0 - ry ) * vr2; + + break; + } + case NearestNeighbour: + default: + { + int row = int( (y - yInterval.minValue() ) / d_data->dy ); + int col = int( (x - xInterval.minValue() ) / d_data->dx ); + + // In case of intervals, where the maximum is included + // we get out of bound for row/col, when the value for the + // maximum is requested. Instead we return the value + // from the last row/col + + if ( row >= d_data->numRows ) + row = d_data->numRows - 1; + + if ( col >= d_data->numColumns ) + col = d_data->numColumns - 1; + + value = d_data->value( row, col ); + } + } + + return value; +} + +void QwtMatrixRasterData::update() +{ + d_data->numRows = 0; + d_data->dx = 0.0; + d_data->dy = 0.0; + + if ( d_data->numColumns > 0 ) + { + d_data->numRows = d_data->values.size() / d_data->numColumns; + + const QwtInterval xInterval = interval( Qt::XAxis ); + const QwtInterval yInterval = interval( Qt::YAxis ); + if ( xInterval.isValid() ) + d_data->dx = xInterval.width() / d_data->numColumns; + if ( yInterval.isValid() ) + d_data->dy = yInterval.width() / d_data->numRows; + } +} diff --git a/libs/qwt/qwt_matrix_raster_data.h b/libs/qwt/qwt_matrix_raster_data.h new file mode 100644 index 0000000000..0b107c9fd9 --- /dev/null +++ b/libs/qwt/qwt_matrix_raster_data.h @@ -0,0 +1,74 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_MATRIX_RASTER_DATA_H +#define QWT_MATRIX_RASTER_DATA_H 1 + +#include "qwt_global.h" +#include "qwt_raster_data.h" +#include <qvector.h> + +/*! + \brief A class representing a matrix of values as raster data + + QwtMatrixRasterData implements an interface for a matrix of + equidistant values, that can be used by a QwtPlotRasterItem. + It implements a couple of resampling algorithms, to provide + values for positions, that or not on the value matrix. +*/ +class QWT_EXPORT QwtMatrixRasterData: public QwtRasterData +{ +public: + /*! + \brief Resampling algorithm + The default setting is NearestNeighbour; + */ + enum ResampleMode + { + /*! + Return the value from the matrix, that is nearest to the + the requested position. + */ + NearestNeighbour, + + /*! + Interpolate the value from the distances and values of the + 4 surrounding values in the matrix, + */ + BilinearInterpolation + }; + + QwtMatrixRasterData(); + virtual ~QwtMatrixRasterData(); + + void setResampleMode(ResampleMode mode); + ResampleMode resampleMode() const; + + virtual void setInterval( Qt::Axis, const QwtInterval & ); + + void setValueMatrix( const QVector<double> &values, int numColumns ); + const QVector<double> valueMatrix() const; + + void setValue( int row, int col, double value ); + + int numColumns() const; + int numRows() const; + + virtual QRectF pixelHint( const QRectF & ) const; + + virtual double value( double x, double y ) const; + +private: + void update(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_null_paintdevice.cpp b/libs/qwt/qwt_null_paintdevice.cpp new file mode 100644 index 0000000000..db1611da25 --- /dev/null +++ b/libs/qwt/qwt_null_paintdevice.cpp @@ -0,0 +1,593 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_null_paintdevice.h" +#include <qpaintengine.h> +#include <qpixmap.h> + +class QwtNullPaintDevice::PrivateData +{ +public: + PrivateData(): + mode( QwtNullPaintDevice::NormalMode ) + { + } + + QwtNullPaintDevice::Mode mode; +}; + +class QwtNullPaintDevice::PaintEngine: public QPaintEngine +{ +public: + PaintEngine(); + + virtual bool begin( QPaintDevice * ); + virtual bool end(); + + virtual Type type () const; + virtual void updateState(const QPaintEngineState &); + + virtual void drawRects(const QRect *, int ); + virtual void drawRects(const QRectF *, int ); + + virtual void drawLines(const QLine *, int ); + virtual void drawLines(const QLineF *, int ); + + virtual void drawEllipse(const QRectF &); + virtual void drawEllipse(const QRect &); + + virtual void drawPath(const QPainterPath &); + + virtual void drawPoints(const QPointF *, int ); + virtual void drawPoints(const QPoint *, int ); + + virtual void drawPolygon(const QPointF *, int , PolygonDrawMode ); + virtual void drawPolygon(const QPoint *, int , PolygonDrawMode ); + + virtual void drawPixmap(const QRectF &, + const QPixmap &, const QRectF &); + + virtual void drawTextItem(const QPointF &, const QTextItem &); + + virtual void drawTiledPixmap(const QRectF &, + const QPixmap &, const QPointF &s); + + virtual void drawImage(const QRectF &, + const QImage &, const QRectF &, Qt::ImageConversionFlags ); + +private: + QwtNullPaintDevice *nullDevice(); +}; + +QwtNullPaintDevice::PaintEngine::PaintEngine(): + QPaintEngine( QPaintEngine::AllFeatures ) +{ +} + +bool QwtNullPaintDevice::PaintEngine::begin( QPaintDevice * ) +{ + setActive( true ); + return true; +} + +bool QwtNullPaintDevice::PaintEngine::end() +{ + setActive( false ); + return true; +} + +QPaintEngine::Type QwtNullPaintDevice::PaintEngine::type() const +{ + return QPaintEngine::User; +} + +void QwtNullPaintDevice::PaintEngine::drawRects( + const QRect *rects, int rectCount) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawRects( rects, rectCount ); + return; + } + + device->drawRects( rects, rectCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawRects( + const QRectF *rects, int rectCount) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawRects( rects, rectCount ); + return; + } + + device->drawRects( rects, rectCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawLines( + const QLine *lines, int lineCount) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawLines( lines, lineCount ); + return; + } + + device->drawLines( lines, lineCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawLines( + const QLineF *lines, int lineCount) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawLines( lines, lineCount ); + return; + } + + device->drawLines( lines, lineCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawEllipse( + const QRectF &rect) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawEllipse( rect ); + return; + } + + device->drawEllipse( rect ); +} + +void QwtNullPaintDevice::PaintEngine::drawEllipse( + const QRect &rect) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawEllipse( rect ); + return; + } + + device->drawEllipse( rect ); +} + + +void QwtNullPaintDevice::PaintEngine::drawPath( + const QPainterPath &path) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + device->drawPath( path ); +} + +void QwtNullPaintDevice::PaintEngine::drawPoints( + const QPointF *points, int pointCount) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawPoints( points, pointCount ); + return; + } + + device->drawPoints( points, pointCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawPoints( + const QPoint *points, int pointCount) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawPoints( points, pointCount ); + return; + } + + device->drawPoints( points, pointCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawPolygon( + const QPointF *points, int pointCount, PolygonDrawMode mode) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() == QwtNullPaintDevice::PathMode ) + { + QPainterPath path; + + if ( pointCount > 0 ) + { + path.moveTo( points[0] ); + for ( int i = 1; i < pointCount; i++ ) + path.lineTo( points[i] ); + + if ( mode != PolylineMode ) + path.closeSubpath(); + } + + device->drawPath( path ); + return; + } + + device->drawPolygon( points, pointCount, mode ); +} + +void QwtNullPaintDevice::PaintEngine::drawPolygon( + const QPoint *points, int pointCount, PolygonDrawMode mode) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() == QwtNullPaintDevice::PathMode ) + { + QPainterPath path; + + if ( pointCount > 0 ) + { + path.moveTo( points[0] ); + for ( int i = 1; i < pointCount; i++ ) + path.lineTo( points[i] ); + + if ( mode != PolylineMode ) + path.closeSubpath(); + } + + device->drawPath( path ); + return; + } + + device->drawPolygon( points, pointCount, mode ); +} + +void QwtNullPaintDevice::PaintEngine::drawPixmap( + const QRectF &rect, const QPixmap &pm, const QRectF &subRect ) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + device->drawPixmap( rect, pm, subRect ); +} + +void QwtNullPaintDevice::PaintEngine::drawTextItem( + const QPointF &pos, const QTextItem &textItem) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawTextItem( pos, textItem ); + return; + } + + device->drawTextItem( pos, textItem ); +} + +void QwtNullPaintDevice::PaintEngine::drawTiledPixmap( + const QRectF &rect, const QPixmap &pixmap, + const QPointF &subRect) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + if ( device->mode() != QwtNullPaintDevice::NormalMode ) + { + QPaintEngine::drawTiledPixmap( rect, pixmap, subRect ); + return; + } + + device->drawTiledPixmap( rect, pixmap, subRect ); +} + +void QwtNullPaintDevice::PaintEngine::drawImage( + const QRectF &rect, const QImage &image, + const QRectF &subRect, Qt::ImageConversionFlags flags) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + device->drawImage( rect, image, subRect, flags ); +} + +void QwtNullPaintDevice::PaintEngine::updateState( + const QPaintEngineState &state) +{ + QwtNullPaintDevice *device = nullDevice(); + if ( device == NULL ) + return; + + device->updateState( state ); +} + +inline QwtNullPaintDevice *QwtNullPaintDevice::PaintEngine::nullDevice() +{ + if ( !isActive() ) + return NULL; + + return static_cast<QwtNullPaintDevice *>( paintDevice() ); +} + +//! Constructor +QwtNullPaintDevice::QwtNullPaintDevice(): + d_engine( NULL ) +{ + d_data = new PrivateData; +} + +//! Destructor +QwtNullPaintDevice::~QwtNullPaintDevice() +{ + delete d_engine; + delete d_data; +} + +/*! + Set the render mode + + \param mode New mode + \sa mode() + */ +void QwtNullPaintDevice::setMode( Mode mode ) +{ + d_data->mode = mode; +} + +/*! + \return Render mode + \sa setMode() +*/ +QwtNullPaintDevice::Mode QwtNullPaintDevice::mode() const +{ + return d_data->mode; +} + +//! See QPaintDevice::paintEngine() +QPaintEngine *QwtNullPaintDevice::paintEngine() const +{ + if ( d_engine == NULL ) + { + QwtNullPaintDevice *that = + const_cast< QwtNullPaintDevice * >( this ); + + that->d_engine = new PaintEngine(); + } + + return d_engine; +} + +/*! + See QPaintDevice::metric() + + \param deviceMetric Type of metric + \return Metric information for the given paint device metric. + + \sa sizeMetrics() +*/ +int QwtNullPaintDevice::metric( PaintDeviceMetric deviceMetric ) const +{ + int value; + + switch ( deviceMetric ) + { + case PdmWidth: + { + value = sizeMetrics().width(); + break; + } + case PdmHeight: + { + value = sizeMetrics().height(); + break; + } + case PdmNumColors: + { + value = 0xffffffff; + break; + } + case PdmDepth: + { + value = 32; + break; + } + case PdmPhysicalDpiX: + case PdmPhysicalDpiY: + case PdmDpiY: + case PdmDpiX: + { + value = 72; + break; + } + case PdmWidthMM: + { + value = qRound( metric( PdmWidth ) * 25.4 / metric( PdmDpiX ) ); + break; + } + case PdmHeightMM: + { + value = qRound( metric( PdmHeight ) * 25.4 / metric( PdmDpiY ) ); + break; + } + default: + value = 0; + } + return value; + +} + +//! See QPaintEngine::drawRects() +void QwtNullPaintDevice::drawRects( + const QRect *rects, int rectCount) +{ + Q_UNUSED(rects); + Q_UNUSED(rectCount); +} + +//! See QPaintEngine::drawRects() +void QwtNullPaintDevice::drawRects( + const QRectF *rects, int rectCount) +{ + Q_UNUSED(rects); + Q_UNUSED(rectCount); +} + +//! See QPaintEngine::drawLines() +void QwtNullPaintDevice::drawLines( + const QLine *lines, int lineCount) +{ + Q_UNUSED(lines); + Q_UNUSED(lineCount); +} + +//! See QPaintEngine::drawLines() +void QwtNullPaintDevice::drawLines( + const QLineF *lines, int lineCount) +{ + Q_UNUSED(lines); + Q_UNUSED(lineCount); +} + +//! See QPaintEngine::drawEllipse() +void QwtNullPaintDevice::drawEllipse( const QRectF &rect ) +{ + Q_UNUSED(rect); +} + +//! See QPaintEngine::drawEllipse() +void QwtNullPaintDevice::drawEllipse( const QRect &rect ) +{ + Q_UNUSED(rect); +} + +//! See QPaintEngine::drawPath() +void QwtNullPaintDevice::drawPath( const QPainterPath &path ) +{ + Q_UNUSED(path); +} + +//! See QPaintEngine::drawPoints() +void QwtNullPaintDevice::drawPoints( + const QPointF *points, int pointCount) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); +} + +//! See QPaintEngine::drawPoints() +void QwtNullPaintDevice::drawPoints( + const QPoint *points, int pointCount) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); +} + +//! See QPaintEngine::drawPolygon() +void QwtNullPaintDevice::drawPolygon( + const QPointF *points, int pointCount, + QPaintEngine::PolygonDrawMode mode) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); + Q_UNUSED(mode); +} + +//! See QPaintEngine::drawPolygon() +void QwtNullPaintDevice::drawPolygon( + const QPoint *points, int pointCount, + QPaintEngine::PolygonDrawMode mode) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); + Q_UNUSED(mode); +} + +//! See QPaintEngine::drawPixmap() +void QwtNullPaintDevice::drawPixmap( const QRectF &rect, + const QPixmap &pm, const QRectF &subRect ) +{ + Q_UNUSED(rect); + Q_UNUSED(pm); + Q_UNUSED(subRect); +} + +//! See QPaintEngine::drawTextItem() +void QwtNullPaintDevice::drawTextItem( + const QPointF &pos, const QTextItem &textItem) +{ + Q_UNUSED(pos); + Q_UNUSED(textItem); +} + +//! See QPaintEngine::drawTiledPixmap() +void QwtNullPaintDevice::drawTiledPixmap( + const QRectF &rect, const QPixmap &pixmap, + const QPointF &subRect) +{ + Q_UNUSED(rect); + Q_UNUSED(pixmap); + Q_UNUSED(subRect); +} + +//! See QPaintEngine::drawImage() +void QwtNullPaintDevice::drawImage( + const QRectF &rect, const QImage &image, + const QRectF &subRect, Qt::ImageConversionFlags flags) +{ + Q_UNUSED(rect); + Q_UNUSED(image); + Q_UNUSED(subRect); + Q_UNUSED(flags); +} + +//! See QPaintEngine::updateState() +void QwtNullPaintDevice::updateState( + const QPaintEngineState &state ) +{ + Q_UNUSED(state); +} diff --git a/libs/qwt/qwt_null_paintdevice.h b/libs/qwt/qwt_null_paintdevice.h new file mode 100644 index 0000000000..d7f03beea9 --- /dev/null +++ b/libs/qwt/qwt_null_paintdevice.h @@ -0,0 +1,126 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_NULL_PAINT_DEVICE_H +#define QWT_NULL_PAINT_DEVICE_H 1 + +#include "qwt_global.h" +#include <qpaintdevice.h> +#include <qpaintengine.h> + +/*! + \brief A null paint device doing nothing + + Sometimes important layout/rendering geometries are not + available or changeable from the public Qt class interface. + ( f.e hidden in the style implementation ). + + QwtNullPaintDevice can be used to manipulate or filter out + this information by analyzing the stream of paint primitives. + + F.e. QwtNullPaintDevice is used by QwtPlotCanvas to identify + styled backgrounds with rounded corners. +*/ + +class QWT_EXPORT QwtNullPaintDevice: public QPaintDevice +{ +public: + /*! + \brief Render mode + + \sa setMode(), mode() + */ + enum Mode + { + /*! + All vector graphic primitives are painted by + the corresponding draw methods + */ + NormalMode, + + /*! + Vector graphic primitives ( beside polygons ) are mapped to a QPainterPath + and are painted by drawPath. In PathMode mode + only a few draw methods are called: + + - drawPath() + - drawPixmap() + - drawImage() + - drawPolygon() + */ + PolygonPathMode, + + /*! + Vector graphic primitives are mapped to a QPainterPath + and are painted by drawPath. In PathMode mode + only a few draw methods are called: + + - drawPath() + - drawPixmap() + - drawImage() + */ + PathMode + }; + + QwtNullPaintDevice(); + virtual ~QwtNullPaintDevice(); + + void setMode( Mode ); + Mode mode() const; + + virtual QPaintEngine *paintEngine() const; + + virtual int metric( PaintDeviceMetric metric ) const; + + virtual void drawRects(const QRect *, int ); + virtual void drawRects(const QRectF *, int ); + + virtual void drawLines(const QLine *, int ); + virtual void drawLines(const QLineF *, int ); + + virtual void drawEllipse(const QRectF &); + virtual void drawEllipse(const QRect &); + + virtual void drawPath(const QPainterPath &); + + virtual void drawPoints(const QPointF *, int ); + virtual void drawPoints(const QPoint *, int ); + + virtual void drawPolygon( + const QPointF *, int , QPaintEngine::PolygonDrawMode ); + + virtual void drawPolygon( + const QPoint *, int , QPaintEngine::PolygonDrawMode ); + + virtual void drawPixmap(const QRectF &, + const QPixmap &, const QRectF &); + + virtual void drawTextItem(const QPointF &, const QTextItem &); + + virtual void drawTiledPixmap(const QRectF &, + const QPixmap &, const QPointF &s); + + virtual void drawImage(const QRectF &, + const QImage &, const QRectF &, Qt::ImageConversionFlags ); + + virtual void updateState( const QPaintEngineState &state ); + +protected: + //! \return Size needed to implement metric() + virtual QSize sizeMetrics() const = 0; + +private: + class PaintEngine; + PaintEngine *d_engine; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_painter.cpp b/libs/qwt/qwt_painter.cpp index dbca763b0b..0bbf258c5f 100644 --- a/libs/qwt/qwt_painter.cpp +++ b/libs/qwt/qwt_painter.cpp @@ -7,685 +7,1260 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_painter.h" +#include "qwt_math.h" +#include "qwt_clipper.h" +#include "qwt_color_map.h" +#include "qwt_scale_map.h" #include <qwindowdefs.h> #include <qwidget.h> +#include <qframe.h> #include <qrect.h> #include <qpainter.h> #include <qpalette.h> #include <qpaintdevice.h> #include <qpixmap.h> #include <qstyle.h> -#if QT_VERSION < 0x040000 -#include <qsimplerichtext.h> -#else #include <qtextdocument.h> #include <qabstracttextdocumentlayout.h> #include <qstyleoption.h> #include <qpaintengine.h> -#endif +#include <qapplication.h> +#include <qdesktopwidget.h> -#include "qwt_clipper.h" -#include "qwt_math.h" -#include "qwt_color_map.h" -#include "qwt_scale_map.h" -#include "qwt_painter.h" +#if QT_VERSION >= 0x050000 +#include <qwindow.h> +#endif -QwtMetricsMap QwtPainter::d_metricsMap; +#if QT_VERSION < 0x050000 -#if defined(Q_WS_X11) -bool QwtPainter::d_deviceClipping = true; -#else -bool QwtPainter::d_deviceClipping = false; +#ifdef Q_WS_X11 +#include <qx11info_x11.h> #endif -#if QT_VERSION < 0x040000 -bool QwtPainter::d_SVGMode = false; #endif -static inline bool needDeviceClipping( - const QPainter *painter, bool deviceClipping) -{ - return deviceClipping && - (painter->device()->devType() == QInternal::Widget || - painter->device()->devType() == QInternal::Pixmap ); -} - -/*! - \brief En/Disable device clipping. +bool QwtPainter::d_polylineSplitting = true; +bool QwtPainter::d_roundingAlignment = true; - On X11 the default for device clipping is enabled, - otherwise it is disabled. - \sa QwtPainter::deviceClipping() -*/ -void QwtPainter::setDeviceClipping(bool enable) +static inline bool qwtIsClippingNeeded( + const QPainter *painter, QRectF &clipRect ) { - d_deviceClipping = enable; -} + bool doClipping = false; + const QPaintEngine *pe = painter->paintEngine(); + if ( pe && pe->type() == QPaintEngine::SVG ) + { + // The SVG paint engine ignores any clipping, -/*! - Returns whether device clipping is enabled. On X11 the default - is enabled, otherwise it is disabled. - \sa QwtPainter::setDeviceClipping() -*/ + if ( painter->hasClipping() ) + { + doClipping = true; + clipRect = painter->clipRegion().boundingRect(); + } + } -bool QwtPainter::deviceClipping() -{ - return d_deviceClipping; + return doClipping; } -/*! - Returns rect for device clipping - \sa QwtPainter::setDeviceClipping() -*/ -const QRect &QwtPainter::deviceClipRect() +template <class T> +static inline void qwtDrawPolyline( QPainter *painter, + const T *points, int pointCount, bool polylineSplitting ) { - static QRect clip; + bool doSplit = false; + if ( polylineSplitting ) + { + const QPaintEngine *pe = painter->paintEngine(); + if ( pe && pe->type() == QPaintEngine::Raster ) + { + /* + The raster paint engine seems to use some algo with O(n*n). + ( Qt 4.3 is better than Qt 4.2, but remains unacceptable) + To work around this problem, we have to split the polygon into + smaller pieces. + */ + doSplit = true; + } + } - if ( !clip.isValid() ) { - clip.setCoords(QWT_COORD_MIN, QWT_COORD_MIN, - QWT_COORD_MAX, QWT_COORD_MAX); + if ( doSplit ) + { + const int splitSize = 20; + for ( int i = 0; i < pointCount; i += splitSize ) + { + const int n = qMin( splitSize + 1, pointCount - i ); + painter->drawPolyline( points + i, n ); + } } - return clip; + else + painter->drawPolyline( points, pointCount ); } -//! Clip a point array -QwtPolygon QwtPainter::clip(const QwtPolygon &pa) +static inline void qwtUnscaleFont( QPainter *painter ) { - return QwtClipper::clipPolygon(deviceClipRect(), pa); -} - -#if QT_VERSION < 0x040000 - -/*! - \brief En/Disable SVG mode. + if ( painter->font().pixelSize() >= 0 ) + return; - When saving a QPicture to a SVG some texts are misaligned. - In SVGMode QwtPainter tries to fix them. + static QSize screenResolution; + if ( !screenResolution.isValid() ) + { + QDesktopWidget *desktop = QApplication::desktop(); + if ( desktop ) + { + screenResolution.setWidth( desktop->logicalDpiX() ); + screenResolution.setHeight( desktop->logicalDpiY() ); + } + } - \sa QwtPainter::isSVGMode() - \note A QPicture that is created in SVG mode and saved to the - native format, will be misaligned. Also it is not possible to - reload and play a SVG document, that was created in SVG mode. -*/ -void QwtPainter::setSVGMode(bool on) -{ - d_SVGMode = on; -} + const QPaintDevice *pd = painter->device(); + if ( pd->logicalDpiX() != screenResolution.width() || + pd->logicalDpiY() != screenResolution.height() ) + { + QFont pixelFont( painter->font(), QApplication::desktop() ); + pixelFont.setPixelSize( QFontInfo( pixelFont ).pixelSize() ); -bool QwtPainter::isSVGMode() -{ - return d_SVGMode; + painter->setFont( pixelFont ); + } } -#endif // QT_VERSION < 0x040000 - /*! - Scale all QwtPainter drawing operations using the ratio - QwtPaintMetrics(from).logicalDpiX() / QwtPaintMetrics(to).logicalDpiX() - and QwtPaintMetrics(from).logicalDpiY() / QwtPaintMetrics(to).logicalDpiY() + Check is the application is running with the X11 graphics system + that has some special capabilities that can be used for incremental + painting to a widget. - \sa QwtPainter::resetScaleMetrics(), QwtPainter::scaleMetricsX, - QwtPainter::scaleMetricsY() + \return True, when the graphics system is X11 */ -void QwtPainter::setMetricsMap(const QPaintDevice *layout, - const QPaintDevice *device) +bool QwtPainter::isX11GraphicsSystem() { - d_metricsMap.setMetrics(layout, device); + static int onX11 = -1; + if ( onX11 < 0 ) + { + QPixmap pm( 1, 1 ); + QPainter painter( &pm ); + + onX11 = ( painter.paintEngine()->type() == QPaintEngine::X11 ) ? 1 : 0; + } + + return onX11 == 1; } /*! - Change the metrics map - \sa QwtPainter::resetMetricsMap, QwtPainter::metricsMap + Check if the painter is using a paint engine, that aligns + coordinates to integers. Today these are all paint engines + beside QPaintEngine::Pdf and QPaintEngine::SVG. + + If we have an integer based paint engine it is also + checked if the painter has a transformation matrix, + that rotates or scales. + + \param painter Painter + \return true, when the painter is aligning + + \sa setRoundingAlignment() */ -void QwtPainter::setMetricsMap(const QwtMetricsMap &map) +bool QwtPainter::isAligning( QPainter *painter ) { - d_metricsMap = map; + if ( painter && painter->isActive() ) + { + switch ( painter->paintEngine()->type() ) + { + case QPaintEngine::Pdf: + case QPaintEngine::SVG: + return false; + + default:; + } + + const QTransform tr = painter->transform(); + if ( tr.isRotating() || tr.isScaling() ) + { + // we might have to check translations too + return false; + } + } + + return true; } /*! - Reset the metrics map to the ratio 1:1 - \sa QwtPainter::setMetricsMap, QwtPainter::resetMetricsMap + Enable whether coordinates should be rounded, before they are painted + to a paint engine that floors to integer values. For other paint engines + this ( PDF, SVG ), this flag has no effect. + QwtPainter stores this flag only, the rounding itself is done in + the painting code ( f.e the plot items ). + + The default setting is true. + + \sa roundingAlignment(), isAligning() */ -void QwtPainter::resetMetricsMap() +void QwtPainter::setRoundingAlignment( bool enable ) { - d_metricsMap = QwtMetricsMap(); + d_roundingAlignment = enable; } /*! - \return Metrics map + \brief En/Disable line splitting for the raster paint engine + + In some Qt versions the raster paint engine paints polylines of many points + much faster when they are split in smaller chunks: f.e all supported Qt versions + >= Qt 5.0 when drawing an antialiased polyline with a pen width >=2. + + The default setting is true. + + \sa polylineSplitting() */ -const QwtMetricsMap &QwtPainter::metricsMap() +void QwtPainter::setPolylineSplitting( bool enable ) { - return d_metricsMap; + d_polylineSplitting = enable; } -/*! - Wrapper for QPainter::setClipRect() -*/ -void QwtPainter::setClipRect(QPainter *painter, const QRect &rect) +//! Wrapper for QPainter::drawPath() +void QwtPainter::drawPath( QPainter *painter, const QPainterPath &path ) { - painter->setClipRect(d_metricsMap.layoutToDevice(rect, painter)); + painter->drawPath( path ); } -/*! - Wrapper for QPainter::drawRect() -*/ -void QwtPainter::drawRect(QPainter *painter, int x, int y, int w, int h) +//! Wrapper for QPainter::drawRect() +void QwtPainter::drawRect( QPainter *painter, double x, double y, double w, double h ) { - drawRect(painter, QRect(x, y, w, h)); + drawRect( painter, QRectF( x, y, w, h ) ); } -/*! - Wrapper for QPainter::drawRect() -*/ -void QwtPainter::drawRect(QPainter *painter, const QRect &rect) +//! Wrapper for QPainter::drawRect() +void QwtPainter::drawRect( QPainter *painter, const QRectF &rect ) { - const QRect r = d_metricsMap.layoutToDevice(rect, painter); + const QRectF r = rect; - QRect clipRect; + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); if ( deviceClipping ) - clipRect = deviceClipRect(); - - if ( clipRect.isValid() ) { - if ( !clipRect.intersects(r) ) + { + if ( !clipRect.intersects( r ) ) return; - if ( !clipRect.contains(r) ) { - fillRect(painter, r & clipRect, painter->brush()); - - int pw = painter->pen().width(); - pw = pw % 2 + pw / 2; - - QwtPolygon pa(5); - pa.setPoint(0, r.left(), r.top()); - pa.setPoint(1, r.right() - pw, r.top()); - pa.setPoint(2, r.right() - pw, r.bottom() - pw); - pa.setPoint(3, r.left(), r.bottom() - pw); - pa.setPoint(4, r.left(), r.top()); + if ( !clipRect.contains( r ) ) + { + fillRect( painter, r & clipRect, painter->brush() ); painter->save(); - painter->setBrush(Qt::NoBrush); - drawPolyline(painter, pa); + painter->setBrush( Qt::NoBrush ); + drawPolyline( painter, QPolygonF( r ) ); painter->restore(); return; } } - painter->drawRect(r); + painter->drawRect( r ); } -/*! - Wrapper for QPainter::fillRect() -*/ -void QwtPainter::fillRect(QPainter *painter, - const QRect &rect, const QBrush &brush) +//! Wrapper for QPainter::fillRect() +void QwtPainter::fillRect( QPainter *painter, + const QRectF &rect, const QBrush &brush ) { if ( !rect.isValid() ) return; - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); - - QRect clipRect; -#if QT_VERSION >= 0x040000 + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); /* - Performance of Qt4 is horrible for non trivial brushs. Without - clipping expect minutes or hours for repainting large rects + Performance of Qt4 is horrible for a non trivial brush. Without + clipping expect minutes or hours for repainting large rectangles (might result from zooming) */ - clipRect = painter->window(); + if ( deviceClipping ) + clipRect &= painter->window(); + else + clipRect = painter->window(); + if ( painter->hasClipping() ) clipRect &= painter->clipRegion().boundingRect(); - if ( deviceClipping ) - clipRect &= deviceClipRect(); -#else - if ( deviceClipping ) - clipRect = deviceClipRect(); -#endif - QRect r = d_metricsMap.layoutToDevice(rect, painter); - if ( clipRect.isValid() ) - r = r.intersect(clipRect); + QRectF r = rect; + if ( deviceClipping ) + r = r.intersected( clipRect ); if ( r.isValid() ) - painter->fillRect(r, brush); + painter->fillRect( r, brush ); } -/*! - Wrapper for QPainter::drawPie() -*/ -void QwtPainter::drawPie(QPainter *painter, const QRect &rect, - int a, int alen) +//! Wrapper for QPainter::drawPie() +void QwtPainter::drawPie( QPainter *painter, const QRectF &rect, + int a, int alen ) { - QRect r = d_metricsMap.layoutToDevice(rect, painter); - - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); - if ( deviceClipping && !deviceClipRect().contains(rect) ) + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); + if ( deviceClipping && !clipRect.contains( rect ) ) return; - painter->drawPie(r, a, alen); + painter->drawPie( rect, a, alen ); } -/*! - Wrapper for QPainter::drawEllipse() -*/ -void QwtPainter::drawEllipse(QPainter *painter, const QRect &rect) +//! Wrapper for QPainter::drawEllipse() +void QwtPainter::drawEllipse( QPainter *painter, const QRectF &rect ) { - QRect r = d_metricsMap.layoutToDevice(rect, painter); - - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - if ( deviceClipping && !deviceClipRect().contains(rect) ) + if ( deviceClipping && !clipRect.contains( rect ) ) return; -#if QT_VERSION >= 0x040000 - if ( painter->pen().style() != Qt::NoPen && - painter->pen().color().isValid() ) { - // Qt4 adds the pen to the rect, Qt3 not. - int pw = painter->pen().width(); - if ( pw == 0 ) - pw = 1; - - r.setWidth(r.width() - pw); - r.setHeight(r.height() - pw); - } -#endif - - painter->drawEllipse(r); + painter->drawEllipse( rect ); } -/*! - Wrapper for QPainter::drawText() -*/ -void QwtPainter::drawText(QPainter *painter, int x, int y, - const QString &text) +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, double x, double y, + const QString &text ) { - drawText(painter, QPoint(x, y), text); + drawText( painter, QPointF( x, y ), text ); } -/*! - Wrapper for QPainter::drawText() -*/ -void QwtPainter::drawText(QPainter *painter, const QPoint &pos, - const QString &text) +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, const QPointF &pos, + const QString &text ) { - const QPoint p = d_metricsMap.layoutToDevice(pos, painter); + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); - - if ( deviceClipping && !deviceClipRect().contains(p) ) + if ( deviceClipping && !clipRect.contains( pos ) ) return; - painter->drawText(p, text); + + painter->save(); + qwtUnscaleFont( painter ); + painter->drawText( pos, text ); + painter->restore(); } -/*! - Wrapper for QPainter::drawText() -*/ -void QwtPainter::drawText(QPainter *painter, int x, int y, int w, int h, - int flags, const QString &text) +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, + double x, double y, double w, double h, + int flags, const QString &text ) { - drawText(painter, QRect(x, y, w, h), flags, text); + drawText( painter, QRectF( x, y, w, h ), flags, text ); } -/*! - Wrapper for QPainter::drawText() -*/ -void QwtPainter::drawText(QPainter *painter, const QRect &rect, - int flags, const QString &text) -{ - QRect textRect = d_metricsMap.layoutToDevice(rect, painter); -#if QT_VERSION < 0x040000 - if ( d_SVGMode && - ( flags == 0 || flags & Qt::AlignVCenter ) - && painter->device()->devType() == QInternal::Picture ) { - /* - Qt3 misalignes texts, when saving a text - to a SVG image. - */ - textRect.setY(textRect.y() - painter->fontMetrics().height() / 4); - } -#endif - painter->drawText(textRect, flags, text); +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, const QRectF &rect, + int flags, const QString &text ) +{ + painter->save(); + qwtUnscaleFont( painter ); + painter->drawText( rect, flags, text ); + painter->restore(); } #ifndef QT_NO_RICHTEXT /*! - Wrapper for QSimpleRichText::draw() -*/ -#if QT_VERSION < 0x040000 + Draw a text document into a rectangle -void QwtPainter::drawSimpleRichText(QPainter *painter, const QRect &rect, - int flags, QSimpleRichText &text) + \param painter Painter + \param rect Traget rectangle + \param flags Alignments/Text flags, see QPainter::drawText() + \param text Text document +*/ +void QwtPainter::drawSimpleRichText( QPainter *painter, const QRectF &rect, + int flags, const QTextDocument &text ) { - QColorGroup cg; - cg.setColor(QColorGroup::Text, painter->pen().color()); + QTextDocument *txt = text.clone(); - const QRect scaledRect = d_metricsMap.layoutToDevice(rect, painter); - - text.setWidth(painter, scaledRect.width()); + painter->save(); - // QSimpleRichText is Qt::AlignTop by default + painter->setFont( txt->defaultFont() ); + qwtUnscaleFont( painter ); - int y = scaledRect.y(); - if (flags & Qt::AlignBottom) - y += (scaledRect.height() - text.height()); - else if (flags & Qt::AlignVCenter) - y += (scaledRect.height() - text.height())/2; + txt->setDefaultFont( painter->font() ); + txt->setPageSize( QSizeF( rect.width(), QWIDGETSIZE_MAX ) ); - text.draw(painter, scaledRect.x(), y, scaledRect, cg); -} -#else -void QwtPainter::drawSimpleRichText(QPainter *painter, const QRect &rect, - int flags, QTextDocument &text) -{ - const QRect scaledRect = d_metricsMap.layoutToDevice(rect, painter); - text.setPageSize(QSize(scaledRect.width(), QWIDGETSIZE_MAX)); + QAbstractTextDocumentLayout* layout = txt->documentLayout(); - QAbstractTextDocumentLayout* layout = text.documentLayout(); - - const int height = qRound(layout->documentSize().height()); - int y = scaledRect.y(); - if (flags & Qt::AlignBottom) - y += (scaledRect.height() - height); - else if (flags & Qt::AlignVCenter) - y += (scaledRect.height() - height)/2; + const double height = layout->documentSize().height(); + double y = rect.y(); + if ( flags & Qt::AlignBottom ) + y += ( rect.height() - height ); + else if ( flags & Qt::AlignVCenter ) + y += ( rect.height() - height ) / 2; QAbstractTextDocumentLayout::PaintContext context; - context.palette.setColor(QPalette::Text, painter->pen().color()); - - painter->save(); + context.palette.setColor( QPalette::Text, painter->pen().color() ); - painter->translate(scaledRect.x(), y); - layout->draw(painter, context); + painter->translate( rect.x(), y ); + layout->draw( painter, context ); painter->restore(); + delete txt; } -#endif #endif // !QT_NO_RICHTEXT -/*! - Wrapper for QPainter::drawLine() -*/ -void QwtPainter::drawLine(QPainter *painter, int x1, int y1, int x2, int y2) +//! Wrapper for QPainter::drawLine() +void QwtPainter::drawLine( QPainter *painter, + const QPointF &p1, const QPointF &p2 ) { - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); if ( deviceClipping && - !(deviceClipRect().contains(x1, y1) && deviceClipRect().contains(x2, y2)) ) { - QwtPolygon pa(2); - pa.setPoint(0, x1, y1); - pa.setPoint(1, x2, y2); - drawPolyline(painter, pa); + !( clipRect.contains( p1 ) && clipRect.contains( p2 ) ) ) + { + QPolygonF polygon; + polygon += p1; + polygon += p2; + drawPolyline( painter, polygon ); return; } - if ( d_metricsMap.isIdentity() ) { -#if QT_VERSION >= 0x030200 && QT_VERSION < 0x040000 - if ( !painter->device()->isExtDev() ) -#endif - { - painter->drawLine(x1, y1, x2, y2); - return; - } - } + painter->drawLine( p1, p2 ); +} - const QPoint p1 = d_metricsMap.layoutToDevice(QPoint(x1, y1)); - const QPoint p2 = d_metricsMap.layoutToDevice(QPoint(x2, y2)); +//! Wrapper for QPainter::drawPolygon() +void QwtPainter::drawPolygon( QPainter *painter, const QPolygonF &polygon ) +{ + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); -#if QT_VERSION >= 0x030200 && QT_VERSION < 0x040000 - if ( painter->device()->isExtDev() ) { - // Strange: the postscript driver of QPrinter adds an offset - // of 0.5 to the start/endpoint when using drawLine, but not - // for lines painted with drawLineSegments. + QPolygonF cpa = polygon; + if ( deviceClipping ) + cpa = QwtClipper::clipPolygonF( clipRect, polygon ); - QwtPolygon pa(2); - pa.setPoint(0, p1); - pa.setPoint(1, p2); - painter->drawLineSegments(pa); - } else - painter->drawLine(p1, p2); -#else - painter->drawLine(p1, p2); -#endif + painter->drawPolygon( cpa ); } -/*! - Wrapper for QPainter::drawPolygon() -*/ -void QwtPainter::drawPolygon(QPainter *painter, const QwtPolygon &pa) +//! Wrapper for QPainter::drawPolyline() +void QwtPainter::drawPolyline( QPainter *painter, const QPolygonF &polygon ) { - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - QwtPolygon cpa = d_metricsMap.layoutToDevice(pa); - if ( deviceClipping ) { -#ifdef __GNUC__ -#endif - cpa = clip(cpa); - } - painter->drawPolygon(cpa); + QPolygonF cpa = polygon; + if ( deviceClipping ) + cpa = QwtClipper::clipPolygonF( clipRect, cpa ); + + qwtDrawPolyline<QPointF>( painter, + cpa.constData(), cpa.size(), d_polylineSplitting ); } -/*! - Wrapper for QPainter::drawPolyline() -*/ -void QwtPainter::drawPolyline(QPainter *painter, const QwtPolygon &pa) +//! Wrapper for QPainter::drawPolyline() +void QwtPainter::drawPolyline( QPainter *painter, + const QPointF *points, int pointCount ) { - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - QwtPolygon cpa = d_metricsMap.layoutToDevice(pa); if ( deviceClipping ) - cpa = clip(cpa); + { + QPolygonF polygon( pointCount ); + ::memcpy( polygon.data(), points, pointCount * sizeof( QPointF ) ); -#if QT_VERSION >= 0x040000 && QT_VERSION < 0x040400 - bool doSplit = false; - if ( painter->paintEngine()->type() == QPaintEngine::Raster && - painter->pen().width() >= 2 ) { - /* - The raster paint engine seems to use some algo with O(n*n). - ( Qt 4.3 is better than Qt 4.2, but remains unacceptable) - To work around this problem, we have to split the polygon into - smaller pieces. - */ - doSplit = true; + polygon = QwtClipper::clipPolygonF( clipRect, polygon ); + qwtDrawPolyline<QPointF>( painter, + polygon.constData(), polygon.size(), d_polylineSplitting ); } + else + { + qwtDrawPolyline<QPointF>( painter, points, pointCount, d_polylineSplitting ); + } +} - if ( doSplit ) { - const int numPoints = cpa.size(); - const QPoint *points = cpa.data(); +//! Wrapper for QPainter::drawPolygon() +void QwtPainter::drawPolygon( QPainter *painter, const QPolygon &polygon ) +{ + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - const int splitSize = 20; - for ( int i = 0; i < numPoints; i += splitSize ) { - const int n = qwtMin(splitSize + 1, cpa.size() - i); - painter->drawPolyline(points + i, n); - } - } else -#endif - painter->drawPolyline(cpa); + QPolygon cpa = polygon; + if ( deviceClipping ) + cpa = QwtClipper::clipPolygon( clipRect, polygon ); + + painter->drawPolygon( cpa ); } -/*! - Wrapper for QPainter::drawPoint() -*/ +//! Wrapper for QPainter::drawPolyline() +void QwtPainter::drawPolyline( QPainter *painter, const QPolygon &polygon ) +{ + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); + + QPolygon cpa = polygon; + if ( deviceClipping ) + cpa = QwtClipper::clipPolygon( clipRect, cpa ); + + qwtDrawPolyline<QPoint>( painter, + cpa.constData(), cpa.size(), d_polylineSplitting ); +} -void QwtPainter::drawPoint(QPainter *painter, int x, int y) +//! Wrapper for QPainter::drawPolyline() +void QwtPainter::drawPolyline( QPainter *painter, + const QPoint *points, int pointCount ) { - const bool deviceClipping = needDeviceClipping(painter, d_deviceClipping); + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - const QPoint pos = d_metricsMap.layoutToDevice(QPoint(x, y)); + if ( deviceClipping ) + { + QPolygon polygon( pointCount ); + ::memcpy( polygon.data(), points, pointCount * sizeof( QPoint ) ); + + polygon = QwtClipper::clipPolygon( clipRect, polygon ); + qwtDrawPolyline<QPoint>( painter, + polygon.constData(), polygon.size(), d_polylineSplitting ); + } + else + qwtDrawPolyline<QPoint>( painter, points, pointCount, d_polylineSplitting ); +} + +//! Wrapper for QPainter::drawPoint() +void QwtPainter::drawPoint( QPainter *painter, const QPointF &pos ) +{ + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); - if ( deviceClipping && !deviceClipRect().contains(pos) ) + if ( deviceClipping && !clipRect.contains( pos ) ) return; - painter->drawPoint(pos); + painter->drawPoint( pos ); } -void QwtPainter::drawColoredArc(QPainter *painter, const QRect &rect, - int peak, int arc, int interval, const QColor &c1, const QColor &c2) +//! Wrapper for QPainter::drawPoint() +void QwtPainter::drawPoint( QPainter *painter, const QPoint &pos ) { - int h1, s1, v1; - int h2, s2, v2; + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); -#if QT_VERSION < 0x040000 - c1.hsv(&h1, &s1, &v1); - c2.hsv(&h2, &s2, &v2); -#else - c1.getHsv(&h1, &s1, &v1); - c2.getHsv(&h2, &s2, &v2); -#endif + if ( deviceClipping ) + { + const int minX = qCeil( clipRect.left() ); + const int maxX = qFloor( clipRect.right() ); + const int minY = qCeil( clipRect.top() ); + const int maxY = qFloor( clipRect.bottom() ); + + if ( pos.x() < minX || pos.x() > maxX + || pos.y() < minY || pos.y() > maxY ) + { + return; + } + } - arc /= 2; - for ( int angle = -arc; angle < arc; angle += interval) { - double ratio; - if ( angle >= 0 ) - ratio = 1.0 - angle / double(arc); - else - ratio = 1.0 + angle / double(arc); + painter->drawPoint( pos ); +} + +//! Wrapper for QPainter::drawPoints() +void QwtPainter::drawPoints( QPainter *painter, + const QPoint *points, int pointCount ) +{ + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); + + if ( deviceClipping ) + { + const int minX = qCeil( clipRect.left() ); + const int maxX = qFloor( clipRect.right() ); + const int minY = qCeil( clipRect.top() ); + const int maxY = qFloor( clipRect.bottom() ); + const QRect r( minX, minY, maxX - minX, maxY - minY ); - QColor c; - c.setHsv( h1 + qRound(ratio * (h2 - h1)), - s1 + qRound(ratio * (s2 - s1)), - v1 + qRound(ratio * (v2 - v1)) ); + QPolygon clippedPolygon( pointCount ); + QPoint *clippedData = clippedPolygon.data(); - painter->setPen(QPen(c, painter->pen().width())); - painter->drawArc(rect, (peak + angle) * 16, interval * 16); + int numClippedPoints = 0; + for ( int i = 0; i < pointCount; i++ ) + { + if ( r.contains( points[i] ) ) + clippedData[ numClippedPoints++ ] = points[i]; + } + painter->drawPoints( clippedData, numClippedPoints ); + } + else + { + painter->drawPoints( points, pointCount ); } } -void QwtPainter::drawFocusRect(QPainter *painter, QWidget *widget) +//! Wrapper for QPainter::drawPoints() +void QwtPainter::drawPoints( QPainter *painter, + const QPointF *points, int pointCount ) { - drawFocusRect(painter, widget, widget->rect()); + QRectF clipRect; + const bool deviceClipping = qwtIsClippingNeeded( painter, clipRect ); + + if ( deviceClipping ) + { + QPolygonF clippedPolygon( pointCount ); + QPointF *clippedData = clippedPolygon.data(); + + int numClippedPoints = 0; + for ( int i = 0; i < pointCount; i++ ) + { + if ( clipRect.contains( points[i] ) ) + clippedData[ numClippedPoints++ ] = points[i]; + } + painter->drawPoints( clippedData, numClippedPoints ); + } + else + { + painter->drawPoints( points, pointCount ); + } } -void QwtPainter::drawFocusRect(QPainter *painter, QWidget *widget, - const QRect &rect) +//! Wrapper for QPainter::drawImage() +void QwtPainter::drawImage( QPainter *painter, + const QRectF &rect, const QImage &image ) +{ + const QRect alignedRect = rect.toAlignedRect(); + + if ( alignedRect != rect ) + { + const QRectF clipRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + + painter->save(); + painter->setClipRect( clipRect, Qt::IntersectClip ); + painter->drawImage( alignedRect, image ); + painter->restore(); + } + else + { + painter->drawImage( alignedRect, image ); + } +} + +//! Wrapper for QPainter::drawPixmap() +void QwtPainter::drawPixmap( QPainter *painter, + const QRectF &rect, const QPixmap &pixmap ) +{ + const QRect alignedRect = rect.toAlignedRect(); + + if ( alignedRect != rect ) + { + const QRectF clipRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + + painter->save(); + painter->setClipRect( clipRect, Qt::IntersectClip ); + painter->drawPixmap( alignedRect, pixmap ); + painter->restore(); + } + else + { + painter->drawPixmap( alignedRect, pixmap ); + } +} + +//! Draw a focus rectangle on a widget using its style. +void QwtPainter::drawFocusRect( QPainter *painter, const QWidget *widget ) +{ + drawFocusRect( painter, widget, widget->rect() ); +} + +//! Draw a focus rectangle on a widget using its style. +void QwtPainter::drawFocusRect( QPainter *painter, const QWidget *widget, + const QRect &rect ) { -#if QT_VERSION < 0x040000 - widget->style().drawPrimitive(QStyle::PE_FocusRect, painter, - rect, widget->colorGroup()); -#else QStyleOptionFocusRect opt; - opt.init(widget); + opt.init( widget ); opt.rect = rect; opt.state |= QStyle::State_HasFocus; - widget->style()->drawPrimitive(QStyle::PE_FrameFocusRect, - &opt, painter, widget); + widget->style()->drawPrimitive( QStyle::PE_FrameFocusRect, + &opt, painter, widget ); +} + +/*! + Draw a round frame + + \param painter Painter + \param rect Frame rectangle + \param palette QPalette::WindowText is used for plain borders + QPalette::Dark and QPalette::Light for raised + or sunken borders + \param lineWidth Line width + \param frameStyle bitwise OR´ed value of QFrame::Shape and QFrame::Shadow +*/ +void QwtPainter::drawRoundFrame( QPainter *painter, + const QRectF &rect, const QPalette &palette, + int lineWidth, int frameStyle ) +{ + enum Style + { + Plain, + Sunken, + Raised + }; + + Style style = Plain; + if ( (frameStyle & QFrame::Sunken) == QFrame::Sunken ) + style = Sunken; + else if ( (frameStyle & QFrame::Raised) == QFrame::Raised ) + style = Raised; + + const double lw2 = 0.5 * lineWidth; + QRectF r = rect.adjusted( lw2, lw2, -lw2, -lw2 ); + + QBrush brush; + + if ( style != Plain ) + { + QColor c1 = palette.color( QPalette::Light ); + QColor c2 = palette.color( QPalette::Dark ); + + if ( style == Sunken ) + qSwap( c1, c2 ); + + QLinearGradient gradient( r.topLeft(), r.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); +#if 0 + gradient.setColorAt( 0.3, c1 ); + gradient.setColorAt( 0.7, c2 ); #endif + gradient.setColorAt( 1.0, c2 ); + + brush = QBrush( gradient ); + } + else // Plain + { + brush = palette.brush( QPalette::WindowText ); + } + + painter->save(); + + painter->setPen( QPen( brush, lineWidth ) ); + painter->setBrush( Qt::NoBrush ); + + painter->drawEllipse( r ); + painter->restore(); } -//! Draw a round frame -#if QT_VERSION < 0x040000 -void QwtPainter::drawRoundFrame(QPainter *painter, const QRect &rect, - int width, const QColorGroup &cg, bool sunken) -#else -void QwtPainter::drawRoundFrame(QPainter *painter, const QRect &rect, - int width, const QPalette &palette, bool sunken) -#endif +/*! + Draw a rectangular frame + + \param painter Painter + \param rect Frame rectangle + \param palette Palette + \param foregroundRole Foreground role used for QFrame::Plain + \param frameWidth Frame width + \param midLineWidth Used for QFrame::Box + \param frameStyle bitwise OR´ed value of QFrame::Shape and QFrame::Shadow +*/ +void QwtPainter::drawFrame( QPainter *painter, const QRectF &rect, + const QPalette &palette, QPalette::ColorRole foregroundRole, + int frameWidth, int midLineWidth, int frameStyle ) { + if ( frameWidth <= 0 || rect.isEmpty() ) + return; -#if QT_VERSION < 0x040000 - QColor c0 = cg.mid(); - QColor c1, c2; - if ( sunken ) { - c1 = cg.dark(); - c2 = cg.light(); - } else { - c1 = cg.light(); - c2 = cg.dark(); - } -#else - QColor c0 = palette.color(QPalette::Mid); - QColor c1, c2; - if ( sunken ) { - c1 = palette.color(QPalette::Dark); - c2 = palette.color(QPalette::Light); - } else { - c1 = palette.color(QPalette::Light); - c2 = palette.color(QPalette::Dark); + const int shadow = frameStyle & QFrame::Shadow_Mask; + + painter->save(); + + if ( shadow == QFrame::Plain ) + { + const QRectF outerRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + const QRectF innerRect = outerRect.adjusted( + frameWidth, frameWidth, -frameWidth, -frameWidth ); + + QPainterPath path; + path.addRect( outerRect ); + path.addRect( innerRect ); + + painter->setPen( Qt::NoPen ); + painter->setBrush( palette.color( foregroundRole ) ); + + painter->drawPath( path ); } + else + { + const int shape = frameStyle & QFrame::Shape_Mask; + + if ( shape == QFrame::Box ) + { + const QRectF outerRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + const QRectF midRect1 = outerRect.adjusted( + frameWidth, frameWidth, -frameWidth, -frameWidth ); + const QRectF midRect2 = midRect1.adjusted( + midLineWidth, midLineWidth, -midLineWidth, -midLineWidth ); + + const QRectF innerRect = midRect2.adjusted( + frameWidth, frameWidth, -frameWidth, -frameWidth ); + + QPainterPath path1; + path1.moveTo( outerRect.bottomLeft() ); + path1.lineTo( outerRect.topLeft() ); + path1.lineTo( outerRect.topRight() ); + path1.lineTo( midRect1.topRight() ); + path1.lineTo( midRect1.topLeft() ); + path1.lineTo( midRect1.bottomLeft() ); + + QPainterPath path2; + path2.moveTo( outerRect.bottomLeft() ); + path2.lineTo( outerRect.bottomRight() ); + path2.lineTo( outerRect.topRight() ); + path2.lineTo( midRect1.topRight() ); + path2.lineTo( midRect1.bottomRight() ); + path2.lineTo( midRect1.bottomLeft() ); + + QPainterPath path3; + path3.moveTo( midRect2.bottomLeft() ); + path3.lineTo( midRect2.topLeft() ); + path3.lineTo( midRect2.topRight() ); + path3.lineTo( innerRect.topRight() ); + path3.lineTo( innerRect.topLeft() ); + path3.lineTo( innerRect.bottomLeft() ); + + QPainterPath path4; + path4.moveTo( midRect2.bottomLeft() ); + path4.lineTo( midRect2.bottomRight() ); + path4.lineTo( midRect2.topRight() ); + path4.lineTo( innerRect.topRight() ); + path4.lineTo( innerRect.bottomRight() ); + path4.lineTo( innerRect.bottomLeft() ); + + QPainterPath path5; + path5.addRect( midRect1 ); + path5.addRect( midRect2 ); + + painter->setPen( Qt::NoPen ); + + QBrush brush1 = palette.dark().color(); + QBrush brush2 = palette.light().color(); + + if ( shadow == QFrame::Raised ) + qSwap( brush1, brush2 ); + + painter->setBrush( brush1 ); + painter->drawPath( path1 ); + painter->drawPath( path4 ); + + painter->setBrush( brush2 ); + painter->drawPath( path2 ); + painter->drawPath( path3 ); + + painter->setBrush( palette.mid() ); + painter->drawPath( path5 ); + } +#if 0 + // qDrawWinPanel doesn't result in something nice + // on a scalable document like PDF. Better draw a + // Panel. + + else if ( shape == QFrame::WinPanel ) + { + painter->setRenderHint( QPainter::NonCosmeticDefaultPen, true ); + qDrawWinPanel ( painter, rect.toRect(), palette, + frameStyle & QFrame::Sunken ); + } + else if ( shape == QFrame::StyledPanel ) + { + } #endif + else + { + const QRectF outerRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + const QRectF innerRect = outerRect.adjusted( + frameWidth - 1.0, frameWidth - 1.0, + -( frameWidth - 1.0 ), -( frameWidth - 1.0 ) ); + + QPainterPath path1; + path1.moveTo( outerRect.bottomLeft() ); + path1.lineTo( outerRect.topLeft() ); + path1.lineTo( outerRect.topRight() ); + path1.lineTo( innerRect.topRight() ); + path1.lineTo( innerRect.topLeft() ); + path1.lineTo( innerRect.bottomLeft() ); + + + QPainterPath path2; + path2.moveTo( outerRect.bottomLeft() ); + path2.lineTo( outerRect.bottomRight() ); + path2.lineTo( outerRect.topRight() ); + path2.lineTo( innerRect.topRight() ); + path2.lineTo( innerRect.bottomRight() ); + path2.lineTo( innerRect.bottomLeft() ); + + painter->setPen( Qt::NoPen ); - painter->setPen(QPen(c0, width)); - painter->drawArc(rect, 0, 360 * 16); // full + QBrush brush1 = palette.dark().color(); + QBrush brush2 = palette.light().color(); - const int peak = 150; - const int interval = 2; + if ( shadow == QFrame::Raised ) + qSwap( brush1, brush2 ); + + painter->setBrush( brush1 ); + painter->drawPath( path1 ); + + painter->setBrush( brush2 ); + painter->drawPath( path2 ); + } + + } - if ( c0 != c1 ) - drawColoredArc(painter, rect, peak, 160, interval, c0, c1); - if ( c0 != c2 ) - drawColoredArc(painter, rect, peak + 180, 120, interval, c0, c2); + painter->restore(); } -void QwtPainter::drawColorBar(QPainter *painter, - const QwtColorMap &colorMap, const QwtDoubleInterval &interval, - const QwtScaleMap &scaleMap, Qt::Orientation orientation, - const QRect &rect) +/*! + Draw a rectangular frame with rounded borders + + \param painter Painter + \param rect Frame rectangle + \param xRadius x-radius of the ellipses defining the corners + \param yRadius y-radius of the ellipses defining the corners + \param palette QPalette::WindowText is used for plain borders + QPalette::Dark and QPalette::Light for raised + or sunken borders + \param lineWidth Line width + \param frameStyle bitwise OR´ed value of QFrame::Shape and QFrame::Shadow +*/ + +void QwtPainter::drawRoundedFrame( QPainter *painter, + const QRectF &rect, double xRadius, double yRadius, + const QPalette &palette, int lineWidth, int frameStyle ) +{ + painter->save(); + painter->setRenderHint( QPainter::Antialiasing, true ); + painter->setBrush( Qt::NoBrush ); + + double lw2 = lineWidth * 0.5; + QRectF r = rect.adjusted( lw2, lw2, -lw2, -lw2 ); + + QPainterPath path; + path.addRoundedRect( r, xRadius, yRadius ); + + enum Style + { + Plain, + Sunken, + Raised + }; + + Style style = Plain; + if ( (frameStyle & QFrame::Sunken) == QFrame::Sunken ) + style = Sunken; + else if ( (frameStyle & QFrame::Raised) == QFrame::Raised ) + style = Raised; + + if ( style != Plain && path.elementCount() == 17 ) + { + // move + 4 * ( cubicTo + lineTo ) + QPainterPath pathList[8]; + + for ( int i = 0; i < 4; i++ ) + { + const int j = i * 4 + 1; + + pathList[ 2 * i ].moveTo( + path.elementAt(j - 1).x, path.elementAt( j - 1 ).y + ); + + pathList[ 2 * i ].cubicTo( + path.elementAt(j + 0).x, path.elementAt(j + 0).y, + path.elementAt(j + 1).x, path.elementAt(j + 1).y, + path.elementAt(j + 2).x, path.elementAt(j + 2).y ); + + pathList[ 2 * i + 1 ].moveTo( + path.elementAt(j + 2).x, path.elementAt(j + 2).y + ); + pathList[ 2 * i + 1 ].lineTo( + path.elementAt(j + 3).x, path.elementAt(j + 3).y + ); + } + + QColor c1( palette.color( QPalette::Dark ) ); + QColor c2( palette.color( QPalette::Light ) ); + + if ( style == Raised ) + qSwap( c1, c2 ); + + for ( int i = 0; i < 4; i++ ) + { + QRectF r = pathList[2 * i].controlPointRect(); + + QPen arcPen; + arcPen.setCapStyle( Qt::FlatCap ); + arcPen.setWidth( lineWidth ); + + QPen linePen; + linePen.setCapStyle( Qt::FlatCap ); + linePen.setWidth( lineWidth ); + + switch( i ) + { + case 0: + { + arcPen.setColor( c1 ); + linePen.setColor( c1 ); + break; + } + case 1: + { + QLinearGradient gradient; + gradient.setStart( r.topLeft() ); + gradient.setFinalStop( r.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 1.0, c2 ); + + arcPen.setBrush( gradient ); + linePen.setColor( c2 ); + break; + } + case 2: + { + arcPen.setColor( c2 ); + linePen.setColor( c2 ); + break; + } + case 3: + { + QLinearGradient gradient; + + gradient.setStart( r.bottomRight() ); + gradient.setFinalStop( r.topLeft() ); + gradient.setColorAt( 0.0, c2 ); + gradient.setColorAt( 1.0, c1 ); + + arcPen.setBrush( gradient ); + linePen.setColor( c1 ); + break; + } + } + + + painter->setPen( arcPen ); + painter->drawPath( pathList[ 2 * i] ); + + painter->setPen( linePen ); + painter->drawPath( pathList[ 2 * i + 1] ); + } + } + else + { + QPen pen( palette.color( QPalette::WindowText ), lineWidth ); + painter->setPen( pen ); + painter->drawPath( path ); + } + + painter->restore(); +} + +/*! + Draw a color bar into a rectangle + + \param painter Painter + \param colorMap Color map + \param interval Value range + \param scaleMap Scale map + \param orientation Orientation + \param rect Traget rectangle +*/ +void QwtPainter::drawColorBar( QPainter *painter, + const QwtColorMap &colorMap, const QwtInterval &interval, + const QwtScaleMap &scaleMap, Qt::Orientation orientation, + const QRectF &rect ) { -#if QT_VERSION < 0x040000 - QValueVector<QRgb> colorTable; -#else QVector<QRgb> colorTable; -#endif if ( colorMap.format() == QwtColorMap::Indexed ) - colorTable = colorMap.colorTable(interval); + colorTable = colorMap.colorTable( interval ); QColor c; - const QRect devRect = d_metricsMap.layoutToDevice(rect); + const QRect devRect = rect.toAlignedRect(); /* We paint to a pixmap first to have something scalable for printing ( f.e. in a Pdf document ) */ - QPixmap pixmap(devRect.size()); - QPainter pmPainter(&pixmap); - pmPainter.translate(-devRect.x(), -devRect.y()); + QPixmap pixmap( devRect.size() ); + QPainter pmPainter( &pixmap ); + pmPainter.translate( -devRect.x(), -devRect.y() ); - if ( orientation == Qt::Horizontal ) { + if ( orientation == Qt::Horizontal ) + { QwtScaleMap sMap = scaleMap; - sMap.setPaintInterval(devRect.left(), devRect.right()); + sMap.setPaintInterval( rect.left(), rect.right() ); - for ( int x = devRect.left(); x <= devRect.right(); x++ ) { - const double value = sMap.invTransform(x); + for ( int x = devRect.left(); x <= devRect.right(); x++ ) + { + const double value = sMap.invTransform( x ); if ( colorMap.format() == QwtColorMap::RGB ) - c.setRgb(colorMap.rgb(interval, value)); + c.setRgba( colorMap.rgb( interval, value ) ); else - c = colorTable[colorMap.colorIndex(interval, value)]; + c = colorTable[colorMap.colorIndex( interval, value )]; - pmPainter.setPen(c); - pmPainter.drawLine(x, devRect.top(), x, devRect.bottom()); + pmPainter.setPen( c ); + pmPainter.drawLine( x, devRect.top(), x, devRect.bottom() ); } - } else { // Vertical + } + else // Vertical + { QwtScaleMap sMap = scaleMap; - sMap.setPaintInterval(devRect.bottom(), devRect.top()); + sMap.setPaintInterval( rect.bottom(), rect.top() ); - for ( int y = devRect.top(); y <= devRect.bottom(); y++ ) { - const double value = sMap.invTransform(y); + for ( int y = devRect.top(); y <= devRect.bottom(); y++ ) + { + const double value = sMap.invTransform( y ); if ( colorMap.format() == QwtColorMap::RGB ) - c.setRgb(colorMap.rgb(interval, value)); + c.setRgb( colorMap.rgb( interval, value ) ); else - c = colorTable[colorMap.colorIndex(interval, value)]; + c = colorTable[colorMap.colorIndex( interval, value )]; - pmPainter.setPen(c); - pmPainter.drawLine(devRect.left(), y, devRect.right(), y); + pmPainter.setPen( c ); + pmPainter.drawLine( devRect.left(), y, devRect.right(), y ); } } pmPainter.end(); - painter->drawPixmap(devRect, pixmap); + + drawPixmap( painter, rect, pixmap ); +} + +static inline void qwtFillRect( const QWidget *widget, QPainter *painter, + const QRect &rect, const QBrush &brush) +{ + if ( brush.style() == Qt::TexturePattern ) + { + painter->save(); + + painter->setClipRect( rect ); + painter->drawTiledPixmap(rect, brush.texture(), rect.topLeft()); + + painter->restore(); + } + else if ( brush.gradient() ) + { + painter->save(); + + painter->setClipRect( rect ); + painter->fillRect(0, 0, widget->width(), + widget->height(), brush); + + painter->restore(); + } + else + { + painter->fillRect(rect, brush); + } } + +/*! + Fill a pixmap with the content of a widget + + In Qt >= 5.0 QPixmap::fill() is a nop, in Qt 4.x it is buggy + for backgrounds with gradients. Thus fillPixmap() offers + an alternative implementation. + + \param widget Widget + \param pixmap Pixmap to be filled + \param offset Offset + + \sa QPixmap::fill() + */ +void QwtPainter::fillPixmap( const QWidget *widget, + QPixmap &pixmap, const QPoint &offset ) +{ + const QRect rect( offset, pixmap.size() ); + + QPainter painter( &pixmap ); + painter.translate( -offset ); + + const QBrush autoFillBrush = + widget->palette().brush( widget->backgroundRole() ); + + if ( !( widget->autoFillBackground() && autoFillBrush.isOpaque() ) ) + { + const QBrush bg = widget->palette().brush( QPalette::Window ); + qwtFillRect( widget, &painter, rect, bg); + } + + if ( widget->autoFillBackground() ) + qwtFillRect( widget, &painter, rect, autoFillBrush); + + if ( widget->testAttribute(Qt::WA_StyledBackground) ) + { + painter.setClipRegion( rect ); + + QStyleOption opt; + opt.initFrom( widget ); + widget->style()->drawPrimitive( QStyle::PE_Widget, + &opt, &painter, widget ); + } +} + +/*! + Fill rect with the background of a widget + + \param painter Painter + \param rect Rectangle to be filled + \param widget Widget + + \sa QStyle::PE_Widget, QWidget::backgroundRole() + */ +void QwtPainter::drawBackgound( QPainter *painter, + const QRectF &rect, const QWidget *widget ) +{ + if ( widget->testAttribute( Qt::WA_StyledBackground ) ) + { + QStyleOption opt; + opt.initFrom( widget ); + opt.rect = rect.toAlignedRect(); + + widget->style()->drawPrimitive( + QStyle::PE_Widget, &opt, painter, widget); + } + else + { + const QBrush brush = + widget->palette().brush( widget->backgroundRole() ); + + painter->fillRect( rect, brush ); + } +} + +/*! + \return A pixmap that can be used as backing store + + \param widget Widget, for which the backinstore is intended + \param size Size of the pixmap + */ +QPixmap QwtPainter::backingStore( QWidget *widget, const QSize &size ) +{ + QPixmap pm; + +#define QWT_HIGH_DPI 1 + +#if QT_VERSION >= 0x050000 && QWT_HIGH_DPI + qreal pixelRatio = 1.0; + + if ( widget && widget->windowHandle() ) + { + pixelRatio = widget->windowHandle()->devicePixelRatio(); + } + else + { + if ( qApp ) + pixelRatio = qApp->devicePixelRatio(); + } + + pm = QPixmap( size * pixelRatio ); + pm.setDevicePixelRatio( pixelRatio ); +#else + Q_UNUSED( widget ) + pm = QPixmap( size ); +#endif + +#if QT_VERSION < 0x050000 +#ifdef Q_WS_X11 + if ( widget && isX11GraphicsSystem() ) + { + if ( pm.x11Info().screen() != widget->x11Info().screen() ) + pm.x11SetScreen( widget->x11Info().screen() ); + } +#endif +#endif + + return pm; +} + diff --git a/libs/qwt/qwt_painter.h b/libs/qwt/qwt_painter.h index 5d5abe375c..9609b6935f 100644 --- a/libs/qwt/qwt_painter.h +++ b/libs/qwt/qwt_painter.h @@ -10,140 +10,179 @@ #ifndef QWT_PAINTER_H #define QWT_PAINTER_H +#include "qwt_global.h" + #include <qpoint.h> #include <qrect.h> -#include "qwt_global.h" -#include "qwt_layout_metrics.h" -#include "qwt_polygon.h" +#include <qpen.h> +#include <qline.h> +#include <qpalette.h> class QPainter; class QBrush; class QColor; class QWidget; +class QPolygonF; +class QRectF; +class QImage; +class QPixmap; class QwtScaleMap; class QwtColorMap; -class QwtDoubleInterval; +class QwtInterval; -#if QT_VERSION < 0x040000 -class QColorGroup; -class QSimpleRichText; -#else -class QPalette; class QTextDocument; -#endif - -#if defined(Q_WS_X11) -// Warning: QCOORD_MIN, QCOORD_MAX are wrong on X11. -#define QWT_COORD_MAX 16384 -#define QWT_COORD_MIN (-QWT_COORD_MAX - 1) -#else -#define QWT_COORD_MAX 2147483647 -#define QWT_COORD_MIN -QWT_COORD_MAX - 1 -#endif +class QPainterPath; /*! \brief A collection of QPainter workarounds - - 1) Clipping to coordinate system limits (Qt3 only) - - On X11 pixel coordinates are stored in shorts. Qt - produces overruns when mapping QCOORDS to shorts. - - 2) Scaling to device metrics - - QPainter scales fonts, line and fill patterns to the metrics - of the paint device. Other values like the geometries of rects, points - remain device independend. To enable a device independent widget - implementation, QwtPainter adds scaling of these geometries. - (Unfortunately QPainter::scale scales both types of paintings, - so the objects of the first type would be scaled twice). */ - class QWT_EXPORT QwtPainter { public: - static void setMetricsMap(const QPaintDevice *layout, - const QPaintDevice *device); - static void setMetricsMap(const QwtMetricsMap &); - static void resetMetricsMap(); - static const QwtMetricsMap &metricsMap(); - - static void setDeviceClipping(bool); - static bool deviceClipping(); - - static void setClipRect(QPainter *, const QRect &); - - static void drawText(QPainter *, int x, int y, - const QString &); - static void drawText(QPainter *, const QPoint &, - const QString &); - static void drawText(QPainter *, int x, int y, int w, int h, - int flags, const QString &); - static void drawText(QPainter *, const QRect &, - int flags, const QString &); + static void setPolylineSplitting( bool ); + static bool polylineSplitting(); + + static void setRoundingAlignment( bool ); + static bool roundingAlignment(); + static bool roundingAlignment(QPainter *); + + static void drawText( QPainter *, double x, double y, const QString & ); + static void drawText( QPainter *, const QPointF &, const QString & ); + static void drawText( QPainter *, double x, double y, double w, double h, + int flags, const QString & ); + static void drawText( QPainter *, const QRectF &, + int flags, const QString & ); #ifndef QT_NO_RICHTEXT -#if QT_VERSION < 0x040000 - static void drawSimpleRichText(QPainter *, const QRect &, - int flags, QSimpleRichText &); -#else - static void drawSimpleRichText(QPainter *, const QRect &, - int flags, QTextDocument &); -#endif + static void drawSimpleRichText( QPainter *, const QRectF &, + int flags, const QTextDocument & ); #endif - static void drawRect(QPainter *, int x, int y, int w, int h); - static void drawRect(QPainter *, const QRect &rect); - static void fillRect(QPainter *, const QRect &, const QBrush &); - - static void drawEllipse(QPainter *, const QRect &); - static void drawPie(QPainter *, const QRect & r, int a, int alen); - - static void drawLine(QPainter *, int x1, int y1, int x2, int y2); - static void drawLine(QPainter *, const QPoint &p1, const QPoint &p2); - static void drawPolygon(QPainter *, const QwtPolygon &pa); - static void drawPolyline(QPainter *, const QwtPolygon &pa); - static void drawPoint(QPainter *, int x, int y); - -#if QT_VERSION < 0x040000 - static void drawRoundFrame(QPainter *, const QRect &, - int width, const QColorGroup &cg, bool sunken); -#else - static void drawRoundFrame(QPainter *, const QRect &, - int width, const QPalette &, bool sunken); -#endif - static void drawFocusRect(QPainter *, QWidget *); - static void drawFocusRect(QPainter *, QWidget *, const QRect &); + static void drawRect( QPainter *, double x, double y, double w, double h ); + static void drawRect( QPainter *, const QRectF &rect ); + static void fillRect( QPainter *, const QRectF &, const QBrush & ); - static QwtPolygon clip(const QwtPolygon &); + static void drawEllipse( QPainter *, const QRectF & ); + static void drawPie( QPainter *, const QRectF & r, int a, int alen ); - static void drawColorBar(QPainter *painter, - const QwtColorMap &, const QwtDoubleInterval &, - const QwtScaleMap &, Qt::Orientation, const QRect &); + static void drawLine( QPainter *, double x1, double y1, double x2, double y2 ); + static void drawLine( QPainter *, const QPointF &p1, const QPointF &p2 ); + static void drawLine( QPainter *, const QLineF & ); -#if QT_VERSION < 0x040000 - static void setSVGMode(bool on); - static bool isSVGMode(); -#endif + static void drawPolygon( QPainter *, const QPolygonF & ); + static void drawPolyline( QPainter *, const QPolygonF & ); + static void drawPolyline( QPainter *, const QPointF *, int pointCount ); -private: - static void drawColoredArc(QPainter *, const QRect &, - int peak, int arc, int intervall, const QColor &c1, const QColor &c2); + static void drawPolygon( QPainter *, const QPolygon & ); + static void drawPolyline( QPainter *, const QPolygon & ); + static void drawPolyline( QPainter *, const QPoint *, int pointCount ); - static const QRect &deviceClipRect(); + static void drawPoint( QPainter *, const QPoint & ); + static void drawPoints( QPainter *, const QPolygon & ); + static void drawPoints( QPainter *, const QPoint *, int pointCount ); - static bool d_deviceClipping; - static QwtMetricsMap d_metricsMap; -#if QT_VERSION < 0x040000 - static bool d_SVGMode; -#endif + static void drawPoint( QPainter *, double x, double y ); + static void drawPoint( QPainter *, const QPointF & ); + static void drawPoints( QPainter *, const QPolygonF & ); + static void drawPoints( QPainter *, const QPointF *, int pointCount ); + + static void drawPath( QPainter *, const QPainterPath & ); + static void drawImage( QPainter *, const QRectF &, const QImage & ); + static void drawPixmap( QPainter *, const QRectF &, const QPixmap & ); + + static void drawRoundFrame( QPainter *, + const QRectF &, const QPalette &, int lineWidth, int frameStyle ); + + static void drawRoundedFrame( QPainter *, + const QRectF &, double xRadius, double yRadius, + const QPalette &, int lineWidth, int frameStyle ); + + static void drawFrame( QPainter *, const QRectF &rect, + const QPalette &palette, QPalette::ColorRole foregroundRole, + int lineWidth, int midLineWidth, int frameStyle ); + + static void drawFocusRect( QPainter *, const QWidget * ); + static void drawFocusRect( QPainter *, const QWidget *, const QRect & ); + + static void drawColorBar( QPainter *painter, + const QwtColorMap &, const QwtInterval &, + const QwtScaleMap &, Qt::Orientation, const QRectF & ); + + static bool isAligning( QPainter *painter ); + static bool isX11GraphicsSystem(); + + static void fillPixmap( const QWidget *, + QPixmap &, const QPoint &offset = QPoint() ); + + static void drawBackgound( QPainter *painter, + const QRectF &rect, const QWidget *widget ); + + static QPixmap backingStore( QWidget *, const QSize & ); + +private: + static bool d_polylineSplitting; + static bool d_roundingAlignment; }; +//! Wrapper for QPainter::drawPoint() +inline void QwtPainter::drawPoint( QPainter *painter, double x, double y ) +{ + QwtPainter::drawPoint( painter, QPointF( x, y ) ); +} + +//! Wrapper for QPainter::drawPoints() +inline void QwtPainter::drawPoints( QPainter *painter, const QPolygon &polygon ) +{ + drawPoints( painter, polygon.data(), polygon.size() ); +} + +//! Wrapper for QPainter::drawPoints() +inline void QwtPainter::drawPoints( QPainter *painter, const QPolygonF &polygon ) +{ + drawPoints( painter, polygon.data(), polygon.size() ); +} + //! Wrapper for QPainter::drawLine() -inline void QwtPainter::drawLine(QPainter *painter, - const QPoint &p1, const QPoint &p2) +inline void QwtPainter::drawLine( QPainter *painter, + double x1, double y1, double x2, double y2 ) { - drawLine(painter, p1.x(), p1.y(), p2.x(), p2.y()); + QwtPainter::drawLine( painter, QPointF( x1, y1 ), QPointF( x2, y2 ) ); } +//! Wrapper for QPainter::drawLine() +inline void QwtPainter::drawLine( QPainter *painter, const QLineF &line ) +{ + QwtPainter::drawLine( painter, line.p1(), line.p2() ); +} + +/*! + \return True, when line splitting for the raster paint engine is enabled. + \sa setPolylineSplitting() +*/ +inline bool QwtPainter::polylineSplitting() +{ + return d_polylineSplitting; +} + +/*! + Check whether coordinates should be rounded, before they are painted + to a paint engine that rounds to integer values. For other paint engines + ( PDF, SVG ), this flag has no effect. + + \return True, when rounding is enabled + \sa setRoundingAlignment(), isAligning() +*/ +inline bool QwtPainter::roundingAlignment() +{ + return d_roundingAlignment; +} + +/*! + \return roundingAlignment() && isAligning(painter); + \param painter Painter +*/ +inline bool QwtPainter::roundingAlignment(QPainter *painter) +{ + return d_roundingAlignment && isAligning(painter); +} #endif diff --git a/libs/qwt/qwt_painter_command.cpp b/libs/qwt/qwt_painter_command.cpp new file mode 100644 index 0000000000..f6affae37e --- /dev/null +++ b/libs/qwt/qwt_painter_command.cpp @@ -0,0 +1,237 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_painter_command.h" + +//! Construct an invalid command +QwtPainterCommand::QwtPainterCommand(): + d_type( Invalid ) +{ +} + +//! Copy constructor +QwtPainterCommand::QwtPainterCommand( const QPainterPath &path ): + d_type( Path ) +{ + d_path = new QPainterPath( path ); +} + +/*! + Constructor for Pixmap paint operation + + \param rect Target rectangle + \param pixmap Pixmap + \param subRect Rectangle inside the pixmap + + \sa QPainter::drawPixmap() + */ +QwtPainterCommand::QwtPainterCommand( const QRectF &rect, + const QPixmap &pixmap, const QRectF& subRect ): + d_type( Pixmap ) +{ + d_pixmapData = new PixmapData(); + d_pixmapData->rect = rect; + d_pixmapData->pixmap = pixmap; + d_pixmapData->subRect = subRect; +} + +/*! + Constructor for Image paint operation + + \param rect Target rectangle + \param image Image + \param subRect Rectangle inside the image + \param flags Conversion flags + + \sa QPainter::drawImage() + */ +QwtPainterCommand::QwtPainterCommand( const QRectF &rect, + const QImage &image, const QRectF& subRect, + Qt::ImageConversionFlags flags ): + d_type( Image ) +{ + d_imageData = new ImageData(); + d_imageData->rect = rect; + d_imageData->image = image; + d_imageData->subRect = subRect; + d_imageData->flags = flags; +} + +/*! + Constructor for State paint operation + \param state Paint engine state + */ +QwtPainterCommand::QwtPainterCommand( const QPaintEngineState &state ): + d_type( State ) +{ + d_stateData = new StateData(); + + d_stateData->flags = state.state(); + + if ( d_stateData->flags & QPaintEngine::DirtyPen ) + d_stateData->pen = state.pen(); + + if ( d_stateData->flags & QPaintEngine::DirtyBrush ) + d_stateData->brush = state.brush(); + + if ( d_stateData->flags & QPaintEngine::DirtyBrushOrigin ) + d_stateData->brushOrigin = state.brushOrigin(); + + if ( d_stateData->flags & QPaintEngine::DirtyFont ) + d_stateData->font = state.font(); + + if ( d_stateData->flags & QPaintEngine::DirtyBackground ) + { + d_stateData->backgroundMode = state.backgroundMode(); + d_stateData->backgroundBrush = state.backgroundBrush(); + } + + if ( d_stateData->flags & QPaintEngine::DirtyTransform ) + d_stateData->transform = state.transform(); + + if ( d_stateData->flags & QPaintEngine::DirtyClipEnabled ) + d_stateData->isClipEnabled = state.isClipEnabled(); + + if ( d_stateData->flags & QPaintEngine::DirtyClipRegion ) + { + d_stateData->clipRegion = state.clipRegion(); + d_stateData->clipOperation = state.clipOperation(); + } + + if ( d_stateData->flags & QPaintEngine::DirtyClipPath ) + { + d_stateData->clipPath = state.clipPath(); + d_stateData->clipOperation = state.clipOperation(); + } + + if ( d_stateData->flags & QPaintEngine::DirtyHints ) + d_stateData->renderHints = state.renderHints(); + + if ( d_stateData->flags & QPaintEngine::DirtyCompositionMode ) + d_stateData->compositionMode = state.compositionMode(); + + if ( d_stateData->flags & QPaintEngine::DirtyOpacity ) + d_stateData->opacity = state.opacity(); +} + +/*! + Copy constructor + \param other Command to be copied + + */ +QwtPainterCommand::QwtPainterCommand(const QwtPainterCommand &other) +{ + copy( other ); +} + +//! Destructor +QwtPainterCommand::~QwtPainterCommand() +{ + reset(); +} + +/*! + Assignment operator + + \param other Command to be copied + \return Modified command + */ +QwtPainterCommand &QwtPainterCommand::operator=(const QwtPainterCommand &other) +{ + reset(); + copy( other ); + + return *this; +} + +void QwtPainterCommand::copy( const QwtPainterCommand &other ) +{ + d_type = other.d_type; + + switch( other.d_type ) + { + case Path: + { + d_path = new QPainterPath( *other.d_path ); + break; + } + case Pixmap: + { + d_pixmapData = new PixmapData( *other.d_pixmapData ); + break; + } + case Image: + { + d_imageData = new ImageData( *other.d_imageData ); + break; + } + case State: + { + d_stateData = new StateData( *other.d_stateData ); + break; + } + default: + break; + } +} + +void QwtPainterCommand::reset() +{ + switch( d_type ) + { + case Path: + { + delete d_path; + break; + } + case Pixmap: + { + delete d_pixmapData; + break; + } + case Image: + { + delete d_imageData; + break; + } + case State: + { + delete d_stateData; + break; + } + default: + break; + } + + d_type = Invalid; +} + +//! \return Painter path to be painted +QPainterPath *QwtPainterCommand::path() +{ + return d_path; +} + +//! \return Attributes how to paint a QPixmap +QwtPainterCommand::PixmapData* QwtPainterCommand::pixmapData() +{ + return d_pixmapData; +} + +//! \return Attributes how to paint a QImage +QwtPainterCommand::ImageData* QwtPainterCommand::imageData() +{ + return d_imageData; +} + +//! \return Attributes of a state change +QwtPainterCommand::StateData* QwtPainterCommand::stateData() +{ + return d_stateData; +} diff --git a/libs/qwt/qwt_painter_command.h b/libs/qwt/qwt_painter_command.h new file mode 100644 index 0000000000..2da597a7fa --- /dev/null +++ b/libs/qwt/qwt_painter_command.h @@ -0,0 +1,173 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PAINTER_COMMAND_H +#define QWT_PAINTER_COMMAND_H + +#include "qwt_global.h" +#include <qpaintengine.h> +#include <qpixmap.h> +#include <qimage.h> +#include <qpolygon.h> + +class QPainterPath; + +/*! + QwtPainterCommand represents the attributes of a paint operation + how it is used between QPainter and QPaintDevice + + It is used by QwtGraphic to record and replay paint operations + + \sa QwtGraphic::commands() + */ + +class QWT_EXPORT QwtPainterCommand +{ +public: + //! Type of the paint command + enum Type + { + //! Invalid command + Invalid = -1, + + //! Draw a QPainterPath + Path, + + //! Draw a QPixmap + Pixmap, + + //! Draw a QImage + Image, + + //! QPainter state change + State + }; + + //! Attributes how to paint a QPixmap + struct PixmapData + { + QRectF rect; + QPixmap pixmap; + QRectF subRect; + }; + + //! Attributes how to paint a QImage + struct ImageData + { + QRectF rect; + QImage image; + QRectF subRect; + Qt::ImageConversionFlags flags; + }; + + //! Attributes of a state change + struct StateData + { + QPaintEngine::DirtyFlags flags; + + QPen pen; + QBrush brush; + QPointF brushOrigin; + QBrush backgroundBrush; + Qt::BGMode backgroundMode; + QFont font; + QMatrix matrix; + QTransform transform; + + Qt::ClipOperation clipOperation; + QRegion clipRegion; + QPainterPath clipPath; + bool isClipEnabled; + + QPainter::RenderHints renderHints; + QPainter::CompositionMode compositionMode; + qreal opacity; + }; + + QwtPainterCommand(); + QwtPainterCommand(const QwtPainterCommand &); + + QwtPainterCommand( const QPainterPath & ); + + QwtPainterCommand( const QRectF &rect, + const QPixmap &, const QRectF& subRect ); + + QwtPainterCommand( const QRectF &rect, + const QImage &, const QRectF& subRect, + Qt::ImageConversionFlags ); + + QwtPainterCommand( const QPaintEngineState & ); + + ~QwtPainterCommand(); + + QwtPainterCommand &operator=(const QwtPainterCommand & ); + + Type type() const; + + QPainterPath *path(); + const QPainterPath *path() const; + + PixmapData* pixmapData(); + const PixmapData* pixmapData() const; + + ImageData* imageData(); + const ImageData* imageData() const; + + StateData* stateData(); + const StateData* stateData() const; + +private: + void copy( const QwtPainterCommand & ); + void reset(); + + Type d_type; + + union + { + QPainterPath *d_path; + PixmapData *d_pixmapData; + ImageData *d_imageData; + StateData *d_stateData; + }; +}; + +//! \return Type of the command +inline QwtPainterCommand::Type QwtPainterCommand::type() const +{ + return d_type; +} + +//! \return Painter path to be painted +inline const QPainterPath *QwtPainterCommand::path() const +{ + return d_path; +} + +//! \return Attributes how to paint a QPixmap +inline const QwtPainterCommand::PixmapData* +QwtPainterCommand::pixmapData() const +{ + return d_pixmapData; +} + +//! \return Attributes how to paint a QImage +inline const QwtPainterCommand::ImageData * +QwtPainterCommand::imageData() const +{ + return d_imageData; +} + +//! \return Attributes of a state change +inline const QwtPainterCommand::StateData * +QwtPainterCommand::stateData() const +{ + return d_stateData; +} + +#endif diff --git a/libs/qwt/qwt_panner.cpp b/libs/qwt/qwt_panner.cpp index deae929181..18497a9163 100644 --- a/libs/qwt/qwt_panner.cpp +++ b/libs/qwt/qwt_panner.cpp @@ -7,49 +7,26 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_panner.h" +#include "qwt_picker.h" +#include "qwt_painter.h" #include <qpainter.h> #include <qpixmap.h> #include <qevent.h> -#include <qframe.h> #include <qcursor.h> -#if QT_VERSION < 0x040000 -#include <qobjectlist.h> -#endif -#include "qwt_picker.h" -#include "qwt_array.h" -#include "qwt_panner.h" +#include <qbitmap.h> -static QwtArray<QwtPicker *> activePickers(QWidget *w) +static QVector<QwtPicker *> qwtActivePickers( QWidget *w ) { - QwtArray<QwtPicker *> pickers; + QVector<QwtPicker *> pickers; -#if QT_VERSION >= 0x040000 QObjectList children = w->children(); - for ( int i = 0; i < children.size(); i++ ) { - QObject *obj = children[i]; - if ( obj->inherits("QwtPicker") ) { - QwtPicker *picker = (QwtPicker *)obj; - if ( picker->isEnabled() ) - pickers += picker; - } - } -#else - QObjectList *children = (QObjectList *)w->children(); - if ( children ) { - for ( QObjectListIterator it(*children); it.current(); ++it ) { - QObject *obj = (QObject *)it.current(); - if ( obj->inherits("QwtPicker") ) { - QwtPicker *picker = (QwtPicker *)obj; - if ( picker->isEnabled() ) { - pickers.resize(pickers.size() + 1); - pickers[int(pickers.size()) - 1] = picker; - } - } - } + for ( int i = 0; i < children.size(); i++ ) + { + QwtPicker *picker = qobject_cast<QwtPicker *>( children[i] ); + if ( picker && picker->isEnabled() ) + pickers += picker; } -#endif return pickers; } @@ -58,51 +35,47 @@ class QwtPanner::PrivateData { public: PrivateData(): - button(Qt::LeftButton), - buttonState(Qt::NoButton), - abortKey(Qt::Key_Escape), - abortKeyState(Qt::NoButton), + button( Qt::LeftButton ), + buttonModifiers( Qt::NoModifier ), + abortKey( Qt::Key_Escape ), + abortKeyModifiers( Qt::NoModifier ), #ifndef QT_NO_CURSOR - cursor(NULL), - restoreCursor(NULL), - hasCursor(false), + cursor( NULL ), + restoreCursor( NULL ), + hasCursor( false ), #endif - isEnabled(false) { -#if QT_VERSION >= 0x040000 + isEnabled( false ) + { orientations = Qt::Vertical | Qt::Horizontal; -#else - orientations[Qt::Vertical] = true; - orientations[Qt::Horizontal] = true; -#endif } - ~PrivateData() { + ~PrivateData() + { #ifndef QT_NO_CURSOR delete cursor; delete restoreCursor; #endif } - int button; - int buttonState; + Qt::MouseButton button; + Qt::KeyboardModifiers buttonModifiers; + int abortKey; - int abortKeyState; + Qt::KeyboardModifiers abortKeyModifiers; QPoint initialPos; QPoint pos; QPixmap pixmap; + QBitmap contentsMask; + #ifndef QT_NO_CURSOR QCursor *cursor; QCursor *restoreCursor; bool hasCursor; #endif bool isEnabled; -#if QT_VERSION >= 0x040000 Qt::Orientations orientations; -#else - bool orientations[2]; -#endif }; /*! @@ -110,22 +83,17 @@ public: \param parent Parent widget to be panned */ -QwtPanner::QwtPanner(QWidget *parent): - QWidget(parent) +QwtPanner::QwtPanner( QWidget *parent ): + QWidget( parent ) { d_data = new PrivateData(); -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_TransparentForMouseEvents); - setAttribute(Qt::WA_NoSystemBackground); - setFocusPolicy(Qt::NoFocus); -#else - setBackgroundMode(Qt::NoBackground); - setFocusPolicy(QWidget::NoFocus); -#endif + setAttribute( Qt::WA_TransparentForMouseEvents ); + setAttribute( Qt::WA_NoSystemBackground ); + setFocusPolicy( Qt::NoFocus ); hide(); - setEnabled(true); + setEnabled( true ); } //! Destructor @@ -135,37 +103,44 @@ QwtPanner::~QwtPanner() } /*! - Change the mouse button - The defaults are Qt::LeftButton and Qt::NoButton + Change the mouse button and modifiers used for panning + The defaults are Qt::LeftButton and Qt::NoModifier */ -void QwtPanner::setMouseButton(int button, int buttonState) +void QwtPanner::setMouseButton( Qt::MouseButton button, + Qt::KeyboardModifiers modifiers ) { d_data->button = button; - d_data->buttonState = buttonState; + d_data->buttonModifiers = modifiers; } -//! Get the mouse button -void QwtPanner::getMouseButton(int &button, int &buttonState) const +//! Get mouse button and modifiers used for panning +void QwtPanner::getMouseButton( Qt::MouseButton &button, + Qt::KeyboardModifiers &modifiers ) const { button = d_data->button; - buttonState = d_data->buttonState; + modifiers = d_data->buttonModifiers; } /*! Change the abort key - The defaults are Qt::Key_Escape and Qt::NoButton + The defaults are Qt::Key_Escape and Qt::NoModifiers + + \param key Key ( See Qt::Keycode ) + \param modifiers Keyboard modifiers */ -void QwtPanner::setAbortKey(int key, int state) +void QwtPanner::setAbortKey( int key, + Qt::KeyboardModifiers modifiers ) { d_data->abortKey = key; - d_data->abortKeyState = state; + d_data->abortKeyModifiers = modifiers; } -//! Get the abort key -void QwtPanner::getAbortKey(int &key, int &state) const +//! Get the abort key and modifiers +void QwtPanner::getAbortKey( int &key, + Qt::KeyboardModifiers &modifiers ) const { key = d_data->abortKey; - state = d_data->abortKeyState; + modifiers = d_data->abortKeyModifiers; } /*! @@ -177,9 +152,9 @@ void QwtPanner::getAbortKey(int &key, int &state) const \sa setCursor() */ #ifndef QT_NO_CURSOR -void QwtPanner::setCursor(const QCursor &cursor) +void QwtPanner::setCursor( const QCursor &cursor ) { - d_data->cursor = new QCursor(cursor); + d_data->cursor = new QCursor( cursor ); } #endif @@ -209,31 +184,35 @@ const QCursor QwtPanner::cursor() const \param on true or false \sa isEnabled(), eventFilter() */ -void QwtPanner::setEnabled(bool on) +void QwtPanner::setEnabled( bool on ) { - if ( d_data->isEnabled != on ) { + if ( d_data->isEnabled != on ) + { d_data->isEnabled = on; QWidget *w = parentWidget(); - if ( w ) { - if ( d_data->isEnabled ) { - w->installEventFilter(this); - } else { - w->removeEventFilter(this); + if ( w ) + { + if ( d_data->isEnabled ) + { + w->installEventFilter( this ); + } + else + { + w->removeEventFilter( this ); hide(); } } } } -#if QT_VERSION >= 0x040000 /*! Set the orientations, where panning is enabled The default value is in both directions: Qt::Horizontal | Qt::Vertical /param o Orientation */ -void QwtPanner::setOrientations(Qt::Orientations o) +void QwtPanner::setOrientations( Qt::Orientations o ) { d_data->orientations = o; } @@ -244,27 +223,13 @@ Qt::Orientations QwtPanner::orientations() const return d_data->orientations; } -#else -void QwtPanner::enableOrientation(Qt::Orientation o, bool enable) -{ - if ( o == Qt::Vertical || o == Qt::Horizontal ) - d_data->orientations[o] = enable; -} -#endif - /*! - Return true if a orientatio is enabled + \return True if an orientation is enabled \sa orientations(), setOrientations() */ -bool QwtPanner::isOrientationEnabled(Qt::Orientation o) const +bool QwtPanner::isOrientationEnabled( Qt::Orientation o ) const { -#if QT_VERSION >= 0x040000 return d_data->orientations & o; -#else - if ( o == Qt::Vertical || o == Qt::Horizontal ) - return d_data->orientations[o]; - return false; -#endif } /*! @@ -284,80 +249,121 @@ bool QwtPanner::isEnabled() const \param pe Paint event */ -void QwtPanner::paintEvent(QPaintEvent *pe) +void QwtPanner::paintEvent( QPaintEvent *pe ) { - QPixmap pm(size()); + int dx = d_data->pos.x() - d_data->initialPos.x(); + int dy = d_data->pos.y() - d_data->initialPos.y(); - QPainter painter(&pm); + QRect r( 0, 0, d_data->pixmap.width(), d_data->pixmap.height() ); + r.moveCenter( QPoint( r.center().x() + dx, r.center().y() + dy ) ); - const QColor bg = -#if QT_VERSION < 0x040000 - parentWidget()->palette().color( - QPalette::Normal, QColorGroup::Background); -#else - parentWidget()->palette().color( - QPalette::Normal, QPalette::Background); -#endif + QPixmap pm( size() ); + QwtPainter::fillPixmap( parentWidget(), pm ); - painter.setPen(Qt::NoPen); - painter.setBrush(QBrush(bg)); - painter.drawRect(0, 0, pm.width(), pm.height()); + QPainter painter( &pm ); - int dx = d_data->pos.x() - d_data->initialPos.x(); - int dy = d_data->pos.y() - d_data->initialPos.y(); - - QRect r(0, 0, d_data->pixmap.width(), d_data->pixmap.height()); - r.moveCenter(QPoint(r.center().x() + dx, r.center().y() + dy)); + if ( !d_data->contentsMask.isNull() ) + { + QPixmap masked = d_data->pixmap; + masked.setMask( d_data->contentsMask ); + painter.drawPixmap( r, masked ); + } + else + { + painter.drawPixmap( r, d_data->pixmap ); + } - painter.drawPixmap(r, d_data->pixmap); painter.end(); - painter.begin(this); - painter.setClipRegion(pe->region()); - painter.drawPixmap(0, 0, pm); + if ( !d_data->contentsMask.isNull() ) + pm.setMask( d_data->contentsMask ); + + painter.begin( this ); + painter.setClipRegion( pe->region() ); + painter.drawPixmap( 0, 0, pm ); +} + +/*! + \brief Calculate a mask for the contents of the panned widget + + Sometimes only parts of the contents of a widget should be + panned. F.e. for a widget with a styled background with rounded borders + only the area inside of the border should be panned. + + \return An empty bitmap, indicating no mask +*/ +QBitmap QwtPanner::contentsMask() const +{ + return QBitmap(); +} + +/*! + Grab the widget into a pixmap. + \return Grabbed pixmap +*/ +QPixmap QwtPanner::grab() const +{ +#if QT_VERSION >= 0x050000 + return parentWidget()->grab( parentWidget()->rect() ); +#else + return QPixmap::grabWidget( parentWidget() ); +#endif } /*! \brief Event filter - When isEnabled() the mouse events of the observed widget are filtered. + When isEnabled() is true mouse events of the + observed widget are filtered. + + \param object Object to be filtered + \param event Event + + \return Always false, beside for paint events for the + parent widget. \sa widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseMoveEvent() */ -bool QwtPanner::eventFilter(QObject *o, QEvent *e) +bool QwtPanner::eventFilter( QObject *object, QEvent *event ) { - if ( o == NULL || o != parentWidget() ) + if ( object == NULL || object != parentWidget() ) return false; - switch(e->type()) { - case QEvent::MouseButtonPress: { - widgetMousePressEvent((QMouseEvent *)e); - break; - } - case QEvent::MouseMove: { - widgetMouseMoveEvent((QMouseEvent *)e); - break; - } - case QEvent::MouseButtonRelease: { - widgetMouseReleaseEvent((QMouseEvent *)e); - break; - } - case QEvent::KeyPress: { - widgetKeyPressEvent((QKeyEvent *)e); - break; - } - case QEvent::KeyRelease: { - widgetKeyReleaseEvent((QKeyEvent *)e); - break; - } - case QEvent::Paint: { - if ( isVisible() ) - return true; - break; - } - default: - ; + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + widgetMousePressEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::MouseMove: + { + widgetMouseMoveEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::MouseButtonRelease: + { + widgetMouseReleaseEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::KeyPress: + { + widgetKeyPressEvent( static_cast<QKeyEvent *>( event ) ); + break; + } + case QEvent::KeyRelease: + { + widgetKeyReleaseEvent( static_cast<QKeyEvent *>( event ) ); + break; + } + case QEvent::Paint: + { + if ( isVisible() ) + return true; + break; + } + default:; } return false; @@ -366,53 +372,40 @@ bool QwtPanner::eventFilter(QObject *o, QEvent *e) /*! Handle a mouse press event for the observed widget. - \param me Mouse event + \param mouseEvent Mouse event \sa eventFilter(), widgetMouseReleaseEvent(), widgetMouseMoveEvent(), */ -void QwtPanner::widgetMousePressEvent(QMouseEvent *me) +void QwtPanner::widgetMousePressEvent( QMouseEvent *mouseEvent ) { - if ( me->button() != d_data->button ) + if ( ( mouseEvent->button() != d_data->button ) + || ( mouseEvent->modifiers() != d_data->buttonModifiers ) ) + { return; + } QWidget *w = parentWidget(); if ( w == NULL ) return; -#if QT_VERSION < 0x040000 - if ( (me->state() & Qt::KeyButtonMask) != - (d_data->buttonState & Qt::KeyButtonMask) ) -#else - if ( (me->modifiers() & Qt::KeyboardModifierMask) != - (int)(d_data->buttonState & Qt::KeyboardModifierMask) ) -#endif - { - return; - } - #ifndef QT_NO_CURSOR - showCursor(true); + showCursor( true ); #endif - d_data->initialPos = d_data->pos = me->pos(); + d_data->initialPos = d_data->pos = mouseEvent->pos(); - QRect cr = parentWidget()->rect(); - if ( parentWidget()->inherits("QFrame") ) { - const QFrame* frame = (QFrame*)parentWidget(); - cr = frame->contentsRect(); - } - setGeometry(cr); + setGeometry( parentWidget()->rect() ); // We don't want to grab the picker ! - QwtArray<QwtPicker *> pickers = activePickers(parentWidget()); - for ( int i = 0; i < (int)pickers.size(); i++ ) - pickers[i]->setEnabled(false); + QVector<QwtPicker *> pickers = qwtActivePickers( parentWidget() ); + for ( int i = 0; i < pickers.size(); i++ ) + pickers[i]->setEnabled( false ); - d_data->pixmap = QPixmap::grabWidget(parentWidget(), - cr.x(), cr.y(), cr.width(), cr.height()); + d_data->pixmap = grab(); + d_data->contentsMask = contentsMask(); - for ( int i = 0; i < (int)pickers.size(); i++ ) - pickers[i]->setEnabled(true); + for ( int i = 0; i < pickers.size(); i++ ) + pickers[i]->setEnabled( true ); show(); } @@ -420,56 +413,60 @@ void QwtPanner::widgetMousePressEvent(QMouseEvent *me) /*! Handle a mouse move event for the observed widget. - \param me Mouse event + \param mouseEvent Mouse event \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent() */ -void QwtPanner::widgetMouseMoveEvent(QMouseEvent *me) +void QwtPanner::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) { if ( !isVisible() ) return; - QPoint pos = me->pos(); - if ( !isOrientationEnabled(Qt::Horizontal) ) - pos.setX(d_data->initialPos.x()); - if ( !isOrientationEnabled(Qt::Vertical) ) - pos.setY(d_data->initialPos.y()); + QPoint pos = mouseEvent->pos(); + if ( !isOrientationEnabled( Qt::Horizontal ) ) + pos.setX( d_data->initialPos.x() ); + if ( !isOrientationEnabled( Qt::Vertical ) ) + pos.setY( d_data->initialPos.y() ); - if ( pos != d_data->pos && rect().contains(pos) ) { + if ( pos != d_data->pos && rect().contains( pos ) ) + { d_data->pos = pos; update(); - emit moved(d_data->pos.x() - d_data->initialPos.x(), - d_data->pos.y() - d_data->initialPos.y()); + Q_EMIT moved( d_data->pos.x() - d_data->initialPos.x(), + d_data->pos.y() - d_data->initialPos.y() ); } } /*! Handle a mouse release event for the observed widget. - \param me Mouse event + \param mouseEvent Mouse event \sa eventFilter(), widgetMousePressEvent(), widgetMouseMoveEvent(), */ -void QwtPanner::widgetMouseReleaseEvent(QMouseEvent *me) +void QwtPanner::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) { - if ( isVisible() ) { + if ( isVisible() ) + { hide(); #ifndef QT_NO_CURSOR - showCursor(false); + showCursor( false ); #endif - QPoint pos = me->pos(); - if ( !isOrientationEnabled(Qt::Horizontal) ) - pos.setX(d_data->initialPos.x()); - if ( !isOrientationEnabled(Qt::Vertical) ) - pos.setY(d_data->initialPos.y()); + QPoint pos = mouseEvent->pos(); + if ( !isOrientationEnabled( Qt::Horizontal ) ) + pos.setX( d_data->initialPos.x() ); + if ( !isOrientationEnabled( Qt::Vertical ) ) + pos.setY( d_data->initialPos.y() ); d_data->pixmap = QPixmap(); + d_data->contentsMask = QBitmap(); d_data->pos = pos; - if ( d_data->pos != d_data->initialPos ) { - emit panned(d_data->pos.x() - d_data->initialPos.x(), - d_data->pos.y() - d_data->initialPos.y()); + if ( d_data->pos != d_data->initialPos ) + { + Q_EMIT panned( d_data->pos.x() - d_data->initialPos.x(), + d_data->pos.y() - d_data->initialPos.y() ); } } } @@ -477,42 +474,36 @@ void QwtPanner::widgetMouseReleaseEvent(QMouseEvent *me) /*! Handle a key press event for the observed widget. - \param ke Key event + \param keyEvent Key event \sa eventFilter(), widgetKeyReleaseEvent() */ -void QwtPanner::widgetKeyPressEvent(QKeyEvent *ke) +void QwtPanner::widgetKeyPressEvent( QKeyEvent *keyEvent ) { - if ( ke->key() == d_data->abortKey ) { - const bool matched = -#if QT_VERSION < 0x040000 - (ke->state() & Qt::KeyButtonMask) == - (d_data->abortKeyState & Qt::KeyButtonMask); -#else - (ke->modifiers() & Qt::KeyboardModifierMask) == - (int)(d_data->abortKeyState & Qt::KeyboardModifierMask); -#endif - if ( matched ) { - hide(); + if ( ( keyEvent->key() == d_data->abortKey ) + && ( keyEvent->modifiers() == d_data->abortKeyModifiers ) ) + { + hide(); + #ifndef QT_NO_CURSOR - showCursor(false); + showCursor( false ); #endif - d_data->pixmap = QPixmap(); - } + d_data->pixmap = QPixmap(); } } /*! Handle a key release event for the observed widget. - \param ke Key event + \param keyEvent Key event \sa eventFilter(), widgetKeyReleaseEvent() */ -void QwtPanner::widgetKeyReleaseEvent(QKeyEvent *) +void QwtPanner::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) { + Q_UNUSED( keyEvent ); } #ifndef QT_NO_CURSOR -void QwtPanner::showCursor(bool on) +void QwtPanner::showCursor( bool on ) { if ( on == d_data->hasCursor ) return; @@ -523,23 +514,24 @@ void QwtPanner::showCursor(bool on) d_data->hasCursor = on; - if ( on ) { -#if QT_VERSION < 0x040000 - if ( w->testWState(WState_OwnCursor) ) -#else - if ( w->testAttribute(Qt::WA_SetCursor) ) -#endif + if ( on ) + { + if ( w->testAttribute( Qt::WA_SetCursor ) ) { delete d_data->restoreCursor; - d_data->restoreCursor = new QCursor(w->cursor()); + d_data->restoreCursor = new QCursor( w->cursor() ); } - w->setCursor(*d_data->cursor); - } else { - if ( d_data->restoreCursor ) { - w->setCursor(*d_data->restoreCursor); + w->setCursor( *d_data->cursor ); + } + else + { + if ( d_data->restoreCursor ) + { + w->setCursor( *d_data->restoreCursor ); delete d_data->restoreCursor; d_data->restoreCursor = NULL; - } else + } + else w->unsetCursor(); } } diff --git a/libs/qwt/qwt_panner.h b/libs/qwt/qwt_panner.h index d648f07da9..a0c6873aba 100644 --- a/libs/qwt/qwt_panner.h +++ b/libs/qwt/qwt_panner.h @@ -10,9 +10,9 @@ #ifndef QWT_PANNER_H #define QWT_PANNER_H 1 -#include <qnamespace.h> -#include <qwidget.h> #include "qwt_global.h" +#include <qwidget.h> +#include <qpixmap.h> class QCursor; @@ -25,8 +25,8 @@ class QCursor; QwtPanner grabs the content of the widget into a pixmap and moves the pixmap around, without initiating any repaint events for the widget. - Areas, that are not part of content are not painted while panning - in in process. This makes panning fast enough for widgets, where + Areas, that are not part of content are not painted while panning. + This makes panning fast enough for widgets, where repaints are too slow for mouse movements. For widgets, where repaints are very fast it might be better to @@ -37,39 +37,38 @@ class QWT_EXPORT QwtPanner: public QWidget Q_OBJECT public: - QwtPanner(QWidget* parent); + QwtPanner( QWidget* parent ); virtual ~QwtPanner(); - void setEnabled(bool); + void setEnabled( bool ); bool isEnabled() const; - void setMouseButton(int button, int buttonState = Qt::NoButton); - void getMouseButton(int &button, int &buttonState) const; - void setAbortKey(int key, int state = Qt::NoButton); - void getAbortKey(int &key, int &state) const; + void setMouseButton( Qt::MouseButton, + Qt::KeyboardModifiers = Qt::NoModifier ); + void getMouseButton( Qt::MouseButton &button, + Qt::KeyboardModifiers & ) const; + + void setAbortKey( int key, Qt::KeyboardModifiers = Qt::NoModifier ); + void getAbortKey( int &key, Qt::KeyboardModifiers & ) const; - void setCursor(const QCursor &); + void setCursor( const QCursor & ); const QCursor cursor() const; -#if QT_VERSION >= 0x040000 - void setOrientations(Qt::Orientations); + void setOrientations( Qt::Orientations ); Qt::Orientations orientations() const; -#else - void enableOrientation(Qt::Orientation, bool enable); -#endif - bool isOrientationEnabled(Qt::Orientation) const; + bool isOrientationEnabled( Qt::Orientation ) const; - virtual bool eventFilter(QObject *, QEvent *); + virtual bool eventFilter( QObject *, QEvent * ); -signals: +Q_SIGNALS: /*! Signal emitted, when panning is done \param dx Offset in horizontal direction \param dy Offset in vertical direction */ - void panned(int dx, int dy); + void panned( int dx, int dy ); /*! Signal emitted, while the widget moved, but panning @@ -78,20 +77,23 @@ signals: \param dx Offset in horizontal direction \param dy Offset in vertical direction */ - void moved(int dx, int dy); + void moved( int dx, int dy ); protected: - virtual void widgetMousePressEvent(QMouseEvent *); - virtual void widgetMouseReleaseEvent(QMouseEvent *); - virtual void widgetMouseMoveEvent(QMouseEvent *); - virtual void widgetKeyPressEvent(QKeyEvent *); - virtual void widgetKeyReleaseEvent(QKeyEvent *); + virtual void widgetMousePressEvent( QMouseEvent * ); + virtual void widgetMouseReleaseEvent( QMouseEvent * ); + virtual void widgetMouseMoveEvent( QMouseEvent * ); + virtual void widgetKeyPressEvent( QKeyEvent * ); + virtual void widgetKeyReleaseEvent( QKeyEvent * ); + + virtual void paintEvent( QPaintEvent * ); - virtual void paintEvent(QPaintEvent *); + virtual QBitmap contentsMask() const; + virtual QPixmap grab() const; private: #ifndef QT_NO_CURSOR - void showCursor(bool); + void showCursor( bool ); #endif class PrivateData; diff --git a/libs/qwt/qwt_picker.cpp b/libs/qwt/qwt_picker.cpp index 82752cb747..335ddf0cd0 100644 --- a/libs/qwt/qwt_picker.cpp +++ b/libs/qwt/qwt_picker.cpp @@ -7,56 +7,108 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_picker.h" +#include "qwt_picker_machine.h" +#include "qwt_painter.h" +#include "qwt_math.h" +#include "qwt_widget_overlay.h" #include <qapplication.h> #include <qevent.h> #include <qpainter.h> #include <qframe.h> #include <qcursor.h> #include <qbitmap.h> -#include "qwt_math.h" -#include "qwt_painter.h" -#include "qwt_picker_machine.h" -#include "qwt_picker.h" -#if QT_VERSION < 0x040000 -#include <qguardedptr.h> -#else #include <qpointer.h> #include <qpaintengine.h> -#endif +#include <qmath.h> -class QwtPicker::PickerWidget: public QWidget +static inline QRegion qwtMaskRegion( const QRect &r, int penWidth ) { -public: - enum Type { - RubberBand, - Text - }; + const int pw = qMax( penWidth, 1 ); + const int pw2 = penWidth / 2; + + int x1 = r.left() - pw2; + int x2 = r.right() + 1 + pw2 + ( pw % 2 ); + + int y1 = r.top() - pw2; + int y2 = r.bottom() + 1 + pw2 + ( pw % 2 ); + + QRegion region; + + region += QRect( x1, y1, x2 - x1, pw ); + region += QRect( x1, y1, pw, y2 - y1 ); + region += QRect( x1, y2 - pw, x2 - x1, pw ); + region += QRect( x2 - pw, y1, pw, y2 - y1 ); + + return region; +} + +static inline QRegion qwtMaskRegion( const QLine &l, int penWidth ) +{ + const int pw = qMax( penWidth, 1 ); + const int pw2 = penWidth / 2; + + QRegion region; + + if ( l.x1() == l.x2() ) + { + region += QRect( l.x1() - pw2, l.y1(), + pw, l.y2() ).normalized(); + } + else if ( l.y1() == l.y2() ) + { + region += QRect( l.x1(), l.y1() - pw2, + l.x2(), pw ).normalized(); + } - PickerWidget(QwtPicker *, QWidget *, Type); - virtual void updateMask(); + return region; +} - /* - For a tracker text with a background we can use the background - rect as mask. Also for "regular" Qt widgets >= 4.3.0 we - don't need to mask the text anymore. - */ - bool d_hasTextMask; +class QwtPickerRubberband: public QwtWidgetOverlay +{ +public: + QwtPickerRubberband( QwtPicker *, QWidget * ); protected: - virtual void paintEvent(QPaintEvent *); + virtual void drawOverlay( QPainter * ) const; + virtual QRegion maskHint() const; QwtPicker *d_picker; - Type d_type; }; +class QwtPickerTracker: public QwtWidgetOverlay +{ +public: + QwtPickerTracker( QwtPicker *, QWidget * ); + +protected: + virtual void drawOverlay( QPainter * ) const; + virtual QRegion maskHint() const; + + QwtPicker *d_picker; +}; + + class QwtPicker::PrivateData { public: + PrivateData(): + enabled( false ), + stateMachine( NULL ), + resizeMode( QwtPicker::Stretch ), + rubberBand( QwtPicker::NoRubberBand ), + trackerMode( QwtPicker::AlwaysOff ), + isActive( false ), + trackerPosition( -1, -1 ), + mouseTracking( false ), + openGL( false ) + { + } + bool enabled; QwtPickerMachine *stateMachine; - int selectionFlags; QwtPicker::ResizeMode resizeMode; QwtPicker::RubberBand rubberBand; @@ -66,246 +118,130 @@ public: QPen trackerPen; QFont trackerFont; - QwtPolygon selection; + QPolygon pickedPoints; bool isActive; QPoint trackerPosition; bool mouseTracking; // used to save previous value - /* - On X11 the widget below the picker widgets gets paint events - with a region that is the bounding rect of the mask, if it is complex. - In case of (f.e) a CrossRubberBand and a text this creates complete - repaints of the widget. So we better use two different widgets. - */ - -#if QT_VERSION < 0x040000 - QGuardedPtr<PickerWidget> rubberBandWidget; - QGuardedPtr<PickerWidget> trackerWidget; -#else - QPointer<PickerWidget> rubberBandWidget; - QPointer<PickerWidget> trackerWidget; -#endif + QPointer< QwtPickerRubberband > rubberBandOverlay; + QPointer< QwtPickerTracker> trackerOverlay; + + bool openGL; }; -QwtPicker::PickerWidget::PickerWidget( - QwtPicker *picker, QWidget *parent, Type type): - QWidget(parent), - d_hasTextMask(false), - d_picker(picker), - d_type(type) +QwtPickerRubberband::QwtPickerRubberband( + QwtPicker *picker, QWidget *parent ): + QwtWidgetOverlay( parent ), + d_picker( picker ) { -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_TransparentForMouseEvents); - setAttribute(Qt::WA_NoSystemBackground); - setFocusPolicy(Qt::NoFocus); -#else - setBackgroundMode(Qt::NoBackground); - setFocusPolicy(QWidget::NoFocus); - setMouseTracking(true); -#endif - hide(); + setMaskMode( QwtWidgetOverlay::MaskHint ); } -void QwtPicker::PickerWidget::updateMask() +QRegion QwtPickerRubberband::maskHint() const { - QRegion mask; - - if ( d_type == RubberBand ) { - QBitmap bm(width(), height()); - bm.fill(Qt::color0); - - QPainter painter(&bm); - QPen pen = d_picker->rubberBandPen(); - pen.setColor(Qt::color1); - painter.setPen(pen); - - d_picker->drawRubberBand(&painter); - - mask = QRegion(bm); - } - if ( d_type == Text ) { - d_hasTextMask = true; -#if QT_VERSION >= 0x040300 - if ( !parentWidget()->testAttribute(Qt::WA_PaintOnScreen) ) { -#if 0 - if ( parentWidget()->paintEngine()->type() != QPaintEngine::OpenGL ) -#endif - { - // With Qt >= 4.3 drawing of the tracker can be implemented in an - // easier way, using the textRect as mask. - - d_hasTextMask = false; - } - } -#endif - - if ( d_hasTextMask ) { - const QwtText label = d_picker->trackerText( - d_picker->trackerPosition()); - if ( label.testPaintAttribute(QwtText::PaintBackground) - && label.backgroundBrush().style() != Qt::NoBrush ) { -#if QT_VERSION >= 0x040300 - if ( label.backgroundBrush().color().alpha() > 0 ) -#endif - // We don't need a text mask, when we have a background - d_hasTextMask = false; - } - } - - if ( d_hasTextMask ) { - QBitmap bm(width(), height()); - bm.fill(Qt::color0); - - QPainter painter(&bm); - painter.setFont(font()); - - QPen pen = d_picker->trackerPen(); - pen.setColor(Qt::color1); - painter.setPen(pen); - - d_picker->drawTracker(&painter); - - mask = QRegion(bm); - } else { - mask = d_picker->trackerRect(font()); - } - } - -#if QT_VERSION < 0x040000 - QWidget *w = parentWidget(); - const bool doUpdate = w->isUpdatesEnabled(); - const Qt::BackgroundMode bgMode = w->backgroundMode(); - w->setUpdatesEnabled(false); - if ( bgMode != Qt::NoBackground ) - w->setBackgroundMode(Qt::NoBackground); -#endif - - setMask(mask); - -#if QT_VERSION < 0x040000 - if ( bgMode != Qt::NoBackground ) - w->setBackgroundMode(bgMode); - - w->setUpdatesEnabled(doUpdate); -#endif + return d_picker->rubberBandMask(); +} - setShown(!mask.isEmpty()); +void QwtPickerRubberband::drawOverlay( QPainter *painter ) const +{ + painter->setPen( d_picker->rubberBandPen() ); + d_picker->drawRubberBand( painter ); } -void QwtPicker::PickerWidget::paintEvent(QPaintEvent *e) +QwtPickerTracker::QwtPickerTracker( + QwtPicker *picker, QWidget *parent ): + QwtWidgetOverlay( parent ), + d_picker( picker ) { - QPainter painter(this); - painter.setClipRegion(e->region()); + setMaskMode( QwtWidgetOverlay::MaskHint ); +} - if ( d_type == RubberBand ) { - painter.setPen(d_picker->rubberBandPen()); - d_picker->drawRubberBand(&painter); - } +QRegion QwtPickerTracker::maskHint() const +{ + return d_picker->trackerRect( font() ); +} - if ( d_type == Text ) { - /* - If we have a text mask we simply fill the region of - the mask. This gives better results for antialiased fonts. - */ - bool doDrawTracker = !d_hasTextMask; -#if QT_VERSION < 0x040000 - if ( !doDrawTracker && QPainter::redirect(this) ) { - // setMask + painter redirection doesn't work - doDrawTracker = true; - } -#endif - if ( doDrawTracker ) { - painter.setPen(d_picker->trackerPen()); - d_picker->drawTracker(&painter); - } else - painter.fillRect(e->rect(), QBrush(d_picker->trackerPen().color())); - } +void QwtPickerTracker::drawOverlay( QPainter *painter ) const +{ + painter->setPen( d_picker->trackerPen() ); + d_picker->drawTracker( painter ); } /*! Constructor - Creates an picker that is enabled, but where selection flag - is set to NoSelection, rubberband and tracker are disabled. + Creates an picker that is enabled, but without a state machine. + rubber band and tracker are disabled. \param parent Parent widget, that will be observed */ -QwtPicker::QwtPicker(QWidget *parent): - QObject(parent) +QwtPicker::QwtPicker( QWidget *parent ): + QObject( parent ) { - init(parent, NoSelection, NoRubberBand, AlwaysOff); + init( parent, NoRubberBand, AlwaysOff ); } /*! Constructor - \param selectionFlags Or'd value of SelectionType, RectSelectionType and - SelectionMode - \param rubberBand Rubberband style + \param rubberBand Rubber band style \param trackerMode Tracker mode \param parent Parent widget, that will be observed */ -QwtPicker::QwtPicker(int selectionFlags, RubberBand rubberBand, - DisplayMode trackerMode, QWidget *parent): - QObject(parent) +QwtPicker::QwtPicker( RubberBand rubberBand, + DisplayMode trackerMode, QWidget *parent ): + QObject( parent ) { - init(parent, selectionFlags, rubberBand, trackerMode); + init( parent, rubberBand, trackerMode ); } //! Destructor QwtPicker::~QwtPicker() { - setMouseTracking(false); + setMouseTracking( false ); + delete d_data->stateMachine; - delete d_data->rubberBandWidget; - delete d_data->trackerWidget; + delete d_data->rubberBandOverlay; + delete d_data->trackerOverlay; + delete d_data; } -//! Init the picker, used by the constructors -void QwtPicker::init(QWidget *parent, int selectionFlags, - RubberBand rubberBand, DisplayMode trackerMode) +//! Initialize the picker - used by the constructors +void QwtPicker::init( QWidget *parent, + RubberBand rubberBand, DisplayMode trackerMode ) { d_data = new PrivateData; - d_data->rubberBandWidget = NULL; - d_data->trackerWidget = NULL; - d_data->rubberBand = rubberBand; - d_data->enabled = false; - d_data->resizeMode = Stretch; - d_data->trackerMode = AlwaysOff; - d_data->isActive = false; - d_data->trackerPosition = QPoint(-1, -1); - d_data->mouseTracking = false; - - d_data->stateMachine = NULL; - setSelectionFlags(selectionFlags); - - if ( parent ) { -#if QT_VERSION >= 0x040000 + + if ( parent ) + { if ( parent->focusPolicy() == Qt::NoFocus ) - parent->setFocusPolicy(Qt::WheelFocus); -#else - if ( parent->focusPolicy() == QWidget::NoFocus ) - parent->setFocusPolicy(QWidget::WheelFocus); -#endif + parent->setFocusPolicy( Qt::WheelFocus ); + d_data->openGL = parent->inherits( "QGLWidget" ); d_data->trackerFont = parent->font(); d_data->mouseTracking = parent->hasMouseTracking(); - setEnabled(true); + + setEnabled( true ); } - setTrackerMode(trackerMode); + + setTrackerMode( trackerMode ); } /*! - Set a state machine and delete the previous one + Set a state machine and delete the previous one + + \param stateMachine State machine + \sa stateMachine() */ -void QwtPicker::setStateMachine(QwtPickerMachine *stateMachine) +void QwtPicker::setStateMachine( QwtPickerMachine *stateMachine ) { - if ( d_data->stateMachine != stateMachine ) { + if ( d_data->stateMachine != stateMachine ) + { reset(); delete d_data->stateMachine; @@ -317,39 +253,21 @@ void QwtPicker::setStateMachine(QwtPickerMachine *stateMachine) } /*! - Create a state machine depending on the selection flags. - - - PointSelection | ClickSelection\n - QwtPickerClickPointMachine() - - PointSelection | DragSelection\n - QwtPickerDragPointMachine() - - RectSelection | ClickSelection\n - QwtPickerClickRectMachine() - - RectSelection | DragSelection\n - QwtPickerDragRectMachine() - - PolygonSelection\n - QwtPickerPolygonMachine() - - \sa setSelectionFlags() + \return Assigned state machine + \sa setStateMachine() */ -QwtPickerMachine *QwtPicker::stateMachine(int flags) const +QwtPickerMachine *QwtPicker::stateMachine() { - if ( flags & PointSelection ) { - if ( flags & ClickSelection ) - return new QwtPickerClickPointMachine; - else - return new QwtPickerDragPointMachine; - } - if ( flags & RectSelection ) { - if ( flags & ClickSelection ) - return new QwtPickerClickRectMachine; - else - return new QwtPickerDragRectMachine; - } - if ( flags & PolygonSelection ) { - return new QwtPickerPolygonMachine(); - } - return NULL; + return d_data->stateMachine; +} + +/*! + \return Assigned state machine + \sa setStateMachine() +*/ +const QwtPickerMachine *QwtPicker::stateMachine() const +{ + return d_data->stateMachine; } //! Return the parent widget, where the selection happens @@ -357,7 +275,7 @@ QWidget *QwtPicker::parentWidget() { QObject *obj = parent(); if ( obj && obj->isWidgetType() ) - return (QWidget *)obj; + return static_cast<QWidget *>( obj ); return NULL; } @@ -367,51 +285,26 @@ const QWidget *QwtPicker::parentWidget() const { QObject *obj = parent(); if ( obj && obj->isWidgetType() ) - return (QWidget *)obj; + return static_cast< const QWidget *>( obj ); return NULL; } /*! - Set the selection flags - - \param flags Or'd value of SelectionType, RectSelectionType and - SelectionMode. The default value is NoSelection. - - \sa selectionFlags(), SelectionType, RectSelectionType, SelectionMode -*/ - -void QwtPicker::setSelectionFlags(int flags) -{ - d_data->selectionFlags = flags; - setStateMachine(stateMachine(flags)); -} - -/*! - \return Selection flags, an Or'd value of SelectionType, RectSelectionType and - SelectionMode. - \sa setSelectionFlags(), SelectionType, RectSelectionType, SelectionMode -*/ -int QwtPicker::selectionFlags() const -{ - return d_data->selectionFlags; -} - -/*! - Set the rubberband style + Set the rubber band style - \param rubberBand Rubberband style + \param rubberBand Rubber band style The default value is NoRubberBand. \sa rubberBand(), RubberBand, setRubberBandPen() */ -void QwtPicker::setRubberBand(RubberBand rubberBand) +void QwtPicker::setRubberBand( RubberBand rubberBand ) { d_data->rubberBand = rubberBand; } /*! - \return Rubberband style + \return Rubber band style \sa setRubberBand(), RubberBand, rubberBandPen() */ QwtPicker::RubberBand QwtPicker::rubberBand() const @@ -435,11 +328,12 @@ QwtPicker::RubberBand QwtPicker::rubberBand() const \sa trackerMode(), DisplayMode */ -void QwtPicker::setTrackerMode(DisplayMode mode) +void QwtPicker::setTrackerMode( DisplayMode mode ) { - if ( d_data->trackerMode != mode ) { + if ( d_data->trackerMode != mode ) + { d_data->trackerMode = mode; - setMouseTracking(d_data->trackerMode == AlwaysOn); + setMouseTracking( d_data->trackerMode == AlwaysOn ); } } @@ -466,7 +360,7 @@ QwtPicker::DisplayMode QwtPicker::trackerMode() const \param mode Resize mode \sa resizeMode(), ResizeMode */ -void QwtPicker::setResizeMode(ResizeMode mode) +void QwtPicker::setResizeMode( ResizeMode mode ) { d_data->resizeMode = mode; } @@ -490,17 +384,19 @@ QwtPicker::ResizeMode QwtPicker::resizeMode() const \param enabled true or false \sa isEnabled(), eventFilter() */ -void QwtPicker::setEnabled(bool enabled) +void QwtPicker::setEnabled( bool enabled ) { - if ( d_data->enabled != enabled ) { + if ( d_data->enabled != enabled ) + { d_data->enabled = enabled; QWidget *w = parentWidget(); - if ( w ) { + if ( w ) + { if ( enabled ) - w->installEventFilter(this); + w->installEventFilter( this ); else - w->removeEventFilter(this); + w->removeEventFilter( this ); } updateDisplay(); @@ -509,7 +405,7 @@ void QwtPicker::setEnabled(bool enabled) /*! \return true when enabled, false otherwise - \sa setEnabled, eventFilter() + \sa setEnabled(), eventFilter() */ bool QwtPicker::isEnabled() const @@ -523,9 +419,10 @@ bool QwtPicker::isEnabled() const \param font Tracker font \sa trackerFont(), setTrackerMode(), setTrackerPen() */ -void QwtPicker::setTrackerFont(const QFont &font) +void QwtPicker::setTrackerFont( const QFont &font ) { - if ( font != d_data->trackerFont ) { + if ( font != d_data->trackerFont ) + { d_data->trackerFont = font; updateDisplay(); } @@ -547,9 +444,10 @@ QFont QwtPicker::trackerFont() const \param pen Tracker pen \sa trackerPen(), setTrackerMode(), setTrackerFont() */ -void QwtPicker::setTrackerPen(const QPen &pen) +void QwtPicker::setTrackerPen( const QPen &pen ) { - if ( pen != d_data->trackerPen ) { + if ( pen != d_data->trackerPen ) + { d_data->trackerPen = pen; updateDisplay(); } @@ -567,19 +465,20 @@ QPen QwtPicker::trackerPen() const /*! Set the pen for the rubberband - \param pen Rubberband pen + \param pen Rubber band pen \sa rubberBandPen(), setRubberBand() */ -void QwtPicker::setRubberBandPen(const QPen &pen) +void QwtPicker::setRubberBandPen( const QPen &pen ) { - if ( pen != d_data->rubberBandPen ) { + if ( pen != d_data->rubberBandPen ) + { d_data->rubberBandPen = pen; updateDisplay(); } } /*! - \return Rubberband pen + \return Rubber band pen \sa setRubberBandPen(), rubberBand() */ QPen QwtPicker::rubberBandPen() const @@ -600,106 +499,227 @@ QPen QwtPicker::rubberBandPen() const \return Converted position as string */ -QwtText QwtPicker::trackerText(const QPoint &pos) const +QwtText QwtPicker::trackerText( const QPoint &pos ) const { QString label; - switch(rubberBand()) { - case HLineRubberBand: - label.sprintf("%d", pos.y()); - break; - case VLineRubberBand: - label.sprintf("%d", pos.x()); - break; - default: - label.sprintf("%d, %d", pos.x(), pos.y()); + switch ( rubberBand() ) + { + case HLineRubberBand: + label.sprintf( "%d", pos.y() ); + break; + case VLineRubberBand: + label.sprintf( "%d", pos.x() ); + break; + default: + label.sprintf( "%d, %d", pos.x(), pos.y() ); } return label; } /*! - Draw a rubberband , depending on rubberBand() and selectionFlags() - - \param painter Painter, initialized with clip rect + Calculate the mask for the rubber band overlay - \sa rubberBand(), RubberBand, selectionFlags() -*/ - -void QwtPicker::drawRubberBand(QPainter *painter) const + \return Region for the mask + \sa QWidget::setMask() + */ +QRegion QwtPicker::rubberBandMask() const { + QRegion mask; + if ( !isActive() || rubberBand() == NoRubberBand || - rubberBandPen().style() == Qt::NoPen ) { - return; + rubberBandPen().style() == Qt::NoPen ) + { + return mask; } - const QRect &pRect = pickRect(); - const QwtPolygon &pa = d_data->selection; + const QPolygon pa = adjustedPoints( d_data->pickedPoints ); - if ( selectionFlags() & PointSelection ) { - if ( pa.count() < 1 ) - return; + QwtPickerMachine::SelectionType selectionType = + QwtPickerMachine::NoSelection; - const QPoint pos = pa[0]; + if ( d_data->stateMachine ) + selectionType = d_data->stateMachine->selectionType(); - switch(rubberBand()) { - case VLineRubberBand: - QwtPainter::drawLine(painter, pos.x(), - pRect.top(), pos.x(), pRect.bottom()); + switch ( selectionType ) + { + case QwtPickerMachine::NoSelection: + case QwtPickerMachine::PointSelection: + { + if ( pa.count() < 1 ) + return mask; + + const QPoint pos = pa[0]; + const int pw = rubberBandPen().width(); + + const QRect pRect = pickArea().boundingRect().toRect(); + switch ( rubberBand() ) + { + case VLineRubberBand: + { + mask += qwtMaskRegion( QLine( pos.x(), pRect.top(), + pos.x(), pRect.bottom() ), pw ); + break; + } + case HLineRubberBand: + { + mask += qwtMaskRegion( QLine( pRect.left(), pos.y(), + pRect.right(), pos.y() ), pw ); + break; + } + case CrossRubberBand: + { + mask += qwtMaskRegion( QLine( pos.x(), pRect.top(), + pos.x(), pRect.bottom() ), pw ); + mask += qwtMaskRegion( QLine( pRect.left(), pos.y(), + pRect.right(), pos.y() ), pw ); + break; + } + default: + break; + } break; + } + case QwtPickerMachine::RectSelection: + { + if ( pa.count() < 2 ) + return mask; - case HLineRubberBand: - QwtPainter::drawLine(painter, pRect.left(), - pos.y(), pRect.right(), pos.y()); + const int pw = rubberBandPen().width(); + + switch ( rubberBand() ) + { + case RectRubberBand: + { + const QRect r = QRect( pa.first(), pa.last() ); + mask = qwtMaskRegion( r.normalized(), pw ); + break; + } + case EllipseRubberBand: + { + const QRect r = QRect( pa.first(), pa.last() ); + mask += r.adjusted( -pw, -pw, pw, pw ); + break; + } + default: + break; + } break; + } + case QwtPickerMachine::PolygonSelection: + { + const int pw = rubberBandPen().width(); + if ( pw <= 1 ) + { + // because of the join style we better + // return a mask for a pen width <= 1 only - case CrossRubberBand: - QwtPainter::drawLine(painter, pos.x(), - pRect.top(), pos.x(), pRect.bottom()); - QwtPainter::drawLine(painter, pRect.left(), - pos.y(), pRect.right(), pos.y()); + const int off = 2 * pw; + const QRect r = pa.boundingRect(); + mask += r.adjusted( -off, -off, off, off ); + } break; + } default: break; - } } - else if ( selectionFlags() & RectSelection ) { - if ( pa.count() < 2 ) - return; - - QPoint p1 = pa[0]; - QPoint p2 = pa[int(pa.count() - 1)]; - - if ( selectionFlags() & CenterToCorner ) { - p1.setX(p1.x() - (p2.x() - p1.x())); - p1.setY(p1.y() - (p2.y() - p1.y())); - } else if ( selectionFlags() & CenterToRadius ) { - const int radius = qwtMax(qwtAbs(p2.x() - p1.x()), - qwtAbs(p2.y() - p1.y())); - p2.setX(p1.x() + radius); - p2.setY(p1.y() + radius); - p1.setX(p1.x() - radius); - p1.setY(p1.y() - radius); + return mask; +} + +/*! + Draw a rubber band, depending on rubberBand() + + \param painter Painter, initialized with a clip region + + \sa rubberBand(), RubberBand +*/ + +void QwtPicker::drawRubberBand( QPainter *painter ) const +{ + if ( !isActive() || rubberBand() == NoRubberBand || + rubberBandPen().style() == Qt::NoPen ) + { + return; + } + + const QPolygon pa = adjustedPoints( d_data->pickedPoints ); + + QwtPickerMachine::SelectionType selectionType = + QwtPickerMachine::NoSelection; + + if ( d_data->stateMachine ) + selectionType = d_data->stateMachine->selectionType(); + + switch ( selectionType ) + { + case QwtPickerMachine::NoSelection: + case QwtPickerMachine::PointSelection: + { + if ( pa.count() < 1 ) + return; + + const QPoint pos = pa[0]; + + const QRect pRect = pickArea().boundingRect().toRect(); + switch ( rubberBand() ) + { + case VLineRubberBand: + { + QwtPainter::drawLine( painter, pos.x(), + pRect.top(), pos.x(), pRect.bottom() ); + break; + } + case HLineRubberBand: + { + QwtPainter::drawLine( painter, pRect.left(), + pos.y(), pRect.right(), pos.y() ); + break; + } + case CrossRubberBand: + { + QwtPainter::drawLine( painter, pos.x(), + pRect.top(), pos.x(), pRect.bottom() ); + QwtPainter::drawLine( painter, pRect.left(), + pos.y(), pRect.right(), pos.y() ); + break; + } + default: + break; + } + break; } + case QwtPickerMachine::RectSelection: + { + if ( pa.count() < 2 ) + return; -#if QT_VERSION < 0x040000 - const QRect rect = QRect(p1, p2).normalize(); -#else - const QRect rect = QRect(p1, p2).normalized(); -#endif - switch(rubberBand()) { - case EllipseRubberBand: - QwtPainter::drawEllipse(painter, rect); + const QRect rect = QRect( pa.first(), pa.last() ).normalized(); + switch ( rubberBand() ) + { + case EllipseRubberBand: + { + QwtPainter::drawEllipse( painter, rect ); + break; + } + case RectRubberBand: + { + QwtPainter::drawRect( painter, rect ); + break; + } + default: + break; + } break; - case RectRubberBand: - QwtPainter::drawRect(painter, rect); + } + case QwtPickerMachine::PolygonSelection: + { + if ( rubberBand() == PolygonRubberBand ) + painter->drawPolyline( pa ); break; + } default: break; - } - } else if ( selectionFlags() & PolygonSelection ) { - if ( rubberBand() == PolygonRubberBand ) - painter->drawPolyline(pa); } } @@ -710,63 +730,114 @@ void QwtPicker::drawRubberBand(QPainter *painter) const \sa trackerRect(), trackerText() */ -void QwtPicker::drawTracker(QPainter *painter) const -{ - const QRect textRect = trackerRect(painter->font()); - if ( !textRect.isEmpty() ) { - QwtText label = trackerText(d_data->trackerPosition); - if ( !label.isEmpty() ) { - painter->save(); - -#if defined(Q_WS_MAC) - // Antialiased fonts are broken on the Mac. -#if QT_VERSION >= 0x040000 - painter->setRenderHint(QPainter::TextAntialiasing, false); -#else - QFont fnt = label.usedFont(painter->font()); - fnt.setStyleStrategy(QFont::NoAntialias); - label.setFont(fnt); -#endif -#endif - label.draw(painter, textRect); - - painter->restore(); - } +void QwtPicker::drawTracker( QPainter *painter ) const +{ + const QRect textRect = trackerRect( painter->font() ); + if ( !textRect.isEmpty() ) + { + const QwtText label = trackerText( d_data->trackerPosition ); + if ( !label.isEmpty() ) + label.draw( painter, textRect ); } } +/*! + \brief Map the pickedPoints() into a selection() + + adjustedPoints() maps the points, that have been collected on + the parentWidget() into a selection(). The default implementation + simply returns the points unmodified. + + The reason, why a selection() differs from the picked points + depends on the application requirements. F.e. : + + - A rectangular selection might need to have a specific aspect ratio only.\n + - A selection could accept non intersecting polygons only.\n + - ...\n + + The example below is for a rectangular selection, where the first + point is the center of the selected rectangle. + \par Example + \verbatim QPolygon MyPicker::adjustedPoints(const QPolygon &points) const +{ + QPolygon adjusted; + if ( points.size() == 2 ) + { + const int width = qAbs(points[1].x() - points[0].x()); + const int height = qAbs(points[1].y() - points[0].y()); + + QRect rect(0, 0, 2 * width, 2 * height); + rect.moveCenter(points[0]); + + adjusted += rect.topLeft(); + adjusted += rect.bottomRight(); + } + return adjusted; +}\endverbatim\n + + \param points Selected points + \return Selected points unmodified +*/ +QPolygon QwtPicker::adjustedPoints( const QPolygon &points ) const +{ + return points; +} + +/*! + \return Selected points + \sa pickedPoints(), adjustedPoints() +*/ +QPolygon QwtPicker::selection() const +{ + return adjustedPoints( d_data->pickedPoints ); +} + +//! \return Current position of the tracker QPoint QwtPicker::trackerPosition() const { return d_data->trackerPosition; } -QRect QwtPicker::trackerRect(const QFont &font) const +/*! + Calculate the bounding rectangle for the tracker text + from the current position of the tracker + + \param font Font of the tracker text + \return Bounding rectangle of the tracker text + + \sa trackerPosition() +*/ +QRect QwtPicker::trackerRect( const QFont &font ) const { if ( trackerMode() == AlwaysOff || - (trackerMode() == ActiveOnly && !isActive() ) ) { + ( trackerMode() == ActiveOnly && !isActive() ) ) + { return QRect(); } if ( d_data->trackerPosition.x() < 0 || d_data->trackerPosition.y() < 0 ) return QRect(); - QwtText text = trackerText(d_data->trackerPosition); + QwtText text = trackerText( d_data->trackerPosition ); if ( text.isEmpty() ) return QRect(); - QRect textRect(QPoint(0, 0), text.textSize(font)); + const QSizeF textSize = text.textSize( font ); + QRect textRect( 0, 0, qCeil( textSize.width() ), qCeil( textSize.height() ) ); const QPoint &pos = d_data->trackerPosition; int alignment = 0; - if ( isActive() && d_data->selection.count() > 1 - && rubberBand() != NoRubberBand ) { + if ( isActive() && d_data->pickedPoints.count() > 1 + && rubberBand() != NoRubberBand ) + { const QPoint last = - d_data->selection[int(d_data->selection.count()) - 2]; + d_data->pickedPoints[int( d_data->pickedPoints.count() ) - 2]; - alignment |= (pos.x() >= last.x()) ? Qt::AlignRight : Qt::AlignLeft; - alignment |= (pos.y() > last.y()) ? Qt::AlignBottom : Qt::AlignTop; - } else + alignment |= ( pos.x() >= last.x() ) ? Qt::AlignRight : Qt::AlignLeft; + alignment |= ( pos.y() > last.y() ) ? Qt::AlignBottom : Qt::AlignTop; + } + else alignment = Qt::AlignTop | Qt::AlignRight; const int margin = 5; @@ -783,15 +854,17 @@ QRect QwtPicker::trackerRect(const QFont &font) const else if ( alignment & Qt::AlignTop ) y -= textRect.height() + margin; - textRect.moveTopLeft(QPoint(x, y)); + textRect.moveTopLeft( QPoint( x, y ) ); - int right = qwtMin(textRect.right(), pickRect().right() - margin); - int bottom = qwtMin(textRect.bottom(), pickRect().bottom() - margin); - textRect.moveBottomRight(QPoint(right, bottom)); + const QRect pickRect = pickArea().boundingRect().toRect(); - int left = qwtMax(textRect.left(), pickRect().left() + margin); - int top = qwtMax(textRect.top(), pickRect().top() + margin); - textRect.moveTopLeft(QPoint(left, top)); + int right = qMin( textRect.right(), pickRect.right() - margin ); + int bottom = qMin( textRect.bottom(), pickRect.bottom() - margin ); + textRect.moveBottomRight( QPoint( right, bottom ) ); + + int left = qMax( textRect.left(), pickRect.left() + margin ); + int top = qMax( textRect.top(), pickRect.top() + margin ); + textRect.moveTopLeft( QPoint( left, top ) ); return textRect; } @@ -799,57 +872,83 @@ QRect QwtPicker::trackerRect(const QFont &font) const /*! \brief Event filter - When isEnabled() == true all events of the observed widget are filtered. + When isEnabled() is true all events of the observed widget are filtered. Mouse and keyboard events are translated into widgetMouse- and widgetKey- and widgetWheel-events. Paint and Resize events are handled to keep - rubberband and tracker up to date. + rubber band and tracker up to date. + + \param object Object to be filtered + \param event Event - \sa event(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + \return Always false. + + \sa widgetEnterEvent(), widgetLeaveEvent(), + widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent(), + QObject::installEventFilter(), QObject::event() */ -bool QwtPicker::eventFilter(QObject *o, QEvent *e) +bool QwtPicker::eventFilter( QObject *object, QEvent *event ) { - if ( o && o == parentWidget() ) { - switch(e->type()) { - case QEvent::Resize: { - const QResizeEvent *re = (QResizeEvent *)e; - if ( d_data->resizeMode == Stretch ) - stretchSelection(re->oldSize(), re->size()); - - if ( d_data->rubberBandWidget ) - d_data->rubberBandWidget->resize(re->size()); + if ( object && object == parentWidget() ) + { + switch ( event->type() ) + { + case QEvent::Resize: + { + const QResizeEvent *re = static_cast<QResizeEvent *>( event ); + if ( d_data->resizeMode == Stretch ) + stretchSelection( re->oldSize(), re->size() ); - if ( d_data->trackerWidget ) - d_data->trackerWidget->resize(re->size()); - break; - } - case QEvent::Leave: - widgetLeaveEvent(e); - break; - case QEvent::MouseButtonPress: - widgetMousePressEvent((QMouseEvent *)e); - break; - case QEvent::MouseButtonRelease: - widgetMouseReleaseEvent((QMouseEvent *)e); - break; - case QEvent::MouseButtonDblClick: - widgetMouseDoubleClickEvent((QMouseEvent *)e); - break; - case QEvent::MouseMove: - widgetMouseMoveEvent((QMouseEvent *)e); - break; - case QEvent::KeyPress: - widgetKeyPressEvent((QKeyEvent *)e); - break; - case QEvent::KeyRelease: - widgetKeyReleaseEvent((QKeyEvent *)e); - break; - case QEvent::Wheel: - widgetWheelEvent((QWheelEvent *)e); - break; - default: - break; + break; + } + case QEvent::Enter: + { + widgetEnterEvent( event ); + break; + } + case QEvent::Leave: + { + widgetLeaveEvent( event ); + break; + } + case QEvent::MouseButtonPress: + { + widgetMousePressEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::MouseButtonRelease: + { + widgetMouseReleaseEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::MouseButtonDblClick: + { + widgetMouseDoubleClickEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::MouseMove: + { + widgetMouseMoveEvent( static_cast<QMouseEvent *>( event ) ); + break; + } + case QEvent::KeyPress: + { + widgetKeyPressEvent( static_cast<QKeyEvent *>( event ) ); + break; + } + case QEvent::KeyRelease: + { + widgetKeyReleaseEvent( static_cast<QKeyEvent *>( event ) ); + break; + } + case QEvent::Wheel: + { + widgetWheelEvent( static_cast<QWheelEvent *>( event ) ); + break; + } + default: + break; } } return false; @@ -858,81 +957,97 @@ bool QwtPicker::eventFilter(QObject *o, QEvent *e) /*! Handle a mouse press event for the observed widget. - Begin and/or end a selection depending on the selection flags. + \param mouseEvent Mouse event - \sa QwtPicker, selectionFlags() \sa eventFilter(), widgetMouseReleaseEvent(), widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() */ -void QwtPicker::widgetMousePressEvent(QMouseEvent *e) +void QwtPicker::widgetMousePressEvent( QMouseEvent *mouseEvent ) { - transition(e); + transition( mouseEvent ); } /*! Handle a mouse move event for the observed widget. - Move the last point of the selection in case of isActive() == true + \param mouseEvent Mouse event \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseDoubleClickEvent(), widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() */ -void QwtPicker::widgetMouseMoveEvent(QMouseEvent *e) +void QwtPicker::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) { - if ( pickRect().contains(e->pos()) ) - d_data->trackerPosition = e->pos(); + if ( pickArea().contains( mouseEvent->pos() ) ) + d_data->trackerPosition = mouseEvent->pos(); else - d_data->trackerPosition = QPoint(-1, -1); + d_data->trackerPosition = QPoint( -1, -1 ); if ( !isActive() ) updateDisplay(); - transition(e); + transition( mouseEvent ); +} + +/*! + Handle a enter event for the observed widget. + + \param event Qt event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetEnterEvent( QEvent *event ) +{ + transition( event ); } /*! Handle a leave event for the observed widget. + \param event Qt event + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseDoubleClickEvent(), widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() */ -void QwtPicker::widgetLeaveEvent(QEvent *) +void QwtPicker::widgetLeaveEvent( QEvent *event ) { - d_data->trackerPosition = QPoint(-1, -1); + transition( event ); + + d_data->trackerPosition = QPoint( -1, -1 ); if ( !isActive() ) updateDisplay(); } /*! - Handle a mouse relase event for the observed widget. + Handle a mouse release event for the observed widget. - End a selection depending on the selection flags. + \param mouseEvent Mouse event - \sa QwtPicker, selectionFlags() \sa eventFilter(), widgetMousePressEvent(), widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() */ -void QwtPicker::widgetMouseReleaseEvent(QMouseEvent *e) +void QwtPicker::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) { - transition(e); + transition( mouseEvent ); } /*! Handle mouse double click event for the observed widget. - Empty implementation, does nothing. + \param mouseEvent Mouse event \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() */ -void QwtPicker::widgetMouseDoubleClickEvent(QMouseEvent *me) +void QwtPicker::widgetMouseDoubleClickEvent( QMouseEvent *mouseEvent ) { - transition(me); + transition( mouseEvent ); } @@ -941,20 +1056,22 @@ void QwtPicker::widgetMouseDoubleClickEvent(QMouseEvent *me) Move the last point of the selection in case of isActive() == true + \param wheelEvent Wheel event + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() */ -void QwtPicker::widgetWheelEvent(QWheelEvent *e) +void QwtPicker::widgetWheelEvent( QWheelEvent *wheelEvent ) { - if ( pickRect().contains(e->pos()) ) - d_data->trackerPosition = e->pos(); + if ( pickArea().contains( wheelEvent->pos() ) ) + d_data->trackerPosition = wheelEvent->pos(); else - d_data->trackerPosition = QPoint(-1, -1); + d_data->trackerPosition = QPoint( -1, -1 ); updateDisplay(); - transition(e); + transition( wheelEvent ); } /*! @@ -964,47 +1081,51 @@ void QwtPicker::widgetWheelEvent(QWheelEvent *e) move the cursor, the abort key aborts a selection. All other keys are handled by the current state machine. - \sa QwtPicker, selectionFlags() + \param keyEvent Key event + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyReleaseEvent(), stateMachine(), QwtEventPattern::KeyPatternCode */ -void QwtPicker::widgetKeyPressEvent(QKeyEvent *ke) +void QwtPicker::widgetKeyPressEvent( QKeyEvent *keyEvent ) { int dx = 0; int dy = 0; int offset = 1; - if ( ke->isAutoRepeat() ) + if ( keyEvent->isAutoRepeat() ) offset = 5; - if ( keyMatch(KeyLeft, ke) ) + if ( keyMatch( KeyLeft, keyEvent ) ) dx = -offset; - else if ( keyMatch(KeyRight, ke) ) + else if ( keyMatch( KeyRight, keyEvent ) ) dx = offset; - else if ( keyMatch(KeyUp, ke) ) + else if ( keyMatch( KeyUp, keyEvent ) ) dy = -offset; - else if ( keyMatch(KeyDown, ke) ) + else if ( keyMatch( KeyDown, keyEvent ) ) dy = offset; - else if ( keyMatch(KeyAbort, ke) ) { + else if ( keyMatch( KeyAbort, keyEvent ) ) + { reset(); - } else - transition(ke); + } + else + transition( keyEvent ); - if ( dx != 0 || dy != 0 ) { - const QRect rect = pickRect(); - const QPoint pos = parentWidget()->mapFromGlobal(QCursor::pos()); + if ( dx != 0 || dy != 0 ) + { + const QRect rect = pickArea().boundingRect().toRect(); + const QPoint pos = parentWidget()->mapFromGlobal( QCursor::pos() ); int x = pos.x() + dx; - x = qwtMax(rect.left(), x); - x = qwtMin(rect.right(), x); + x = qMax( rect.left(), x ); + x = qMin( rect.right(), x ); int y = pos.y() + dy; - y = qwtMax(rect.top(), y); - y = qwtMin(rect.bottom(), y); + y = qMax( rect.top(), y ); + y = qMin( rect.bottom(), y ); - QCursor::setPos(parentWidget()->mapToGlobal(QPoint(x, y))); + QCursor::setPos( parentWidget()->mapToGlobal( QPoint( x, y ) ) ); } } @@ -1013,62 +1134,78 @@ void QwtPicker::widgetKeyPressEvent(QKeyEvent *ke) Passes the event to the state machine. + \param keyEvent Key event + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyPressEvent(), stateMachine() */ -void QwtPicker::widgetKeyReleaseEvent(QKeyEvent *ke) +void QwtPicker::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) { - transition(ke); + transition( keyEvent ); } /*! Passes an event to the state machine and executes the resulting commands. Append and Move commands use the current position - of the cursor (QCursor::pos()). + of the cursor ( QCursor::pos() ). - \param e Event + \param event Event */ -void QwtPicker::transition(const QEvent *e) +void QwtPicker::transition( const QEvent *event ) { if ( !d_data->stateMachine ) return; - QwtPickerMachine::CommandList commandList = - d_data->stateMachine->transition(*this, e); + const QList<QwtPickerMachine::Command> commandList = + d_data->stateMachine->transition( *this, event ); QPoint pos; - switch(e->type()) { - case QEvent::MouseButtonDblClick: - case QEvent::MouseButtonPress: - case QEvent::MouseButtonRelease: - case QEvent::MouseMove: { - const QMouseEvent *me = (QMouseEvent *)e; - pos = me->pos(); - break; - } - default: - pos = parentWidget()->mapFromGlobal(QCursor::pos()); - } - - for ( uint i = 0; i < (uint)commandList.count(); i++ ) { - switch(commandList[i]) { - case QwtPickerMachine::Begin: { - begin(); - break; - } - case QwtPickerMachine::Append: { - append(pos); - break; - } - case QwtPickerMachine::Move: { - move(pos); - break; - } - case QwtPickerMachine::End: { - end(); + switch ( event->type() ) + { + case QEvent::MouseButtonDblClick: + case QEvent::MouseButtonPress: + case QEvent::MouseButtonRelease: + case QEvent::MouseMove: + { + const QMouseEvent *me = + static_cast< const QMouseEvent * >( event ); + pos = me->pos(); break; } + default: + pos = parentWidget()->mapFromGlobal( QCursor::pos() ); + } + + for ( int i = 0; i < commandList.count(); i++ ) + { + switch ( commandList[i] ) + { + case QwtPickerMachine::Begin: + { + begin(); + break; + } + case QwtPickerMachine::Append: + { + append( pos ); + break; + } + case QwtPickerMachine::Move: + { + move( pos ); + break; + } + case QwtPickerMachine::Remove: + { + remove(); + break; + } + case QwtPickerMachine::End: + { + end(); + break; + } } } } @@ -1076,93 +1213,99 @@ void QwtPicker::transition(const QEvent *e) /*! Open a selection setting the state to active - \sa isActive, end(), append(), move() + \sa isActive(), end(), append(), move() */ void QwtPicker::begin() { if ( d_data->isActive ) return; - d_data->selection.resize(0); + d_data->pickedPoints.resize( 0 ); d_data->isActive = true; + Q_EMIT activated( true ); - if ( trackerMode() != AlwaysOff ) { - if ( d_data->trackerPosition.x() < 0 || d_data->trackerPosition.y() < 0 ) { + if ( trackerMode() != AlwaysOff ) + { + if ( d_data->trackerPosition.x() < 0 || d_data->trackerPosition.y() < 0 ) + { QWidget *w = parentWidget(); if ( w ) - d_data->trackerPosition = w->mapFromGlobal(QCursor::pos()); + d_data->trackerPosition = w->mapFromGlobal( QCursor::pos() ); } } updateDisplay(); - setMouseTracking(true); + setMouseTracking( true ); } /*! \brief Close a selection setting the state to inactive. - The selection is validated and maybe fixed by QwtPicker::accept(). + The selection is validated and maybe fixed by accept(). \param ok If true, complete the selection and emit a selected signal otherwise discard the selection. \return true if the selection is accepted, false otherwise - \sa isActive, begin(), append(), move(), selected(), accept() + \sa isActive(), begin(), append(), move(), selected(), accept() */ -bool QwtPicker::end(bool ok) +bool QwtPicker::end( bool ok ) { - if ( d_data->isActive ) { - setMouseTracking(false); + if ( d_data->isActive ) + { + setMouseTracking( false ); d_data->isActive = false; + Q_EMIT activated( false ); if ( trackerMode() == ActiveOnly ) - d_data->trackerPosition = QPoint(-1, -1); + d_data->trackerPosition = QPoint( -1, -1 ); if ( ok ) - ok = accept(d_data->selection); + ok = accept( d_data->pickedPoints ); if ( ok ) - emit selected(d_data->selection); + Q_EMIT selected( d_data->pickedPoints ); else - d_data->selection.resize(0); + d_data->pickedPoints.resize( 0 ); updateDisplay(); - } else + } + else ok = false; return ok; } /*! - Reset the state machine and terminate (end(false)) the selection + Reset the state machine and terminate ( end(false) ) the selection */ void QwtPicker::reset() { if ( d_data->stateMachine ) d_data->stateMachine->reset(); - if (isActive()) - end(false); + if ( isActive() ) + end( false ); } /*! - Append a point to the selection and update rubberband and tracker. + Append a point to the selection and update rubber band and tracker. The appended() signal is emitted. \param pos Additional point - \sa isActive, begin(), end(), move(), appended() + \sa isActive(), begin(), end(), move(), appended() */ -void QwtPicker::append(const QPoint &pos) +void QwtPicker::append( const QPoint &pos ) { - if ( d_data->isActive ) { - const int idx = d_data->selection.count(); - d_data->selection.resize(idx + 1); - d_data->selection[idx] = pos; + if ( d_data->isActive ) + { + const int idx = d_data->pickedPoints.count(); + d_data->pickedPoints.resize( idx + 1 ); + d_data->pickedPoints[idx] = pos; updateDisplay(); - - emit appended(pos); + Q_EMIT appended( pos ); } } @@ -1171,27 +1314,61 @@ void QwtPicker::append(const QPoint &pos) The moved() signal is emitted. \param pos New position - \sa isActive, begin(), end(), append() - + \sa isActive(), begin(), end(), append() */ -void QwtPicker::move(const QPoint &pos) +void QwtPicker::move( const QPoint &pos ) { - if ( d_data->isActive ) { - const int idx = d_data->selection.count() - 1; - if ( idx >= 0 ) { - if ( d_data->selection[idx] != pos ) { - d_data->selection[idx] = pos; + if ( d_data->isActive ) + { + const int idx = d_data->pickedPoints.count() - 1; + if ( idx >= 0 ) + { + if ( d_data->pickedPoints[idx] != pos ) + { + d_data->pickedPoints[idx] = pos; updateDisplay(); - - emit moved(pos); + Q_EMIT moved( pos ); } } } } -bool QwtPicker::accept(QwtPolygon &) const +/*! + Remove the last point of the selection + The removed() signal is emitted. + + \sa isActive(), begin(), end(), append(), move() +*/ +void QwtPicker::remove() +{ + if ( d_data->isActive ) + { + const int idx = d_data->pickedPoints.count() - 1; + if ( idx > 0 ) + { + const int idx = d_data->pickedPoints.count(); + + const QPoint pos = d_data->pickedPoints[idx - 1]; + d_data->pickedPoints.resize( idx - 1 ); + + updateDisplay(); + Q_EMIT removed( pos ); + } + } +} + +/*! + \brief Validate and fix up the selection + + Accepts all selections unmodified + + \param selection Selection to validate and fix up + \return true, when accepted, false otherwise +*/ +bool QwtPicker::accept( QPolygon &selection ) const { + Q_UNUSED( selection ); return true; } @@ -1204,10 +1381,14 @@ bool QwtPicker::isActive() const return d_data->isActive; } -//! Return Selected points -const QwtPolygon &QwtPicker::selection() const +/*! + Return the points, that have been collected so far. The selection() + is calculated from the pickedPoints() in adjustedPoints(). + \return Picked points +*/ +const QPolygon &QwtPicker::pickedPoints() const { - return d_data->selection; + return d_data->pickedPoints; } /*! @@ -1219,25 +1400,27 @@ const QwtPolygon &QwtPicker::selection() const \sa ResizeMode, setResizeMode(), resizeMode() */ -void QwtPicker::stretchSelection(const QSize &oldSize, const QSize &newSize) +void QwtPicker::stretchSelection( const QSize &oldSize, const QSize &newSize ) { - if ( oldSize.isEmpty() ) { + if ( oldSize.isEmpty() ) + { // avoid division by zero. But scaling for small sizes also // doesn't make much sense, because of rounding losses. TODO ... return; } const double xRatio = - double(newSize.width()) / double(oldSize.width()); + double( newSize.width() ) / double( oldSize.width() ); const double yRatio = - double(newSize.height()) / double(oldSize.height()); + double( newSize.height() ) / double( oldSize.height() ); - for ( int i = 0; i < int(d_data->selection.count()); i++ ) { - QPoint &p = d_data->selection[i]; - p.setX(qRound(p.x() * xRatio)); - p.setY(qRound(p.y() * yRatio)); + for ( int i = 0; i < int( d_data->pickedPoints.count() ); i++ ) + { + QPoint &p = d_data->pickedPoints[i]; + p.setX( qRound( p.x() * xRatio ) ); + p.setY( qRound( p.y() * yRatio ) ); - emit changed(d_data->selection); + Q_EMIT changed( d_data->pickedPoints ); } } @@ -1254,98 +1437,141 @@ void QwtPicker::stretchSelection(const QSize &oldSize, const QSize &newSize) be restored. */ -void QwtPicker::setMouseTracking(bool enable) +void QwtPicker::setMouseTracking( bool enable ) { QWidget *widget = parentWidget(); if ( !widget ) return; - if ( enable ) { + if ( enable ) + { d_data->mouseTracking = widget->hasMouseTracking(); - widget->setMouseTracking(true); - } else { - widget->setMouseTracking(d_data->mouseTracking); + widget->setMouseTracking( true ); + } + else + { + widget->setMouseTracking( d_data->mouseTracking ); } } /*! Find the area of the observed widget, where selection might happen. - \return QFrame::contentsRect() if it is a QFrame, QWidget::rect() otherwise. + \return parentWidget()->contentsRect() */ -QRect QwtPicker::pickRect() const +QPainterPath QwtPicker::pickArea() const { - QRect rect; + QPainterPath path; const QWidget *widget = parentWidget(); - if ( !widget ) - return rect; - - if ( widget->inherits("QFrame") ) - rect = ((QFrame *)widget)->contentsRect(); - else - rect = widget->rect(); + if ( widget ) + path.addRect( widget->contentsRect() ); - return rect; + return path; } +//! Update the state of rubber band and tracker label void QwtPicker::updateDisplay() { QWidget *w = parentWidget(); bool showRubberband = false; bool showTracker = false; - if ( w && w->isVisible() && d_data->enabled ) { + + if ( w && w->isVisible() && d_data->enabled ) + { if ( rubberBand() != NoRubberBand && isActive() && - rubberBandPen().style() != Qt::NoPen ) { + rubberBandPen().style() != Qt::NoPen ) + { showRubberband = true; } if ( trackerMode() == AlwaysOn || - (trackerMode() == ActiveOnly && isActive() ) ) { - if ( trackerPen() != Qt::NoPen ) + ( trackerMode() == ActiveOnly && isActive() ) ) + { + if ( trackerPen() != Qt::NoPen + && !trackerRect( QFont() ).isEmpty() ) + { showTracker = true; + } } } -#if QT_VERSION < 0x040000 - QGuardedPtr<PickerWidget> &rw = d_data->rubberBandWidget; -#else - QPointer<PickerWidget> &rw = d_data->rubberBandWidget; -#endif - if ( showRubberband ) { - if ( rw.isNull() ) { - rw = new PickerWidget( this, w, PickerWidget::RubberBand); - rw->resize(w->size()); + QPointer< QwtPickerRubberband > &rw = d_data->rubberBandOverlay; + if ( showRubberband ) + { + if ( rw.isNull() ) + { + rw = new QwtPickerRubberband( this, w ); + rw->setObjectName( "PickerRubberBand" ); + rw->resize( w->size() ); } - rw->updateMask(); - rw->update(); // Needed, when the mask doesn't change - } else - delete rw; - -#if QT_VERSION < 0x040000 - QGuardedPtr<PickerWidget> &tw = d_data->trackerWidget; -#else - QPointer<PickerWidget> &tw = d_data->trackerWidget; -#endif - if ( showTracker ) { - if ( tw.isNull() ) { - tw = new PickerWidget( this, w, PickerWidget::Text); - tw->resize(w->size()); + + if ( d_data->rubberBand <= RectRubberBand ) + rw->setMaskMode( QwtWidgetOverlay::MaskHint ); + else + rw->setMaskMode( QwtWidgetOverlay::AlphaMask ); + + rw->updateOverlay(); + } + else + { + if ( d_data->openGL ) + { + // Qt 4.8 crashes for a delete + if ( !rw.isNull() ) + { + rw->hide(); + rw->deleteLater(); + rw = NULL; + } + } + else + { + delete rw; } - tw->updateMask(); - tw->update(); // Needed, when the mask doesn't change - } else - delete tw; + } + + QPointer< QwtPickerTracker > &tw = d_data->trackerOverlay; + if ( showTracker ) + { + if ( tw.isNull() ) + { + tw = new QwtPickerTracker( this, w ); + tw->setObjectName( "PickerTracker" ); + tw->resize( w->size() ); + } + tw->setFont( d_data->trackerFont ); + tw->updateOverlay(); + } + else + { + if ( d_data->openGL ) + { + // Qt 4.8 crashes for a delete + if ( !tw.isNull() ) + { + tw->hide(); + tw->deleteLater(); + tw = NULL; + } + } + else + { + delete tw; + } + } } -const QWidget *QwtPicker::rubberBandWidget() const +//! \return Overlay displaying the rubber band +const QwtWidgetOverlay *QwtPicker::rubberBandOverlay() const { - return d_data->rubberBandWidget; + return d_data->rubberBandOverlay; } -const QWidget *QwtPicker::trackerWidget() const +//! \return Overlay displaying the tracker text +const QwtWidgetOverlay *QwtPicker::trackerOverlay() const { - return d_data->trackerWidget; + return d_data->trackerOverlay; } diff --git a/libs/qwt/qwt_picker.h b/libs/qwt/qwt_picker.h index f3e6580bab..87d6805e9e 100644 --- a/libs/qwt/qwt_picker.h +++ b/libs/qwt/qwt_picker.h @@ -10,62 +10,77 @@ #ifndef QWT_PICKER #define QWT_PICKER 1 +#include "qwt_global.h" +#include "qwt_text.h" +#include "qwt_event_pattern.h" #include <qobject.h> #include <qpen.h> #include <qfont.h> #include <qrect.h> -#include "qwt_global.h" -#include "qwt_text.h" -#include "qwt_polygon.h" -#include "qwt_event_pattern.h" +#include <qpainterpath.h> class QWidget; class QMouseEvent; class QWheelEvent; class QKeyEvent; class QwtPickerMachine; +class QwtWidgetOverlay; /*! \brief QwtPicker provides selections on a widget - QwtPicker filters all mouse and keyboard events of a widget - and translates them into an array of selected points. Depending - on the QwtPicker::SelectionType the selection might be a single point, - a rectangle or a polygon. The selection process is supported by - optional rubberbands (rubberband selection) and position trackers. + QwtPicker filters all enter, leave, mouse and keyboard events of a widget + and translates them into an array of selected points. + + The way how the points are collected depends on type of state machine + that is connected to the picker. Qwt offers a couple of predefined + state machines for selecting: - QwtPicker is useful for widgets where the event handlers - can't be overloaded, like for components of composite widgets. - It offers alternative handlers for mouse and key events. + - Nothing\n + QwtPickerTrackerMachine + - Single points\n + QwtPickerClickPointMachine, QwtPickerDragPointMachine + - Rectangles\n + QwtPickerClickRectMachine, QwtPickerDragRectMachine + - Polygons\n + QwtPickerPolygonMachine + + While these state machines cover the most common ways to collect points + it is also possible to implement individual machines as well. + + QwtPicker translates the picked points into a selection using the + adjustedPoints() method. adjustedPoints() is intended to be reimplemented + to fix up the selection according to application specific requirements. + (F.e. when an application accepts rectangles of a fixed aspect ratio only.) + + Optionally QwtPicker support the process of collecting points by a + rubber band and tracker displaying a text for the current mouse + position. \par Example \verbatim #include <qwt_picker.h> +#include <qwt_picker_machine.h> QwtPicker *picker = new QwtPicker(widget); +picker->setStateMachine(new QwtPickerDragRectMachine); picker->setTrackerMode(QwtPicker::ActiveOnly); -connect(picker, SIGNAL(selected(const QwtPolygon &)), ...); - -// emit the position of clicks on widget -picker->setSelectionFlags(QwtPicker::PointSelection | QwtPicker::ClickSelection); - - ... - -// now select rectangles -picker->setSelectionFlags(QwtPicker::RectSelection | QwtPicker::DragSelection); picker->setRubberBand(QwtPicker::RectRubberBand); \endverbatim\n - The selection process uses the commands begin(), append(), move() and end(). - append() adds a new point to the selection, move() changes the position of - the latest point. + The state machine triggers the following commands: - The commands are initiated from a small state machine (QwtPickerMachine) - that translates mouse and key events. There are a couple of predefined - state machines for point, rect and polygon selections. The selectionFlags() - control which one should be used. It is possible to use other machines - by overloading stateMachine(). + - begin()\n + Activate/Initialize the selection. + - append()\n + Add a new point + - move() \n + Change the position of the last point. + - remove()\n + Remove the last point. + - end()\n + Terminate the selection and call accept to validate the picked points. The picker is active (isActive()), between begin() and end(). - In active state the rubberband is displayed, and the tracker is visible + In active state the rubber band is displayed, and the tracker is visible in case of trackerMode is ActiveOnly or AlwaysOn. The cursor can be moved using the arrow keys. All selections can be aborted @@ -73,7 +88,7 @@ picker->setRubberBand(QwtPicker::RectRubberBand); \endverbatim\n \warning In case of QWidget::NoFocus the focus policy of the observed widget is set to QWidget::WheelFocus and mouse tracking - will be manipulated for ClickSelection while the picker is active, + will be manipulated while the picker is active, or if trackerMode() is AlwayOn. */ @@ -81,214 +96,158 @@ class QWT_EXPORT QwtPicker: public QObject, public QwtEventPattern { Q_OBJECT - Q_ENUMS(RubberBand) - Q_ENUMS(DisplayMode) - Q_ENUMS(ResizeMode) + Q_ENUMS( RubberBand DisplayMode ResizeMode ) - Q_PROPERTY(int selectionFlags READ selectionFlags WRITE setSelectionFlags) - Q_PROPERTY(DisplayMode trackerMode READ trackerMode WRITE setTrackerMode) - Q_PROPERTY(QFont trackerFont READ trackerFont WRITE setTrackerFont) - Q_PROPERTY(RubberBand rubberBand READ rubberBand WRITE setRubberBand) - Q_PROPERTY(ResizeMode resizeMode READ resizeMode WRITE setResizeMode) - Q_PROPERTY(bool isEnabled READ isEnabled WRITE setEnabled) + Q_PROPERTY( bool isEnabled READ isEnabled WRITE setEnabled ) + Q_PROPERTY( ResizeMode resizeMode READ resizeMode WRITE setResizeMode ) - Q_PROPERTY(QPen trackerPen READ trackerPen WRITE setTrackerPen) - Q_PROPERTY(QPen rubberBandPen READ rubberBandPen WRITE setRubberBandPen) + Q_PROPERTY( DisplayMode trackerMode READ trackerMode WRITE setTrackerMode ) + Q_PROPERTY( QPen trackerPen READ trackerPen WRITE setTrackerPen ) + Q_PROPERTY( QFont trackerFont READ trackerFont WRITE setTrackerFont ) -public: - /*! - This enum type describes the type of a selection. It can be or'd - with QwtPicker::RectSelectionType and QwtPicker::SelectionMode - and passed to QwtPicker::setSelectionFlags() - - NoSelection\n - Selection is disabled. Note this is different to the disabled - state, as you might have a tracker. - - PointSelection\n - Select a single point. - - RectSelection\n - Select a rectangle. - - PolygonSelection\n - Select a polygon. - - The default value is NoSelection. - \sa QwtPicker::setSelectionFlags(), QwtPicker::selectionFlags() - */ - - enum SelectionType { - NoSelection = 0, - PointSelection = 1, - RectSelection = 2, - PolygonSelection = 4 - }; - - /*! - \brief Selection subtype for RectSelection - This enum type describes the type of rectangle selections. - It can be or'd with QwtPicker::RectSelectionType and - QwtPicker::SelectionMode and passed to QwtPicker::setSelectionFlags(). - - CornerToCorner\n - The first and the second selected point are the corners - of the rectangle. - - CenterToCorner\n - The first point is the center, the second a corner of the - rectangle. - - CenterToRadius\n - The first point is the center of a quadrat, calculated by the maximum - of the x- and y-distance. - - The default value is CornerToCorner. - \sa QwtPicker::setSelectionFlags(), QwtPicker::selectionFlags() - */ - enum RectSelectionType { - CornerToCorner = 64, - CenterToCorner = 128, - CenterToRadius = 256 - }; + Q_PROPERTY( RubberBand rubberBand READ rubberBand WRITE setRubberBand ) + Q_PROPERTY( QPen rubberBandPen READ rubberBandPen WRITE setRubberBandPen ) +public: /*! - Values of this enum type or'd together with a SelectionType value - identifies which state machine should be used for the selection. - - The default value is ClickSelection. - \sa stateMachine() - */ - enum SelectionMode { - ClickSelection = 1024, - DragSelection = 2048 - }; + Rubber band style - /*! - Rubberband style - - NoRubberBand\n - No rubberband. - - HLineRubberBand & PointSelection\n - A horizontal line. - - VLineRubberBand & PointSelection\n - A vertical line. - - CrossRubberBand & PointSelection\n - A horizontal and a vertical line. - - RectRubberBand & RectSelection\n - A rectangle. - - EllipseRubberBand & RectSelection\n - An ellipse. - - PolygonRubberBand &PolygonSelection\n - A polygon. - - UserRubberBand\n - Values >= UserRubberBand can be used to define additional - rubber bands. - - The default value is NoRubberBand. - \sa QwtPicker::setRubberBand(), QwtPicker::rubberBand() + The default value is QwtPicker::NoRubberBand. + \sa setRubberBand(), rubberBand() */ - enum RubberBand { + enum RubberBand + { + //! No rubberband. NoRubberBand = 0, - // Point + //! A horizontal line ( only for QwtPickerMachine::PointSelection ) HLineRubberBand, + + //! A vertical line ( only for QwtPickerMachine::PointSelection ) VLineRubberBand, + + //! A crosshair ( only for QwtPickerMachine::PointSelection ) CrossRubberBand, - // Rect + //! A rectangle ( only for QwtPickerMachine::RectSelection ) RectRubberBand, + + //! An ellipse ( only for QwtPickerMachine::RectSelection ) EllipseRubberBand, - // Polygon + //! A polygon ( only for QwtPickerMachine::PolygonSelection ) PolygonRubberBand, + /*! + Values >= UserRubberBand can be used to define additional + rubber bands. + */ UserRubberBand = 100 }; /*! - - AlwaysOff\n - Display never. - - AlwaysOn\n - Display always. - - ActiveOnly\n - Display only when the selection is active. - - \sa QwtPicker::setTrackerMode(), QwtPicker::trackerMode(), - QwtPicker::isActive() + \brief Display mode + \sa setTrackerMode(), trackerMode(), isActive() */ - enum DisplayMode { + enum DisplayMode + { + //! Display never AlwaysOff, + + //! Display always AlwaysOn, + + //! Display only when the selection is active ActiveOnly }; /*! Controls what to do with the selected points of an active selection when the observed widget is resized. - - Stretch\n - All points are scaled according to the new size, - - KeepSize\n - All points remain unchanged. - The default value is Stretch. - \sa QwtPicker::setResizeMode(), QwtPicker::resize() + The default value is QwtPicker::Stretch. + \sa setResizeMode() */ - enum ResizeMode { + enum ResizeMode + { + //! All points are scaled according to the new size, Stretch, + + //! All points remain unchanged. KeepSize }; - explicit QwtPicker(QWidget *parent); - explicit QwtPicker(int selectionFlags, RubberBand rubberBand, - DisplayMode trackerMode, QWidget *); + explicit QwtPicker( QWidget *parent ); + explicit QwtPicker( RubberBand rubberBand, + DisplayMode trackerMode, QWidget * ); virtual ~QwtPicker(); - virtual void setSelectionFlags(int); - int selectionFlags() const; + void setStateMachine( QwtPickerMachine * ); + const QwtPickerMachine *stateMachine() const; + QwtPickerMachine *stateMachine(); - virtual void setRubberBand(RubberBand); + void setRubberBand( RubberBand ); RubberBand rubberBand() const; - virtual void setTrackerMode(DisplayMode); + void setTrackerMode( DisplayMode ); DisplayMode trackerMode() const; - virtual void setResizeMode(ResizeMode); + void setResizeMode( ResizeMode ); ResizeMode resizeMode() const; - virtual void setRubberBandPen(const QPen &); + void setRubberBandPen( const QPen & ); QPen rubberBandPen() const; - virtual void setTrackerPen(const QPen &); + void setTrackerPen( const QPen & ); QPen trackerPen() const; - virtual void setTrackerFont(const QFont &); + void setTrackerFont( const QFont & ); QFont trackerFont() const; bool isEnabled() const; - virtual void setEnabled(bool); - bool isActive() const; - virtual bool eventFilter(QObject *, QEvent *); + virtual bool eventFilter( QObject *, QEvent * ); QWidget *parentWidget(); const QWidget *parentWidget() const; - virtual QRect pickRect() const; - const QwtPolygon &selection() const; + virtual QPainterPath pickArea() const; + + virtual void drawRubberBand( QPainter * ) const; + virtual void drawTracker( QPainter * ) const; - virtual void drawRubberBand(QPainter *) const; - virtual void drawTracker(QPainter *) const; + virtual QRegion rubberBandMask() const; - virtual QwtText trackerText(const QPoint &pos) const; + virtual QwtText trackerText( const QPoint &pos ) const; QPoint trackerPosition() const; - QRect trackerRect(const QFont &) const; + virtual QRect trackerRect( const QFont & ) const; + QPolygon selection() const; + +public Q_SLOTS: + void setEnabled( bool ); + +Q_SIGNALS: + /*! + A signal indicating, when the picker has been activated. + Together with setEnabled() it can be used to implement + selections with more than one picker. + + \param on True, when the picker has been activated + */ + void activated( bool on ); -signals: /*! A signal emitting the selected points, at the end of a selection. - \param pa Selected points + \param polygon Selected points */ - void selected(const QwtPolygon &pa); + void selected( const QPolygon &polygon ); /*! A signal emitted when a point has been appended to the selection @@ -296,7 +255,7 @@ signals: \param pos Position of the appended point. \sa append(). moved() */ - void appended(const QPoint &pos); + void appended( const QPoint &pos ); /*! A signal emitted whenever the last appended point of the @@ -305,64 +264,64 @@ signals: \param pos Position of the moved last point of the selection. \sa move(), appended() */ - void moved(const QPoint &pos); + void moved( const QPoint &pos ); + + /*! + A signal emitted whenever the last appended point of the + selection has been removed. + \param pos Position of the point, that has been removed + \sa remove(), appended() + */ + void removed( const QPoint &pos ); /*! A signal emitted when the active selection has been changed. This might happen when the observed widget is resized. - \param pa Changed selection + \param selection Changed selection \sa stretchSelection() */ - void changed(const QwtPolygon &pa); + void changed( const QPolygon &selection ); protected: - /*! - \brief Validate and fixup the selection - - Accepts all selections unmodified - - \param selection Selection to validate and fixup - \return true, when accepted, false otherwise - */ - virtual bool accept(QwtPolygon &selection) const; + virtual QPolygon adjustedPoints( const QPolygon & ) const; - virtual void transition(const QEvent *); + virtual void transition( const QEvent * ); virtual void begin(); - virtual void append(const QPoint &); - virtual void move(const QPoint &); - virtual bool end(bool ok = true); + virtual void append( const QPoint & ); + virtual void move( const QPoint & ); + virtual void remove(); + virtual bool end( bool ok = true ); + virtual bool accept( QPolygon & ) const; virtual void reset(); - virtual void widgetMousePressEvent(QMouseEvent *); - virtual void widgetMouseReleaseEvent(QMouseEvent *); - virtual void widgetMouseDoubleClickEvent(QMouseEvent *); - virtual void widgetMouseMoveEvent(QMouseEvent *); - virtual void widgetWheelEvent(QWheelEvent *); - virtual void widgetKeyPressEvent(QKeyEvent *); - virtual void widgetKeyReleaseEvent(QKeyEvent *); - virtual void widgetLeaveEvent(QEvent *); - - virtual void stretchSelection(const QSize &oldSize, - const QSize &newSize); + virtual void widgetMousePressEvent( QMouseEvent * ); + virtual void widgetMouseReleaseEvent( QMouseEvent * ); + virtual void widgetMouseDoubleClickEvent( QMouseEvent * ); + virtual void widgetMouseMoveEvent( QMouseEvent * ); + virtual void widgetWheelEvent( QWheelEvent * ); + virtual void widgetKeyPressEvent( QKeyEvent * ); + virtual void widgetKeyReleaseEvent( QKeyEvent * ); + virtual void widgetEnterEvent( QEvent * ); + virtual void widgetLeaveEvent( QEvent * ); - virtual QwtPickerMachine *stateMachine(int) const; + virtual void stretchSelection( const QSize &oldSize, + const QSize &newSize ); virtual void updateDisplay(); - const QWidget *rubberBandWidget() const; - const QWidget *trackerWidget() const; + const QwtWidgetOverlay *rubberBandOverlay() const; + const QwtWidgetOverlay *trackerOverlay() const; + + const QPolygon &pickedPoints() const; private: - void init(QWidget *, int selectionFlags, RubberBand rubberBand, - DisplayMode trackerMode); + void init( QWidget *, RubberBand rubberBand, DisplayMode trackerMode ); - void setStateMachine(QwtPickerMachine *); - void setMouseTracking(bool); + void setMouseTracking( bool ); - class PickerWidget; class PrivateData; PrivateData *d_data; }; diff --git a/libs/qwt/qwt_picker_machine.cpp b/libs/qwt/qwt_picker_machine.cpp index 6752b1c475..b6644bf930 100644 --- a/libs/qwt/qwt_picker_machine.cpp +++ b/libs/qwt/qwt_picker_machine.cpp @@ -7,13 +7,14 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qevent.h> -#include "qwt_event_pattern.h" #include "qwt_picker_machine.h" +#include "qwt_event_pattern.h" +#include <qevent.h> //! Constructor -QwtPickerMachine::QwtPickerMachine(): - d_state(0) +QwtPickerMachine::QwtPickerMachine( SelectionType type ): + d_selectionType( type ), + d_state( 0 ) { } @@ -22,6 +23,12 @@ QwtPickerMachine::~QwtPickerMachine() { } +//! Return the selection type +QwtPickerMachine::SelectionType QwtPickerMachine::selectionType() const +{ + return d_selectionType; +} + //! Return the current state int QwtPickerMachine::state() const { @@ -29,7 +36,7 @@ int QwtPickerMachine::state() const } //! Change the current state -void QwtPickerMachine::setState(int state) +void QwtPickerMachine::setState( int state ) { d_state = state; } @@ -37,271 +44,483 @@ void QwtPickerMachine::setState(int state) //! Set the current state to 0. void QwtPickerMachine::reset() { - setState(0); + setState( 0 ); +} + +//! Constructor +QwtPickerTrackerMachine::QwtPickerTrackerMachine(): + QwtPickerMachine( NoSelection ) +{ } //! Transition -QwtPickerMachine::CommandList QwtPickerClickPointMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e) +QList<QwtPickerMachine::Command> QwtPickerTrackerMachine::transition( + const QwtEventPattern &, const QEvent *e ) { - QwtPickerMachine::CommandList cmdList; - - switch(e->type()) { - case QEvent::MouseButtonPress: { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, (const QMouseEvent *)e) ) { - cmdList += Begin; - cmdList += Append; - cmdList += End; + QList<QwtPickerMachine::Command> cmdList; + + switch ( e->type() ) + { + case QEvent::Enter: + case QEvent::MouseMove: + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += Move; + } + break; } - break; - } - case QEvent::KeyPress: { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, (const QKeyEvent *)e) ) { - cmdList += Begin; - cmdList += Append; + case QEvent::Leave: + { + cmdList += Remove; cmdList += End; + setState( 0 ); } - break; - } - default: - break; + default: + break; } return cmdList; } +//! Constructor +QwtPickerClickPointMachine::QwtPickerClickPointMachine(): + QwtPickerMachine( PointSelection ) +{ +} + //! Transition -QwtPickerMachine::CommandList QwtPickerDragPointMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e) +QList<QwtPickerMachine::Command> QwtPickerClickPointMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *event ) { - QwtPickerMachine::CommandList cmdList; + QList<QwtPickerMachine::Command> cmdList; - switch(e->type()) { - case QEvent::MouseButtonPress: { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, (const QMouseEvent *)e) ) { - if ( state() == 0 ) { + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect1, + static_cast<const QMouseEvent *>( event ) ) ) + { cmdList += Begin; cmdList += Append; - setState(1); + cmdList += End; } + break; } - break; - } - case QEvent::MouseMove: - case QEvent::Wheel: { - if ( state() != 0 ) - cmdList += Move; - break; - } - case QEvent::MouseButtonRelease: { - if ( state() != 0 ) { - cmdList += End; - setState(0); - } - break; - } - case QEvent::KeyPress: { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, (const QKeyEvent *)e) ) { - if ( state() == 0 ) { + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( QwtEventPattern::KeySelect1, + static_cast<const QKeyEvent *> ( event ) ) ) + { cmdList += Begin; cmdList += Append; - setState(1); - } else { cmdList += End; - setState(0); } + break; } - break; - } - default: - break; + default: + break; } return cmdList; } +//! Constructor +QwtPickerDragPointMachine::QwtPickerDragPointMachine(): + QwtPickerMachine( PointSelection ) +{ +} + //! Transition -QwtPickerMachine::CommandList QwtPickerClickRectMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e) +QList<QwtPickerMachine::Command> QwtPickerDragPointMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *event ) { - QwtPickerMachine::CommandList cmdList; - - switch(e->type()) { - case QEvent::MouseButtonPress: { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, (const QMouseEvent *)e) ) { - switch(state()) { - case 0: { - cmdList += Begin; - cmdList += Append; - setState(1); - break; - } - case 1: { - // Uh, strange we missed the MouseButtonRelease - break; + QList<QwtPickerMachine::Command> cmdList; + + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect1, + static_cast<const QMouseEvent *>( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } } - default: { + break; + } + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; + } + case QEvent::MouseButtonRelease: + { + if ( state() != 0 ) + { cmdList += End; - setState(0); + setState( 0 ); } + break; + } + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( QwtEventPattern::KeySelect1, + static_cast<const QKeyEvent *>( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += End; + setState( 0 ); + } } + break; } + default: + break; } - case QEvent::MouseMove: - case QEvent::Wheel: { - if ( state() != 0 ) - cmdList += Move; - break; - } - case QEvent::MouseButtonRelease: { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, (const QMouseEvent *)e) ) { - if ( state() == 1 ) { - cmdList += Append; - setState(2); + + return cmdList; +} + +//! Constructor +QwtPickerClickRectMachine::QwtPickerClickRectMachine(): + QwtPickerMachine( RectSelection ) +{ +} + +//! Transition +QList<QwtPickerMachine::Command> QwtPickerClickRectMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *event ) +{ + QList<QwtPickerMachine::Command> cmdList; + + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect1, + static_cast<const QMouseEvent *>( event ) ) ) + { + switch ( state() ) + { + case 0: + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + break; + } + case 1: + { + // Uh, strange we missed the MouseButtonRelease + break; + } + default: + { + cmdList += End; + setState( 0 ); + } + } } + break; } - break; - } - case QEvent::KeyPress: { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, (const QKeyEvent *)e) ) { - if ( state() == 0 ) { - cmdList += Begin; - cmdList += Append; - setState(1); - } else { - if ( state() == 1 ) { + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; + } + case QEvent::MouseButtonRelease: + { + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect1, + static_cast<const QMouseEvent *>( event ) ) ) + { + if ( state() == 1 ) + { cmdList += Append; - setState(2); - } else if ( state() == 2 ) { - cmdList += End; - setState(0); + setState( 2 ); } } + break; } - break; - } - default: - break; + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( QwtEventPattern::KeySelect1, + static_cast<const QKeyEvent *> ( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } + else + { + if ( state() == 1 ) + { + cmdList += Append; + setState( 2 ); + } + else if ( state() == 2 ) + { + cmdList += End; + setState( 0 ); + } + } + } + break; + } + default: + break; } return cmdList; } +//! Constructor +QwtPickerDragRectMachine::QwtPickerDragRectMachine(): + QwtPickerMachine( RectSelection ) +{ +} + //! Transition -QwtPickerMachine::CommandList QwtPickerDragRectMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e) +QList<QwtPickerMachine::Command> QwtPickerDragRectMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *event ) { - QwtPickerMachine::CommandList cmdList; + QList<QwtPickerMachine::Command> cmdList; - switch(e->type()) { - case QEvent::MouseButtonPress: { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, (const QMouseEvent *)e) ) { - if ( state() == 0 ) { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState(2); + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect1, + static_cast<const QMouseEvent *>( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 2 ); + } } + break; } - break; - } - case QEvent::MouseMove: - case QEvent::Wheel: { - if ( state() != 0 ) - cmdList += Move; - break; - } - case QEvent::MouseButtonRelease: { - if ( state() == 2 ) { - cmdList += End; - setState(0); + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; } - break; - } - case QEvent::KeyPress: { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, (const QKeyEvent *)e) ) { - if ( state() == 0 ) { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState(2); - } else { + case QEvent::MouseButtonRelease: + { + if ( state() == 2 ) + { cmdList += End; - setState(0); + setState( 0 ); } + break; } - break; - } - default: - break; + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( QwtEventPattern::KeySelect1, + static_cast<const QKeyEvent *> ( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 2 ); + } + else + { + cmdList += End; + setState( 0 ); + } + } + break; + } + default: + break; } return cmdList; } +//! Constructor +QwtPickerPolygonMachine::QwtPickerPolygonMachine(): + QwtPickerMachine( PolygonSelection ) +{ +} + //! Transition -QwtPickerMachine::CommandList QwtPickerPolygonMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e) +QList<QwtPickerMachine::Command> QwtPickerPolygonMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *event ) { - QwtPickerMachine::CommandList cmdList; + QList<QwtPickerMachine::Command> cmdList; - switch(e->type()) { - case QEvent::MouseButtonPress: { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, (const QMouseEvent *)e) ) { - if (state() == 0) { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState(1); - } else { - cmdList += End; - setState(0); + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect1, + static_cast<const QMouseEvent *>( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += Append; + } + } + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect2, + static_cast<const QMouseEvent *>( event ) ) ) + { + if ( state() == 1 ) + { + cmdList += End; + setState( 0 ); + } } + break; } - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect2, (const QMouseEvent *)e) ) { - if (state() == 1) - cmdList += Append; + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; } - break; - } - case QEvent::MouseMove: - case QEvent::Wheel: { - if ( state() != 0 ) - cmdList += Move; - break; + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( QwtEventPattern::KeySelect1, + static_cast<const QKeyEvent *> ( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += Append; + } + } + else if ( eventPattern.keyMatch( QwtEventPattern::KeySelect2, + static_cast<const QKeyEvent *> ( event ) ) ) + { + if ( state() == 1 ) + { + cmdList += End; + setState( 0 ); + } + } + break; + } + default: + break; } - case QEvent::KeyPress: { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, (const QKeyEvent *)e) ) { - if ( state() == 0 ) { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState(1); - } else { + + return cmdList; +} + +//! Constructor +QwtPickerDragLineMachine::QwtPickerDragLineMachine(): + QwtPickerMachine( PolygonSelection ) +{ +} + +//! Transition +QList<QwtPickerMachine::Command> QwtPickerDragLineMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *event ) +{ + QList<QwtPickerMachine::Command> cmdList; + + switch( event->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( QwtEventPattern::MouseSelect1, + static_cast<const QMouseEvent *>( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 1 ); + } + } + break; + } + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( QwtEventPattern::KeySelect1, + static_cast<const QKeyEvent *> ( event ) ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += End; + setState( 0 ); + } + } + break; + } + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + + break; + } + case QEvent::MouseButtonRelease: + { + if ( state() != 0 ) + { cmdList += End; - setState(0); + setState( 0 ); } - } else if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect2, (const QKeyEvent *)e) ) { - if ( state() == 1 ) - cmdList += Append; } - break; - } - default: - break; + default: + break; } return cmdList; diff --git a/libs/qwt/qwt_picker_machine.h b/libs/qwt/qwt_picker_machine.h index b6dd4b8cc2..6164b93b5b 100644 --- a/libs/qwt/qwt_picker_machine.h +++ b/libs/qwt/qwt_picker_machine.h @@ -11,11 +11,7 @@ #define QWT_PICKER_MACHINE 1 #include "qwt_global.h" -#if QT_VERSION < 0x040000 -#include <qvaluelist.h> -#else #include <qlist.h> -#endif class QEvent; class QwtEventPattern; @@ -32,37 +28,69 @@ class QwtEventPattern; class QWT_EXPORT QwtPickerMachine { public: - //! Commands - the output of the state machine - enum Command { + /*! + Type of a selection. + \sa selectionType() + */ + enum SelectionType + { + //! The state machine not usable for any type of selection. + NoSelection = -1, + + //! The state machine is for selecting a single point. + PointSelection, + + //! The state machine is for selecting a rectangle (2 points). + RectSelection, + + //! The state machine is for selecting a polygon (many points). + PolygonSelection + }; + + //! Commands - the output of a state machine + enum Command + { Begin, Append, Move, + Remove, End }; -#if QT_VERSION < 0x040000 - typedef QValueList<Command> CommandList; -#else - typedef QList<Command> CommandList; -#endif - + QwtPickerMachine( SelectionType ); virtual ~QwtPickerMachine(); //! Transition - virtual CommandList transition( - const QwtEventPattern &, const QEvent *) = 0; + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ) = 0; void reset(); int state() const; - void setState(int); + void setState( int ); -protected: - QwtPickerMachine(); + SelectionType selectionType() const; private: + const SelectionType d_selectionType; int d_state; }; +/*! + \brief A state machine for indicating mouse movements + + QwtPickerTrackerMachine supports displaying information + corresponding to mouse movements, but is not intended for + selecting anything. Begin/End are related to Enter/Leave events. +*/ +class QWT_EXPORT QwtPickerTrackerMachine: public QwtPickerMachine +{ +public: + QwtPickerTrackerMachine(); + + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ); +}; + /*! \brief A state machine for point selections @@ -74,8 +102,10 @@ private: class QWT_EXPORT QwtPickerClickPointMachine: public QwtPickerMachine { public: - virtual CommandList transition( - const QwtEventPattern &, const QEvent *); + QwtPickerClickPointMachine(); + + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ); }; /*! @@ -88,8 +118,10 @@ public: class QWT_EXPORT QwtPickerDragPointMachine: public QwtPickerMachine { public: - virtual CommandList transition( - const QwtEventPattern &, const QEvent *); + QwtPickerDragPointMachine(); + + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ); }; /*! @@ -108,8 +140,10 @@ public: class QWT_EXPORT QwtPickerClickRectMachine: public QwtPickerMachine { public: - virtual CommandList transition( - const QwtEventPattern &, const QEvent *); + QwtPickerClickRectMachine(); + + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ); }; /*! @@ -127,8 +161,34 @@ public: class QWT_EXPORT QwtPickerDragRectMachine: public QwtPickerMachine { public: - virtual CommandList transition( - const QwtEventPattern &, const QEvent *); + QwtPickerDragRectMachine(); + + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ); +}; + +/*! + \brief A state machine for line selections + + Pressing QwtEventPattern::MouseSelect1 selects + the first point, releasing it the second point. + Pressing QwtEventPattern::KeySelect1 also selects the + first point, a second press selects the second point and terminates + the selection. + + A common use case of QwtPickerDragLineMachine are pickers for + distance measurements. + + \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode +*/ + +class QWT_EXPORT QwtPickerDragLineMachine: public QwtPickerMachine +{ +public: + QwtPickerDragLineMachine(); + + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ); }; /*! @@ -145,8 +205,10 @@ public: class QWT_EXPORT QwtPickerPolygonMachine: public QwtPickerMachine { public: - virtual CommandList transition( - const QwtEventPattern &, const QEvent *); + QwtPickerPolygonMachine(); + + virtual QList<Command> transition( + const QwtEventPattern &, const QEvent * ); }; #endif diff --git a/libs/qwt/qwt_pixel_matrix.cpp b/libs/qwt/qwt_pixel_matrix.cpp new file mode 100644 index 0000000000..627992c7a1 --- /dev/null +++ b/libs/qwt/qwt_pixel_matrix.cpp @@ -0,0 +1,51 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2003 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_pixel_matrix.h" + +/*! + \brief Constructor + + \param rect Bounding rectangle for the matrix +*/ +QwtPixelMatrix::QwtPixelMatrix( const QRect& rect ): + QBitArray( qMax( rect.width() * rect.height(), 0 ) ), + d_rect( rect ) +{ +} + +//! Destructor +QwtPixelMatrix::~QwtPixelMatrix() +{ +} + +/*! + Set the bounding rectangle of the matrix + + \param rect Bounding rectangle + + \note All bits are cleared + */ +void QwtPixelMatrix::setRect( const QRect& rect ) +{ + if ( rect != d_rect ) + { + d_rect = rect; + const int sz = qMax( rect.width() * rect.height(), 0 ); + resize( sz ); + } + + fill( false ); +} + +//! \return Bounding rectangle +QRect QwtPixelMatrix::rect() const +{ + return d_rect; +} diff --git a/libs/qwt/qwt_pixel_matrix.h b/libs/qwt/qwt_pixel_matrix.h new file mode 100644 index 0000000000..0fe9daf1cb --- /dev/null +++ b/libs/qwt/qwt_pixel_matrix.h @@ -0,0 +1,98 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2003 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PIXEL_MATRIX_H +#define QWT_PIXEL_MATRIX_H + +#include "qwt_global.h" +#include <qbitarray.h> +#include <qrect.h> + +/*! + \brief A bit field corresponding to the pixels of a rectangle + + QwtPixelMatrix is intended to filter out duplicates in an + unsorted array of points. +*/ +class QWT_EXPORT QwtPixelMatrix: public QBitArray +{ +public: + QwtPixelMatrix( const QRect& rect ); + ~QwtPixelMatrix(); + + void setRect( const QRect& rect ); + QRect rect() const; + + bool testPixel( int x, int y ) const; + bool testAndSetPixel( int x, int y, bool on ); + + int index( int x, int y ) const; + +private: + QRect d_rect; +}; + +/*! + \brief Test if a pixel has been set + + \param x X-coordinate + \param y Y-coordinate + + \return true, when pos is outside of rect(), or when the pixel + has already been set. + */ +inline bool QwtPixelMatrix::testPixel( int x, int y ) const +{ + const int idx = index( x, y ); + return ( idx >= 0 ) ? testBit( idx ) : true; +} + +/*! + \brief Set a pixel and test if a pixel has been set before + + \param x X-coordinate + \param y Y-coordinate + \param on Set/Clear the pixel + + \return true, when pos is outside of rect(), or when the pixel + was set before. + */ +inline bool QwtPixelMatrix::testAndSetPixel( int x, int y, bool on ) +{ + const int idx = index( x, y ); + if ( idx < 0 ) + return true; + + const bool onBefore = testBit( idx ); + setBit( idx, on ); + + return onBefore; +} + +/*! + \brief Calculate the index in the bit field corresponding to a position + + \param x X-coordinate + \param y Y-coordinate + \return Index, when rect() contains pos - otherwise -1. + */ +inline int QwtPixelMatrix::index( int x, int y ) const +{ + const int dx = x - d_rect.x(); + if ( dx < 0 || dx >= d_rect.width() ) + return -1; + + const int dy = y - d_rect.y(); + if ( dy < 0 || dy >= d_rect.height() ) + return -1; + + return dy * d_rect.width() + dx; +} + +#endif diff --git a/libs/qwt/qwt_plot.cpp b/libs/qwt/qwt_plot.cpp index 0816d22608..d4740c051a 100644 --- a/libs/qwt/qwt_plot.cpp +++ b/libs/qwt/qwt_plot.cpp @@ -7,16 +7,6 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qpainter.h> -#if QT_VERSION < 0x040000 -#include <qguardedptr.h> -#include <qfocusdata.h> -#else -#include <qpointer.h> -#include <qpaintengine.h> -#endif -#include <qapplication.h> -#include <qevent.h> #include "qwt_plot.h" #include "qwt_plot_dict.h" #include "qwt_plot_layout.h" @@ -24,22 +14,90 @@ #include "qwt_scale_engine.h" #include "qwt_text_label.h" #include "qwt_legend.h" -#include "qwt_dyngrid_layout.h" +#include "qwt_legend_data.h" #include "qwt_plot_canvas.h" -#include "qwt_paint_buffer.h" +#include <qmath.h> +#include <qpainter.h> +#include <qpointer.h> +#include <qpaintengine.h> +#include <qapplication.h> +#include <qevent.h> + +static inline void qwtEnableLegendItems( QwtPlot *plot, bool on ) +{ + if ( on ) + { + QObject::connect( + plot, SIGNAL( legendDataChanged( + const QVariant &, const QList<QwtLegendData> & ) ), + plot, SLOT( updateLegendItems( + const QVariant &, const QList<QwtLegendData> & ) ) ); + } + else + { + QObject::disconnect( + plot, SIGNAL( legendDataChanged( + const QVariant &, const QList<QwtLegendData> & ) ), + plot, SLOT( updateLegendItems( + const QVariant &, const QList<QwtLegendData> & ) ) ); + } +} + +static void qwtSetTabOrder( + QWidget *first, QWidget *second, bool withChildren ) +{ + QList<QWidget *> tabChain; + tabChain += first; + tabChain += second; + + if ( withChildren ) + { + QList<QWidget *> children = second->findChildren<QWidget *>(); + + QWidget *w = second->nextInFocusChain(); + while ( children.contains( w ) ) + { + children.removeAll( w ); + + tabChain += w; + w = w->nextInFocusChain(); + } + } + + for ( int i = 0; i < tabChain.size() - 1; i++ ) + { + QWidget *from = tabChain[i]; + QWidget *to = tabChain[i+1]; + + const Qt::FocusPolicy policy1 = from->focusPolicy(); + const Qt::FocusPolicy policy2 = to->focusPolicy(); + + QWidget *proxy1 = from->focusProxy(); + QWidget *proxy2 = to->focusProxy(); + + from->setFocusPolicy( Qt::TabFocus ); + from->setFocusProxy( NULL); + + to->setFocusPolicy( Qt::TabFocus ); + to->setFocusProxy( NULL); + + QWidget::setTabOrder( from, to ); + + from->setFocusPolicy( policy1 ); + from->setFocusProxy( proxy1); + + to->setFocusPolicy( policy2 ); + to->setFocusProxy( proxy2 ); + } +} class QwtPlot::PrivateData { public: -#if QT_VERSION < 0x040000 - QGuardedPtr<QwtTextLabel> lblTitle; - QGuardedPtr<QwtPlotCanvas> canvas; - QGuardedPtr<QwtLegend> legend; -#else - QPointer<QwtTextLabel> lblTitle; - QPointer<QwtPlotCanvas> canvas; - QPointer<QwtLegend> legend; -#endif + QPointer<QwtTextLabel> titleLabel; + QPointer<QwtTextLabel> footerLabel; + QPointer<QWidget> canvas; + QPointer<QwtAbstractLegend> legend; QwtPlotLayout *layout; bool autoReplot; @@ -49,10 +107,10 @@ public: \brief Constructor \param parent Parent widget */ -QwtPlot::QwtPlot(QWidget *parent): - QFrame(parent) +QwtPlot::QwtPlot( QWidget *parent ): + QFrame( parent ) { - initPlot(QwtText()); + initPlot( QwtText() ); } /*! @@ -60,30 +118,16 @@ QwtPlot::QwtPlot(QWidget *parent): \param title Title text \param parent Parent widget */ -QwtPlot::QwtPlot(const QwtText &title, QWidget *parent): - QFrame(parent) -{ - initPlot(title); -} - -#if QT_VERSION < 0x040000 -/*! - \brief Constructor - \param parent Parent widget - \param name Object name - */ -QwtPlot::QwtPlot(QWidget *parent, const char *name): - QFrame(parent, name) +QwtPlot::QwtPlot( const QwtText &title, QWidget *parent ): + QFrame( parent ) { - initPlot(QwtText()); + initPlot( title ); } -#endif - //! Destructor QwtPlot::~QwtPlot() { - detachItems(QwtPlotItem::Rtti_PlotItem, autoDelete()); + detachItems( QwtPlotItem::Rtti_PlotItem, autoDelete() ); delete d_data->layout; deleteAxesData(); @@ -94,75 +138,160 @@ QwtPlot::~QwtPlot() \brief Initializes a QwtPlot instance \param title Title text */ -void QwtPlot::initPlot(const QwtText &title) +void QwtPlot::initPlot( const QwtText &title ) { d_data = new PrivateData; -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#endif - d_data->layout = new QwtPlotLayout; - d_data->autoReplot = false; - d_data->lblTitle = new QwtTextLabel(title, this); - d_data->lblTitle->setFont(QFont(fontInfo().family(), 14, QFont::Bold)); + // title + d_data->titleLabel = new QwtTextLabel( this ); + d_data->titleLabel->setObjectName( "QwtPlotTitle" ); + d_data->titleLabel->setFont( QFont( fontInfo().family(), 14, QFont::Bold ) ); - QwtText text(title); - int flags = Qt::AlignCenter; -#if QT_VERSION < 0x040000 - flags |= Qt::WordBreak | Qt::ExpandTabs; -#else - flags |= Qt::TextWordWrap; -#endif - text.setRenderFlags(flags); - d_data->lblTitle->setText(text); + QwtText text( title ); + text.setRenderFlags( Qt::AlignCenter | Qt::TextWordWrap ); + d_data->titleLabel->setText( text ); + + // footer + d_data->footerLabel = new QwtTextLabel( this ); + d_data->footerLabel->setObjectName( "QwtPlotFooter" ); + + QwtText footer; + footer.setRenderFlags( Qt::AlignCenter | Qt::TextWordWrap ); + d_data->footerLabel->setText( footer ); + // legend d_data->legend = NULL; + // axis initAxesData(); - d_data->canvas = new QwtPlotCanvas(this); - d_data->canvas->setFrameStyle(QFrame::Panel|QFrame::Sunken); - d_data->canvas->setLineWidth(2); - d_data->canvas->setMidLineWidth(0); + // canvas + d_data->canvas = new QwtPlotCanvas( this ); + d_data->canvas->setObjectName( "QwtPlotCanvas" ); + d_data->canvas->installEventFilter( this ); + + setSizePolicy( QSizePolicy::MinimumExpanding, + QSizePolicy::MinimumExpanding ); + + resize( 200, 200 ); + + QList<QWidget *> focusChain; + focusChain << this << d_data->titleLabel << axisWidget( xTop ) + << axisWidget( yLeft ) << d_data->canvas << axisWidget( yRight ) + << axisWidget( xBottom ) << d_data->footerLabel; + + for ( int i = 0; i < focusChain.size() - 1; i++ ) + qwtSetTabOrder( focusChain[i], focusChain[i+1], false ); + + qwtEnableLegendItems( this, true ); +} + +/*! + \brief Set the drawing canvas of the plot widget + + QwtPlot invokes methods of the canvas as meta methods ( see QMetaObject ). + In opposite to using conventional C++ techniques like virtual methods + they allow to use canvas implementations that are derived from + QWidget or QGLWidget. + + The following meta methods could be implemented: + + - replot() + When the canvas doesn't offer a replot method, QwtPlot calls + update() instead. + + - borderPath() + The border path is necessary to clip the content of the canvas + When the canvas doesn't have any special border ( f.e rounded corners ) + it is o.k. not to implement this method. + + The default canvas is a QwtPlotCanvas - updateTabOrder(); + \param canvas Canvas Widget + \sa canvas() + */ +void QwtPlot::setCanvas( QWidget *canvas ) +{ + if ( canvas == d_data->canvas ) + return; + + delete d_data->canvas; + d_data->canvas = canvas; + + if ( canvas ) + { + canvas->setParent( this ); + canvas->installEventFilter( this ); - setSizePolicy(QSizePolicy::MinimumExpanding, - QSizePolicy::MinimumExpanding); + if ( isVisible() ) + canvas->show(); + } } /*! \brief Adds handling of layout requests + \param event Event + + \return See QFrame::event() */ -bool QwtPlot::event(QEvent *e) -{ - bool ok = QFrame::event(e); - switch(e->type()) { -#if QT_VERSION < 0x040000 - case QEvent::LayoutHint: -#else - case QEvent::LayoutRequest: -#endif - updateLayout(); - break; -#if QT_VERSION >= 0x040000 - case QEvent::PolishRequest: - polish(); - break; -#endif - default: - ; +bool QwtPlot::event( QEvent *event ) +{ + bool ok = QFrame::event( event ); + switch ( event->type() ) + { + case QEvent::LayoutRequest: + updateLayout(); + break; + case QEvent::PolishRequest: + replot(); + break; + default:; } return ok; } -//! Replots the plot if QwtPlot::autoReplot() is \c true. +/*! + \brief Event filter + + The plot handles the following events for the canvas: + + - QEvent::Resize + The canvas margins might depend on its size + + - QEvent::ContentsRectChange + The layout needs to be recalculated + + \param object Object to be filtered + \param event Event + + \return See QFrame::eventFilter() + + \sa updateCanvasMargins(), updateLayout() +*/ +bool QwtPlot::eventFilter( QObject *object, QEvent *event ) +{ + if ( object == d_data->canvas ) + { + if ( event->type() == QEvent::Resize ) + { + updateCanvasMargins(); + } + else if ( event->type() == QEvent::ContentsRectChange ) + { + updateLayout(); + } + } + + return QFrame::eventFilter( object, event ); +} + +//! Replots the plot if autoReplot() is \c true. void QwtPlot::autoRefresh() { - if (d_data->autoReplot) + if ( d_data->autoReplot ) replot(); } @@ -181,12 +310,15 @@ void QwtPlot::autoRefresh() \param tf \c true or \c false. Defaults to \c true. \sa replot() */ -void QwtPlot::setAutoReplot(bool tf) +void QwtPlot::setAutoReplot( bool tf ) { d_data->autoReplot = tf; } -//! \return true if the autoReplot option is set. +/*! + \return true if the autoReplot option is set. + \sa setAutoReplot() +*/ bool QwtPlot::autoReplot() const { return d_data->autoReplot; @@ -196,10 +328,11 @@ bool QwtPlot::autoReplot() const Change the plot's title \param title New title */ -void QwtPlot::setTitle(const QString &title) +void QwtPlot::setTitle( const QString &title ) { - if ( title != d_data->lblTitle->text().text() ) { - d_data->lblTitle->setText(title); + if ( title != d_data->titleLabel->text().text() ) + { + d_data->titleLabel->setText( title ); updateLayout(); } } @@ -208,51 +341,111 @@ void QwtPlot::setTitle(const QString &title) Change the plot's title \param title New title */ -void QwtPlot::setTitle(const QwtText &title) +void QwtPlot::setTitle( const QwtText &title ) { - if ( title != d_data->lblTitle->text() ) { - d_data->lblTitle->setText(title); + if ( title != d_data->titleLabel->text() ) + { + d_data->titleLabel->setText( title ); updateLayout(); } } -//! \return the plot's title +//! \return Title of the plot QwtText QwtPlot::title() const { - return d_data->lblTitle->text(); + return d_data->titleLabel->text(); } -//! \return the plot's title -QwtPlotLayout *QwtPlot::plotLayout() +//! \return Title label widget. +QwtTextLabel *QwtPlot::titleLabel() { - return d_data->layout; + return d_data->titleLabel; } -//! \return the plot's titel label. -const QwtPlotLayout *QwtPlot::plotLayout() const +//! \return Title label widget. +const QwtTextLabel *QwtPlot::titleLabel() const { - return d_data->layout; + return d_data->titleLabel; } -//! \return the plot's titel label. -QwtTextLabel *QwtPlot::titleLabel() +/*! + Change the text the footer + \param text New text of the footer +*/ +void QwtPlot::setFooter( const QString &text ) { - return d_data->lblTitle; + if ( text != d_data->footerLabel->text().text() ) + { + d_data->footerLabel->setText( text ); + updateLayout(); + } } /*! - \return the plot's titel label. + Change the text the footer + \param text New text of the footer */ -const QwtTextLabel *QwtPlot::titleLabel() const +void QwtPlot::setFooter( const QwtText &text ) +{ + if ( text != d_data->footerLabel->text() ) + { + d_data->footerLabel->setText( text ); + updateLayout(); + } +} + +//! \return Text of the footer +QwtText QwtPlot::footer() const +{ + return d_data->footerLabel->text(); +} + +//! \return Footer label widget. +QwtTextLabel *QwtPlot::footerLabel() +{ + return d_data->footerLabel; +} + +//! \return Footer label widget. +const QwtTextLabel *QwtPlot::footerLabel() const +{ + return d_data->footerLabel; +} + +/*! + \brief Assign a new plot layout + + \param layout Layout() + \sa plotLayout() + */ +void QwtPlot::setPlotLayout( QwtPlotLayout *layout ) +{ + if ( layout != d_data->layout ) + { + delete d_data->layout; + d_data->layout = layout; + + updateLayout(); + } +} + +//! \return the plot's layout +QwtPlotLayout *QwtPlot::plotLayout() +{ + return d_data->layout; +} + +//! \return the plot's layout +const QwtPlotLayout *QwtPlot::plotLayout() const { - return d_data->lblTitle; + return d_data->layout; } /*! \return the plot's legend \sa insertLegend() */ -QwtLegend *QwtPlot::legend() +QwtAbstractLegend *QwtPlot::legend() { return d_data->legend; } @@ -261,7 +454,7 @@ QwtLegend *QwtPlot::legend() \return the plot's legend \sa insertLegend() */ -const QwtLegend *QwtPlot::legend() const +const QwtAbstractLegend *QwtPlot::legend() const { return d_data->legend; } @@ -270,7 +463,7 @@ const QwtLegend *QwtPlot::legend() const /*! \return the plot's canvas */ -QwtPlotCanvas *QwtPlot::canvas() +QWidget *QwtPlot::canvas() { return d_data->canvas; } @@ -278,51 +471,45 @@ QwtPlotCanvas *QwtPlot::canvas() /*! \return the plot's canvas */ -const QwtPlotCanvas *QwtPlot::canvas() const +const QWidget *QwtPlot::canvas() const { return d_data->canvas; } -//! Polish -void QwtPlot::polish() -{ - replot(); - -#if QT_VERSION < 0x040000 - QFrame::polish(); -#endif -} - /*! - Return sizeHint + \return Size hint for the plot widget \sa minimumSizeHint() */ - QSize QwtPlot::sizeHint() const { int dw = 0; int dh = 0; - for ( int axisId = 0; axisId < axisCnt; axisId++ ) { - if ( axisEnabled(axisId) ) { + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { + if ( axisEnabled( axisId ) ) + { const int niceDist = 40; - const QwtScaleWidget *scaleWidget = axisWidget(axisId); + const QwtScaleWidget *scaleWidget = axisWidget( axisId ); const QwtScaleDiv &scaleDiv = scaleWidget->scaleDraw()->scaleDiv(); - const int majCnt = scaleDiv.ticks(QwtScaleDiv::MajorTick).count(); + const int majCnt = scaleDiv.ticks( QwtScaleDiv::MajorTick ).count(); - if ( axisId == yLeft || axisId == yRight ) { - int hDiff = (majCnt - 1) * niceDist - - scaleWidget->minimumSizeHint().height(); + if ( axisId == yLeft || axisId == yRight ) + { + int hDiff = ( majCnt - 1 ) * niceDist + - scaleWidget->minimumSizeHint().height(); if ( hDiff > dh ) dh = hDiff; - } else { - int wDiff = (majCnt - 1) * niceDist - - scaleWidget->minimumSizeHint().width(); + } + else + { + int wDiff = ( majCnt - 1 ) * niceDist + - scaleWidget->minimumSizeHint().width(); if ( wDiff > dw ) dw = wDiff; } } } - return minimumSizeHint() + QSize(dw, dh); + return minimumSizeHint() + QSize( dw, dh ); } /*! @@ -330,16 +517,19 @@ QSize QwtPlot::sizeHint() const */ QSize QwtPlot::minimumSizeHint() const { - QSize hint = d_data->layout->minimumSizeHint(this); - hint += QSize(2 * frameWidth(), 2 * frameWidth()); + QSize hint = d_data->layout->minimumSizeHint( this ); + hint += QSize( 2 * frameWidth(), 2 * frameWidth() ); return hint; } -//! Resize and update internal layout -void QwtPlot::resizeEvent(QResizeEvent *e) +/*! + Resize and update internal layout + \param e Resize event +*/ +void QwtPlot::resizeEvent( QResizeEvent *e ) { - QFrame::resizeEvent(e); + QFrame::resizeEvent( e ); updateLayout(); } @@ -350,13 +540,12 @@ void QwtPlot::resizeEvent(QResizeEvent *e) or if any curves are attached to raw data, the plot has to be refreshed explicitly in order to make changes visible. - \sa setAutoReplot() - \warning Calls canvas()->repaint, take care of infinite recursions + \sa updateAxes(), setAutoReplot() */ void QwtPlot::replot() { bool doAutoReplot = autoReplot(); - setAutoReplot(false); + setAutoReplot( false ); updateAxes(); @@ -365,38 +554,20 @@ void QwtPlot::replot() axes labels. We need to process them here before painting to avoid that scales and canvas get out of sync. */ -#if QT_VERSION >= 0x040000 - QApplication::sendPostedEvents(this, QEvent::LayoutRequest); -#else - QApplication::sendPostedEvents(this, QEvent::LayoutHint); -#endif + QApplication::sendPostedEvents( this, QEvent::LayoutRequest ); - QwtPlotCanvas &canvas = *d_data->canvas; - - canvas.invalidatePaintCache(); - - /* - In case of cached or packed painting the canvas - is repainted completely and doesn't need to be erased. - */ - const bool erase = - !canvas.testPaintAttribute(QwtPlotCanvas::PaintPacked) - && !canvas.testPaintAttribute(QwtPlotCanvas::PaintCached); - -#if QT_VERSION >= 0x040000 - const bool noBackgroundMode = canvas.testAttribute(Qt::WA_NoBackground); - if ( !erase && !noBackgroundMode ) - canvas.setAttribute(Qt::WA_NoBackground, true); - - canvas.repaint(canvas.contentsRect()); - - if ( !erase && !noBackgroundMode ) - canvas.setAttribute(Qt::WA_NoBackground, false); -#else - canvas.repaint(canvas.contentsRect(), erase); -#endif + if ( d_data->canvas ) + { + const bool ok = QMetaObject::invokeMethod( + d_data->canvas, "replot", Qt::DirectConnection ); + if ( !ok ) + { + // fallback, when canvas has no a replot method + d_data->canvas->update( d_data->canvas->contentsRect() ); + } + } - setAutoReplot(doAutoReplot); + setAutoReplot( doAutoReplot ); } /*! @@ -405,119 +576,153 @@ void QwtPlot::replot() */ void QwtPlot::updateLayout() { - d_data->layout->activate(this, contentsRect()); + d_data->layout->activate( this, contentsRect() ); + + QRect titleRect = d_data->layout->titleRect().toRect(); + QRect footerRect = d_data->layout->footerRect().toRect(); + QRect scaleRect[QwtPlot::axisCnt]; + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + scaleRect[axisId] = d_data->layout->scaleRect( axisId ).toRect(); + QRect legendRect = d_data->layout->legendRect().toRect(); + QRect canvasRect = d_data->layout->canvasRect().toRect(); - // // resize and show the visible widgets - // - if (!d_data->lblTitle->text().isEmpty()) { - d_data->lblTitle->setGeometry(d_data->layout->titleRect()); - if (!d_data->lblTitle->isVisible()) - d_data->lblTitle->show(); - } else - d_data->lblTitle->hide(); - - for (int axisId = 0; axisId < axisCnt; axisId++ ) { - if (axisEnabled(axisId) ) { - axisWidget(axisId)->setGeometry(d_data->layout->scaleRect(axisId)); - - if ( axisId == xBottom || axisId == xTop ) { - QRegion r(d_data->layout->scaleRect(axisId)); - if ( axisEnabled(yLeft) ) - r = r.subtract(QRegion(d_data->layout->scaleRect(yLeft))); - if ( axisEnabled(yRight) ) - r = r.subtract(QRegion(d_data->layout->scaleRect(yRight))); - r.translate(-d_data->layout->scaleRect(axisId).x(), - -d_data->layout->scaleRect(axisId).y()); - - axisWidget(axisId)->setMask(r); + + if ( !d_data->titleLabel->text().isEmpty() ) + { + d_data->titleLabel->setGeometry( titleRect ); + if ( !d_data->titleLabel->isVisibleTo( this ) ) + d_data->titleLabel->show(); + } + else + d_data->titleLabel->hide(); + + if ( !d_data->footerLabel->text().isEmpty() ) + { + d_data->footerLabel->setGeometry( footerRect ); + if ( !d_data->footerLabel->isVisibleTo( this ) ) + d_data->footerLabel->show(); + } + else + d_data->footerLabel->hide(); + + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { + if ( axisEnabled( axisId ) ) + { + axisWidget( axisId )->setGeometry( scaleRect[axisId] ); + +#if 1 + if ( axisId == xBottom || axisId == xTop ) + { + // do we need this code any longer ??? + + QRegion r( scaleRect[axisId] ); + if ( axisEnabled( yLeft ) ) + r = r.subtracted( QRegion( scaleRect[yLeft] ) ); + if ( axisEnabled( yRight ) ) + r = r.subtracted( QRegion( scaleRect[yRight] ) ); + r.translate( -scaleRect[ axisId ].x(), + -scaleRect[axisId].y() ); + + axisWidget( axisId )->setMask( r ); } - if (!axisWidget(axisId)->isVisible()) - axisWidget(axisId)->show(); - } else - axisWidget(axisId)->hide(); +#endif + if ( !axisWidget( axisId )->isVisibleTo( this ) ) + axisWidget( axisId )->show(); + } + else + axisWidget( axisId )->hide(); } - if ( d_data->legend && - d_data->layout->legendPosition() != ExternalLegend ) { - if (d_data->legend->itemCount() > 0) { - d_data->legend->setGeometry(d_data->layout->legendRect()); - d_data->legend->show(); - } else + if ( d_data->legend ) + { + if ( d_data->legend->isEmpty() ) + { d_data->legend->hide(); + } + else + { + d_data->legend->setGeometry( legendRect ); + d_data->legend->show(); + } } - d_data->canvas->setGeometry(d_data->layout->canvasRect()); + d_data->canvas->setGeometry( canvasRect ); } /*! - Update the focus tab order + \brief Calculate the canvas margins - The order is changed so that the canvas will be in front of the - first legend item, or behind the last legend item - depending - on the position of the legend. -*/ + \param maps QwtPlot::axisCnt maps, mapping between plot and paint device coordinates + \param canvasRect Bounding rectangle where to paint + \param left Return parameter for the left margin + \param top Return parameter for the top margin + \param right Return parameter for the right margin + \param bottom Return parameter for the bottom margin -void QwtPlot::updateTabOrder() + Plot items might indicate, that they need some extra space + at the borders of the canvas by the QwtPlotItem::Margins flag. + + updateCanvasMargins(), QwtPlotItem::getCanvasMarginHint() + */ +void QwtPlot::getCanvasMarginsHint( + const QwtScaleMap maps[], const QRectF &canvasRect, + double &left, double &top, double &right, double &bottom) const { -#if QT_VERSION >= 0x040000 - using namespace Qt; // QWidget::NoFocus/Qt::NoFocus -#else - if ( d_data->canvas->focusPolicy() == NoFocus ) - return; -#endif - if ( d_data->legend.isNull() - || d_data->layout->legendPosition() == ExternalLegend - || d_data->legend->legendItems().count() == 0 ) { - return; - } + left = top = right = bottom = -1.0; - // Depending on the position of the legend the - // tab order will be changed that the canvas is - // next to the last legend item, or before - // the first one. + const QwtPlotItemList& itmList = itemList(); + for ( QwtPlotItemIterator it = itmList.begin(); + it != itmList.end(); ++it ) + { + const QwtPlotItem *item = *it; + if ( item->testItemAttribute( QwtPlotItem::Margins ) ) + { + double m[ QwtPlot::axisCnt ]; + item->getCanvasMarginHint( + maps[ item->xAxis() ], maps[ item->yAxis() ], + canvasRect, m[yLeft], m[xTop], m[yRight], m[xBottom] ); + + left = qMax( left, m[yLeft] ); + top = qMax( top, m[xTop] ); + right = qMax( right, m[yRight] ); + bottom = qMax( bottom, m[xBottom] ); + } + } +} - const bool canvasFirst = - d_data->layout->legendPosition() == QwtPlot::BottomLegend || - d_data->layout->legendPosition() == QwtPlot::RightLegend; +/*! + \brief Update the canvas margins - QWidget *previous = NULL; + Plot items might indicate, that they need some extra space + at the borders of the canvas by the QwtPlotItem::Margins flag. - QWidget *w; -#if QT_VERSION >= 0x040000 - w = d_data->canvas; - while ( ( w = w->nextInFocusChain() ) != d_data->canvas ) -#else - if ( focusData() == NULL ) - return; + getCanvasMarginsHint(), QwtPlotItem::getCanvasMarginHint() + */ +void QwtPlot::updateCanvasMargins() +{ + QwtScaleMap maps[axisCnt]; + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + maps[axisId] = canvasMap( axisId ); - while ( focusData()->next() != d_data->canvas ); - while ( (w = focusData()->next()) != d_data->canvas ) -#endif + double margins[axisCnt]; + getCanvasMarginsHint( maps, canvas()->contentsRect(), + margins[yLeft], margins[xTop], margins[yRight], margins[xBottom] ); + + bool doUpdate = false; + for ( int axisId = 0; axisId < axisCnt; axisId++ ) { - bool isLegendItem = false; - if ( w->focusPolicy() != NoFocus - && w->parent() && w->parent() == d_data->legend->contentsWidget() ) { - isLegendItem = true; - } - - if ( canvasFirst ) { - if ( isLegendItem ) - break; - - previous = w; - } else { - if ( isLegendItem ) - previous = w; - else { - if ( previous ) - break; - } + if ( margins[axisId] >= 0.0 ) + { + const int m = qCeil( margins[axisId] ); + plotLayout()->setCanvasMargin( m, axisId); + doUpdate = true; } } - if ( previous && previous != d_data->canvas) - setTabOrder(previous, d_data->canvas); + if ( doUpdate ) + updateLayout(); } /*! @@ -529,48 +734,48 @@ void QwtPlot::updateTabOrder() plot items better overload drawItems() \sa drawItems() */ -void QwtPlot::drawCanvas(QPainter *painter) +void QwtPlot::drawCanvas( QPainter *painter ) { QwtScaleMap maps[axisCnt]; for ( int axisId = 0; axisId < axisCnt; axisId++ ) - maps[axisId] = canvasMap(axisId); + maps[axisId] = canvasMap( axisId ); - drawItems(painter, - d_data->canvas->contentsRect(), maps, QwtPlotPrintFilter()); + drawItems( painter, d_data->canvas->contentsRect(), maps ); } /*! Redraw the canvas items. + \param painter Painter used for drawing - \param rect Bounding rectangle where to paint - \param map QwtPlot::axisCnt maps, mapping between plot and paint device coordinates - \param pfilter Plot print filter + \param canvasRect Bounding rectangle where to paint + \param maps QwtPlot::axisCnt maps, mapping between plot and paint device coordinates + + \note Usually canvasRect is contentsRect() of the plot canvas. + Due to a bug in Qt this rectangle might be wrong for certain + frame styles ( f.e QFrame::Box ) and it might be necessary to + fix the margins manually using QWidget::setContentsMargins() */ -void QwtPlot::drawItems(QPainter *painter, const QRect &rect, - const QwtScaleMap map[axisCnt], - const QwtPlotPrintFilter &pfilter) const +void QwtPlot::drawItems( QPainter *painter, const QRectF &canvasRect, + const QwtScaleMap maps[axisCnt] ) const { const QwtPlotItemList& itmList = itemList(); for ( QwtPlotItemIterator it = itmList.begin(); - it != itmList.end(); ++it ) { + it != itmList.end(); ++it ) + { QwtPlotItem *item = *it; - if ( item && item->isVisible() ) { - if ( !(pfilter.options() & QwtPlotPrintFilter::PrintGrid) - && item->rtti() == QwtPlotItem::Rtti_PlotGrid ) { - continue; - } - + if ( item && item->isVisible() ) + { painter->save(); -#if QT_VERSION >= 0x040000 - painter->setRenderHint(QPainter::Antialiasing, - item->testRenderHint(QwtPlotItem::RenderAntialiased) ); -#endif + painter->setRenderHint( QPainter::Antialiasing, + item->testRenderHint( QwtPlotItem::RenderAntialiased ) ); + painter->setRenderHint( QPainter::HighQualityAntialiasing, + item->testRenderHint( QwtPlotItem::RenderAntialiased ) ); - item->draw(painter, - map[item->xAxis()], map[item->yAxis()], - rect); + item->draw( painter, + maps[item->xAxis()], maps[item->yAxis()], + canvasRect ); painter->restore(); } @@ -584,174 +789,92 @@ void QwtPlot::drawItems(QPainter *painter, const QRect &rect, \sa QwtScaleMap, transform(), invTransform() */ -QwtScaleMap QwtPlot::canvasMap(int axisId) const +QwtScaleMap QwtPlot::canvasMap( int axisId ) const { QwtScaleMap map; if ( !d_data->canvas ) return map; - map.setTransformation(axisScaleEngine(axisId)->transformation()); - - const QwtScaleDiv *sd = axisScaleDiv(axisId); - map.setScaleInterval(sd->lBound(), sd->hBound()); - - if ( axisEnabled(axisId) ) { - const QwtScaleWidget *s = axisWidget(axisId); - if ( axisId == yLeft || axisId == yRight ) { - int y = s->y() + s->startBorderDist() - d_data->canvas->y(); - int h = s->height() - s->startBorderDist() - s->endBorderDist(); - map.setPaintInterval(y + h, y); - } else { - int x = s->x() + s->startBorderDist() - d_data->canvas->x(); - int w = s->width() - s->startBorderDist() - s->endBorderDist(); - map.setPaintInterval(x, x + w); + map.setTransformation( axisScaleEngine( axisId )->transformation() ); + + const QwtScaleDiv &sd = axisScaleDiv( axisId ); + map.setScaleInterval( sd.lowerBound(), sd.upperBound() ); + + if ( axisEnabled( axisId ) ) + { + const QwtScaleWidget *s = axisWidget( axisId ); + if ( axisId == yLeft || axisId == yRight ) + { + double y = s->y() + s->startBorderDist() - d_data->canvas->y(); + double h = s->height() - s->startBorderDist() - s->endBorderDist(); + map.setPaintInterval( y + h, y ); + } + else + { + double x = s->x() + s->startBorderDist() - d_data->canvas->x(); + double w = s->width() - s->startBorderDist() - s->endBorderDist(); + map.setPaintInterval( x, x + w ); } - } else { - const int margin = plotLayout()->canvasMargin(axisId); + } + else + { + int margin = 0; + if ( !plotLayout()->alignCanvasToScale( axisId ) ) + margin = plotLayout()->canvasMargin( axisId ); const QRect &canvasRect = d_data->canvas->contentsRect(); - if ( axisId == yLeft || axisId == yRight ) { - map.setPaintInterval(canvasRect.bottom() - margin, - canvasRect.top() + margin); - } else { - map.setPaintInterval(canvasRect.left() + margin, - canvasRect.right() - margin); + if ( axisId == yLeft || axisId == yRight ) + { + map.setPaintInterval( canvasRect.bottom() - margin, + canvasRect.top() + margin ); + } + else + { + map.setPaintInterval( canvasRect.left() + margin, + canvasRect.right() - margin ); } } return map; } -/*! - Change the margin of the plot. The margin is the space - around all components. - - \param margin new margin - \sa QwtPlotLayout::setMargin(), margin(), plotLayout() -*/ -void QwtPlot::setMargin(int margin) -{ - if ( margin < 0 ) - margin = 0; - - if ( margin != d_data->layout->margin() ) { - d_data->layout->setMargin(margin); - updateLayout(); - } -} - -/*! - \return margin - \sa setMargin(), QwtPlotLayout::margin(), plotLayout() -*/ -int QwtPlot::margin() const -{ - return d_data->layout->margin(); -} - /*! \brief Change the background of the plotting area - Sets c to QColorGroup::Background of all colorgroups of + Sets brush to QPalette::Window of all color groups of the palette of the canvas. Using canvas()->setPalette() is a more powerful way to set these colors. - \param c new background color + + \param brush New background brush + \sa canvasBackground() */ -void QwtPlot::setCanvasBackground(const QColor &c) +void QwtPlot::setCanvasBackground( const QBrush &brush ) { - QPalette p = d_data->canvas->palette(); - - for ( int i = 0; i < QPalette::NColorGroups; i++ ) { -#if QT_VERSION < 0x040000 - p.setColor((QPalette::ColorGroup)i, QColorGroup::Background, c); -#else - p.setColor((QPalette::ColorGroup)i, QPalette::Background, c); -#endif - } + QPalette pal = d_data->canvas->palette(); + pal.setBrush( QPalette::Window, brush ); - canvas()->setPalette(p); + canvas()->setPalette( pal ); } /*! - Nothing else than: canvas()->palette().color( - QPalette::Normal, QColorGroup::Background); - - \return the background color of the plotting area. -*/ -const QColor & QwtPlot::canvasBackground() const -{ -#if QT_VERSION < 0x040000 - return canvas()->palette().color( - QPalette::Normal, QColorGroup::Background); -#else - return canvas()->palette().color( - QPalette::Normal, QPalette::Background); -#endif -} - -/*! - \brief Change the border width of the plotting area - Nothing else than canvas()->setLineWidth(w), - left for compatibility only. - \param w new border width -*/ -void QwtPlot::setCanvasLineWidth(int w) -{ - canvas()->setLineWidth(w); - updateLayout(); -} + Nothing else than: canvas()->palette().brush( + QPalette::Normal, QPalette::Window); -/*! - Nothing else than: canvas()->lineWidth(), - left for compatibility only. - \return the border width of the plotting area + \return Background brush of the plotting area. + \sa setCanvasBackground() */ -int QwtPlot::canvasLineWidth() const +QBrush QwtPlot::canvasBackground() const { - return canvas()->lineWidth(); + return canvas()->palette().brush( + QPalette::Normal, QPalette::Window ); } /*! \return \c true if the specified axis exists, otherwise \c false \param axisId axis index */ -bool QwtPlot::axisValid(int axisId) +bool QwtPlot::axisValid( int axisId ) { - return ((axisId >= QwtPlot::yLeft) && (axisId < QwtPlot::axisCnt)); -} - -/*! - Called internally when the legend has been clicked on. - Emits a legendClicked() signal. -*/ -void QwtPlot::legendItemClicked() -{ - if ( d_data->legend && sender()->isWidgetType() ) { - QwtPlotItem *plotItem = - (QwtPlotItem*)d_data->legend->find((QWidget *)sender()); - if ( plotItem ) - emit legendClicked(plotItem); - } -} - -/*! - Called internally when the legend has been checked - Emits a legendClicked() signal. -*/ -void QwtPlot::legendItemChecked(bool on) -{ - if ( d_data->legend && sender()->isWidgetType() ) { - QwtPlotItem *plotItem = - (QwtPlotItem*)d_data->legend->find((QWidget *)sender()); - if ( plotItem ) - emit legendChecked(plotItem, on); - } -} - -//! Remove all curves and markers -void QwtPlot::clear() -{ - detachItems(QwtPlotItem::Rtti_PlotCurve); - detachItems(QwtPlotItem::Rtti_PlotMarker); + return ( ( axisId >= QwtPlot::yLeft ) && ( axisId < QwtPlot::axisCnt ) ); } /*! @@ -762,17 +885,23 @@ void QwtPlot::clear() Otherwise the legend items will be placed in a table with a best fit number of columns from left to right. - If pos != QwtPlot::ExternalLegend the plot widget will become - parent of the legend. It will be deleted when the plot is deleted, - or another legend is set with insertLegend(). + insertLegend() will set the plot widget as parent for the legend. + The legend will be deleted in the destructor of the plot or when + another legend is inserted. + + Legends, that are not inserted into the layout of the plot widget + need to connect to the legendDataChanged() signal. Calling updateLegend() + initiates this signal for an initial update. When the application code + wants to implement its own layout this also needs to be done for + rendering plots to a document ( see QwtPlotRenderer ). \param legend Legend \param pos The legend's position. For top/left position the number - of colums will be limited to 1, otherwise it will be set to + of columns will be limited to 1, otherwise it will be set to unlimited. - \param ratio Ratio between legend and the bounding rect - of title, canvas and axes. The legend will be shrinked + \param ratio Ratio between legend and the bounding rectangle + of title, canvas and axes. The legend will be shrunk if it would need more space than the given ratio. The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 it will be reset to the default ratio. @@ -781,53 +910,254 @@ void QwtPlot::clear() \sa legend(), QwtPlotLayout::legendPosition(), QwtPlotLayout::setLegendPosition() */ -void QwtPlot::insertLegend(QwtLegend *legend, - QwtPlot::LegendPosition pos, double ratio) +void QwtPlot::insertLegend( QwtAbstractLegend *legend, + QwtPlot::LegendPosition pos, double ratio ) { - d_data->layout->setLegendPosition(pos, ratio); + d_data->layout->setLegendPosition( pos, ratio ); - if ( legend != d_data->legend ) { + if ( legend != d_data->legend ) + { if ( d_data->legend && d_data->legend->parent() == this ) delete d_data->legend; d_data->legend = legend; - if ( d_data->legend ) { - if ( pos != ExternalLegend ) { - if ( d_data->legend->parent() != this ) { -#if QT_VERSION < 0x040000 - d_data->legend->reparent(this, QPoint(0, 0)); -#else - d_data->legend->setParent(this); -#endif + if ( d_data->legend ) + { + connect( this, + SIGNAL( legendDataChanged( + const QVariant &, const QList<QwtLegendData> & ) ), + d_data->legend, + SLOT( updateLegend( + const QVariant &, const QList<QwtLegendData> & ) ) + ); + + if ( d_data->legend->parent() != this ) + d_data->legend->setParent( this ); + + qwtEnableLegendItems( this, false ); + updateLegend(); + qwtEnableLegendItems( this, true ); + + QwtLegend *lgd = qobject_cast<QwtLegend *>( legend ); + if ( lgd ) + { + switch ( d_data->layout->legendPosition() ) + { + case LeftLegend: + case RightLegend: + { + if ( lgd->maxColumns() == 0 ) + lgd->setMaxColumns( 1 ); // 1 column: align vertical + break; + } + case TopLegend: + case BottomLegend: + { + lgd->setMaxColumns( 0 ); // unlimited + break; + } + default: + break; } } - const QwtPlotItemList& itmList = itemList(); - for ( QwtPlotItemIterator it = itmList.begin(); - it != itmList.end(); ++it ) { - (*it)->updateLegend(d_data->legend); - } - - QLayout *l = d_data->legend->contentsWidget()->layout(); - if ( l && l->inherits("QwtDynGridLayout") ) { - QwtDynGridLayout *tl = (QwtDynGridLayout *)l; - switch(d_data->layout->legendPosition()) { + QWidget *previousInChain = NULL; + switch ( d_data->layout->legendPosition() ) + { case LeftLegend: - case RightLegend: - tl->setMaxCols(1); // 1 column: align vertical + { + previousInChain = axisWidget( QwtPlot::xTop ); break; + } case TopLegend: - case BottomLegend: - tl->setMaxCols(0); // unlimited + { + previousInChain = this; break; - case ExternalLegend: + } + case RightLegend: + { + previousInChain = axisWidget( QwtPlot::yRight ); + break; + } + case BottomLegend: + { + previousInChain = footerLabel(); break; } } + + if ( previousInChain ) + qwtSetTabOrder( previousInChain, legend, true ); } - updateTabOrder(); } updateLayout(); } + +/*! + Emit legendDataChanged() for all plot item + + \sa QwtPlotItem::legendData(), legendDataChanged() + */ +void QwtPlot::updateLegend() +{ + const QwtPlotItemList& itmList = itemList(); + for ( QwtPlotItemIterator it = itmList.begin(); + it != itmList.end(); ++it ) + { + updateLegend( *it ); + } +} + +/*! + Emit legendDataChanged() for a plot item + + \param plotItem Plot item + \sa QwtPlotItem::legendData(), legendDataChanged() + */ +void QwtPlot::updateLegend( const QwtPlotItem *plotItem ) +{ + if ( plotItem == NULL ) + return; + + QList<QwtLegendData> legendData; + + if ( plotItem->testItemAttribute( QwtPlotItem::Legend ) ) + legendData = plotItem->legendData(); + + const QVariant itemInfo = itemToInfo( const_cast< QwtPlotItem *>( plotItem) ); + Q_EMIT legendDataChanged( itemInfo, legendData ); +} + +/*! + \brief Update all plot items interested in legend attributes + + Call QwtPlotItem::updateLegend(), when the QwtPlotItem::LegendInterest + flag is set. + + \param itemInfo Info about the plot item + \param legendData Entries to be displayed for the plot item ( usually 1 ) + + \sa QwtPlotItem::LegendInterest, + QwtPlotLegendItem, QwtPlotItem::updateLegend() + */ +void QwtPlot::updateLegendItems( const QVariant &itemInfo, + const QList<QwtLegendData> &legendData ) +{ + QwtPlotItem *plotItem = infoToItem( itemInfo ); + if ( plotItem ) + { + const QwtPlotItemList& itmList = itemList(); + for ( QwtPlotItemIterator it = itmList.begin(); + it != itmList.end(); ++it ) + { + QwtPlotItem *item = *it; + if ( item->testItemInterest( QwtPlotItem::LegendInterest ) ) + item->updateLegend( plotItem, legendData ); + } + } +} + +/*! + \brief Attach/Detach a plot item + + \param plotItem Plot item + \param on When true attach the item, otherwise detach it + */ +void QwtPlot::attachItem( QwtPlotItem *plotItem, bool on ) +{ + if ( plotItem->testItemInterest( QwtPlotItem::LegendInterest ) ) + { + // plotItem is some sort of legend + + const QwtPlotItemList& itmList = itemList(); + for ( QwtPlotItemIterator it = itmList.begin(); + it != itmList.end(); ++it ) + { + QwtPlotItem *item = *it; + + QList<QwtLegendData> legendData; + if ( on && item->testItemAttribute( QwtPlotItem::Legend ) ) + { + legendData = item->legendData(); + plotItem->updateLegend( item, legendData ); + } + } + } + + if ( on ) + insertItem( plotItem ); + else + removeItem( plotItem ); + + Q_EMIT itemAttached( plotItem, on ); + + if ( plotItem->testItemAttribute( QwtPlotItem::Legend ) ) + { + // the item wants to be represented on the legend + + if ( on ) + { + updateLegend( plotItem ); + } + else + { + const QVariant itemInfo = itemToInfo( plotItem ); + Q_EMIT legendDataChanged( itemInfo, QList<QwtLegendData>() ); + } + } + + if ( autoReplot() ) + update(); +} + +/*! + \brief Build an information, that can be used to identify + a plot item on the legend. + + The default implementation simply wraps the plot item + into a QVariant object. When overloading itemToInfo() + usually infoToItem() needs to reimplemeted too. + +\code + QVariant itemInfo; + qVariantSetValue( itemInfo, plotItem ); +\endcode + + \param plotItem Plot item + \return Plot item embedded in a QVariant + \sa infoToItem() + */ +QVariant QwtPlot::itemToInfo( QwtPlotItem *plotItem ) const +{ + QVariant itemInfo; + qVariantSetValue( itemInfo, plotItem ); + + return itemInfo; +} + +/*! + \brief Identify the plot item according to an item info object, + that has bee generated from itemToInfo(). + + The default implementation simply tries to unwrap a QwtPlotItem + pointer: + +\code + if ( itemInfo.canConvert<QwtPlotItem *>() ) + return qvariant_cast<QwtPlotItem *>( itemInfo ); +\endcode + \param itemInfo Plot item + \return A plot item, when successful, otherwise a NULL pointer. + \sa itemToInfo() +*/ +QwtPlotItem *QwtPlot::infoToItem( const QVariant &itemInfo ) const +{ + if ( itemInfo.canConvert<QwtPlotItem *>() ) + return qvariant_cast<QwtPlotItem *>( itemInfo ); + + return NULL; +} + + diff --git a/libs/qwt/qwt_plot.h b/libs/qwt/qwt_plot.h index 7efa080e34..d6626136d8 100644 --- a/libs/qwt/qwt_plot.h +++ b/libs/qwt/qwt_plot.h @@ -10,23 +10,22 @@ #ifndef QWT_PLOT_H #define QWT_PLOT_H -#include <qframe.h> #include "qwt_global.h" -#include "qwt_array.h" #include "qwt_text.h" #include "qwt_plot_dict.h" #include "qwt_scale_map.h" -#include "qwt_plot_printfilter.h" +#include "qwt_interval.h" +#include <qframe.h> +#include <qlist.h> +#include <qvariant.h> class QwtPlotLayout; -class QwtLegend; +class QwtAbstractLegend; class QwtScaleWidget; class QwtScaleEngine; class QwtScaleDiv; class QwtScaleDraw; class QwtTextLabel; -class QwtPlotCanvas; -class QwtPlotPrintFilter; /*! \brief A 2-D plotting widget @@ -37,10 +36,13 @@ class QwtPlotPrintFilter; (QwtPlotMarker), the grid (QwtPlotGrid), or anything else derived from QwtPlotItem. A plot can have up to four axes, with each plot item attached to an x- and - a y axis. The scales at the axes can be explicitely set (QwtScaleDiv), or + a y axis. The scales at the axes can be explicitly set (QwtScaleDiv), or are calculated from the plot items, using algorithms (QwtScaleEngine) which can be configured separately for each axis. + The simpleplot example is a good starting point to see how to set up a + plot widget. + \image html plot.png \par Example @@ -51,20 +53,15 @@ class QwtPlotPrintFilter; #include <qwt_plot.h> #include <qwt_plot_curve.h> -QwtPlot *myPlot; -double x[100], y1[100], y2[100]; // x and y values - -myPlot = new QwtPlot("Two Curves", parent); +QwtPlot *myPlot = new QwtPlot("Two Curves", parent); // add curves QwtPlotCurve *curve1 = new QwtPlotCurve("Curve 1"); QwtPlotCurve *curve2 = new QwtPlotCurve("Curve 2"); -getSomeValues(x, y1, y2); - -// copy the data into the curves -curve1->setData(x, y1, 100); -curve2->setData(x, y2, 100); +// connect or copy the data to the curves +curve1->setData(...); +curve2->setData(...); curve1->attach(myPlot); curve2->attach(myPlot); @@ -76,227 +73,234 @@ myPlot->replot(); class QWT_EXPORT QwtPlot: public QFrame, public QwtPlotDict { - friend class QwtPlotCanvas; - Q_OBJECT + + Q_PROPERTY( QBrush canvasBackground + READ canvasBackground WRITE setCanvasBackground ) + Q_PROPERTY( bool autoReplot READ autoReplot WRITE setAutoReplot ) + +#if 0 + // This property is intended to configure the plot + // widget from a special dialog in the deigner plugin. + // Disabled until such a dialog has been implemented. + Q_PROPERTY( QString propertiesDocument - READ grabProperties WRITE applyProperties ) + READ grabProperties WRITE applyProperties ) +#endif public: - //! Axis index - enum Axis { + //! \brief Axis index + enum Axis + { + //! Y axis left of the canvas yLeft, + + //! Y axis right of the canvas yRight, + + //! X axis below the canvas xBottom, + + //! X axis above the canvas xTop, + //! Number of axes axisCnt }; /*! - \brief Position of the legend, relative to the canvas. + Position of the legend, relative to the canvas. - ExternalLegend means that only the content of the legend - will be handled by QwtPlot, but not its geometry. - This might be interesting if an application wants to - have a legend in an external window. + \sa insertLegend() */ - enum LegendPosition { + enum LegendPosition + { + //! The legend will be left from the QwtPlot::yLeft axis. LeftLegend, + + //! The legend will be right from the QwtPlot::yRight axis. RightLegend, + + //! The legend will be below the footer BottomLegend, - TopLegend, - ExternalLegend + //! The legend will be above the title + TopLegend }; - explicit QwtPlot(QWidget * = NULL); - explicit QwtPlot(const QwtText &title, QWidget *p = NULL); -#if QT_VERSION < 0x040000 - explicit QwtPlot(QWidget *, const char* name); -#endif + explicit QwtPlot( QWidget * = NULL ); + explicit QwtPlot( const QwtText &title, QWidget * = NULL ); virtual ~QwtPlot(); - void applyProperties(const QString &); + void applyProperties( const QString & ); QString grabProperties() const; - void setAutoReplot(bool tf = true); + void setAutoReplot( bool = true ); bool autoReplot() const; - void print(QPaintDevice &p, - const QwtPlotPrintFilter & = QwtPlotPrintFilter()) const; - virtual void print(QPainter *, const QRect &rect, - const QwtPlotPrintFilter & = QwtPlotPrintFilter()) const; - // Layout + void setPlotLayout( QwtPlotLayout * ); + QwtPlotLayout *plotLayout(); const QwtPlotLayout *plotLayout() const; - void setMargin(int margin); - int margin() const; - // Title - void setTitle(const QString &); - void setTitle(const QwtText &t); + void setTitle( const QString & ); + void setTitle( const QwtText &t ); QwtText title() const; QwtTextLabel *titleLabel(); const QwtTextLabel *titleLabel() const; + // Footer + + void setFooter( const QString & ); + void setFooter( const QwtText &t ); + QwtText footer() const; + + QwtTextLabel *footerLabel(); + const QwtTextLabel *footerLabel() const; + // Canvas - QwtPlotCanvas *canvas(); - const QwtPlotCanvas *canvas() const; + void setCanvas( QWidget * ); - void setCanvasBackground (const QColor &c); - const QColor& canvasBackground() const; + QWidget *canvas(); + const QWidget *canvas() const; - void setCanvasLineWidth(int w); - int canvasLineWidth() const; + void setCanvasBackground( const QBrush & ); + QBrush canvasBackground() const; - virtual QwtScaleMap canvasMap(int axisId) const; + virtual QwtScaleMap canvasMap( int axisId ) const; - double invTransform(int axisId, int pos) const; - int transform(int axisId, double value) const; + double invTransform( int axisId, int pos ) const; + double transform( int axisId, double value ) const; // Axes - QwtScaleEngine *axisScaleEngine(int axisId); - const QwtScaleEngine *axisScaleEngine(int axisId) const; - void setAxisScaleEngine(int axisId, QwtScaleEngine *); + QwtScaleEngine *axisScaleEngine( int axisId ); + const QwtScaleEngine *axisScaleEngine( int axisId ) const; + void setAxisScaleEngine( int axisId, QwtScaleEngine * ); - void setAxisAutoScale(int axisId); - bool axisAutoScale(int axisId) const; + void setAxisAutoScale( int axisId, bool on = true ); + bool axisAutoScale( int axisId ) const; - void enableAxis(int axisId, bool tf = true); - bool axisEnabled(int axisId) const; + void enableAxis( int axisId, bool tf = true ); + bool axisEnabled( int axisId ) const; - void setAxisFont(int axisId, const QFont &f); - QFont axisFont(int axisId) const; + void setAxisFont( int axisId, const QFont &f ); + QFont axisFont( int axisId ) const; - void setAxisScale(int axisId, double min, double max, double step = 0); - void setAxisScaleDiv(int axisId, const QwtScaleDiv &); - void setAxisScaleDraw(int axisId, QwtScaleDraw *); + void setAxisScale( int axisId, double min, double max, double step = 0 ); + void setAxisScaleDiv( int axisId, const QwtScaleDiv & ); + void setAxisScaleDraw( int axisId, QwtScaleDraw * ); - double axisStepSize(int axisId) const; + double axisStepSize( int axisId ) const; + QwtInterval axisInterval( int axisId ) const; - const QwtScaleDiv *axisScaleDiv(int axisId) const; - QwtScaleDiv *axisScaleDiv(int axisId); + const QwtScaleDiv &axisScaleDiv( int axisId ) const; - const QwtScaleDraw *axisScaleDraw(int axisId) const; - QwtScaleDraw *axisScaleDraw(int axisId); + const QwtScaleDraw *axisScaleDraw( int axisId ) const; + QwtScaleDraw *axisScaleDraw( int axisId ); - const QwtScaleWidget *axisWidget(int axisId) const; - QwtScaleWidget *axisWidget(int axisId); + const QwtScaleWidget *axisWidget( int axisId ) const; + QwtScaleWidget *axisWidget( int axisId ); -#if QT_VERSION < 0x040000 - void setAxisLabelAlignment(int axisId, int); -#else - void setAxisLabelAlignment(int axisId, Qt::Alignment); -#endif - void setAxisLabelRotation(int axisId, double rotation); + void setAxisLabelAlignment( int axisId, Qt::Alignment ); + void setAxisLabelRotation( int axisId, double rotation ); + + void setAxisTitle( int axisId, const QString & ); + void setAxisTitle( int axisId, const QwtText & ); + QwtText axisTitle( int axisId ) const; - void setAxisTitle(int axisId, const QString &); - void setAxisTitle(int axisId, const QwtText &); - QwtText axisTitle(int axisId) const; + void setAxisMaxMinor( int axisId, int maxMinor ); + int axisMaxMinor( int axisId ) const; - void setAxisMaxMinor(int axisId, int maxMinor); - int axisMaxMajor(int axisId) const; - void setAxisMaxMajor(int axisId, int maxMajor); - int axisMaxMinor(int axisId) const; + void setAxisMaxMajor( int axisId, int maxMajor ); + int axisMaxMajor( int axisId ) const; // Legend - void insertLegend(QwtLegend *, LegendPosition = QwtPlot::RightLegend, - double ratio = -1.0); + void insertLegend( QwtAbstractLegend *, + LegendPosition = QwtPlot::RightLegend, double ratio = -1.0 ); + + QwtAbstractLegend *legend(); + const QwtAbstractLegend *legend() const; - QwtLegend *legend(); - const QwtLegend *legend() const; + void updateLegend(); + void updateLegend( const QwtPlotItem * ); // Misc - virtual void polish(); virtual QSize sizeHint() const; virtual QSize minimumSizeHint() const; virtual void updateLayout(); + virtual void drawCanvas( QPainter * ); - virtual bool event(QEvent *); + void updateAxes(); + void updateCanvasMargins(); -signals: - /*! - A signal which is emitted when the user has clicked on - a legend item, which is in QwtLegend::ClickableItem mode. + virtual void getCanvasMarginsHint( + const QwtScaleMap maps[], const QRectF &canvasRect, + double &left, double &top, double &right, double &bottom) const; - \param plotItem Corresponding plot item of the - selected legend item + virtual bool event( QEvent * ); + virtual bool eventFilter( QObject *, QEvent * ); - \note clicks are disabled as default - \sa QwtLegend::setItemMode, QwtLegend::itemMode - */ - void legendClicked(QwtPlotItem *plotItem); + virtual void drawItems( QPainter *, const QRectF &, + const QwtScaleMap maps[axisCnt] ) const; - /*! - A signal which is emitted when the user has clicked on - a legend item, which is in QwtLegend::CheckableItem mode + virtual QVariant itemToInfo( QwtPlotItem * ) const; + virtual QwtPlotItem *infoToItem( const QVariant & ) const; - \param plotItem Corresponding plot item of the - selected legend item - \param on True when the legen item is checked +Q_SIGNALS: + /*! + A signal indicating, that an item has been attached/detached - \note clicks are disabled as default - \sa QwtLegend::setItemMode, QwtLegend::itemMode + \param plotItem Plot item + \param on Attached/Detached */ + void itemAttached( QwtPlotItem *plotItem, bool on ); - void legendChecked(QwtPlotItem *plotItem, bool on); + /*! + A signal with the attributes how to update + the legend entries for a plot item. -public slots: - virtual void clear(); + \param itemInfo Info about a plot item, build from itemToInfo() + \param data Attributes of the entries ( usually <= 1 ) for + the plot item. + + \sa itemToInfo(), infoToItem(), QwtAbstractLegend::updateLegend() + */ + void legendDataChanged( const QVariant &itemInfo, + const QList<QwtLegendData> &data ); +public Q_SLOTS: virtual void replot(); void autoRefresh(); -protected slots: - virtual void legendItemClicked(); - virtual void legendItemChecked(bool); - protected: - static bool axisValid(int axisId); - - virtual void drawCanvas(QPainter *); - virtual void drawItems(QPainter *, const QRect &, - const QwtScaleMap maps[axisCnt], - const QwtPlotPrintFilter &) const; - - virtual void updateTabOrder(); - - void updateAxes(); + static bool axisValid( int axisId ); - virtual void resizeEvent(QResizeEvent *e); + virtual void resizeEvent( QResizeEvent *e ); - virtual void printLegendItem(QPainter *, - const QWidget *, const QRect &) const; - - virtual void printTitle(QPainter *, const QRect &) const; - - virtual void printScale(QPainter *, int axisId, int startDist, int endDist, - int baseDist, const QRect &) const; - - virtual void printCanvas(QPainter *, - const QRect &boundingRect, const QRect &canvasRect, - const QwtScaleMap maps[axisCnt], const QwtPlotPrintFilter &) const; - - virtual void printLegend(QPainter *, const QRect &) const; +private Q_SLOTS: + void updateLegendItems( const QVariant &itemInfo, + const QList<QwtLegendData> &data ); private: + friend class QwtPlotItem; + void attachItem( QwtPlotItem *, bool ); + void initAxesData(); void deleteAxesData(); void updateScaleDiv(); - void initPlot(const QwtText &title); + void initPlot( const QwtText &title ); class AxisData; AxisData *d_axisData[axisCnt]; diff --git a/libs/qwt/qwt_plot_abstract_barchart.cpp b/libs/qwt/qwt_plot_abstract_barchart.cpp new file mode 100644 index 0000000000..9a72fdd5b3 --- /dev/null +++ b/libs/qwt/qwt_plot_abstract_barchart.cpp @@ -0,0 +1,367 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_abstract_barchart.h" +#include "qwt_scale_map.h" + +static inline double qwtTransformWidth( + const QwtScaleMap &map, double value, double width ) +{ + const double w2 = 0.5 * width; + + const double v1 = map.transform( value - w2 ); + const double v2 = map.transform( value + w2 ); + + return qAbs( v2 - v1 ); +} + +class QwtPlotAbstractBarChart::PrivateData +{ +public: + PrivateData(): + layoutPolicy( QwtPlotAbstractBarChart::AutoAdjustSamples ), + layoutHint( 0.5 ), + spacing( 10 ), + margin( 5 ), + baseline( 0.0 ) + { + } + + QwtPlotAbstractBarChart::LayoutPolicy layoutPolicy; + double layoutHint; + int spacing; + int margin; + double baseline; +}; + +/*! + Constructor + \param title Title of the chart +*/ +QwtPlotAbstractBarChart::QwtPlotAbstractBarChart( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + d_data = new PrivateData; + + setItemAttribute( QwtPlotItem::Legend, true ); + setItemAttribute( QwtPlotItem::AutoScale, true ); + setItemAttribute( QwtPlotItem::Margins, true ); + setZ( 19.0 ); +} + +//! Destructor +QwtPlotAbstractBarChart::~QwtPlotAbstractBarChart() +{ + delete d_data; +} + +/*! + The combination of layoutPolicy() and layoutHint() define how the width + of the bars is calculated + + \param policy Layout policy + + \sa layoutPolicy(), layoutHint() + */ +void QwtPlotAbstractBarChart::setLayoutPolicy( LayoutPolicy policy ) +{ + if ( policy != d_data->layoutPolicy ) + { + d_data->layoutPolicy = policy; + itemChanged(); + } +} + +/*! + The combination of layoutPolicy() and layoutHint() define how the width + of the bars is calculated + + \return Layout policy of the chart item + \sa setLayoutPolicy(), layoutHint() + */ +QwtPlotAbstractBarChart::LayoutPolicy QwtPlotAbstractBarChart::layoutPolicy() const +{ + return d_data->layoutPolicy; +} + +/*! + The combination of layoutPolicy() and layoutHint() define how the width + of the bars is calculated + + \param hint Layout hint + + \sa LayoutPolicy, layoutPolicy(), layoutHint() + */ +void QwtPlotAbstractBarChart::setLayoutHint( double hint ) +{ + hint = qMax( 0.0, hint ); + if ( hint != d_data->layoutHint ) + { + d_data->layoutHint = hint; + itemChanged(); + } +} + +/*! + The combination of layoutPolicy() and layoutHint() define how the width + of the bars is calculated + + \return Layout policy of the chart item + \sa LayoutPolicy, setLayoutHint(), layoutPolicy() +*/ +double QwtPlotAbstractBarChart::layoutHint() const +{ + return d_data->layoutHint; +} + +/*! + \brief Set the spacing + + The spacing is the distance between 2 samples ( bars for QwtPlotBarChart or + a group of bars for QwtPlotMultiBarChart ) in paint device coordinates. + + \sa spacing() + */ +void QwtPlotAbstractBarChart::setSpacing( int spacing ) +{ + spacing = qMax( spacing, 0 ); + if ( spacing != d_data->spacing ) + { + d_data->spacing = spacing; + itemChanged(); + } +} + +/*! + \return Spacing between 2 samples ( bars or groups of bars ) + \sa setSpacing(), margin() + */ +int QwtPlotAbstractBarChart::spacing() const +{ + return d_data->spacing; +} +/*! + \brief Set the margin + + The margin is the distance between the outmost bars and the contentsRect() + of the canvas. The default setting is 5 pixels. + + \param margin Margin + + \sa spacing(), margin() + */ +void QwtPlotAbstractBarChart::setMargin( int margin ) +{ + margin = qMax( margin, 0 ); + if ( margin != d_data->margin ) + { + d_data->margin = margin; + itemChanged(); + } +} + +/*! + \return Margin between the outmost bars and the contentsRect() + of the canvas. + + \sa setMargin(), spacing() + */ +int QwtPlotAbstractBarChart::margin() const +{ + return d_data->margin; +} + +/*! + \brief Set the baseline + + The baseline is the origin for the chart. Each bar is + painted from the baseline in the direction of the sample + value. In case of a horizontal orientation() the baseline + is interpreted as x - otherwise as y - value. + + The default value for the baseline is 0. + + \param value Value for the baseline + + \sa baseline(), QwtPlotSeriesItem::orientation() +*/ +void QwtPlotAbstractBarChart::setBaseline( double value ) +{ + if ( value != d_data->baseline ) + { + d_data->baseline = value; + itemChanged(); + } +} + +/*! + \return Value for the origin of the bar chart + \sa setBaseline(), QwtPlotSeriesItem::orientation() + */ +double QwtPlotAbstractBarChart::baseline() const +{ + return d_data->baseline; +} + +/*! + Calculate the width for a sample in paint device coordinates + + \param map Scale map for the corresponding scale + \param canvasSize Size of the canvas in paint device coordinates + \param boundingSize Bounding size of the chart in plot coordinates + ( used in AutoAdjustSamples mode ) + \param value Value of the sample + + \return Sample width + \sa layoutPolicy(), layoutHint() +*/ +double QwtPlotAbstractBarChart::sampleWidth( const QwtScaleMap &map, + double canvasSize, double boundingSize, double value ) const +{ + double width; + + switch( d_data->layoutPolicy ) + { + case ScaleSamplesToAxes: + { + width = qwtTransformWidth( map, value, d_data->layoutHint ); + break; + } + case ScaleSampleToCanvas: + { + width = canvasSize * d_data->layoutHint; + break; + } + case FixedSampleSize: + { + width = d_data->layoutHint; + break; + } + case AutoAdjustSamples: + default: + { + const size_t numSamples = dataSize(); + + double w = 1.0; + if ( numSamples > 1 ) + { + w = qAbs( boundingSize / ( numSamples - 1 ) ); + } + + width = qwtTransformWidth( map, value, w ); + width -= d_data->spacing; + } + } + + return width; +} + +/*! + \brief Calculate a hint for the canvas margin + + Bar charts need to reserve some space for displaying the bars + for the first and the last sample. The hint is calculated + from the layoutHint() depending on the layoutPolicy(). + + The margins are in target device coordinates ( pixels on screen ) + + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas in painter coordinates + \param left Returns the left margin + \param top Returns the top margin + \param right Returns the right margin + \param bottom Returns the bottom margin + + \return Margin + + \sa layoutPolicy(), layoutHint(), QwtPlotItem::Margins + QwtPlot::getCanvasMarginsHint(), QwtPlot::updateCanvasMargins() + */ +void QwtPlotAbstractBarChart::getCanvasMarginHint( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QRectF &canvasRect, + double &left, double &top, double &right, double &bottom ) const +{ + double hint = -1.0; + + switch( layoutPolicy() ) + { + case ScaleSampleToCanvas: + { + if ( orientation() == Qt::Vertical ) + hint = 0.5 * canvasRect.width() * d_data->layoutHint; + else + hint = 0.5 * canvasRect.height() * d_data->layoutHint; + + break; + } + case FixedSampleSize: + { + hint = 0.5 * d_data->layoutHint; + break; + } + case AutoAdjustSamples: + case ScaleSamplesToAxes: + default: + { + const size_t numSamples = dataSize(); + if ( numSamples <= 0 ) + break; + + // doesn't work for nonlinear scales + + const QRectF br = dataRect(); + double spacing = 0.0; + double sampleWidthS = 1.0; + + if ( layoutPolicy() == ScaleSamplesToAxes ) + { + sampleWidthS = qMax( d_data->layoutHint, 0.0 ); + } + else + { + spacing = d_data->spacing; + + if ( numSamples > 1 ) + { + sampleWidthS = qAbs( br.width() / ( numSamples - 1 ) ); + } + } + + double ds, w; + if ( orientation() == Qt::Vertical ) + { + ds = qAbs( xMap.sDist() ); + w = canvasRect.width(); + } + else + { + ds = qAbs( yMap.sDist() ); + w = canvasRect.height(); + } + + const double sampleWidthP = ( w - spacing * ds ) + * sampleWidthS / ( ds + sampleWidthS ); + + hint = 0.5 * sampleWidthP; + hint += qMax( d_data->margin, 0 ); + } + } + + if ( orientation() == Qt::Vertical ) + { + left = right = hint; + top = bottom = -1.0; // no hint + } + else + { + left = right = -1.0; // no hint + top = bottom = hint; + } +} diff --git a/libs/qwt/qwt_plot_abstract_barchart.h b/libs/qwt/qwt_plot_abstract_barchart.h new file mode 100644 index 0000000000..78b98a5314 --- /dev/null +++ b/libs/qwt/qwt_plot_abstract_barchart.h @@ -0,0 +1,97 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_ABSTRACT_BAR_CHART_H +#define QWT_PLOT_ABSTRACT_BAR_CHART_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_series_data.h" + +/*! + \brief Abstract base class for bar chart items + + In opposite to almost all other plot items bar charts can't be + displayed inside of their bounding rectangle and need a special + API how to calculate the width of the bars and how they affect + the layout of the attached plot. + */ +class QWT_EXPORT QwtPlotAbstractBarChart: public QwtPlotSeriesItem +{ +public: + /*! + \brief Mode how to calculate the bar width + + setLayoutPolicy(), setLayoutHint(), barWidthHint() + */ + enum LayoutPolicy + { + /*! + The sample width is calculated by dividing the bounding rectangle + by the number of samples. + + \sa boundingRectangle() + \note The layoutHint() is ignored + */ + AutoAdjustSamples, + + /*! + layoutHint() defines an interval in axis coordinates + */ + ScaleSamplesToAxes, + + /*! + The bar width is calculated by multiplying layoutHint() + with the height or width of the canvas. + + \sa boundingRectangle() + */ + ScaleSampleToCanvas, + + /*! + layoutHint() defines a fixed width in paint device coordinates. + */ + FixedSampleSize + }; + + explicit QwtPlotAbstractBarChart( const QwtText &title ); + virtual ~QwtPlotAbstractBarChart(); + + void setLayoutPolicy( LayoutPolicy ); + LayoutPolicy layoutPolicy() const; + + void setLayoutHint( double ); + double layoutHint() const; + + void setSpacing( int ); + int spacing() const; + + void setMargin( int ); + int margin() const; + + void setBaseline( double ); + double baseline() const; + + virtual void getCanvasMarginHint( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, + double &left, double &top, double &right, double &bottom) const; + + +protected: + double sampleWidth( const QwtScaleMap &map, + double canvasSize, double dataSize, + double value ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_axis.cpp b/libs/qwt/qwt_plot_axis.cpp index 5f1a9a501f..e3802f68ec 100644 --- a/libs/qwt/qwt_plot_axis.cpp +++ b/libs/qwt/qwt_plot_axis.cpp @@ -26,6 +26,8 @@ public: int maxMajor; int maxMinor; + bool isValid; + QwtScaleDiv scaleDiv; QwtScaleEngine *scaleEngine; QwtScaleWidget *scaleWidget; @@ -36,31 +38,44 @@ void QwtPlot::initAxesData() { int axisId; - for( axisId = 0; axisId < axisCnt; axisId++) + for ( axisId = 0; axisId < axisCnt; axisId++ ) d_axisData[axisId] = new AxisData; d_axisData[yLeft]->scaleWidget = - new QwtScaleWidget(QwtScaleDraw::LeftScale, this); + new QwtScaleWidget( QwtScaleDraw::LeftScale, this ); d_axisData[yRight]->scaleWidget = - new QwtScaleWidget(QwtScaleDraw::RightScale, this); + new QwtScaleWidget( QwtScaleDraw::RightScale, this ); d_axisData[xTop]->scaleWidget = - new QwtScaleWidget(QwtScaleDraw::TopScale, this); + new QwtScaleWidget( QwtScaleDraw::TopScale, this ); d_axisData[xBottom]->scaleWidget = - new QwtScaleWidget(QwtScaleDraw::BottomScale, this); + new QwtScaleWidget( QwtScaleDraw::BottomScale, this ); + d_axisData[yLeft]->scaleWidget->setObjectName( "QwtPlotAxisYLeft" ); + d_axisData[yRight]->scaleWidget->setObjectName( "QwtPlotAxisYRight" ); + d_axisData[xTop]->scaleWidget->setObjectName( "QwtPlotAxisXTop" ); + d_axisData[xBottom]->scaleWidget->setObjectName( "QwtPlotAxisXBottom" ); - QFont fscl(fontInfo().family(), 10); - QFont fttl(fontInfo().family(), 12, QFont::Bold); +#if 1 + // better find the font sizes from the application font + QFont fscl( fontInfo().family(), 10 ); + QFont fttl( fontInfo().family(), 12, QFont::Bold ); +#endif - for(axisId = 0; axisId < axisCnt; axisId++) { + for ( axisId = 0; axisId < axisCnt; axisId++ ) + { AxisData &d = *d_axisData[axisId]; - d.scaleWidget->setFont(fscl); - d.scaleWidget->setMargin(2); + d.scaleEngine = new QwtLinearScaleEngine; + + d.scaleWidget->setTransformation( + d.scaleEngine->transformation() ); + + d.scaleWidget->setFont( fscl ); + d.scaleWidget->setMargin( 2 ); QwtText text = d.scaleWidget->title(); - text.setFont(fttl); - d.scaleWidget->setTitle(text); + text.setFont( fttl ); + d.scaleWidget->setTitle( text ); d.doAutoScale = true; @@ -71,9 +86,8 @@ void QwtPlot::initAxesData() d.maxMinor = 5; d.maxMajor = 8; - d.scaleEngine = new QwtLinearScaleEngine; - d.scaleDiv.invalidate(); + d.isValid = false; } d_axisData[yLeft]->isEnabled = true; @@ -84,7 +98,8 @@ void QwtPlot::initAxesData() void QwtPlot::deleteAxesData() { - for( int axisId = 0; axisId < axisCnt; axisId++) { + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { delete d_axisData[axisId]->scaleEngine; delete d_axisData[axisId]; d_axisData[axisId] = NULL; @@ -92,75 +107,85 @@ void QwtPlot::deleteAxesData() } /*! - \return specified axis, or NULL if axisId is invalid. - \param axisId axis index + \return Scale widget of the specified axis, or NULL if axisId is invalid. + \param axisId Axis index */ -const QwtScaleWidget *QwtPlot::axisWidget(int axisId) const +const QwtScaleWidget *QwtPlot::axisWidget( int axisId ) const { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->scaleWidget; return NULL; } /*! - \return specified axis, or NULL if axisId is invalid. - \param axisId axis index + \return Scale widget of the specified axis, or NULL if axisId is invalid. + \param axisId Axis index */ -QwtScaleWidget *QwtPlot::axisWidget(int axisId) +QwtScaleWidget *QwtPlot::axisWidget( int axisId ) { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->scaleWidget; return NULL; } /*! - Change the scale engine for an axis + Change the scale engine for an axis - \param axisId axis index + \param axisId Axis index \param scaleEngine Scale engine \sa axisScaleEngine() */ -void QwtPlot::setAxisScaleEngine(int axisId, QwtScaleEngine *scaleEngine) +void QwtPlot::setAxisScaleEngine( int axisId, QwtScaleEngine *scaleEngine ) { - if (axisValid(axisId) && scaleEngine != NULL ) { + if ( axisValid( axisId ) && scaleEngine != NULL ) + { AxisData &d = *d_axisData[axisId]; delete d.scaleEngine; d.scaleEngine = scaleEngine; - d.scaleDiv.invalidate(); + d_axisData[axisId]->scaleWidget->setTransformation( + scaleEngine->transformation() ); + + d.isValid = false; autoRefresh(); } } -//! \return Scale engine for a specific axis -QwtScaleEngine *QwtPlot::axisScaleEngine(int axisId) +/*! + \param axisId Axis index + \return Scale engine for a specific axis +*/ +QwtScaleEngine *QwtPlot::axisScaleEngine( int axisId ) { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->scaleEngine; else return NULL; } -//! \return Scale engine for a specific axis -const QwtScaleEngine *QwtPlot::axisScaleEngine(int axisId) const +/*! + \param axisId Axis index + \return Scale engine for a specific axis +*/ +const QwtScaleEngine *QwtPlot::axisScaleEngine( int axisId ) const { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->scaleEngine; else return NULL; } /*! - \return \c true if autoscaling is enabled - \param axisId axis index + \return \c True, if autoscaling is enabled + \param axisId Axis index */ -bool QwtPlot::axisAutoScale(int axisId) const +bool QwtPlot::axisAutoScale( int axisId ) const { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->doAutoScale; else return false; @@ -168,38 +193,38 @@ bool QwtPlot::axisAutoScale(int axisId) const } /*! - \return \c true if a specified axis is enabled - \param axisId axis index + \return \c True, if a specified axis is enabled + \param axisId Axis index */ -bool QwtPlot::axisEnabled(int axisId) const +bool QwtPlot::axisEnabled( int axisId ) const { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->isEnabled; else return false; } /*! - \return the font of the scale labels for a specified axis - \param axisId axis index + \return The font of the scale labels for a specified axis + \param axisId Axis index */ -QFont QwtPlot::axisFont(int axisId) const +QFont QwtPlot::axisFont( int axisId ) const { - if (axisValid(axisId)) - return axisWidget(axisId)->font(); + if ( axisValid( axisId ) ) + return axisWidget( axisId )->font(); else return QFont(); } /*! - \return the maximum number of major ticks for a specified axis - \param axisId axis index - sa setAxisMaxMajor() + \return The maximum number of major ticks for a specified axis + \param axisId Axis index + \sa setAxisMaxMajor(), QwtScaleEngine::divideScale() */ -int QwtPlot::axisMaxMajor(int axisId) const +int QwtPlot::axisMaxMajor( int axisId ) const { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->maxMajor; else return 0; @@ -207,12 +232,12 @@ int QwtPlot::axisMaxMajor(int axisId) const /*! \return the maximum number of minor ticks for a specified axis - \param axisId axis index - sa setAxisMaxMinor() + \param axisId Axis index + \sa setAxisMaxMinor(), QwtScaleEngine::divideScale() */ -int QwtPlot::axisMaxMinor(int axisId) const +int QwtPlot::axisMaxMinor( int axisId ) const { - if (axisValid(axisId)) + if ( axisValid( axisId ) ) return d_axisData[axisId]->maxMinor; else return 0; @@ -221,95 +246,91 @@ int QwtPlot::axisMaxMinor(int axisId) const /*! \brief Return the scale division of a specified axis - axisScaleDiv(axisId)->lBound(), axisScaleDiv(axisId)->hBound() + axisScaleDiv(axisId).lowerBound(), axisScaleDiv(axisId).upperBound() are the current limits of the axis scale. - \param axisId axis index + \param axisId Axis index \return Scale division - \sa QwtScaleDiv, setAxisScaleDiv + \sa QwtScaleDiv, setAxisScaleDiv(), QwtScaleEngine::divideScale() */ -const QwtScaleDiv *QwtPlot::axisScaleDiv(int axisId) const +const QwtScaleDiv &QwtPlot::axisScaleDiv( int axisId ) const { - if (!axisValid(axisId)) - return NULL; - - return &d_axisData[axisId]->scaleDiv; + return d_axisData[axisId]->scaleDiv; } /*! - \brief Return the scale division of a specified axis - - axisScaleDiv(axisId)->lBound(), axisScaleDiv(axisId)->hBound() - are the current limits of the axis scale. - - \param axisId axis index - \return Scale division + \brief Return the scale draw of a specified axis - \sa QwtScaleDiv, setAxisScaleDiv + \param axisId Axis index + \return Specified scaleDraw for axis, or NULL if axis is invalid. */ -QwtScaleDiv *QwtPlot::axisScaleDiv(int axisId) +const QwtScaleDraw *QwtPlot::axisScaleDraw( int axisId ) const { - if (!axisValid(axisId)) + if ( !axisValid( axisId ) ) return NULL; - return &d_axisData[axisId]->scaleDiv; + return axisWidget( axisId )->scaleDraw(); } /*! - \returns the scale draw of a specified axis - \param axisId axis index - \return specified scaleDraw for axis, or NULL if axis is invalid. - \sa QwtScaleDraw + \brief Return the scale draw of a specified axis + + \param axisId Axis index + \return Specified scaleDraw for axis, or NULL if axis is invalid. */ -const QwtScaleDraw *QwtPlot::axisScaleDraw(int axisId) const +QwtScaleDraw *QwtPlot::axisScaleDraw( int axisId ) { - if (!axisValid(axisId)) + if ( !axisValid( axisId ) ) return NULL; - return axisWidget(axisId)->scaleDraw(); + return axisWidget( axisId )->scaleDraw(); } /*! - \returns the scale draw of a specified axis - \param axisId axis index - \return specified scaleDraw for axis, or NULL if axis is invalid. - \sa QwtScaleDraw + \brief Return the step size parameter that has been set in setAxisScale. + + This doesn't need to be the step size of the current scale. + + \param axisId Axis index + \return step size parameter value + + \sa setAxisScale(), QwtScaleEngine::divideScale() */ -QwtScaleDraw *QwtPlot::axisScaleDraw(int axisId) +double QwtPlot::axisStepSize( int axisId ) const { - if (!axisValid(axisId)) - return NULL; + if ( !axisValid( axisId ) ) + return 0; - return axisWidget(axisId)->scaleDraw(); + return d_axisData[axisId]->stepSize; } /*! - Return the step size parameter, that has been set - in setAxisScale. This doesn't need to be the step size - of the current scale. + \brief Return the current interval of the specified axis - \param axisId axis index - \return step size parameter value + This is only a convenience function for axisScaleDiv( axisId )->interval(); + + \param axisId Axis index + \return Scale interval - \sa setAxisScale + \sa QwtScaleDiv, axisScaleDiv() */ -double QwtPlot::axisStepSize(int axisId) const +QwtInterval QwtPlot::axisInterval( int axisId ) const { - if (!axisValid(axisId)) - return 0; + if ( !axisValid( axisId ) ) + return QwtInterval(); - return d_axisData[axisId]->stepSize; + return d_axisData[axisId]->scaleDiv.interval(); } /*! - \return the title of a specified axis - \param axisId axis index + \return Title of a specified axis + \param axisId Axis index */ -QwtText QwtPlot::axisTitle(int axisId) const +QwtText QwtPlot::axisTitle( int axisId ) const { - if (axisValid(axisId)) - return axisWidget(axisId)->title(); + if ( axisValid( axisId ) ) + return axisWidget( axisId )->title(); else return QwtText(); } @@ -323,12 +344,14 @@ QwtText QwtPlot::axisTitle(int axisId) const into values works as normal. Only xBottom and yLeft are enabled by default. - \param axisId axis index + + \param axisId Axis index \param tf \c true (enabled) or \c false (disabled) */ -void QwtPlot::enableAxis(int axisId, bool tf) +void QwtPlot::enableAxis( int axisId, bool tf ) { - if (axisValid(axisId) && tf != d_axisData[axisId]->isEnabled) { + if ( axisValid( axisId ) && tf != d_axisData[axisId]->isEnabled ) + { d_axisData[axisId]->isEnabled = tf; updateLayout(); } @@ -337,15 +360,19 @@ void QwtPlot::enableAxis(int axisId, bool tf) /*! Transform the x or y coordinate of a position in the drawing region into a value. - \param axisId axis index + + \param axisId Axis index \param pos position + + \return Position as axis coordinate + \warning The position can be an x or a y coordinate, depending on the specified axis. */ -double QwtPlot::invTransform(int axisId, int pos) const +double QwtPlot::invTransform( int axisId, int pos ) const { - if (axisValid(axisId)) - return(canvasMap(axisId).invTransform(pos)); + if ( axisValid( axisId ) ) + return( canvasMap( axisId ).invTransform( pos ) ); else return 0.0; } @@ -353,31 +380,32 @@ double QwtPlot::invTransform(int axisId, int pos) const /*! \brief Transform a value into a coordinate in the plotting region - \param axisId axis index + + \param axisId Axis index \param value value - \return X or y coordinate in the plotting region corresponding + \return X or Y coordinate in the plotting region corresponding to the value. */ -int QwtPlot::transform(int axisId, double value) const +double QwtPlot::transform( int axisId, double value ) const { - if (axisValid(axisId)) - return(canvasMap(axisId).transform(value)); + if ( axisValid( axisId ) ) + return( canvasMap( axisId ).transform( value ) ); else - return 0; - + return 0.0; } /*! \brief Change the font of an axis - \param axisId axis index - \param f font + + \param axisId Axis index + \param font Font \warning This function changes the font of the tick labels, not of the axis title. */ -void QwtPlot::setAxisFont(int axisId, const QFont &f) +void QwtPlot::setAxisFont( int axisId, const QFont &font ) { - if (axisValid(axisId)) - axisWidget(axisId)->setFont(f); + if ( axisValid( axisId ) ) + axisWidget( axisId )->setFont( font ); } /*! @@ -386,33 +414,45 @@ void QwtPlot::setAxisFont(int axisId, const QFont &f) This member function is used to switch back to autoscaling mode after a fixed scale has been set. Autoscaling is enabled by default. - \param axisId axis index - \sa QwtPlot::setAxisScale(), QwtPlot::setAxisScaleDiv() + \param axisId Axis index + \param on On/Off + \sa setAxisScale(), setAxisScaleDiv(), updateAxes() + + \note The autoscaling flag has no effect until updateAxes() is executed + ( called by replot() ). */ -void QwtPlot::setAxisAutoScale(int axisId) +void QwtPlot::setAxisAutoScale( int axisId, bool on ) { - if (axisValid(axisId) && !d_axisData[axisId]->doAutoScale ) { - d_axisData[axisId]->doAutoScale = true; + if ( axisValid( axisId ) && ( d_axisData[axisId]->doAutoScale != on ) ) + { + d_axisData[axisId]->doAutoScale = on; autoRefresh(); } } /*! \brief Disable autoscaling and specify a fixed scale for a selected axis. - \param axisId axis index - \param min - \param max minimum and maximum of the scale + + In updateAxes() the scale engine calculates a scale division from the + specified parameters, that will be assigned to the scale widget. So + updates of the scale widget usually happen delayed with the next replot. + + \param axisId Axis index + \param min Minimum of the scale + \param max Maximum of the scale \param stepSize Major step size. If <code>step == 0</code>, the step size is - calculated automatically using the maxMajor setting. - \sa setAxisMaxMajor(), setAxisAutoScale() + calculated automatically using the maxMajor setting. + + \sa setAxisMaxMajor(), setAxisAutoScale(), axisStepSize(), QwtScaleEngine::divideScale() */ -void QwtPlot::setAxisScale(int axisId, double min, double max, double stepSize) +void QwtPlot::setAxisScale( int axisId, double min, double max, double stepSize ) { - if (axisValid(axisId)) { + if ( axisValid( axisId ) ) + { AxisData &d = *d_axisData[axisId]; d.doAutoScale = false; - d.scaleDiv.invalidate(); + d.isValid = false; d.minValue = min; d.maxValue = max; @@ -424,17 +464,25 @@ void QwtPlot::setAxisScale(int axisId, double min, double max, double stepSize) /*! \brief Disable autoscaling and specify a fixed scale for a selected axis. - \param axisId axis index + + The scale division will be stored locally only until the next call + of updateAxes(). So updates of the scale widget usually happen delayed with + the next replot. + + \param axisId Axis index \param scaleDiv Scale division + \sa setAxisScale(), setAxisAutoScale() */ -void QwtPlot::setAxisScaleDiv(int axisId, const QwtScaleDiv &scaleDiv) +void QwtPlot::setAxisScaleDiv( int axisId, const QwtScaleDiv &scaleDiv ) { - if (axisValid(axisId)) { + if ( axisValid( axisId ) ) + { AxisData &d = *d_axisData[axisId]; d.doAutoScale = false; d.scaleDiv = scaleDiv; + d.isValid = true; autoRefresh(); } @@ -442,8 +490,9 @@ void QwtPlot::setAxisScaleDiv(int axisId, const QwtScaleDiv &scaleDiv) /*! \brief Set a scale draw - \param axisId axis index - \param scaleDraw object responsible for drawing scales. + + \param axisId Axis index + \param scaleDraw Object responsible for drawing scales. By passing scaleDraw it is possible to extend QwtScaleDraw functionality and let it take place in QwtPlot. Please note @@ -455,63 +504,63 @@ void QwtPlot::setAxisScaleDiv(int axisId, const QwtScaleDiv &scaleDiv) previous QwtScaleDraw. */ -void QwtPlot::setAxisScaleDraw(int axisId, QwtScaleDraw *scaleDraw) +void QwtPlot::setAxisScaleDraw( int axisId, QwtScaleDraw *scaleDraw ) { - if (axisValid(axisId)) { - axisWidget(axisId)->setScaleDraw(scaleDraw); + if ( axisValid( axisId ) ) + { + axisWidget( axisId )->setScaleDraw( scaleDraw ); autoRefresh(); } } /*! Change the alignment of the tick labels - \param axisId axis index - \param alignment Or'd Qt::AlignmentFlags <see qnamespace.h> + + \param axisId Axis index + \param alignment Or'd Qt::AlignmentFlags see <qnamespace.h> + \sa QwtScaleDraw::setLabelAlignment() */ -#if QT_VERSION < 0x040000 -void QwtPlot::setAxisLabelAlignment(int axisId, int alignment) -#else -void QwtPlot::setAxisLabelAlignment(int axisId, Qt::Alignment alignment) -#endif +void QwtPlot::setAxisLabelAlignment( int axisId, Qt::Alignment alignment ) { - if (axisValid(axisId)) - axisWidget(axisId)->setLabelAlignment(alignment); + if ( axisValid( axisId ) ) + axisWidget( axisId )->setLabelAlignment( alignment ); } /*! Rotate all tick labels - \param axisId axis index + + \param axisId Axis index \param rotation Angle in degrees. When changing the label rotation, the label alignment might be adjusted too. - \sa QwtScaleDraw::setLabelRotation(), QwtPlot::setAxisLabelAlignment + + \sa QwtScaleDraw::setLabelRotation(), setAxisLabelAlignment() */ -void QwtPlot::setAxisLabelRotation(int axisId, double rotation) +void QwtPlot::setAxisLabelRotation( int axisId, double rotation ) { - if (axisValid(axisId)) - axisWidget(axisId)->setLabelRotation(rotation); + if ( axisValid( axisId ) ) + axisWidget( axisId )->setLabelRotation( rotation ); } /*! Set the maximum number of minor scale intervals for a specified axis - \param axisId axis index - \param maxMinor maximum number of minor steps + \param axisId Axis index + \param maxMinor Maximum number of minor steps + \sa axisMaxMinor() */ -void QwtPlot::setAxisMaxMinor(int axisId, int maxMinor) +void QwtPlot::setAxisMaxMinor( int axisId, int maxMinor ) { - if (axisValid(axisId)) { - if ( maxMinor < 0 ) - maxMinor = 0; - if ( maxMinor > 100 ) - maxMinor = 100; + if ( axisValid( axisId ) ) + { + maxMinor = qBound( 0, maxMinor, 100 ); AxisData &d = *d_axisData[axisId]; - - if ( maxMinor != d.maxMinor ) { + if ( maxMinor != d.maxMinor ) + { d.maxMinor = maxMinor; - d.scaleDiv.invalidate(); + d.isValid = false; autoRefresh(); } } @@ -520,22 +569,22 @@ void QwtPlot::setAxisMaxMinor(int axisId, int maxMinor) /*! Set the maximum number of major scale intervals for a specified axis - \param axisId axis index - \param maxMajor maximum number of major steps + \param axisId Axis index + \param maxMajor Maximum number of major steps + \sa axisMaxMajor() */ -void QwtPlot::setAxisMaxMajor(int axisId, int maxMajor) +void QwtPlot::setAxisMaxMajor( int axisId, int maxMajor ) { - if (axisValid(axisId)) { - if ( maxMajor < 1 ) - maxMajor = 1; - if ( maxMajor > 1000 ) - maxMajor = 10000; + if ( axisValid( axisId ) ) + { + maxMajor = qBound( 1, maxMajor, 10000 ); AxisData &d = *d_axisData[axisId]; - if ( maxMajor != d.maxMinor ) { + if ( maxMajor != d.maxMajor ) + { d.maxMajor = maxMajor; - d.scaleDiv.invalidate(); + d.isValid = false; autoRefresh(); } } @@ -543,87 +592,128 @@ void QwtPlot::setAxisMaxMajor(int axisId, int maxMajor) /*! \brief Change the title of a specified axis - \param axisId axis index + + \param axisId Axis index \param title axis title */ -void QwtPlot::setAxisTitle(int axisId, const QString &title) +void QwtPlot::setAxisTitle( int axisId, const QString &title ) { - if (axisValid(axisId)) - axisWidget(axisId)->setTitle(title); + if ( axisValid( axisId ) ) + axisWidget( axisId )->setTitle( title ); } /*! \brief Change the title of a specified axis - \param axisId axis index - \param title axis title + + \param axisId Axis index + \param title Axis title */ -void QwtPlot::setAxisTitle(int axisId, const QwtText &title) +void QwtPlot::setAxisTitle( int axisId, const QwtText &title ) { - if (axisValid(axisId)) - axisWidget(axisId)->setTitle(title); + if ( axisValid( axisId ) ) + axisWidget( axisId )->setTitle( title ); } -//! Rebuild the scales +/*! + \brief Rebuild the axes scales + + In case of autoscaling the boundaries of a scale are calculated + from the bounding rectangles of all plot items, having the + QwtPlotItem::AutoScale flag enabled ( QwtScaleEngine::autoScale() ). + Then a scale division is calculated ( QwtScaleEngine::didvideScale() ) + and assigned to scale widget. + + When the scale boundaries have been assigned with setAxisScale() a + scale division is calculated ( QwtScaleEngine::didvideScale() ) + for this interval and assigned to the scale widget. + + When the scale has been set explicitly by setAxisScaleDiv() the + locally stored scale division gets assigned to the scale widget. + + The scale widget indicates modifications by emitting a + QwtScaleWidget::scaleDivChanged() signal. + + updateAxes() is usually called by replot(). + + \sa setAxisAutoScale(), setAxisScale(), setAxisScaleDiv(), replot() + QwtPlotItem::boundingRect() + */ void QwtPlot::updateAxes() { // Find bounding interval of the item data // for all axes, where autoscaling is enabled - QwtDoubleInterval intv[axisCnt]; + QwtInterval intv[axisCnt]; const QwtPlotItemList& itmList = itemList(); QwtPlotItemIterator it; - for ( it = itmList.begin(); it != itmList.end(); ++it ) { + for ( it = itmList.begin(); it != itmList.end(); ++it ) + { const QwtPlotItem *item = *it; - if ( !item->testItemAttribute(QwtPlotItem::AutoScale) ) + if ( !item->testItemAttribute( QwtPlotItem::AutoScale ) ) + continue; + + if ( !item->isVisible() ) continue; - if ( axisAutoScale(item->xAxis()) || axisAutoScale(item->yAxis()) ) { - const QwtDoubleRect rect = item->boundingRect(); - intv[item->xAxis()] |= QwtDoubleInterval(rect.left(), rect.right()); - intv[item->yAxis()] |= QwtDoubleInterval(rect.top(), rect.bottom()); + if ( axisAutoScale( item->xAxis() ) || axisAutoScale( item->yAxis() ) ) + { + const QRectF rect = item->boundingRect(); + + if ( rect.width() >= 0.0 ) + intv[item->xAxis()] |= QwtInterval( rect.left(), rect.right() ); + + if ( rect.height() >= 0.0 ) + intv[item->yAxis()] |= QwtInterval( rect.top(), rect.bottom() ); } } // Adjust scales - for (int axisId = 0; axisId < axisCnt; axisId++) { + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { AxisData &d = *d_axisData[axisId]; double minValue = d.minValue; double maxValue = d.maxValue; double stepSize = d.stepSize; - if ( d.doAutoScale && intv[axisId].isValid() ) { - d.scaleDiv.invalidate(); + if ( d.doAutoScale && intv[axisId].isValid() ) + { + d.isValid = false; minValue = intv[axisId].minValue(); maxValue = intv[axisId].maxValue(); - d.scaleEngine->autoScale(d.maxMajor, - minValue, maxValue, stepSize); + d.scaleEngine->autoScale( d.maxMajor, + minValue, maxValue, stepSize ); } - if ( !d.scaleDiv.isValid() ) { + if ( !d.isValid ) + { d.scaleDiv = d.scaleEngine->divideScale( - minValue, maxValue, - d.maxMajor, d.maxMinor, stepSize); + minValue, maxValue, + d.maxMajor, d.maxMinor, stepSize ); + d.isValid = true; } - QwtScaleWidget *scaleWidget = axisWidget(axisId); - scaleWidget->setScaleDiv( - d.scaleEngine->transformation(), d.scaleDiv); + QwtScaleWidget *scaleWidget = axisWidget( axisId ); + scaleWidget->setScaleDiv( d.scaleDiv ); int startDist, endDist; - scaleWidget->getBorderDistHint(startDist, endDist); - scaleWidget->setBorderDist(startDist, endDist); + scaleWidget->getBorderDistHint( startDist, endDist ); + scaleWidget->setBorderDist( startDist, endDist ); } - for ( it = itmList.begin(); it != itmList.end(); ++it ) { + for ( it = itmList.begin(); it != itmList.end(); ++it ) + { QwtPlotItem *item = *it; - item->updateScaleDiv( *axisScaleDiv(item->xAxis()), - *axisScaleDiv(item->yAxis())); + if ( item->testItemInterest( QwtPlotItem::ScaleInterest ) ) + { + item->updateScaleDiv( axisScaleDiv( item->xAxis() ), + axisScaleDiv( item->yAxis() ) ); + } } } diff --git a/libs/qwt/qwt_plot_barchart.cpp b/libs/qwt/qwt_plot_barchart.cpp new file mode 100644 index 0000000000..b9db8e22f5 --- /dev/null +++ b/libs/qwt/qwt_plot_barchart.cpp @@ -0,0 +1,459 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_barchart.h" +#include "qwt_scale_map.h" +#include "qwt_column_symbol.h" +#include "qwt_painter.h" +#include <qpainter.h> + +class QwtPlotBarChart::PrivateData +{ +public: + PrivateData(): + symbol( NULL ), + legendMode( QwtPlotBarChart::LegendChartTitle ) + { + } + + ~PrivateData() + { + delete symbol; + } + + QwtColumnSymbol *symbol; + QwtPlotBarChart::LegendMode legendMode; +}; + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotBarChart::QwtPlotBarChart( const QwtText &title ): + QwtPlotAbstractBarChart( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotBarChart::QwtPlotBarChart( const QString &title ): + QwtPlotAbstractBarChart( QwtText( title ) ) +{ + init(); +} + +//! Destructor +QwtPlotBarChart::~QwtPlotBarChart() +{ + delete d_data; +} + +void QwtPlotBarChart::init() +{ + d_data = new PrivateData; + setData( new QwtPointSeriesData() ); +} + +//! \return QwtPlotItem::Rtti_PlotBarChart +int QwtPlotBarChart::rtti() const +{ + return QwtPlotItem::Rtti_PlotBarChart; +} + +/*! + Initialize data with an array of points + + \param samples Vector of points + \note QVector is implicitly shared + \note QPolygonF is derived from QVector<QPointF> +*/ +void QwtPlotBarChart::setSamples( + const QVector<QPointF> &samples ) +{ + setData( new QwtPointSeriesData( samples ) ); +} + +/*! + Initialize data with an array of doubles + + The indices in the array are taken as x coordinate, + while the doubles are interpreted as y values. + + \param samples Vector of y coordinates + \note QVector is implicitly shared +*/ +void QwtPlotBarChart::setSamples( + const QVector<double> &samples ) +{ + QVector<QPointF> points; + for ( int i = 0; i < samples.size(); i++ ) + points += QPointF( i, samples[ i ] ); + + setData( new QwtPointSeriesData( points ) ); +} + +/*! + Assign a series of samples + + setSamples() is just a wrapper for setData() without any additional + value - beside that it is easier to find for the developer. + + \param data Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. +*/ +void QwtPlotBarChart::setSamples( QwtSeriesData<QPointF> *data ) +{ + setData( data ); +} + +/*! + \brief Assign a symbol + + The bar chart will take the ownership of the symbol, hence the previously + set symbol will be delete by setting a new one. If \p symbol is + \c NULL no symbol will be drawn. + + \param symbol Symbol + \sa symbol() +*/ +void QwtPlotBarChart::setSymbol( QwtColumnSymbol *symbol ) +{ + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Current symbol or NULL, when no symbol has been assigned + \sa setSymbol() +*/ +const QwtColumnSymbol *QwtPlotBarChart::symbol() const +{ + return d_data->symbol; +} + +/*! + Set the mode that decides what to display on the legend + + In case of LegendBarTitles barTitle() needs to be overloaded + to return individual titles for each bar. + + \param mode New mode + \sa legendMode(), legendData(), barTitle(), QwtPlotItem::ItemAttribute + */ +void QwtPlotBarChart::setLegendMode( LegendMode mode ) +{ + if ( mode != d_data->legendMode ) + { + d_data->legendMode = mode; + legendChanged(); + } +} + +/*! + \return Legend mode + \sa setLegendMode() + */ +QwtPlotBarChart::LegendMode QwtPlotBarChart::legendMode() const +{ + return d_data->legendMode; +} + +/*! + \return Bounding rectangle of all samples. + For an empty series the rectangle is invalid. +*/ +QRectF QwtPlotBarChart::boundingRect() const +{ + const size_t numSamples = dataSize(); + if ( numSamples == 0 ) + return QwtPlotSeriesItem::boundingRect(); + + QRectF rect = QwtPlotSeriesItem::boundingRect(); + if ( rect.height() >= 0 ) + { + const double baseLine = baseline(); + + if ( rect.bottom() < baseLine ) + rect.setBottom( baseLine ); + + if ( rect.top() > baseLine ) + rect.setTop( baseLine ); + } + + if ( orientation() == Qt::Horizontal ) + rect.setRect( rect.y(), rect.x(), rect.height(), rect.width() ); + + return rect; +} + +/*! + Draw an interval of the bar chart + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rect of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted. If to < 0 the + curve will be painted to its last point. + + \sa drawSymbols() +*/ +void QwtPlotBarChart::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( to < 0 ) + to = dataSize() - 1; + + if ( from < 0 ) + from = 0; + + if ( from > to ) + return; + + + const QRectF br = data()->boundingRect(); + const QwtInterval interval( br.left(), br.right() ); + + painter->save(); + + for ( int i = from; i <= to; i++ ) + { + drawSample( painter, xMap, yMap, + canvasRect, interval, i, sample( i ) ); + } + + painter->restore(); +} + +/*! + Draw a sample + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param boundingInterval Bounding interval of sample values + \param index Index of the sample + \param sample Value of the sample + + \sa drawSeries() +*/ +void QwtPlotBarChart::drawSample( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, const QwtInterval &boundingInterval, + int index, const QPointF &sample ) const +{ + QwtColumnRect barRect; + + if ( orientation() == Qt::Horizontal ) + { + const double barHeight = sampleWidth( yMap, canvasRect.height(), + boundingInterval.width(), sample.y() ); + + const double x1 = xMap.transform( baseline() ); + const double x2 = xMap.transform( sample.y() ); + + const double y = yMap.transform( sample.x() ); + const double y1 = y - 0.5 * barHeight; + const double y2 = y + 0.5 * barHeight; + + barRect.direction = ( x1 < x2 ) ? + QwtColumnRect::LeftToRight : QwtColumnRect::RightToLeft; + + barRect.hInterval = QwtInterval( x1, x2 ).normalized(); + barRect.vInterval = QwtInterval( y1, y2 ); + } + else + { + const double barWidth = sampleWidth( xMap, canvasRect.width(), + boundingInterval.width(), sample.y() ); + + const double x = xMap.transform( sample.x() ); + const double x1 = x - 0.5 * barWidth; + const double x2 = x + 0.5 * barWidth; + + const double y1 = yMap.transform( baseline() ); + const double y2 = yMap.transform( sample.y() ); + + barRect.direction = ( y1 < y2 ) ? + QwtColumnRect::TopToBottom : QwtColumnRect::BottomToTop; + + barRect.hInterval = QwtInterval( x1, x2 ); + barRect.vInterval = QwtInterval( y1, y2 ).normalized(); + } + + drawBar( painter, index, sample, barRect ); +} + +/*! + Draw a bar + + \param painter Painter + \param sampleIndex Index of the sample represented by the bar + \param sample Value of the sample + \param rect Bounding rectangle of the bar + */ +void QwtPlotBarChart::drawBar( QPainter *painter, + int sampleIndex, const QPointF &sample, + const QwtColumnRect &rect ) const +{ + const QwtColumnSymbol *specialSym = + specialSymbol( sampleIndex, sample ); + + const QwtColumnSymbol *sym = specialSym; + if ( sym == NULL ) + sym = d_data->symbol; + + if ( sym ) + { + sym->draw( painter, rect ); + } + else + { + // we build a temporary default symbol + QwtColumnSymbol sym( QwtColumnSymbol::Box ); + sym.setLineWidth( 1 ); + sym.setFrameStyle( QwtColumnSymbol::Plain ); + sym.draw( painter, rect ); + } + + delete specialSym; +} + +/*! + Needs to be overloaded to return a + non default symbol for a specific sample + + \param sampleIndex Index of the sample represented by the bar + \param sample Value of the sample + + \return NULL, indicating to use the default symbol + */ +QwtColumnSymbol *QwtPlotBarChart::specialSymbol( + int sampleIndex, const QPointF &sample ) const +{ + Q_UNUSED( sampleIndex ); + Q_UNUSED( sample ); + + return NULL; +} + +/*! + \brief Return the title of a bar + + In LegendBarTitles mode the title is displayed on + the legend entry corresponding to a bar. + + The default implementation is a dummy, that is intended + to be overloaded. + + \param sampleIndex Index of the bar + \return An empty text + \sa LegendBarTitles + */ +QwtText QwtPlotBarChart::barTitle( int sampleIndex ) const +{ + Q_UNUSED( sampleIndex ); + return QwtText(); +} + +/*! + \brief Return all information, that is needed to represent + the item on the legend + + In case of LegendBarTitles an entry for each bar is returned, + otherwise the chart is represented like any other plot item + from its title() and the legendIcon(). + + \return Information, that is needed to represent the item on the legend + \sa title(), setLegendMode(), barTitle(), QwtLegend, QwtPlotLegendItem + */ +QList<QwtLegendData> QwtPlotBarChart::legendData() const +{ + QList<QwtLegendData> list; + + if ( d_data->legendMode == LegendBarTitles ) + { + const size_t numSamples = dataSize(); + for ( size_t i = 0; i < numSamples; i++ ) + { + QwtLegendData data; + + QVariant titleValue; + qVariantSetValue( titleValue, barTitle( i ) ); + data.setValue( QwtLegendData::TitleRole, titleValue ); + + if ( !legendIconSize().isEmpty() ) + { + QVariant iconValue; + qVariantSetValue( iconValue, + legendIcon( i, legendIconSize() ) ); + + data.setValue( QwtLegendData::IconRole, iconValue ); + } + + list += data; + } + } + else + { + return QwtPlotAbstractBarChart::legendData(); + } + + return list; +} + +/*! + \return Icon representing a bar or the chart on the legend + + When the legendMode() is LegendBarTitles the icon shows + the bar corresponding to index - otherwise the bar + displays the default symbol. + + \param index Index of the legend entry + \param size Icon size + + \sa setLegendMode(), drawBar(), + QwtPlotItem::setLegendIconSize(), QwtPlotItem::legendData() + */ +QwtGraphic QwtPlotBarChart::legendIcon( + int index, const QSizeF &size ) const +{ + QwtColumnRect column; + column.hInterval = QwtInterval( 0.0, size.width() - 1.0 ); + column.vInterval = QwtInterval( 0.0, size.height() - 1.0 ); + + QwtGraphic icon; + icon.setDefaultSize( size ); + icon.setRenderHint( QwtGraphic::RenderPensUnscaled, true ); + + QPainter painter( &icon ); + painter.setRenderHint( QPainter::Antialiasing, + testRenderHint( QwtPlotItem::RenderAntialiased ) ); + + int barIndex = -1; + if ( d_data->legendMode == QwtPlotBarChart::LegendBarTitles ) + barIndex = index; + + drawBar( &painter, barIndex, QPointF(), column ); + + return icon; +} diff --git a/libs/qwt/qwt_plot_barchart.h b/libs/qwt/qwt_plot_barchart.h new file mode 100644 index 0000000000..d47bfb9725 --- /dev/null +++ b/libs/qwt/qwt_plot_barchart.h @@ -0,0 +1,118 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_BAR_CHART_H +#define QWT_PLOT_BAR_CHART_H + +#include "qwt_global.h" +#include "qwt_plot_abstract_barchart.h" +#include "qwt_series_data.h" + +class QwtColumnRect; +class QwtColumnSymbol; + +/*! + \brief QwtPlotBarChart displays a series of a values as bars. + + Each bar might be customized individually by implementing + a specialSymbol(). Otherwise it is rendered using a default symbol. + + Depending on its orientation() the bars are displayed horizontally + or vertically. The bars cover the interval between the baseline() + and the value. + + By activating the LegendBarTitles mode each sample will have + its own entry on the legend. + + The most common use case of a bar chart is to display a + list of y coordinates, where the x coordinate is simply the index + in the list. But for other situations ( f.e. when values are related + to dates ) it is also possible to set x coordinates explicitly. + + \sa QwtPlotMultiBarChart, QwtPlotHistogram, QwtPlotCurve::Sticks, + QwtPlotSeriesItem::orientation(), QwtPlotAbstractBarChart::baseline() + */ +class QWT_EXPORT QwtPlotBarChart: + public QwtPlotAbstractBarChart, public QwtSeriesStore<QPointF> +{ +public: + /*! + \brief Legend modes. + + The default setting is QwtPlotBarChart::LegendChartTitle. + \sa setLegendMode(), legendMode() + */ + enum LegendMode + { + /*! + One entry on the legend showing the default symbol + and the title() of the chart + + \sa QwtPlotItem::title() + */ + LegendChartTitle, + + /*! + One entry for each value showing the individual symbol + of the corresponding bar and the bar title. + + \sa specialSymbol(), barTitle() + */ + LegendBarTitles + }; + + explicit QwtPlotBarChart( const QString &title = QString::null ); + explicit QwtPlotBarChart( const QwtText &title ); + + virtual ~QwtPlotBarChart(); + + virtual int rtti() const; + + void setSamples( const QVector<QPointF> & ); + void setSamples( const QVector<double> & ); + void setSamples( QwtSeriesData<QPointF> *series ); + + void setSymbol( QwtColumnSymbol * ); + const QwtColumnSymbol *symbol() const; + + void setLegendMode( LegendMode ); + LegendMode legendMode() const; + + virtual void drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual QRectF boundingRect() const; + + virtual QwtColumnSymbol *specialSymbol( + int sampleIndex, const QPointF& ) const; + + virtual QwtText barTitle( int sampleIndex ) const; + +protected: + virtual void drawSample( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, const QwtInterval &boundingInterval, + int index, const QPointF& sample ) const; + + virtual void drawBar( QPainter *, + int sampleIndex, const QPointF& point, + const QwtColumnRect & ) const; + + QList<QwtLegendData> legendData() const; + QwtGraphic legendIcon( int index, const QSizeF & ) const; + +private: + void init(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_canvas.cpp b/libs/qwt/qwt_plot_canvas.cpp index 1980bb46f4..0271713a8b 100644 --- a/libs/qwt/qwt_plot_canvas.cpp +++ b/libs/qwt/qwt_plot_canvas.cpp @@ -7,66 +7,541 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_plot_canvas.h" +#include "qwt_painter.h" +#include "qwt_null_paintdevice.h" +#include "qwt_math.h" +#include "qwt_plot.h" #include <qpainter.h> #include <qstyle.h> -#if QT_VERSION >= 0x040000 #include <qstyleoption.h> #include <qpaintengine.h> -#ifdef Q_WS_X11 -#include <qx11info_x11.h> +#include <qevent.h> + +class QwtStyleSheetRecorder: public QwtNullPaintDevice +{ +public: + QwtStyleSheetRecorder( const QSize &size ): + d_size( size ) + { + } + + virtual void updateState( const QPaintEngineState &state ) + { + if ( state.state() & QPaintEngine::DirtyPen ) + { + d_pen = state.pen(); + } + if ( state.state() & QPaintEngine::DirtyBrush ) + { + d_brush = state.brush(); + } + if ( state.state() & QPaintEngine::DirtyBrushOrigin ) + { + d_origin = state.brushOrigin(); + } + } + + virtual void drawRects(const QRectF *rects, int count ) + { + for ( int i = 0; i < count; i++ ) + border.rectList += rects[i]; + } + + virtual void drawPath( const QPainterPath &path ) + { + const QRectF rect( QPointF( 0.0, 0.0 ), d_size ); + if ( path.controlPointRect().contains( rect.center() ) ) + { + setCornerRects( path ); + alignCornerRects( rect ); + + background.path = path; + background.brush = d_brush; + background.origin = d_origin; + } + else + { + border.pathList += path; + } + } + + void setCornerRects( const QPainterPath &path ) + { + QPointF pos( 0.0, 0.0 ); + + for ( int i = 0; i < path.elementCount(); i++ ) + { + QPainterPath::Element el = path.elementAt(i); + switch( el.type ) + { + case QPainterPath::MoveToElement: + case QPainterPath::LineToElement: + { + pos.setX( el.x ); + pos.setY( el.y ); + break; + } + case QPainterPath::CurveToElement: + { + QRectF r( pos, QPointF( el.x, el.y ) ); + clipRects += r.normalized(); + + pos.setX( el.x ); + pos.setY( el.y ); + + break; + } + case QPainterPath::CurveToDataElement: + { + if ( clipRects.size() > 0 ) + { + QRectF r = clipRects.last(); + r.setCoords( + qMin( r.left(), el.x ), + qMin( r.top(), el.y ), + qMax( r.right(), el.x ), + qMax( r.bottom(), el.y ) + ); + clipRects.last() = r.normalized(); + } + break; + } + } + } + } + +protected: + virtual QSize sizeMetrics() const + { + return d_size; + } + +private: + void alignCornerRects( const QRectF &rect ) + { + for ( int i = 0; i < clipRects.size(); i++ ) + { + QRectF &r = clipRects[i]; + if ( r.center().x() < rect.center().x() ) + r.setLeft( rect.left() ); + else + r.setRight( rect.right() ); + + if ( r.center().y() < rect.center().y() ) + r.setTop( rect.top() ); + else + r.setBottom( rect.bottom() ); + } + } + + +public: + QVector<QRectF> clipRects; + + struct Border + { + QList<QPainterPath> pathList; + QList<QRectF> rectList; + QRegion clipRegion; + } border; + + struct Background + { + QPainterPath path; + QBrush brush; + QPointF origin; + } background; + +private: + const QSize d_size; + + QPen d_pen; + QBrush d_brush; + QPointF d_origin; +}; + +static void qwtDrawBackground( QPainter *painter, QwtPlotCanvas *canvas ) +{ + painter->save(); + + const QPainterPath borderClip = canvas->borderPath( canvas->rect() ); + if ( !borderClip.isEmpty() ) + painter->setClipPath( borderClip, Qt::IntersectClip ); + + const QBrush &brush = + canvas->palette().brush( canvas->backgroundRole() ); + + if ( brush.style() == Qt::TexturePattern ) + { + QPixmap pm( canvas->size() ); + QwtPainter::fillPixmap( canvas, pm ); + painter->drawPixmap( 0, 0, pm ); + } + else if ( brush.gradient() ) + { + QVector<QRect> rects; + + if ( brush.gradient()->coordinateMode() == QGradient::ObjectBoundingMode ) + { + rects += canvas->rect(); + } + else + { + rects = painter->clipRegion().rects(); + } + +#if 1 + bool useRaster = false; + + if ( painter->paintEngine()->type() == QPaintEngine::X11 ) + { + // Qt 4.7.1: gradients on X11 are broken ( subrects + + // QGradient::StretchToDeviceMode ) and horrible slow. + // As workaround we have to use the raster paintengine. + // Even if the QImage -> QPixmap translation is slow + // it is three times faster, than using X11 directly + + useRaster = true; + } #endif + if ( useRaster ) + { + QImage::Format format = QImage::Format_RGB32; + + const QGradientStops stops = brush.gradient()->stops(); + for ( int i = 0; i < stops.size(); i++ ) + { + if ( stops[i].second.alpha() != 255 ) + { + // don't use Format_ARGB32_Premultiplied. It's + // recommended by the Qt docs, but QPainter::drawImage() + // is horrible slow on X11. + + format = QImage::Format_ARGB32; + break; + } + } + + QImage image( canvas->size(), format ); + + QPainter p( &image ); + p.setPen( Qt::NoPen ); + p.setBrush( brush ); + + p.drawRects( rects ); + + p.end(); + + painter->drawImage( 0, 0, image ); + } + else + { + painter->setPen( Qt::NoPen ); + painter->setBrush( brush ); + + painter->drawRects( rects ); + } + } + else + { + painter->setPen( Qt::NoPen ); + painter->setBrush( brush ); + + painter->drawRects( painter->clipRegion().rects() ); + + } + + painter->restore(); +} + +static inline void qwtRevertPath( QPainterPath &path ) +{ + if ( path.elementCount() == 4 ) + { + QPainterPath::Element el0 = path.elementAt(0); + QPainterPath::Element el3 = path.elementAt(3); + + path.setElementPositionAt( 0, el3.x, el3.y ); + path.setElementPositionAt( 3, el0.x, el0.y ); + } +} + +static QPainterPath qwtCombinePathList( const QRectF &rect, + const QList<QPainterPath> &pathList ) +{ + if ( pathList.isEmpty() ) + return QPainterPath(); + + QPainterPath ordered[8]; // starting top left + + for ( int i = 0; i < pathList.size(); i++ ) + { + int index = -1; + QPainterPath subPath = pathList[i]; + + const QRectF br = pathList[i].controlPointRect(); + if ( br.center().x() < rect.center().x() ) + { + if ( br.center().y() < rect.center().y() ) + { + if ( qAbs( br.top() - rect.top() ) < + qAbs( br.left() - rect.left() ) ) + { + index = 1; + } + else + { + index = 0; + } + } + else + { + if ( qAbs( br.bottom() - rect.bottom() ) < + qAbs( br.left() - rect.left() ) ) + { + index = 6; + } + else + { + index = 7; + } + } + + if ( subPath.currentPosition().y() > br.center().y() ) + qwtRevertPath( subPath ); + } + else + { + if ( br.center().y() < rect.center().y() ) + { + if ( qAbs( br.top() - rect.top() ) < + qAbs( br.right() - rect.right() ) ) + { + index = 2; + } + else + { + index = 3; + } + } + else + { + if ( qAbs( br.bottom() - rect.bottom() ) < + qAbs( br.right() - rect.right() ) ) + { + index = 5; + } + else + { + index = 4; + } + } + if ( subPath.currentPosition().y() < br.center().y() ) + qwtRevertPath( subPath ); + } + ordered[index] = subPath; + } + + for ( int i = 0; i < 4; i++ ) + { + if ( ordered[ 2 * i].isEmpty() != ordered[2 * i + 1].isEmpty() ) + { + // we don't accept incomplete rounded borders + return QPainterPath(); + } + } + + + const QPolygonF corners( rect ); + + QPainterPath path; + //path.moveTo( rect.topLeft() ); + + for ( int i = 0; i < 4; i++ ) + { + if ( ordered[2 * i].isEmpty() ) + { + path.lineTo( corners[i] ); + } + else + { + path.connectPath( ordered[2 * i] ); + path.connectPath( ordered[2 * i + 1] ); + } + } + + path.closeSubpath(); + +#if 0 + return path.simplified(); +#else + return path; #endif -#include <qevent.h> -#include "qwt_painter.h" -#include "qwt_math.h" -#include "qwt_plot.h" -#include "qwt_paint_buffer.h" -#include "qwt_plot_canvas.h" +} + +static inline void qwtDrawStyledBackground( + QWidget *w, QPainter *painter ) +{ + QStyleOption opt; + opt.initFrom(w); + w->style()->drawPrimitive( QStyle::PE_Widget, &opt, painter, w); +} + +static QWidget *qwtBackgroundWidget( QWidget *w ) +{ + if ( w->parentWidget() == NULL ) + return w; + + if ( w->autoFillBackground() ) + { + const QBrush brush = w->palette().brush( w->backgroundRole() ); + if ( brush.color().alpha() > 0 ) + return w; + } + + if ( w->testAttribute( Qt::WA_StyledBackground ) ) + { + QImage image( 1, 1, QImage::Format_ARGB32 ); + image.fill( Qt::transparent ); + + QPainter painter( &image ); + painter.translate( -w->rect().center() ); + qwtDrawStyledBackground( w, &painter ); + painter.end(); + + if ( qAlpha( image.pixel( 0, 0 ) ) != 0 ) + return w; + } + + return qwtBackgroundWidget( w->parentWidget() ); +} + +static void qwtFillBackground( QPainter *painter, + QWidget *widget, const QVector<QRectF> &fillRects ) +{ + if ( fillRects.isEmpty() ) + return; + + QRegion clipRegion; + if ( painter->hasClipping() ) + clipRegion = painter->transform().map( painter->clipRegion() ); + else + clipRegion = widget->contentsRect(); + + // Try to find out which widget fills + // the unfilled areas of the styled background + + QWidget *bgWidget = qwtBackgroundWidget( widget->parentWidget() ); + + for ( int i = 0; i < fillRects.size(); i++ ) + { + const QRect rect = fillRects[i].toAlignedRect(); + if ( clipRegion.intersects( rect ) ) + { + QPixmap pm( rect.size() ); + QwtPainter::fillPixmap( bgWidget, pm, widget->mapTo( bgWidget, rect.topLeft() ) ); + painter->drawPixmap( rect, pm ); + } + } +} + +static void qwtFillBackground( QPainter *painter, QwtPlotCanvas *canvas ) +{ + QVector<QRectF> rects; + + if ( canvas->testAttribute( Qt::WA_StyledBackground ) ) + { + QwtStyleSheetRecorder recorder( canvas->size() ); + + QPainter p( &recorder ); + qwtDrawStyledBackground( canvas, &p ); + p.end(); + + if ( recorder.background.brush.isOpaque() ) + rects = recorder.clipRects; + else + rects += canvas->rect(); + } + else + { + const QRectF r = canvas->rect(); + const double radius = canvas->borderRadius(); + if ( radius > 0.0 ) + { + QSizeF sz( radius, radius ); + + rects += QRectF( r.topLeft(), sz ); + rects += QRectF( r.topRight() - QPointF( radius, 0 ), sz ); + rects += QRectF( r.bottomRight() - QPointF( radius, radius ), sz ); + rects += QRectF( r.bottomLeft() - QPointF( 0, radius ), sz ); + } + } + + qwtFillBackground( painter, canvas, rects); +} + class QwtPlotCanvas::PrivateData { public: PrivateData(): - focusIndicator(NoFocusIndicator), - paintAttributes(0), - cache(NULL) { + focusIndicator( NoFocusIndicator ), + borderRadius( 0 ), + paintAttributes( 0 ), + backingStore( NULL ) + { + styleSheet.hasBorder = false; } - ~PrivateData() { - delete cache; + ~PrivateData() + { + delete backingStore; } FocusIndicator focusIndicator; - int paintAttributes; - QPixmap *cache; + double borderRadius; + QwtPlotCanvas::PaintAttributes paintAttributes; + QPixmap *backingStore; + + struct StyleSheet + { + bool hasBorder; + QPainterPath borderPath; + QVector<QRectF> cornerRects; + + struct StyleSheetBackground + { + QBrush brush; + QPointF origin; + } background; + + } styleSheet; + }; -//! Sets a cross cursor, enables QwtPlotCanvas::PaintCached +/*! + \brief Constructor -QwtPlotCanvas::QwtPlotCanvas(QwtPlot *plot): - QFrame(plot) + \param plot Parent plot widget + \sa QwtPlot::setCanvas() +*/ +QwtPlotCanvas::QwtPlotCanvas( QwtPlot *plot ): + QFrame( plot ) { - d_data = new PrivateData; + setFrameStyle( QFrame::Panel | QFrame::Sunken ); + setLineWidth( 2 ); -#if QT_VERSION >= 0x040100 - setAutoFillBackground(true); -#endif + d_data = new PrivateData; -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#ifndef QT_NO_CURSOR - setCursor(Qt::crossCursor); -#endif -#else #ifndef QT_NO_CURSOR - setCursor(Qt::CrossCursor); + setCursor( Qt::CrossCursor ); #endif -#endif // >= 0x040000 - setPaintAttribute(PaintCached, true); - setPaintAttribute(PaintPacked, true); + setAutoFillBackground( true ); + setPaintAttribute( QwtPlotCanvas::BackingStore, true ); + setPaintAttribute( QwtPlotCanvas::Opaque, true ); + setPaintAttribute( QwtPlotCanvas::HackStyledBackground, true ); } //! Destructor @@ -78,21 +553,13 @@ QwtPlotCanvas::~QwtPlotCanvas() //! Return parent plot widget QwtPlot *QwtPlotCanvas::plot() { - QWidget *w = parentWidget(); - if ( w && w->inherits("QwtPlot") ) - return (QwtPlot *)w; - - return NULL; + return qobject_cast<QwtPlot *>( parent() ); } //! Return parent plot widget const QwtPlot *QwtPlotCanvas::plot() const { - const QWidget *w = parentWidget(); - if ( w && w->inherits("QwtPlot") ) - return (QwtPlot *)w; - - return NULL; + return qobject_cast<const QwtPlot *>( parent() ); } /*! @@ -101,13 +568,11 @@ const QwtPlot *QwtPlotCanvas::plot() const \param attribute Paint attribute \param on On/Off - The default setting enables PaintCached and PaintPacked - - \sa testPaintAttribute(), drawCanvas(), drawContents(), paintCache() + \sa testPaintAttribute(), backingStore() */ -void QwtPlotCanvas::setPaintAttribute(PaintAttribute attribute, bool on) +void QwtPlotCanvas::setPaintAttribute( PaintAttribute attribute, bool on ) { - if ( bool(d_data->paintAttributes & attribute) == on ) + if ( bool( d_data->paintAttributes & attribute ) == on ) return; if ( on ) @@ -115,76 +580,78 @@ void QwtPlotCanvas::setPaintAttribute(PaintAttribute attribute, bool on) else d_data->paintAttributes &= ~attribute; - switch(attribute) { - case PaintCached: { - if ( on ) { - if ( d_data->cache == NULL ) - d_data->cache = new QPixmap(); - - if ( isVisible() ) { - const QRect cr = contentsRect(); - *d_data->cache = QPixmap::grabWidget(this, - cr.x(), cr.y(), cr.width(), cr.height() ); + switch ( attribute ) + { + case BackingStore: + { + if ( on ) + { + if ( d_data->backingStore == NULL ) + d_data->backingStore = new QPixmap(); + + if ( isVisible() ) + { +#if QT_VERSION >= 0x050000 + *d_data->backingStore = grab( rect() ); +#else + *d_data->backingStore = + QPixmap::grabWidget( this, rect() ); +#endif + } } - } else { - delete d_data->cache; - d_data->cache = NULL; + else + { + delete d_data->backingStore; + d_data->backingStore = NULL; + } + break; } - break; - } - case PaintPacked: { - /* - If not visible, changing of the background mode - is delayed until it becomes visible. This tries to avoid - looking through the canvas when the canvas is shown the first - time. - */ - - if ( on == false || isVisible() ) - QwtPlotCanvas::setSystemBackground(!on); + case Opaque: + { + if ( on ) + setAttribute( Qt::WA_OpaquePaintEvent, true ); - break; - } + break; + } + case HackStyledBackground: + case ImmediatePaint: + { + break; + } } } /*! - Test wether a paint attribute is enabled + Test whether a paint attribute is enabled \param attribute Paint attribute - \return true if the attribute is enabled + \return true, when attribute is enabled \sa setPaintAttribute() */ -bool QwtPlotCanvas::testPaintAttribute(PaintAttribute attribute) const -{ - return (d_data->paintAttributes & attribute) != 0; -} - -//! Return the paint cache, might be null -QPixmap *QwtPlotCanvas::paintCache() +bool QwtPlotCanvas::testPaintAttribute( PaintAttribute attribute ) const { - return d_data->cache; + return d_data->paintAttributes & attribute; } -//! Return the paint cache, might be null -const QPixmap *QwtPlotCanvas::paintCache() const +//! \return Backing store, might be null +const QPixmap *QwtPlotCanvas::backingStore() const { - return d_data->cache; + return d_data->backingStore; } -//! Invalidate the internal paint cache -void QwtPlotCanvas::invalidatePaintCache() +//! Invalidate the internal backing store +void QwtPlotCanvas::invalidateBackingStore() { - if ( d_data->cache ) - *d_data->cache = QPixmap(); + if ( d_data->backingStore ) + *d_data->backingStore = QPixmap(); } /*! Set the focus indicator - \sa FocusIndicator, focusIndicator + \sa FocusIndicator, focusIndicator() */ -void QwtPlotCanvas::setFocusIndicator(FocusIndicator focusIndicator) +void QwtPlotCanvas::setFocusIndicator( FocusIndicator focusIndicator ) { d_data->focusIndicator = focusIndicator; } @@ -192,165 +659,439 @@ void QwtPlotCanvas::setFocusIndicator(FocusIndicator focusIndicator) /*! \return Focus indicator - \sa FocusIndicator, setFocusIndicator + \sa FocusIndicator, setFocusIndicator() */ QwtPlotCanvas::FocusIndicator QwtPlotCanvas::focusIndicator() const { return d_data->focusIndicator; } -void QwtPlotCanvas::hideEvent(QHideEvent *e) +/*! + Set the radius for the corners of the border frame + + \param radius Radius of a rounded corner + \sa borderRadius() +*/ +void QwtPlotCanvas::setBorderRadius( double radius ) { - QFrame::hideEvent(e); + d_data->borderRadius = qMax( 0.0, radius ); +} + +/*! + \return Radius for the corners of the border frame + \sa setBorderRadius() +*/ +double QwtPlotCanvas::borderRadius() const +{ + return d_data->borderRadius; +} - if ( d_data->paintAttributes & PaintPacked ) { - // enable system background to avoid the "looking through - // the canvas" effect, for the next show +/*! + Qt event handler for QEvent::PolishRequest and QEvent::StyleChange - setSystemBackground(true); + \param event Qt Event + \return See QFrame::event() +*/ +bool QwtPlotCanvas::event( QEvent *event ) +{ + if ( event->type() == QEvent::PolishRequest ) + { + if ( testPaintAttribute( QwtPlotCanvas::Opaque ) ) + { + // Setting a style sheet changes the + // Qt::WA_OpaquePaintEvent attribute, but we insist + // on painting the background. + + setAttribute( Qt::WA_OpaquePaintEvent, true ); + } } + + if ( event->type() == QEvent::PolishRequest || + event->type() == QEvent::StyleChange ) + { + updateStyleSheetInfo(); + } + + return QFrame::event( event ); } -//! Paint event -void QwtPlotCanvas::paintEvent(QPaintEvent *event) +/*! + Paint event + \param event Paint event +*/ +void QwtPlotCanvas::paintEvent( QPaintEvent *event ) { -#if QT_VERSION >= 0x040000 - QPainter painter(this); + QPainter painter( this ); + painter.setClipRegion( event->region() ); + + if ( testPaintAttribute( QwtPlotCanvas::BackingStore ) && + d_data->backingStore != NULL ) + { + QPixmap &bs = *d_data->backingStore; + if ( bs.size() != size() ) + { + bs = QwtPainter::backingStore( this, size() ); - if ( !contentsRect().contains( event->rect() ) ) { - painter.save(); - painter.setClipRegion( event->region() & frameRect() ); - drawFrame( &painter ); - painter.restore(); + if ( testAttribute(Qt::WA_StyledBackground) ) + { + QPainter p( &bs ); + qwtFillBackground( &p, this ); + drawCanvas( &p, true ); + } + else + { + QPainter p; + if ( d_data->borderRadius <= 0.0 ) + { + QwtPainter::fillPixmap( this, bs ); + p.begin( &bs ); + drawCanvas( &p, false ); + } + else + { + p.begin( &bs ); + qwtFillBackground( &p, this ); + drawCanvas( &p, true ); + } + + if ( frameWidth() > 0 ) + drawBorder( &p ); + } + } + + painter.drawPixmap( 0, 0, *d_data->backingStore ); } + else + { + if ( testAttribute(Qt::WA_StyledBackground ) ) + { + if ( testAttribute( Qt::WA_OpaquePaintEvent ) ) + { + qwtFillBackground( &painter, this ); + drawCanvas( &painter, true ); + } + else + { + drawCanvas( &painter, false ); + } + } + else + { + if ( testAttribute( Qt::WA_OpaquePaintEvent ) ) + { + if ( autoFillBackground() ) + { + qwtFillBackground( &painter, this ); + qwtDrawBackground( &painter, this ); + } + } + else + { + if ( borderRadius() > 0.0 ) + { + QPainterPath clipPath; + clipPath.addRect( rect() ); + clipPath = clipPath.subtracted( borderPath( rect() ) ); + + painter.save(); + + painter.setClipPath( clipPath, Qt::IntersectClip ); + qwtFillBackground( &painter, this ); + qwtDrawBackground( &painter, this ); + + painter.restore(); + } + } - painter.setClipRegion(event->region() & contentsRect()); + drawCanvas( &painter, false ); - drawContents( &painter ); -#else // QT_VERSION < 0x040000 - QFrame::paintEvent(event); -#endif + if ( frameWidth() > 0 ) + drawBorder( &painter ); + } + } - if ( d_data->paintAttributes & PaintPacked ) - setSystemBackground(false); + if ( hasFocus() && focusIndicator() == CanvasFocusIndicator ) + drawFocusIndicator( &painter ); } -//! Redraw the canvas, and focus rect -void QwtPlotCanvas::drawContents(QPainter *painter) +void QwtPlotCanvas::drawCanvas( QPainter *painter, bool withBackground ) { - if ( d_data->paintAttributes & PaintCached && d_data->cache - && d_data->cache->size() == contentsRect().size() ) { - painter->drawPixmap(contentsRect().topLeft(), *d_data->cache); - } else { - QwtPlot *plot = ((QwtPlot *)parent()); - const bool doAutoReplot = plot->autoReplot(); - plot->setAutoReplot(false); + bool hackStyledBackground = false; + + if ( withBackground && testAttribute( Qt::WA_StyledBackground ) + && testPaintAttribute( HackStyledBackground ) ) + { + // Antialiasing rounded borders is done by + // inserting pixels with colors between the + // border color and the color on the canvas, + // When the border is painted before the plot items + // these colors are interpolated for the canvas + // and the plot items need to be clipped excluding + // the anialiased pixels. In situations, where + // the plot items fill the area at the rounded + // borders this is noticeable. + // The only way to avoid these annoying "artefacts" + // is to paint the border on top of the plot items. + + if ( d_data->styleSheet.hasBorder && + !d_data->styleSheet.borderPath.isEmpty() ) + { + // We have a border with at least one rounded corner + hackStyledBackground = true; + } + } - drawCanvas(painter); + if ( withBackground ) + { + painter->save(); - plot->setAutoReplot(doAutoReplot); + if ( testAttribute( Qt::WA_StyledBackground ) ) + { + if ( hackStyledBackground ) + { + // paint background without border + + painter->setPen( Qt::NoPen ); + painter->setBrush( d_data->styleSheet.background.brush ); + painter->setBrushOrigin( d_data->styleSheet.background.origin ); + painter->setClipPath( d_data->styleSheet.borderPath ); + painter->drawRect( contentsRect() ); + } + else + { + qwtDrawStyledBackground( this, painter ); + } + } + else if ( autoFillBackground() ) + { + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().brush( backgroundRole() ) ); + + if ( d_data->borderRadius > 0.0 && ( rect() == frameRect() ) ) + { + if ( frameWidth() > 0 ) + { + painter->setClipPath( borderPath( rect() ) ); + painter->drawRect( rect() ); + } + else + { + painter->setRenderHint( QPainter::Antialiasing, true ); + painter->drawPath( borderPath( rect() ) ); + } + } + else + { + painter->drawRect( rect() ); + } + } + + painter->restore(); } - if ( hasFocus() && focusIndicator() == CanvasFocusIndicator ) - drawFocusIndicator(painter); + painter->save(); + + if ( !d_data->styleSheet.borderPath.isEmpty() ) + { + painter->setClipPath( + d_data->styleSheet.borderPath, Qt::IntersectClip ); + } + else + { + if ( d_data->borderRadius > 0.0 ) + painter->setClipPath( borderPath( frameRect() ), Qt::IntersectClip ); + else + painter->setClipRect( contentsRect(), Qt::IntersectClip ); + } + + plot()->drawCanvas( painter ); + + painter->restore(); + + if ( withBackground && hackStyledBackground ) + { + // Now paint the border on top + QStyleOptionFrame opt; + opt.initFrom(this); + style()->drawPrimitive( QStyle::PE_Frame, &opt, painter, this); + } } /*! - Draw the the canvas - - Paints all plot items to the contentsRect(), using QwtPlot::drawCanvas - and updates the paint cache. + Draw the border of the plot canvas - \sa QwtPlot::drawCanvas, setPaintAttributes(), testPaintAttributes() + \param painter Painter + \sa setBorderRadius() */ - -void QwtPlotCanvas::drawCanvas(QPainter *painter) +void QwtPlotCanvas::drawBorder( QPainter *painter ) { - if ( !contentsRect().isValid() ) - return; + if ( d_data->borderRadius > 0 ) + { + if ( frameWidth() > 0 ) + { + QwtPainter::drawRoundedFrame( painter, QRectF( frameRect() ), + d_data->borderRadius, d_data->borderRadius, + palette(), frameWidth(), frameStyle() ); + } + } + else + { +#if QT_VERSION >= 0x040500 + QStyleOptionFrameV3 opt; + opt.init(this); - QBrush bgBrush; -#if QT_VERSION >= 0x040000 - bgBrush = palette().brush(backgroundRole()); -#else - QColorGroup::ColorRole role = - QPalette::backgroundRoleFromMode( backgroundMode() ); - bgBrush = colorGroup().brush( role ); + int frameShape = frameStyle() & QFrame::Shape_Mask; + int frameShadow = frameStyle() & QFrame::Shadow_Mask; + + opt.frameShape = QFrame::Shape( int( opt.frameShape ) | frameShape ); +#if 0 + opt.rect = frameRect(); #endif - if ( d_data->paintAttributes & PaintCached && d_data->cache ) { - *d_data->cache = QPixmap(contentsRect().size()); + switch (frameShape) + { + case QFrame::Box: + case QFrame::HLine: + case QFrame::VLine: + case QFrame::StyledPanel: + case QFrame::Panel: + { + opt.lineWidth = lineWidth(); + opt.midLineWidth = midLineWidth(); + break; + } + default: + { + opt.lineWidth = frameWidth(); + break; + } + } + + if ( frameShadow == Sunken ) + opt.state |= QStyle::State_Sunken; + else if ( frameShadow == Raised ) + opt.state |= QStyle::State_Raised; -#ifdef Q_WS_X11 -#if QT_VERSION >= 0x040000 - if ( d_data->cache->x11Info().screen() != x11Info().screen() ) - d_data->cache->x11SetScreen(x11Info().screen()); + style()->drawControl(QStyle::CE_ShapedFrame, &opt, painter, this); #else - if ( d_data->cache->x11Screen() != x11Screen() ) - d_data->cache->x11SetScreen(x11Screen()); -#endif + drawFrame( painter ); #endif + } +} - if ( d_data->paintAttributes & PaintPacked ) { - QPainter bgPainter(d_data->cache); - bgPainter.setPen(Qt::NoPen); +/*! + Resize event + \param event Resize event +*/ +void QwtPlotCanvas::resizeEvent( QResizeEvent *event ) +{ + QFrame::resizeEvent( event ); + updateStyleSheetInfo(); +} - bgPainter.setBrush(bgBrush); - bgPainter.drawRect(d_data->cache->rect()); - } else - d_data->cache->fill(this, d_data->cache->rect().topLeft()); +/*! + Draw the focus indication + \param painter Painter +*/ +void QwtPlotCanvas::drawFocusIndicator( QPainter *painter ) +{ + const int margin = 1; - QPainter cachePainter(d_data->cache); - cachePainter.translate(-contentsRect().x(), - -contentsRect().y()); + QRect focusRect = contentsRect(); + focusRect.setRect( focusRect.x() + margin, focusRect.y() + margin, + focusRect.width() - 2 * margin, focusRect.height() - 2 * margin ); - ((QwtPlot *)parent())->drawCanvas(&cachePainter); + QwtPainter::drawFocusRect( painter, this, focusRect ); +} - cachePainter.end(); +/*! + Invalidate the paint cache and repaint the canvas + \sa invalidatePaintCache() +*/ +void QwtPlotCanvas::replot() +{ + invalidateBackingStore(); - painter->drawPixmap(contentsRect(), *d_data->cache); - } else { -#if QT_VERSION >= 0x040000 - if ( d_data->paintAttributes & PaintPacked ) -#endif - { - painter->save(); + if ( testPaintAttribute( QwtPlotCanvas::ImmediatePaint ) ) + repaint( contentsRect() ); + else + update( contentsRect() ); +} - painter->setPen(Qt::NoPen); - painter->setBrush(bgBrush); - painter->drawRect(contentsRect()); +//! Update the cached information about the current style sheet +void QwtPlotCanvas::updateStyleSheetInfo() +{ + if ( !testAttribute(Qt::WA_StyledBackground ) ) + return; - painter->restore(); + QwtStyleSheetRecorder recorder( size() ); + + QPainter painter( &recorder ); + + QStyleOption opt; + opt.initFrom(this); + style()->drawPrimitive( QStyle::PE_Widget, &opt, &painter, this); + + painter.end(); + + d_data->styleSheet.hasBorder = !recorder.border.rectList.isEmpty(); + d_data->styleSheet.cornerRects = recorder.clipRects; + + if ( recorder.background.path.isEmpty() ) + { + if ( !recorder.border.rectList.isEmpty() ) + { + d_data->styleSheet.borderPath = + qwtCombinePathList( rect(), recorder.border.pathList ); } - - ((QwtPlot *)parent())->drawCanvas(painter); + } + else + { + d_data->styleSheet.borderPath = recorder.background.path; + d_data->styleSheet.background.brush = recorder.background.brush; + d_data->styleSheet.background.origin = recorder.background.origin; } } -//! Draw the focus indication -void QwtPlotCanvas::drawFocusIndicator(QPainter *painter) +/*! + Calculate the painter path for a styled or rounded border + + When the canvas has no styled background or rounded borders + the painter path is empty. + + \param rect Bounding rectangle of the canvas + \return Painter path, that can be used for clipping +*/ +QPainterPath QwtPlotCanvas::borderPath( const QRect &rect ) const { - const int margin = 1; + if ( testAttribute(Qt::WA_StyledBackground ) ) + { + QwtStyleSheetRecorder recorder( rect.size() ); - QRect focusRect = contentsRect(); - focusRect.setRect(focusRect.x() + margin, focusRect.y() + margin, - focusRect.width() - 2 * margin, focusRect.height() - 2 * margin); + QPainter painter( &recorder ); - QwtPainter::drawFocusRect(painter, this, focusRect); -} + QStyleOption opt; + opt.initFrom(this); + opt.rect = rect; + style()->drawPrimitive( QStyle::PE_Widget, &opt, &painter, this); -void QwtPlotCanvas::setSystemBackground(bool on) -{ -#if QT_VERSION < 0x040000 - if ( backgroundMode() == Qt::NoBackground ) { - if ( on ) - setBackgroundMode(Qt::PaletteBackground); - } else { - if ( !on ) - setBackgroundMode(Qt::NoBackground); + painter.end(); + + if ( !recorder.background.path.isEmpty() ) + return recorder.background.path; + + if ( !recorder.border.rectList.isEmpty() ) + return qwtCombinePathList( rect, recorder.border.pathList ); } -#else - if ( testAttribute(Qt::WA_NoSystemBackground) == on ) - setAttribute(Qt::WA_NoSystemBackground, !on); -#endif + else if ( d_data->borderRadius > 0.0 ) + { + double fw2 = frameWidth() * 0.5; + QRectF r = QRectF(rect).adjusted( fw2, fw2, -fw2, -fw2 ); + + QPainterPath path; + path.addRoundedRect( r, d_data->borderRadius, d_data->borderRadius ); + return path; + } + + return QPainterPath(); } diff --git a/libs/qwt/qwt_plot_canvas.h b/libs/qwt/qwt_plot_canvas.h index f3ff0ffa21..daea8a086f 100644 --- a/libs/qwt/qwt_plot_canvas.h +++ b/libs/qwt/qwt_plot_canvas.h @@ -7,109 +7,165 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_PLOT_CANVAS_H #define QWT_PLOT_CANVAS_H -#include <qframe.h> -#include <qpen.h> #include "qwt_global.h" +#include <qframe.h> +#include <qpainterpath.h> class QwtPlot; class QPixmap; /*! - Canvas of a QwtPlot. - \sa QwtPlot + \brief Canvas of a QwtPlot. + + Canvas is the widget where all plot items are displayed + + \sa QwtPlot::setCanvas(), QwtPlotGLCanvas */ class QWT_EXPORT QwtPlotCanvas : public QFrame { Q_OBJECT + Q_PROPERTY( double borderRadius READ borderRadius WRITE setBorderRadius ) + public: /*! \brief Paint attributes - - PaintCached\n - Paint double buffered and reuse the content of the pixmap buffer - for some spontaneous repaints that happen when a plot gets unhidden, - deiconified or changes the focus. - Disabling the cache will improve the performance for - incremental paints (using QwtPlotCurve::draw). + The default setting enables BackingStore and Opaque. - - PaintPacked\n - Suppress system background repaints and paint it together with - the canvas contents. - Painting packed might avoid flickering for expensive repaints, - when there is a notable gap between painting the background - and the plot contents. - - The default setting enables PaintCached and PaintPacked - - \sa setPaintAttribute(), testPaintAttribute(), paintCache() + \sa setPaintAttribute(), testPaintAttribute() */ - enum PaintAttribute { - PaintCached = 1, - PaintPacked = 2 + enum PaintAttribute + { + /*! + \brief Paint double buffered reusing the content + of the pixmap buffer when possible. + + Using a backing store might improve the performance + significantly, when working with widget overlays ( like rubber bands ). + Disabling the cache might improve the performance for + incremental paints (using QwtPlotDirectPainter ). + + \sa backingStore(), invalidateBackingStore() + */ + BackingStore = 1, + + /*! + \brief Try to fill the complete contents rectangle + of the plot canvas + + When using styled backgrounds Qt assumes, that the + canvas doesn't fill its area completely + ( f.e because of rounded borders ) and fills the area + below the canvas. When this is done with gradients it might + result in a serious performance bottleneck - depending on the size. + + When the Opaque attribute is enabled the canvas tries to + identify the gaps with some heuristics and to fill those only. + + \warning Will not work for semitransparent backgrounds + */ + Opaque = 2, + + /*! + \brief Try to improve painting of styled backgrounds + + QwtPlotCanvas supports the box model attributes for + customizing the layout with style sheets. Unfortunately + the design of Qt style sheets has no concept how to + handle backgrounds with rounded corners - beside of padding. + + When HackStyledBackground is enabled the plot canvas tries + to separate the background from the background border + by reverse engineering to paint the background before and + the border after the plot items. In this order the border + gets perfectly antialiased and you can avoid some pixel + artifacts in the corners. + */ + HackStyledBackground = 4, + + /*! + When ImmediatePaint is set replot() calls repaint() + instead of update(). + + \sa replot(), QWidget::repaint(), QWidget::update() + */ + ImmediatePaint = 8 }; + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + /*! \brief Focus indicator - - - NoFocusIndicator\n - Don't paint a focus indicator - - - CanvasFocusIndicator\n - The focus is related to the complete canvas. - Paint the focus indicator using paintFocus() - - - ItemFocusIndicator\n - The focus is related to an item (curve, point, ...) on - the canvas. It is up to the application to display a - focus indication using f.e. highlighting. - + The default setting is NoFocusIndicator \sa setFocusIndicator(), focusIndicator(), paintFocus() */ - enum FocusIndicator { + enum FocusIndicator + { + //! Don't paint a focus indicator NoFocusIndicator, + + /*! + The focus is related to the complete canvas. + Paint the focus indicator using paintFocus() + */ CanvasFocusIndicator, + + /*! + The focus is related to an item (curve, point, ...) on + the canvas. It is up to the application to display a + focus indication using f.e. highlighting. + */ ItemFocusIndicator }; - explicit QwtPlotCanvas(QwtPlot *); + explicit QwtPlotCanvas( QwtPlot * = NULL ); virtual ~QwtPlotCanvas(); QwtPlot *plot(); const QwtPlot *plot() const; - void setFocusIndicator(FocusIndicator); + void setFocusIndicator( FocusIndicator ); FocusIndicator focusIndicator() const; - void setPaintAttribute(PaintAttribute, bool on = true); - bool testPaintAttribute(PaintAttribute) const; + void setBorderRadius( double ); + double borderRadius() const; - QPixmap *paintCache(); - const QPixmap *paintCache() const; - void invalidatePaintCache(); + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; -protected: - virtual void hideEvent(QHideEvent *); + const QPixmap *backingStore() const; + void invalidateBackingStore(); - virtual void paintEvent(QPaintEvent *); + virtual bool event( QEvent * ); - virtual void drawContents(QPainter *); - virtual void drawFocusIndicator(QPainter *); + Q_INVOKABLE QPainterPath borderPath( const QRect & ) const; - void drawCanvas(QPainter *painter = NULL); +public Q_SLOTS: + void replot(); + +protected: + virtual void paintEvent( QPaintEvent * ); + virtual void resizeEvent( QResizeEvent * ); + + virtual void drawFocusIndicator( QPainter * ); + virtual void drawBorder( QPainter * ); + + void updateStyleSheetInfo(); private: - void setSystemBackground(bool); + void drawCanvas( QPainter *, bool withBackground ); class PrivateData; PrivateData *d_data; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCanvas::PaintAttributes ) + #endif diff --git a/libs/qwt/qwt_plot_curve.cpp b/libs/qwt/qwt_plot_curve.cpp index fd744207c5..140cc5996a 100644 --- a/libs/qwt/qwt_plot_curve.cpp +++ b/libs/qwt/qwt_plot_curve.cpp @@ -7,260 +7,111 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qpainter.h> -#include <qpixmap.h> -#include <qbitarray.h> -#include "qwt_global.h" -#include "qwt_legend.h" -#include "qwt_legend_item.h" -#include "qwt_data.h" -#include "qwt_scale_map.h" -#include "qwt_double_rect.h" +#include "qwt_plot_curve.h" +#include "qwt_point_data.h" #include "qwt_math.h" #include "qwt_clipper.h" #include "qwt_painter.h" +#include "qwt_scale_map.h" #include "qwt_plot.h" -#include "qwt_plot_canvas.h" #include "qwt_curve_fitter.h" #include "qwt_symbol.h" -#include "qwt_plot_curve.h" - -#define SCALE_PEN 0 - -#if QT_VERSION < 0x040000 -#include <qguardedptr.h> -#else -#include <qpointer.h> -#endif - -#if QT_VERSION >= 0x040000 - -#include <qevent.h> -#include <qpaintengine.h> - -class QwtPlotCurvePaintHelper: public QObject -{ -public: - QwtPlotCurvePaintHelper(const QwtPlotCurve *curve, int from, int to): - _curve(curve), - _from(from), - _to(to) { - } - - virtual bool eventFilter(QObject *, QEvent *event) { - if ( event->type() == QEvent::Paint ) { - _curve->draw(_from, _to); - return true; - } - return false; - } -private: - const QwtPlotCurve *_curve; - int _from; - int _to; -}; - -#endif // QT_VERSION >= 0x040000 - -// Creating and initializing a QPainter is an -// expensive operation. So we keep an painter -// open for situations, where we paint outside -// of paint events. This improves the performance -// of incremental painting like in the realtime -// example a lot. -// But it is not possible to have more than -// one QPainter open at the same time. So we -// need to close it before regular paint events -// are processed. +#include "qwt_point_mapper.h" +#include <qpainter.h> +#include <qpixmap.h> +#include <qalgorithms.h> +#include <qmath.h> -class QwtGuardedPainter: public QObject +static void qwtUpdateLegendIconSize( QwtPlotCurve *curve ) { -public: - ~QwtGuardedPainter() { - end(); - } - - QPainter *begin(QwtPlotCanvas *canvas) { - _canvas = canvas; - - QMap<QwtPlotCanvas *, QPainter *>::iterator it = _map.find(_canvas); - if ( it == _map.end() ) { - QPainter *painter = new QPainter(_canvas); - painter->setClipping(true); - painter->setClipRect(_canvas->contentsRect()); + if ( curve->symbol() && + curve->testLegendAttribute( QwtPlotCurve::LegendShowSymbol ) ) + { + QSize sz = curve->symbol()->boundingRect().size(); + sz += QSize( 2, 2 ); // margin - it = _map.insert(_canvas, painter); - _canvas->installEventFilter(this); - } -#if QT_VERSION < 0x040000 - return it.data(); -#else - return it.value(); -#endif - } + if ( curve->testLegendAttribute( QwtPlotCurve::LegendShowLine ) ) + { + // Avoid, that the line is completely covered by the symbol - void end() { - if ( _canvas ) { - QMap<QwtPlotCanvas *, QPainter *>::iterator it = _map.find(_canvas); - if ( it != _map.end() ) { - _canvas->removeEventFilter(this); + int w = qCeil( 1.5 * sz.width() ); + if ( w % 2 ) + w++; -#if QT_VERSION < 0x040000 - delete it.data(); -#else - delete it.value(); -#endif - _map.erase(it); - } + sz.setWidth( qMax( 8, w ) ); } - } - virtual bool eventFilter(QObject *, QEvent *event) { - if ( event->type() == QEvent::Paint ) - end(); - - return false; + curve->setLegendIconSize( sz ); } - -private: -#if QT_VERSION < 0x040000 - QGuardedPtr<QwtPlotCanvas> _canvas; -#else - QPointer<QwtPlotCanvas> _canvas; -#endif - static QMap<QwtPlotCanvas *, QPainter *> _map; -}; - -QMap<QwtPlotCanvas *, QPainter *> QwtGuardedPainter::_map; - -static QwtPolygon clipPolygon(QPainter *painter, int attributes, - const QwtPolygon &polygon) -{ - bool doClipping = attributes & QwtPlotCurve::ClipPolygons; - QRect clipRect = painter->window(); - - if ( !doClipping ) { -#if QT_VERSION >= 0x040000 - const QPaintEngine *pe = painter->paintEngine(); - if ( pe && pe->type() == QPaintEngine::SVG ) -#else - if ( painter->device()->devType() == QInternal::Picture ) -#endif - { - // The SVG paint engine ignores any clipping, - // so we enable polygon clipping. - - doClipping = true; - if ( painter->hasClipping() ) - clipRect &= painter->clipRegion().boundingRect(); - } - } - - if ( doClipping ) - return QwtClipper::clipPolygon(clipRect, polygon); - - return polygon; } -static int verifyRange(int size, int &i1, int &i2) +static int qwtVerifyRange( int size, int &i1, int &i2 ) { - if (size < 1) + if ( size < 1 ) return 0; - i1 = qwtLim(i1, 0, size-1); - i2 = qwtLim(i2, 0, size-1); + i1 = qBound( 0, i1, size - 1 ); + i2 = qBound( 0, i2, size - 1 ); if ( i1 > i2 ) - qSwap(i1, i2); + qSwap( i1, i2 ); - return (i2 - i1 + 1); + return ( i2 - i1 + 1 ); } class QwtPlotCurve::PrivateData { public: - class PixelMatrix: private QBitArray - { - public: - PixelMatrix(const QRect& rect): - QBitArray(rect.width() * rect.height()), - _rect(rect) { - fill(false); - } - - inline bool testPixel(const QPoint& pos) { - if ( !_rect.contains(pos) ) - return false; - - const int idx = _rect.width() * (pos.y() - _rect.y()) + - (pos.x() - _rect.x()); - - const bool marked = testBit(idx); - if ( !marked ) - setBit(idx, true); - - return !marked; - } - - private: - QRect _rect; - }; - PrivateData(): - curveType(Yfx), - style(QwtPlotCurve::Lines), - reference(0.0), - attributes(0), - paintAttributes(0) { - symbol = new QwtSymbol(); - pen = QPen(Qt::black); + style( QwtPlotCurve::Lines ), + baseline( 0.0 ), + symbol( NULL ), + attributes( 0 ), + paintAttributes( + QwtPlotCurve::ClipPolygons | QwtPlotCurve::FilterPoints ), + legendAttributes( 0 ) + { + pen = QPen( Qt::black ); curveFitter = new QwtSplineCurveFitter; } - ~PrivateData() { + ~PrivateData() + { delete symbol; delete curveFitter; } - QwtPlotCurve::CurveType curveType; QwtPlotCurve::CurveStyle style; - double reference; + double baseline; - QwtSymbol *symbol; + const QwtSymbol *symbol; QwtCurveFitter *curveFitter; QPen pen; QBrush brush; - int attributes; - int paintAttributes; + QwtPlotCurve::CurveAttributes attributes; + QwtPlotCurve::PaintAttributes paintAttributes; - QwtGuardedPainter guardedPainter; + QwtPlotCurve::LegendAttributes legendAttributes; }; -//! Constructor -QwtPlotCurve::QwtPlotCurve(): - QwtPlotItem(QwtText()) -{ - init(); -} - /*! Constructor - \param title title of the curve + \param title Title of the curve */ -QwtPlotCurve::QwtPlotCurve(const QwtText &title): - QwtPlotItem(title) +QwtPlotCurve::QwtPlotCurve( const QwtText &title ): + QwtPlotSeriesItem( title ) { init(); } /*! Constructor - \param title title of the curve + \param title Title of the curve */ -QwtPlotCurve::QwtPlotCurve(const QString &title): - QwtPlotItem(QwtText(title)) +QwtPlotCurve::QwtPlotCurve( const QString &title ): + QwtPlotSeriesItem( QwtText( title ) ) { init(); } @@ -268,22 +119,19 @@ QwtPlotCurve::QwtPlotCurve(const QString &title): //! Destructor QwtPlotCurve::~QwtPlotCurve() { - delete d_xy; delete d_data; } -/*! - \brief Initialize data members -*/ +//! Initialize internal members void QwtPlotCurve::init() { - setItemAttribute(QwtPlotItem::Legend); - setItemAttribute(QwtPlotItem::AutoScale); + setItemAttribute( QwtPlotItem::Legend ); + setItemAttribute( QwtPlotItem::AutoScale ); d_data = new PrivateData; - d_xy = new QwtPolygonFData(QwtArray<QwtDoublePoint>()); + setData( new QwtPointSeriesData() ); - setZ(20.0); + setZ( 20.0 ); } //! \return QwtPlotItem::Rtti_PlotCurve @@ -293,29 +141,13 @@ int QwtPlotCurve::rtti() const } /*! - \brief Specify an attribute how to draw the curve - - The attributes can be used to modify the drawing algorithm. - - The following attributes are defined:<dl> - <dt>PaintFiltered</dt> - <dd>Tries to reduce the data that has to be painted, by sorting out - duplicates, or paintings outside the visible area. Might have a - notable impact on curves with many close points. - Only a couple of very basic filtering algos are implemented.</dd> - <dt>ClipPolygons</dt> - <dd>Clip polygons before painting them. In situations, where points - are far outside the visible area this might be a great improvement - for the painting performance ( especially on Windows ). - </dl> - - The default is, that no paint attributes are enabled. + Specify an attribute how to draw the curve \param attribute Paint attribute \param on On/Off - /sa testPaintAttribute() + \sa testPaintAttribute() */ -void QwtPlotCurve::setPaintAttribute(PaintAttribute attribute, bool on) +void QwtPlotCurve::setPaintAttribute( PaintAttribute attribute, bool on ) { if ( on ) d_data->paintAttributes |= attribute; @@ -324,366 +156,211 @@ void QwtPlotCurve::setPaintAttribute(PaintAttribute attribute, bool on) } /*! - \brief Return the current paint attributes - \sa setPaintAttribute + \return True, when attribute is enabled + \sa setPaintAttribute() */ -bool QwtPlotCurve::testPaintAttribute(PaintAttribute attribute) const +bool QwtPlotCurve::testPaintAttribute( PaintAttribute attribute ) const { - return (d_data->paintAttributes & attribute); + return ( d_data->paintAttributes & attribute ); } /*! - \brief Set the curve's drawing style - - Valid styles are: - <dl> - <dt>NoCurve</dt> - <dd>Don't draw a curve. Note: This doesn't affect the symbol. </dd> - <dt>Lines</dt> - <dd>Connect the points with straight lines. The lines might - be interpolated depending on the 'Fitted' option. Curve - fitting can be configured using setCurveFitter.</dd> - <dt>Sticks</dt> - <dd>Draw vertical sticks from a baseline which is defined by setBaseline().</dd> - <dt>Steps</dt> - <dd>Connect the points with a step function. The step function - is drawn from the left to the right or vice versa, - depending on the 'Inverted' option.</dd> - <dt>Dots</dt> - <dd>Draw dots at the locations of the data points. Note: - This is different from a dotted line (see setPen()).</dd> - <dt>UserCurve ...</dt> - <dd>Styles >= UserCurve are reserved for derived - classes of QwtPlotCurve that overload drawCurve() with - additional application specific curve types.</dd> - </dl> - \sa style() + Specify an attribute how to draw the legend icon + + \param attribute Attribute + \param on On/Off + /sa testLegendAttribute(). legendIcon() */ -void QwtPlotCurve::setStyle(CurveStyle style) +void QwtPlotCurve::setLegendAttribute( LegendAttribute attribute, bool on ) { - if ( style != d_data->style ) { - d_data->style = style; - itemChanged(); + if ( on != testLegendAttribute( attribute ) ) + { + if ( on ) + d_data->legendAttributes |= attribute; + else + d_data->legendAttributes &= ~attribute; + + qwtUpdateLegendIconSize( this ); + legendChanged(); } } /*! - \brief Return the current style - \sa setStyle() + \return True, when attribute is enabled + \sa setLegendAttribute() */ -QwtPlotCurve::CurveStyle QwtPlotCurve::style() const +bool QwtPlotCurve::testLegendAttribute( LegendAttribute attribute ) const { - return d_data->style; + return ( d_data->legendAttributes & attribute ); } /*! - \brief Assign a symbol - \param symbol Symbol - \sa symbol() -*/ -void QwtPlotCurve::setSymbol(const QwtSymbol &symbol ) -{ - delete d_data->symbol; - d_data->symbol = symbol.clone(); - itemChanged(); -} + Set the curve's drawing style -/*! - \brief Return the current symbol - \sa setSymbol() + \param style Curve style + \sa style() */ -const QwtSymbol &QwtPlotCurve::symbol() const +void QwtPlotCurve::setStyle( CurveStyle style ) { - return *d_data->symbol; -} + if ( style != d_data->style ) + { + d_data->style = style; -/*! - \brief Assign a pen - \param pen New pen - \sa pen(), brush() -*/ -void QwtPlotCurve::setPen(const QPen &pen) -{ - if ( pen != d_data->pen ) { - d_data->pen = pen; + legendChanged(); itemChanged(); } } /*! - \brief Return the pen used to draw the lines - \sa setPen(), brush() + \return Style of the curve + \sa setStyle() */ -const QPen& QwtPlotCurve::pen() const +QwtPlotCurve::CurveStyle QwtPlotCurve::style() const { - return d_data->pen; + return d_data->style; } /*! - \brief Assign a brush. - In case of brush.style() != QBrush::NoBrush - and style() != QwtPlotCurve::Sticks - the area between the curve and the baseline will be filled. - In case !brush.color().isValid() the area will be filled by - pen.color(). The fill algorithm simply connects the first and the - last curve point to the baseline. So the curve data has to be sorted - (ascending or descending). - \param brush New brush - \sa brush(), setBaseline(), baseline() + \brief Assign a symbol + + The curve will take the ownership of the symbol, hence the previously + set symbol will be delete by setting a new one. If \p symbol is + \c NULL no symbol will be drawn. + + \param symbol Symbol + \sa symbol() */ -void QwtPlotCurve::setBrush(const QBrush &brush) +void QwtPlotCurve::setSymbol( QwtSymbol *symbol ) { - if ( brush != d_data->brush ) { - d_data->brush = brush; + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + + qwtUpdateLegendIconSize( this ); + + legendChanged(); itemChanged(); } } /*! - \brief Return the brush used to fill the area between lines and the baseline - \sa setBrush(), setBaseline(), baseline() + \return Current symbol or NULL, when no symbol has been assigned + \sa setSymbol() */ -const QBrush& QwtPlotCurve::brush() const +const QwtSymbol *QwtPlotCurve::symbol() const { - return d_data->brush; + return d_data->symbol; } - /*! - Set data by copying x- and y-values from specified memory blocks. - Contrary to setCurveRawData(), this function makes a 'deep copy' of - the data. - - \param xData pointer to x values - \param yData pointer to y values - \param size size of xData and yData - - \sa QwtCPointerData -*/ -void QwtPlotCurve::setData(const double *xData, const double *yData, int size) -{ - delete d_xy; - d_xy = new QwtArrayData(xData, yData, size); - itemChanged(); -} + Build and assign a pen -/*! - \brief Initialize data with x- and y-arrays (explicitly shared) + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. - \param xData x data - \param yData y data + \param color Pen color + \param width Pen width + \param style Pen style - \sa QwtArrayData -*/ -void QwtPlotCurve::setData(const QwtArray<double> &xData, - const QwtArray<double> &yData) + \sa pen(), brush() + */ +void QwtPlotCurve::setPen( const QColor &color, qreal width, Qt::PenStyle style ) { - delete d_xy; - d_xy = new QwtArrayData(xData, yData); - itemChanged(); + setPen( QPen( color, width, style ) ); } /*! - Initialize data with an array of points (explicitly shared). + Assign a pen - \param data Data - \sa QwtPolygonFData + \param pen New pen + \sa pen(), brush() */ -#if QT_VERSION < 0x040000 -void QwtPlotCurve::setData(const QwtArray<QwtDoublePoint> &data) -#else -void QwtPlotCurve::setData(const QPolygonF &data) -#endif +void QwtPlotCurve::setPen( const QPen &pen ) { - delete d_xy; - d_xy = new QwtPolygonFData(data); - itemChanged(); + if ( pen != d_data->pen ) + { + d_data->pen = pen; + + legendChanged(); + itemChanged(); + } } /*! - Initialize data with a pointer to QwtData. - - \param data Data - \sa QwtData::copy() + \return Pen used to draw the lines + \sa setPen(), brush() */ -void QwtPlotCurve::setData(const QwtData &data) +const QPen& QwtPlotCurve::pen() const { - delete d_xy; - d_xy = data.copy(); - itemChanged(); + return d_data->pen; } /*! - \brief Initialize the data by pointing to memory blocks which are not managed - by QwtPlotCurve. + \brief Assign a brush. - setRawData is provided for efficiency. It is important to keep the pointers - during the lifetime of the underlying QwtCPointerData class. + In case of brush.style() != QBrush::NoBrush + and style() != QwtPlotCurve::Sticks + the area between the curve and the baseline will be filled. - \param xData pointer to x data - \param yData pointer to y data - \param size size of x and y + In case !brush.color().isValid() the area will be filled by + pen.color(). The fill algorithm simply connects the first and the + last curve point to the baseline. So the curve data has to be sorted + (ascending or descending). - \sa QwtCPointerData::setData. + \param brush New brush + \sa brush(), setBaseline(), baseline() */ -void QwtPlotCurve::setRawData(const double *xData, const double *yData, int size) +void QwtPlotCurve::setBrush( const QBrush &brush ) { - delete d_xy; - d_xy = new QwtCPointerData(xData, yData, size); - itemChanged(); + if ( brush != d_data->brush ) + { + d_data->brush = brush; + + legendChanged(); + itemChanged(); + } } /*! - Returns the bounding rectangle of the curve data. If there is - no bounding rect, like for empty data the rectangle is invalid. - \sa QwtData::boundingRect(), QwtDoubleRect::isValid() + \return Brush used to fill the area between lines and the baseline + \sa setBrush(), setBaseline(), baseline() */ - -QwtDoubleRect QwtPlotCurve::boundingRect() const +const QBrush& QwtPlotCurve::brush() const { - if ( d_xy == NULL ) - return QwtDoubleRect(1.0, 1.0, -2.0, -2.0); // invalid - - return d_xy->boundingRect(); + return d_data->brush; } /*! - \brief Draw the complete curve + Draw an interval of the curve \param painter Painter \param xMap Maps x-values into pixel coordinates. \param yMap Maps y-values into pixel coordinates. - - \sa drawCurve(), drawSymbols() -*/ -void QwtPlotCurve::draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &) const -{ - draw(painter, xMap, yMap, 0, -1); -} - -/*! - \brief Draw a set of points of a curve. - - When observing an measurement while it is running, new points have to be - added to an existing curve. drawCurve can be used to display them avoiding - a complete redraw of the canvas. - - Setting plot()->canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, true); - will result in faster painting, if the paint engine of the canvas widget - supports this feature. - + \param canvasRect Contents rectangle of the canvas \param from Index of the first point to be painted \param to Index of the last point to be painted. If to < 0 the curve will be painted to its last point. - \sa drawCurve(), drawSymbols() + \sa drawCurve(), drawSymbols(), */ -void QwtPlotCurve::draw(int from, int to) const +void QwtPlotCurve::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const { - if ( !plot() ) - return; + const size_t numSamples = dataSize(); - QwtPlotCanvas *canvas = plot()->canvas(); - -#if QT_VERSION >= 0x040000 -#if 0 - if ( canvas->paintEngine()->type() == QPaintEngine::OpenGL ) { - /* - OpenGL alway repaint the complete widget. - So for this operation OpenGL is one of the slowest - environments. - */ - canvas->repaint(); + if ( !painter || numSamples <= 0 ) return; - } -#endif - if ( !canvas->testAttribute(Qt::WA_WState_InPaintEvent) && - !canvas->testAttribute(Qt::WA_PaintOutsidePaintEvent) ) { - /* - We save curve and range in helper and call repaint. - The helper filters the Paint event, to repeat - the QwtPlotCurve::draw, but now from inside the paint - event. - */ - - QwtPlotCurvePaintHelper helper(this, from, to); - canvas->installEventFilter(&helper); - - const bool noSystemBackground = - canvas->testAttribute(Qt::WA_NoSystemBackground); - canvas->setAttribute(Qt::WA_NoSystemBackground, true); - canvas->repaint(); - canvas->setAttribute(Qt::WA_NoSystemBackground, noSystemBackground); + if ( to < 0 ) + to = numSamples - 1; - return; - } -#endif - - const QwtScaleMap xMap = plot()->canvasMap(xAxis()); - const QwtScaleMap yMap = plot()->canvasMap(yAxis()); - - if ( canvas->testPaintAttribute(QwtPlotCanvas::PaintCached) && - canvas->paintCache() && !canvas->paintCache()->isNull() ) { - QPainter cachePainter((QPixmap *)canvas->paintCache()); - cachePainter.translate(-canvas->contentsRect().x(), - -canvas->contentsRect().y()); - - draw(&cachePainter, xMap, yMap, from, to); - } - -#if QT_VERSION >= 0x040000 - if ( canvas->testAttribute(Qt::WA_WState_InPaintEvent) ) { - QPainter painter(canvas); - - painter.setClipping(true); - painter.setClipRect(canvas->contentsRect()); - - draw(&painter, xMap, yMap, from, to); - } else -#endif + if ( qwtVerifyRange( numSamples, from, to ) > 0 ) { - QPainter *painter = d_data->guardedPainter.begin(canvas); - draw(painter, xMap, yMap, from, to); - } -} - -/*! - \brief Draw an interval of the curve - \param painter Painter - \param xMap maps x-values into pixel coordinates. - \param yMap maps y-values into pixel coordinates. - \param from index of the first point to be painted - \param to index of the last point to be painted. If to < 0 the - curve will be painted to its last point. - - \sa drawCurve(), drawSymbols(), -*/ -void QwtPlotCurve::draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const -{ - if ( !painter || dataSize() <= 0 ) - return; - - if (to < 0) - to = dataSize() - 1; - - if ( verifyRange(dataSize(), from, to) > 0 ) { painter->save(); - - QPen pen = d_data->pen; - -#if SCALE_PEN - if ( pen.width() > 0 ) { - const QwtMetricsMap &metricsMap = QwtPainter::metricsMap(); - pen.setWidth(metricsMap.screenToLayoutX(pen.width())); - } -#endif - - painter->setPen(pen); + painter->setPen( d_data->pen ); /* Qt 4.0.0 is slow when drawing lines, but it's even @@ -691,12 +368,15 @@ void QwtPlotCurve::draw(QPainter *painter, set the brush before we really need it. */ - drawCurve(painter, d_data->style, xMap, yMap, from, to); + drawCurve( painter, d_data->style, xMap, yMap, canvasRect, from, to ); painter->restore(); - if (d_data->symbol->style() != QwtSymbol::NoSymbol) { + if ( d_data->symbol && + ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) + { painter->save(); - drawSymbols(painter, *d_data->symbol, xMap, yMap, from, to); + drawSymbols( painter, *d_data->symbol, + xMap, yMap, canvasRect, from, to ); painter->restore(); } } @@ -708,37 +388,39 @@ void QwtPlotCurve::draw(QPainter *painter, \param style curve style, see QwtPlotCurve::CurveStyle \param xMap x map \param yMap y map + \param canvasRect Contents rectangle of the canvas \param from index of the first point to be painted \param to index of the last point to be painted \sa draw(), drawDots(), drawLines(), drawSteps(), drawSticks() */ - -void QwtPlotCurve::drawCurve(QPainter *painter, int style, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const +void QwtPlotCurve::drawCurve( QPainter *painter, int style, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const { - switch (style) { - case Lines: - if ( testCurveAttribute(Fitted) ) { - // we always need the complete - // curve for fitting - from = 0; - to = dataSize() - 1; - } - drawLines(painter, xMap, yMap, from, to); - break; - case Sticks: - drawSticks(painter, xMap, yMap, from, to); - break; - case Steps: - drawSteps(painter, xMap, yMap, from, to); - break; - case Dots: - drawDots(painter, xMap, yMap, from, to); - break; - case NoCurve: - default: - break; + switch ( style ) + { + case Lines: + if ( testCurveAttribute( Fitted ) ) + { + // we always need the complete + // curve for fitting + from = 0; + to = dataSize() - 1; + } + drawLines( painter, xMap, yMap, canvasRect, from, to ); + break; + case Sticks: + drawSticks( painter, xMap, yMap, canvasRect, from, to ); + break; + case Steps: + drawSteps( painter, xMap, yMap, canvasRect, from, to ); + break; + case Dots: + drawDots( painter, xMap, yMap, canvasRect, from, to ); + break; + case NoCurve: + default: + break; } } @@ -751,108 +433,100 @@ void QwtPlotCurve::drawCurve(QPainter *painter, int style, \param painter Painter \param xMap x map \param yMap y map + \param canvasRect Contents rectangle of the canvas \param from index of the first point to be painted \param to index of the last point to be painted \sa setCurveAttribute(), setCurveFitter(), draw(), drawLines(), drawDots(), drawSteps(), drawSticks() */ -void QwtPlotCurve::drawLines(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const +void QwtPlotCurve::drawLines( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const { - int size = to - from + 1; - if ( size <= 0 ) + if ( from > to ) return; - QwtPolygon polyline; - if ( ( d_data->attributes & Fitted ) && d_data->curveFitter ) { - // Transform x and y values to window coordinates - // to avoid a distinction between linear and - // logarithmic scales. + const bool doAlign = QwtPainter::roundingAlignment( painter ); + const bool doFit = ( d_data->attributes & Fitted ) && d_data->curveFitter; + const bool doFill = ( d_data->brush.style() != Qt::NoBrush ) + && ( d_data->brush.color().alpha() > 0 ); -#if QT_VERSION < 0x040000 - QwtArray<QwtDoublePoint> points(size); -#else - QPolygonF points(size); -#endif - for (int i = from; i <= to; i++) { - QwtDoublePoint &p = points[i]; - p.setX( xMap.xTransform(x(i)) ); - p.setY( yMap.xTransform(y(i)) ); - } + QRectF clipRect; + if ( d_data->paintAttributes & ClipPolygons ) + { + qreal pw = qMax( qreal( 1.0 ), painter->pen().widthF()); + clipRect = canvasRect.adjusted(-pw, -pw, pw, pw); + } + + bool doIntegers = false; + +#if QT_VERSION < 0x040800 + + // For Qt <= 4.7 the raster paint engine is significantly faster + // for rendering QPolygon than for QPolygonF. So let's + // see if we can use it. - points = d_data->curveFitter->fitCurve(points); - size = points.size(); + if ( painter->paintEngine()->type() == QPaintEngine::Raster ) + { + // In case of filling or fitting performance doesn't count + // because both operations are much more expensive + // then drawing the polyline itself - if ( size == 0 ) - return; + if ( !doFit && !doFill ) + doIntegers = true; + } +#endif - // Round QwtDoublePoints to QPoints - // When Qwt support for Qt3 has been dropped (Qwt 6.x) - // we will use a doubles for painting and the following - // step will be obsolete. + const bool noDuplicates = d_data->paintAttributes & FilterPoints; - polyline.resize(size); + QwtPointMapper mapper; + mapper.setFlag( QwtPointMapper::RoundPoints, doAlign ); + mapper.setFlag( QwtPointMapper::WeedOutPoints, noDuplicates ); + mapper.setBoundingRect( canvasRect ); - const QwtDoublePoint *p = points.data(); - QPoint *pl = polyline.data(); - if ( d_data->paintAttributes & PaintFiltered ) { + if ( doIntegers ) + { + const QPolygon polyline = mapper.toPolygon( + xMap, yMap, data(), from, to ); - QPoint pp(qRound(p[0].x()), qRound(p[0].y())); - pl[0] = pp; + if ( d_data->paintAttributes & ClipPolygons ) + { + const QPolygon clipped = QwtClipper::clipPolygon( + clipRect.toAlignedRect(), polyline, false ); - int count = 1; - for (int i = 1; i < size; i++) { - const QPoint pi(qRound(p[i].x()), qRound(p[i].y())); - if ( pi != pp ) { - pl[count++] = pi; - pp = pi; - } - } - if ( count != size ) - polyline.resize(count); - } else { - for ( int i = 0; i < size; i++ ) { - pl[i].setX( qRound(p[i].x()) ); - pl[i].setY( qRound(p[i].y()) ); - } + QwtPainter::drawPolyline( painter, clipped ); } - } else { - polyline.resize(size); - - if ( d_data->paintAttributes & PaintFiltered ) { - QPoint pp( xMap.transform(x(from)), yMap.transform(y(from)) ); - polyline.setPoint(0, pp); - - int count = 1; - for (int i = from + 1; i <= to; i++) { - const QPoint pi(xMap.transform(x(i)), yMap.transform(y(i))); - if ( pi != pp ) { - polyline.setPoint(count, pi); - count++; - - pp = pi; - } - } - if ( count != size ) - polyline.resize(count); - } else { - for (int i = from; i <= to; i++) { - int xi = xMap.transform(x(i)); - int yi = yMap.transform(y(i)); - - polyline.setPoint(i - from, xi, yi); - } + else + { + QwtPainter::drawPolyline( painter, polyline ); } } + else + { + QPolygonF polyline = mapper.toPolygonF( xMap, yMap, + data(), from, to ); - polyline = ::clipPolygon(painter, d_data->paintAttributes, polyline); + if ( doFit ) + polyline = d_data->curveFitter->fitCurve( polyline ); - QwtPainter::drawPolyline(painter, polyline); + if ( d_data->paintAttributes & ClipPolygons ) + { + const QPolygonF clipped = QwtClipper::clipPolygonF( + clipRect, polyline, false ); - if ( d_data->brush.style() != Qt::NoBrush ) - fillCurve(painter, xMap, yMap, polyline); + QwtPainter::drawPolyline( painter, clipped ); + } + else + { + QwtPainter::drawPolyline( painter, polyline ); + } + + if ( doFill ) + { + fillCurve( painter, xMap, yMap, canvasRect, polyline ); + } + } } /*! @@ -861,27 +535,51 @@ void QwtPlotCurve::drawLines(QPainter *painter, \param painter Painter \param xMap x map \param yMap y map + \param canvasRect Contents rectangle of the canvas \param from index of the first point to be painted \param to index of the last point to be painted \sa draw(), drawCurve(), drawDots(), drawLines(), drawSteps() */ -void QwtPlotCurve::drawSticks(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const +void QwtPlotCurve::drawSticks( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &, int from, int to ) const { - int x0 = xMap.transform(d_data->reference); - int y0 = yMap.transform(d_data->reference); + painter->save(); + painter->setRenderHint( QPainter::Antialiasing, false ); - for (int i = from; i <= to; i++) { - const int xi = xMap.transform(x(i)); - const int yi = yMap.transform(y(i)); + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double x0 = xMap.transform( d_data->baseline ); + double y0 = yMap.transform( d_data->baseline ); + if ( doAlign ) + { + x0 = qRound( x0 ); + y0 = qRound( y0 ); + } - if (d_data->curveType == Xfy) - QwtPainter::drawLine(painter, x0, yi, xi, yi); + const Qt::Orientation o = orientation(); + + const QwtSeriesData<QPointF> *series = data(); + + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = series->sample( i ); + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); + } + + if ( o == Qt::Horizontal ) + QwtPainter::drawLine( painter, x0, yi, xi, yi ); else - QwtPainter::drawLine(painter, xi, y0, xi, yi); + QwtPainter::drawLine( painter, xi, y0, xi, yi ); } + + painter->restore(); } /*! @@ -890,74 +588,95 @@ void QwtPlotCurve::drawSticks(QPainter *painter, \param painter Painter \param xMap x map \param yMap y map + \param canvasRect Contents rectangle of the canvas \param from index of the first point to be painted \param to index of the last point to be painted \sa draw(), drawCurve(), drawSticks(), drawLines(), drawSteps() */ -void QwtPlotCurve::drawDots(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const +void QwtPlotCurve::drawDots( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const { - const QRect window = painter->window(); - if ( window.isEmpty() ) + const QColor color = painter->pen().color(); + + if ( painter->pen().style() == Qt::NoPen || color.alpha() == 0 ) + { return; + } - const bool doFill = d_data->brush.style() != Qt::NoBrush; + const bool doFill = ( d_data->brush.style() != Qt::NoBrush ) + && ( d_data->brush.color().alpha() > 0 ); + const bool doAlign = QwtPainter::roundingAlignment( painter ); - QwtPolygon polyline; - if ( doFill ) - polyline.resize(to - from + 1); + QwtPointMapper mapper; + mapper.setBoundingRect( canvasRect ); + mapper.setFlag( QwtPointMapper::RoundPoints, doAlign ); - if ( to > from && d_data->paintAttributes & PaintFiltered ) { - if ( doFill ) { - QPoint pp( xMap.transform(x(from)), yMap.transform(y(from)) ); + if ( d_data->paintAttributes & FilterPoints ) + { + if ( ( color.alpha() == 255 ) + && !( painter->renderHints() & QPainter::Antialiasing ) ) + { + mapper.setFlag( QwtPointMapper::WeedOutPoints, true ); + } + } - QwtPainter::drawPoint(painter, pp.x(), pp.y()); - polyline.setPoint(0, pp); + if ( doFill ) + { + mapper.setFlag( QwtPointMapper::WeedOutPoints, false ); - int count = 1; - for (int i = from + 1; i <= to; i++) { - const QPoint pi(xMap.transform(x(i)), yMap.transform(y(i))); - if ( pi != pp ) { - QwtPainter::drawPoint(painter, pi.x(), pi.y()); + QPolygonF points = mapper.toPointsF( + xMap, yMap, data(), from, to ); - polyline.setPoint(count, pi); - count++; + QwtPainter::drawPoints( painter, points ); + fillCurve( painter, xMap, yMap, canvasRect, points ); + } + else if ( d_data->paintAttributes & ImageBuffer ) + { + const QImage image = mapper.toImage( xMap, yMap, + data(), from, to, d_data->pen, + painter->testRenderHint( QPainter::Antialiasing ), + renderThreadCount() ); - pp = pi; - } - } - if ( int(polyline.size()) != count ) - polyline.resize(count); - } else { - // if we don't need to fill, we can sort out - // duplicates independent from the order + painter->drawImage( canvasRect.toAlignedRect(), image ); + } + else if ( d_data->paintAttributes & MinimizeMemory ) + { + const QwtSeriesData<QPointF> *series = data(); - PrivateData::PixelMatrix pixelMatrix(window); + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = series->sample( i ); - for (int i = from; i <= to; i++) { - const QPoint p( xMap.transform(x(i)), - yMap.transform(y(i)) ); + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); - if ( pixelMatrix.testPixel(p) ) - QwtPainter::drawPoint(painter, p.x(), p.y()); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); } - } - } else { - for (int i = from; i <= to; i++) { - const int xi = xMap.transform(x(i)); - const int yi = yMap.transform(y(i)); - QwtPainter::drawPoint(painter, xi, yi); - - if ( doFill ) - polyline.setPoint(i - from, xi, yi); + + QwtPainter::drawPoint( painter, QPointF( xi, yi ) ); } } + else + { + if ( doAlign ) + { + const QPolygon points = mapper.toPoints( + xMap, yMap, data(), from, to ); + + QwtPainter::drawPoints( painter, points ); + } + else + { + const QPolygonF points = mapper.toPointsF( + xMap, yMap, data(), from, to ); - if ( doFill ) { - polyline = ::clipPolygon(painter, d_data->paintAttributes, polyline); - fillCurve(painter, xMap, yMap, polyline); + QwtPainter::drawPoints( painter, points ); + } } } @@ -969,71 +688,89 @@ void QwtPlotCurve::drawDots(QPainter *painter, \param painter Painter \param xMap x map \param yMap y map + \param canvasRect Contents rectangle of the canvas \param from index of the first point to be painted \param to index of the last point to be painted \sa CurveAttribute, setCurveAttribute(), draw(), drawCurve(), drawDots(), drawLines(), drawSticks() */ -void QwtPlotCurve::drawSteps(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const +void QwtPlotCurve::drawSteps( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const { - QwtPolygon polyline(2 * (to - from) + 1); + const bool doAlign = QwtPainter::roundingAlignment( painter ); - bool inverted = d_data->curveType == Yfx; + QPolygonF polygon( 2 * ( to - from ) + 1 ); + QPointF *points = polygon.data(); + + bool inverted = orientation() == Qt::Vertical; if ( d_data->attributes & Inverted ) inverted = !inverted; - int i,ip; - for (i = from, ip = 0; i <= to; i++, ip += 2) { - const int xi = xMap.transform(x(i)); - const int yi = yMap.transform(y(i)); + const QwtSeriesData<QPointF> *series = data(); + + int i, ip; + for ( i = from, ip = 0; i <= to; i++, ip += 2 ) + { + const QPointF sample = series->sample( i ); + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); + } - if ( ip > 0 ) { - if (inverted) - polyline.setPoint(ip - 1, polyline[ip-2].x(), yi); + if ( ip > 0 ) + { + const QPointF &p0 = points[ip - 2]; + QPointF &p = points[ip - 1]; + + if ( inverted ) + { + p.rx() = p0.x(); + p.ry() = yi; + } else - polyline.setPoint(ip - 1, xi, polyline[ip-2].y()); + { + p.rx() = xi; + p.ry() = p0.y(); + } } - polyline.setPoint(ip, xi, yi); + points[ip].rx() = xi; + points[ip].ry() = yi; } - polyline = ::clipPolygon(painter, d_data->paintAttributes, polyline); + if ( d_data->paintAttributes & ClipPolygons ) + { + const QPolygonF clipped = QwtClipper::clipPolygonF( + canvasRect, polygon, false ); - QwtPainter::drawPolyline(painter, polyline); + QwtPainter::drawPolyline( painter, clipped ); + } + else + { + QwtPainter::drawPolyline( painter, polygon ); + } if ( d_data->brush.style() != Qt::NoBrush ) - fillCurve(painter, xMap, yMap, polyline); + fillCurve( painter, xMap, yMap, canvasRect, polygon ); } /*! - \brief Specify an attribute for drawing the curve - - The attributes can be used to modify the drawing style. - The following attributes are defined:<dl> - <dt>Fitted</dt> - <dd>For Lines only. A QwtCurveFitter tries to - interpolate/smooth the curve, before it is painted. - Note that curve fitting requires temorary memory - for calculating coefficients and additional points. - If painting in Fitted mode is slow it might be better - to fit the points, before they are passed to QwtPlotCurve. - </dd> - <dt>Inverted</dt> - <dd>For Steps only. Draws a step function - from the right to the left.</dd></dl> + Specify an attribute for drawing the curve \param attribute Curve attribute \param on On/Off /sa testCurveAttribute(), setCurveFitter() */ -void QwtPlotCurve::setCurveAttribute(CurveAttribute attribute, bool on) +void QwtPlotCurve::setCurveAttribute( CurveAttribute attribute, bool on ) { - if ( bool(d_data->attributes & attribute) == on ) + if ( bool( d_data->attributes & attribute ) == on ) return; if ( on ) @@ -1048,45 +785,29 @@ void QwtPlotCurve::setCurveAttribute(CurveAttribute attribute, bool on) \return true, if attribute is enabled \sa setCurveAttribute() */ -bool QwtPlotCurve::testCurveAttribute(CurveAttribute attribute) const +bool QwtPlotCurve::testCurveAttribute( CurveAttribute attribute ) const { return d_data->attributes & attribute; } /*! - Assign the curve type + Assign a curve fitter - <dt>QwtPlotCurve::Yfx - <dd>Draws y as a function of x (the default). The - baseline is interpreted as a horizontal line - with y = baseline().</dd> - <dt>QwtPlotCurve::Xfy - <dd>Draws x as a function of y. The baseline is - interpreted as a vertical line with x = baseline().</dd> + The curve fitter "smooths" the curve points, when the Fitted + CurveAttribute is set. setCurveFitter(NULL) also disables curve fitting. - The baseline is used for aligning the sticks, or - filling the curve with a brush. + The curve fitter operates on the translated points ( = widget coordinates) + to be functional for logarithmic scales. Obviously this is less performant + for fitting algorithms, that reduce the number of points. - \sa curveType() -*/ -void QwtPlotCurve::setCurveType(CurveType curveType) -{ - if ( d_data->curveType != curveType ) { - d_data->curveType = curveType; - itemChanged(); - } -} + For situations, where curve fitting is used to improve the performance + of painting huge series of points it might be better to execute the fitter + on the curve points once and to cache the result in the QwtSeriesData object. -/*! - Return the curve type - \sa setCurveType() + \param curveFitter() Curve fitter + \sa Fitted */ -QwtPlotCurve::CurveType QwtPlotCurve::curveType() const -{ - return d_data->curveType; -} - -void QwtPlotCurve::setCurveFitter(QwtCurveFitter *curveFitter) +void QwtPlotCurve::setCurveFitter( QwtCurveFitter *curveFitter ) { delete d_data->curveFitter; d_data->curveFitter = curveFitter; @@ -1094,6 +815,12 @@ void QwtPlotCurve::setCurveFitter(QwtCurveFitter *curveFitter) itemChanged(); } +/*! + Get the curve fitter. If curve fitting is disabled NULL is returned. + + \return Curve fitter + \sa setCurveFitter(), Fitted +*/ QwtCurveFitter *QwtPlotCurve::curveFitter() const { return d_data->curveFitter; @@ -1106,123 +833,120 @@ QwtCurveFitter *QwtPlotCurve::curveFitter() const \param painter Painter \param xMap x map \param yMap y map - \param pa Polygon + \param canvasRect Contents rectangle of the canvas + \param polygon Polygon - will be modified ! - \sa setBrush(), setBaseline(), setCurveType() + \sa setBrush(), setBaseline(), setStyle() */ - -void QwtPlotCurve::fillCurve(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - QwtPolygon &pa) const +void QwtPlotCurve::fillCurve( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, QPolygonF &polygon ) const { if ( d_data->brush.style() == Qt::NoBrush ) return; - closePolyline(xMap, yMap, pa); - if ( pa.count() <= 2 ) // a line can't be filled + closePolyline( painter, xMap, yMap, polygon ); + if ( polygon.count() <= 2 ) // a line can't be filled return; - QBrush b = d_data->brush; - if ( !b.color().isValid() ) - b.setColor(d_data->pen.color()); + QBrush brush = d_data->brush; + if ( !brush.color().isValid() ) + brush.setColor( d_data->pen.color() ); + + if ( d_data->paintAttributes & ClipPolygons ) + polygon = QwtClipper::clipPolygonF( canvasRect, polygon, true ); painter->save(); - painter->setPen(QPen(Qt::NoPen)); - painter->setBrush(b); + painter->setPen( Qt::NoPen ); + painter->setBrush( brush ); - QwtPainter::drawPolygon(painter, pa); + QwtPainter::drawPolygon( painter, polygon ); painter->restore(); } /*! - \brief Complete a polygon to be a closed polygon - including the area between the original polygon - and the baseline. + \brief Complete a polygon to be a closed polygon including the + area between the original polygon and the baseline. + + \param painter Painter \param xMap X map \param yMap Y map - \param pa Polygon to be completed + \param polygon Polygon to be completed */ - -void QwtPlotCurve::closePolyline( +void QwtPlotCurve::closePolyline( QPainter *painter, const QwtScaleMap &xMap, const QwtScaleMap &yMap, - QwtPolygon &pa) const + QPolygonF &polygon ) const { - const int sz = pa.size(); - if ( sz < 2 ) + if ( polygon.size() < 2 ) return; - pa.resize(sz + 2); - - if ( d_data->curveType == QwtPlotCurve::Xfy ) { - pa.setPoint(sz, - xMap.transform(d_data->reference), pa.point(sz - 1).y()); - pa.setPoint(sz + 1, - xMap.transform(d_data->reference), pa.point(0).y()); - } else { - pa.setPoint(sz, - pa.point(sz - 1).x(), yMap.transform(d_data->reference)); - pa.setPoint(pa.size() - 1, - pa.point(0).x(), yMap.transform(d_data->reference)); + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double baseline = d_data->baseline; + + if ( orientation() == Qt::Vertical ) + { + if ( yMap.transformation() ) + baseline = yMap.transformation()->bounded( baseline ); + + double refY = yMap.transform( baseline ); + if ( doAlign ) + refY = qRound( refY ); + + polygon += QPointF( polygon.last().x(), refY ); + polygon += QPointF( polygon.first().x(), refY ); + } + else + { + if ( xMap.transformation() ) + baseline = xMap.transformation()->bounded( baseline ); + + double refX = xMap.transform( baseline ); + if ( doAlign ) + refX = qRound( refX ); + + polygon += QPointF( refX, polygon.last().y() ); + polygon += QPointF( refX, polygon.first().y() ); } } /*! - \brief Draw symbols + Draw symbols + \param painter Painter \param symbol Curve symbol \param xMap x map \param yMap y map - \param from index of the first point to be painted - \param to index of the last point to be painted + \param canvasRect Contents rectangle of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted - \sa setSymbol(), draw(), drawCurve() + \sa setSymbol(), drawSeries(), drawCurve() */ -void QwtPlotCurve::drawSymbols(QPainter *painter, const QwtSymbol &symbol, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const +void QwtPlotCurve::drawSymbols( QPainter *painter, const QwtSymbol &symbol, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const { - painter->setBrush(symbol.brush()); + QwtPointMapper mapper; + mapper.setFlag( QwtPointMapper::RoundPoints, + QwtPainter::roundingAlignment( painter ) ); + mapper.setFlag( QwtPointMapper::WeedOutPoints, + testPaintAttribute( QwtPlotCurve::FilterPoints ) ); + mapper.setBoundingRect( canvasRect ); - const QwtMetricsMap &metricsMap = QwtPainter::metricsMap(); + const int chunkSize = 500; - QPen pen = symbol.pen(); - -#if SCALE_PEN - if ( pen.width() > 0 ) - pen.setWidth(metricsMap.screenToLayoutX(pen.width())); -#endif - - painter->setPen(pen); - - QRect rect; - rect.setSize(metricsMap.screenToLayout(symbol.size())); - - if ( to > from && d_data->paintAttributes & PaintFiltered ) { - const QRect window = painter->window(); - if ( window.isEmpty() ) - return; - - PrivateData::PixelMatrix pixelMatrix(window); - - for (int i = from; i <= to; i++) { - const QPoint pi( xMap.transform(x(i)), - yMap.transform(y(i)) ); + for ( int i = from; i <= to; i += chunkSize ) + { + const int n = qMin( chunkSize, to - i + 1 ); - if ( pixelMatrix.testPixel(pi) ) { - rect.moveCenter(pi); - symbol.draw(painter, rect); - } - } - } else { - for (int i = from; i <= to; i++) { - const int xi = xMap.transform(x(i)); - const int yi = yMap.transform(y(i)); + const QPolygonF points = mapper.toPointsF( xMap, yMap, + data(), i, i + n - 1 ); - rect.moveCenter(QPoint(xi, yi)); - symbol.draw(painter, rect); - } + if ( points.size() > 0 ) + symbol.drawSymbols( painter, points ); } } @@ -1231,125 +955,237 @@ void QwtPlotCurve::drawSymbols(QPainter *painter, const QwtSymbol &symbol, The baseline is needed for filling the curve with a brush or the Sticks drawing style. - The default value is 0.0. The interpretation - of the baseline depends on the CurveType. With QwtPlotCurve::Yfx, - the baseline is interpreted as a horizontal line at y = baseline(), - with QwtPlotCurve::Yfy, it is interpreted as a vertical line at - x = baseline(). - \param reference baseline - \sa baseline(), setBrush(), setStyle(), setCurveType() + + The interpretation of the baseline depends on the orientation(). + With Qt::Horizontal, the baseline is interpreted as a horizontal line + at y = baseline(), with Qt::Vertical, it is interpreted as a vertical + line at x = baseline(). + + The default value is 0.0. + + \param value Value of the baseline + \sa baseline(), setBrush(), setStyle(), QwtPlotAbstractSeriesItem::orientation() */ -void QwtPlotCurve::setBaseline(double reference) +void QwtPlotCurve::setBaseline( double value ) { - if ( d_data->reference != reference ) { - d_data->reference = reference; + if ( d_data->baseline != value ) + { + d_data->baseline = value; itemChanged(); } } /*! - Return the value of the baseline - \sa setBaseline + \return Value of the baseline + \sa setBaseline() */ double QwtPlotCurve::baseline() const { - return d_data->reference; + return d_data->baseline; } /*! - Return the size of the data arrays - \sa setData() + Find the closest curve point for a specific position + + \param pos Position, where to look for the closest curve point + \param dist If dist != NULL, closestPoint() returns the distance between + the position and the closest curve point + \return Index of the closest curve point, or -1 if none can be found + ( f.e when the curve has no points ) + \note closestPoint() implements a dumb algorithm, that iterates + over all points */ -int QwtPlotCurve::dataSize() const +int QwtPlotCurve::closestPoint( const QPoint &pos, double *dist ) const { - return d_xy->size(); -} + const size_t numSamples = dataSize(); -int QwtPlotCurve::closestPoint(const QPoint &pos, double *dist) const -{ - if ( plot() == NULL || dataSize() <= 0 ) + if ( plot() == NULL || numSamples <= 0 ) return -1; - const QwtScaleMap xMap = plot()->canvasMap(xAxis()); - const QwtScaleMap yMap = plot()->canvasMap(yAxis()); + const QwtSeriesData<QPointF> *series = data(); + + const QwtScaleMap xMap = plot()->canvasMap( xAxis() ); + const QwtScaleMap yMap = plot()->canvasMap( yAxis() ); int index = -1; double dmin = 1.0e10; - for (int i=0; i < dataSize(); i++) { - const double cx = xMap.xTransform(x(i)) - pos.x(); - const double cy = yMap.xTransform(y(i)) - pos.y(); + for ( uint i = 0; i < numSamples; i++ ) + { + const QPointF sample = series->sample( i ); + + const double cx = xMap.transform( sample.x() ) - pos.x(); + const double cy = yMap.transform( sample.y() ) - pos.y(); - const double f = qwtSqr(cx) + qwtSqr(cy); - if (f < dmin) { + const double f = qwtSqr( cx ) + qwtSqr( cy ); + if ( f < dmin ) + { index = i; dmin = f; } } if ( dist ) - *dist = sqrt(dmin); + *dist = qSqrt( dmin ); return index; } -//! Update the widget that represents the curve on the legend -void QwtPlotCurve::updateLegend(QwtLegend *legend) const -{ - if ( !legend ) - return; +/*! + \return Icon representing the curve on the legend - QwtPlotItem::updateLegend(legend); + \param index Index of the legend entry + ( ignored as there is only one ) + \param size Icon size - QWidget *widget = legend->find(this); - if ( !widget || !widget->inherits("QwtLegendItem") ) - return; + \sa QwtPlotItem::setLegendIconSize(), QwtPlotItem::legendData() + */ +QwtGraphic QwtPlotCurve::legendIcon( int index, + const QSizeF &size ) const +{ + Q_UNUSED( index ); - QwtLegendItem *legendItem = (QwtLegendItem *)widget; + if ( size.isEmpty() ) + return QwtGraphic(); -#if QT_VERSION < 0x040000 - const bool doUpdate = legendItem->isUpdatesEnabled(); -#else - const bool doUpdate = legendItem->updatesEnabled(); -#endif - legendItem->setUpdatesEnabled(false); + QwtGraphic graphic; + graphic.setDefaultSize( size ); + graphic.setRenderHint( QwtGraphic::RenderPensUnscaled, true ); - const int policy = legend->displayPolicy(); + QPainter painter( &graphic ); + painter.setRenderHint( QPainter::Antialiasing, + testRenderHint( QwtPlotItem::RenderAntialiased ) ); - if (policy == QwtLegend::FixedIdentifier) { - int mode = legend->identifierMode(); + if ( d_data->legendAttributes == 0 || + d_data->legendAttributes & QwtPlotCurve::LegendShowBrush ) + { + QBrush brush = d_data->brush; - if (mode & QwtLegendItem::ShowLine) - legendItem->setCurvePen(pen()); + if ( brush.style() == Qt::NoBrush && + d_data->legendAttributes == 0 ) + { + if ( style() != QwtPlotCurve::NoCurve ) + { + brush = QBrush( pen().color() ); + } + else if ( d_data->symbol && + ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) + { + brush = QBrush( d_data->symbol->pen().color() ); + } + } - if (mode & QwtLegendItem::ShowSymbol) - legendItem->setSymbol(symbol()); + if ( brush.style() != Qt::NoBrush ) + { + QRectF r( 0, 0, size.width(), size.height() ); + painter.fillRect( r, brush ); + } + } - if (mode & QwtLegendItem::ShowText) - legendItem->setText(title()); - else - legendItem->setText(QwtText()); + if ( d_data->legendAttributes & QwtPlotCurve::LegendShowLine ) + { + if ( pen() != Qt::NoPen ) + { + QPen pn = pen(); + pn.setCapStyle( Qt::FlatCap ); - legendItem->setIdentifierMode(mode); - } else if (policy == QwtLegend::AutoIdentifier) { - int mode = 0; + painter.setPen( pn ); - if (QwtPlotCurve::NoCurve != style()) { - legendItem->setCurvePen(pen()); - mode |= QwtLegendItem::ShowLine; + const double y = 0.5 * size.height(); + QwtPainter::drawLine( &painter, 0.0, y, size.width(), y ); } - if (QwtSymbol::NoSymbol != symbol().style()) { - legendItem->setSymbol(symbol()); - mode |= QwtLegendItem::ShowSymbol; - } - if ( !title().isEmpty() ) { - legendItem->setText(title()); - mode |= QwtLegendItem::ShowText; - } else { - legendItem->setText(QwtText()); + } + + if ( d_data->legendAttributes & QwtPlotCurve::LegendShowSymbol ) + { + if ( d_data->symbol ) + { + QRectF r( 0, 0, size.width(), size.height() ); + d_data->symbol->drawSymbol( &painter, r ); } - legendItem->setIdentifierMode(mode); } - legendItem->setUpdatesEnabled(doUpdate); - legendItem->update(); + return graphic; +} + +/*! + Initialize data with an array of points. + + \param samples Vector of points + \note QVector is implicitly shared + \note QPolygonF is derived from QVector<QPointF> +*/ +void QwtPlotCurve::setSamples( const QVector<QPointF> &samples ) +{ + setData( new QwtPointSeriesData( samples ) ); +} + +/*! + Assign a series of points + + setSamples() is just a wrapper for setData() without any additional + value - beside that it is easier to find for the developer. + + \param data Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. +*/ +void QwtPlotCurve::setSamples( QwtSeriesData<QPointF> *data ) +{ + setData( data ); +} + +#ifndef QWT_NO_COMPAT + +/*! + \brief Initialize the data by pointing to memory blocks which + are not managed by QwtPlotCurve. + + setRawSamples is provided for efficiency. + It is important to keep the pointers + during the lifetime of the underlying QwtCPointerData class. + + \param xData pointer to x data + \param yData pointer to y data + \param size size of x and y + + \sa QwtCPointerData +*/ +void QwtPlotCurve::setRawSamples( + const double *xData, const double *yData, int size ) +{ + setData( new QwtCPointerData( xData, yData, size ) ); } + +/*! + Set data by copying x- and y-values from specified memory blocks. + Contrary to setRawSamples(), this function makes a 'deep copy' of + the data. + + \param xData pointer to x values + \param yData pointer to y values + \param size size of xData and yData + + \sa QwtPointArrayData +*/ +void QwtPlotCurve::setSamples( + const double *xData, const double *yData, int size ) +{ + setData( new QwtPointArrayData( xData, yData, size ) ); +} + +/*! + \brief Initialize data with x- and y-arrays (explicitly shared) + + \param xData x data + \param yData y data + + \sa QwtPointArrayData +*/ +void QwtPlotCurve::setSamples( const QVector<double> &xData, + const QVector<double> &yData ) +{ + setData( new QwtPointArrayData( xData, yData ) ); +} + +#endif // !QWT_NO_COMPAT + diff --git a/libs/qwt/qwt_plot_curve.h b/libs/qwt/qwt_plot_curve.h index 5e92194649..3421abf816 100644 --- a/libs/qwt/qwt_plot_curve.h +++ b/libs/qwt/qwt_plot_curve.h @@ -10,241 +10,328 @@ #ifndef QWT_PLOT_CURVE_H #define QWT_PLOT_CURVE_H -#include <qpen.h> -#include <qstring.h> #include "qwt_global.h" -#include "qwt_plot_item.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_series_data.h" #include "qwt_text.h" -#include "qwt_polygon.h" -#include "qwt_data.h" +#include <qpen.h> +#include <qstring.h> class QPainter; +class QPolygonF; class QwtScaleMap; class QwtSymbol; class QwtCurveFitter; /*! - \brief A class which draws curves + \brief A plot item, that represents a series of points - This class can be used to display data as a curve in the x-y plane. - It supports different display styles, spline interpolation and symbols. + A curve is the representation of a series of points in the x-y plane. + It supports different display styles, interpolation ( f.e. spline ) + and symbols. \par Usage - <dl><dt>A. Assign curve properties</dt> + <dl><dt>a) Assign curve properties</dt> <dd>When a curve is created, it is configured to draw black solid lines - with QwtPlotCurve::Lines and no symbols. You can change this by calling + with in QwtPlotCurve::Lines style and no symbols. + You can change this by calling setPen(), setStyle() and setSymbol().</dd> - <dt>B. Assign or change data.</dt> - <dd>Data can be set in two ways:<ul> - <li>setData() is overloaded to initialize the x and y data by - copying from different data structures with different kind of copy semantics. - <li>setRawData() only stores the pointers and size information - and is provided for backwards compatibility. This function is less safe (you - must not delete the data while they are attached), but has been more - efficient, and has been more convenient for dynamically changing data. - Use of setData() in combination with a problem-specific subclass - of QwtData is always preferrable.</ul></dd> - <dt>C. Draw</dt> - <dd>draw() maps the data into pixel coordinates and paints them. + <dt>b) Connect/Assign data.</dt> + <dd>QwtPlotCurve gets its points using a QwtSeriesData object offering + a bridge to the real storage of the points ( like QAbstractItemModel ). + There are several convenience classes derived from QwtSeriesData, that also store + the points inside ( like QStandardItemModel ). QwtPlotCurve also offers + a couple of variations of setSamples(), that build QwtSeriesData objects from + arrays internally.</dd> + <dt>c) Attach the curve to a plot</dt> + <dd>See QwtPlotItem::attach() </dd></dl> \par Example: - see examples/curvdemo + see examples/bode - \sa QwtData, QwtSymbol, QwtScaleMap + \sa QwtPointSeriesData, QwtSymbol, QwtScaleMap */ -class QWT_EXPORT QwtPlotCurve: public QwtPlotItem +class QWT_EXPORT QwtPlotCurve: + public QwtPlotSeriesItem, public QwtSeriesStore<QPointF> { public: - enum CurveType { - Yfx, - Xfy - }; - /*! Curve styles. - \sa setStyle + \sa setStyle(), style() */ - enum CurveStyle { - NoCurve, - + enum CurveStyle + { + /*! + Don't draw a curve. Note: This doesn't affect the symbols. + */ + NoCurve = -1, + + /*! + Connect the points with straight lines. The lines might + be interpolated depending on the 'Fitted' attribute. Curve + fitting can be configured using setCurveFitter(). + */ Lines, + + /*! + Draw vertical or horizontal sticks ( depending on the + orientation() ) from a baseline which is defined by setBaseline(). + */ Sticks, + + /*! + Connect the points with a step function. The step function + is drawn from the left to the right or vice versa, + depending on the QwtPlotCurve::Inverted attribute. + */ Steps, + + /*! + Draw dots at the locations of the data points. Note: + This is different from a dotted line (see setPen()), and faster + as a curve in QwtPlotCurve::NoStyle style and a symbol + painting a point. + */ Dots, + /*! + Styles >= QwtPlotCurve::UserCurve are reserved for derived + classes of QwtPlotCurve that overload drawCurve() with + additional application specific curve types. + */ UserCurve = 100 }; /*! - Curve attributes. - \sa setCurveAttribute, testCurveAttribute + Attribute for drawing the curve + \sa setCurveAttribute(), testCurveAttribute(), curveFitter() */ - enum CurveAttribute { - Inverted = 1, - Fitted = 2 + enum CurveAttribute + { + /*! + For QwtPlotCurve::Steps only. + Draws a step function from the right to the left. + */ + Inverted = 0x01, + + /*! + Only in combination with QwtPlotCurve::Lines + A QwtCurveFitter tries to + interpolate/smooth the curve, before it is painted. + + \note Curve fitting requires temporary memory + for calculating coefficients and additional points. + If painting in QwtPlotCurve::Fitted mode is slow it might be better + to fit the points, before they are passed to QwtPlotCurve. + */ + Fitted = 0x02 }; + //! Curve attributes + typedef QFlags<CurveAttribute> CurveAttributes; + /*! - Paint attributes - \sa setPaintAttribute, testPaintAttribute + Attributes how to represent the curve on the legend + + \sa setLegendAttribute(), testLegendAttribute(), + QwtPlotItem::legendData(), legendIcon() + */ + + enum LegendAttribute + { + /*! + QwtPlotCurve tries to find a color representing the curve + and paints a rectangle with it. + */ + LegendNoAttribute = 0x00, + + /*! + If the style() is not QwtPlotCurve::NoCurve a line + is painted with the curve pen(). + */ + LegendShowLine = 0x01, + + /*! + If the curve has a valid symbol it is painted. + */ + LegendShowSymbol = 0x02, + + /*! + If the curve has a brush a rectangle filled with the + curve brush() is painted. + */ + LegendShowBrush = 0x04 + }; + + //! Legend attributes + typedef QFlags<LegendAttribute> LegendAttributes; + + /*! + Attributes to modify the drawing algorithm. + The default setting enables ClipPolygons | FilterPoints + + \sa setPaintAttribute(), testPaintAttribute() */ - enum PaintAttribute { - PaintFiltered = 1, - ClipPolygons = 2 + enum PaintAttribute + { + /*! + Clip polygons before painting them. In situations, where points + are far outside the visible area (f.e when zooming deep) this + might be a substantial improvement for the painting performance + */ + ClipPolygons = 0x01, + + /*! + Tries to reduce the data that has to be painted, by sorting out + duplicates, or paintings outside the visible area. Might have a + notable impact on curves with many close points. + Only a couple of very basic filtering algorithms are implemented. + */ + FilterPoints = 0x02, + + /*! + Minimize memory usage that is temporarily needed for the + translated points, before they get painted. + This might slow down the performance of painting + */ + MinimizeMemory = 0x04, + + /*! + Render the points to a temporary image and paint the image. + This is a very special optimization for Dots style, when + having a huge amount of points. + With a reasonable number of points QPainter::drawPoints() + will be faster. + */ + ImageBuffer = 0x08 }; - explicit QwtPlotCurve(); - explicit QwtPlotCurve(const QwtText &title); - explicit QwtPlotCurve(const QString &title); + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + + explicit QwtPlotCurve( const QString &title = QString::null ); + explicit QwtPlotCurve( const QwtText &title ); virtual ~QwtPlotCurve(); virtual int rtti() const; - void setCurveType(CurveType); - CurveType curveType() const; + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; - void setPaintAttribute(PaintAttribute, bool on = true); - bool testPaintAttribute(PaintAttribute) const; + void setLegendAttribute( LegendAttribute, bool on = true ); + bool testLegendAttribute( LegendAttribute ) const; - void setRawData(const double *x, const double *y, int size); - void setData(const double *xData, const double *yData, int size); - void setData(const QwtArray<double> &xData, const QwtArray<double> &yData); -#if QT_VERSION < 0x040000 - void setData(const QwtArray<QwtDoublePoint> &data); -#else - void setData(const QPolygonF &data); +#ifndef QWT_NO_COMPAT + void setRawSamples( const double *xData, const double *yData, int size ); + void setSamples( const double *xData, const double *yData, int size ); + void setSamples( const QVector<double> &xData, const QVector<double> &yData ); #endif - void setData(const QwtData &data); - - int closestPoint(const QPoint &pos, double *dist = NULL) const; - - QwtData &data(); - const QwtData &data() const; - - int dataSize() const; - inline double x(int i) const; - inline double y(int i) const; - - virtual QwtDoubleRect boundingRect() const; - - //! boundingRect().left() - inline double minXValue() const { - return boundingRect().left(); - } - //! boundingRect().right() - inline double maxXValue() const { - return boundingRect().right(); - } - //! boundingRect().top() - inline double minYValue() const { - return boundingRect().top(); - } - //! boundingRect().bottom() - inline double maxYValue() const { - return boundingRect().bottom(); - } - - void setCurveAttribute(CurveAttribute, bool on = true); - bool testCurveAttribute(CurveAttribute) const; - - void setPen(const QPen &); + void setSamples( const QVector<QPointF> & ); + void setSamples( QwtSeriesData<QPointF> * ); + + int closestPoint( const QPoint &pos, double *dist = NULL ) const; + + double minXValue() const; + double maxXValue() const; + double minYValue() const; + double maxYValue() const; + + void setCurveAttribute( CurveAttribute, bool on = true ); + bool testCurveAttribute( CurveAttribute ) const; + + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); const QPen &pen() const; - void setBrush(const QBrush &); + void setBrush( const QBrush & ); const QBrush &brush() const; - void setBaseline(double ref); + void setBaseline( double ); double baseline() const; - void setStyle(CurveStyle style); + void setStyle( CurveStyle style ); CurveStyle style() const; - void setSymbol(const QwtSymbol &s); - const QwtSymbol& symbol() const; + void setSymbol( QwtSymbol * ); + const QwtSymbol *symbol() const; - void setCurveFitter(QwtCurveFitter *); + void setCurveFitter( QwtCurveFitter * ); QwtCurveFitter *curveFitter() const; - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &) const; - - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const; - - void draw(int from, int to) const; + virtual void drawSeries( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; - virtual void updateLegend(QwtLegend *) const; + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; protected: void init(); - virtual void drawCurve(QPainter *p, int style, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const; - - virtual void drawSymbols(QPainter *p, const QwtSymbol &, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const; - - void drawLines(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const; - void drawSticks(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const; - void drawDots(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const; - void drawSteps(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to) const; - - void fillCurve(QPainter *, - const QwtScaleMap &, const QwtScaleMap &, - QwtPolygon &) const; - void closePolyline(const QwtScaleMap &, const QwtScaleMap &, - QwtPolygon &) const; + virtual void drawCurve( QPainter *p, int style, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; -private: - QwtData *d_xy; + virtual void drawSymbols( QPainter *p, const QwtSymbol &, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void drawLines( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void drawSticks( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void drawDots( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + virtual void drawSteps( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void fillCurve( QPainter *, + const QwtScaleMap &, const QwtScaleMap &, + const QRectF &canvasRect, QPolygonF & ) const; + + void closePolyline( QPainter *, + const QwtScaleMap &, const QwtScaleMap &, QPolygonF & ) const; + +private: class PrivateData; PrivateData *d_data; }; -//! \return the the curve data -inline QwtData &QwtPlotCurve::data() +//! boundingRect().left() +inline double QwtPlotCurve::minXValue() const { - return *d_xy; + return boundingRect().left(); } -//! \return the the curve data -inline const QwtData &QwtPlotCurve::data() const +//! boundingRect().right() +inline double QwtPlotCurve::maxXValue() const { - return *d_xy; + return boundingRect().right(); } -/*! - \param i index - \return x-value at position i -*/ -inline double QwtPlotCurve::x(int i) const +//! boundingRect().top() +inline double QwtPlotCurve::minYValue() const { - return d_xy->x(i); + return boundingRect().top(); } -/*! - \param i index - \return y-value at position i -*/ -inline double QwtPlotCurve::y(int i) const +//! boundingRect().bottom() +inline double QwtPlotCurve::maxYValue() const { - return d_xy->y(i); + return boundingRect().bottom(); } +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::PaintAttributes ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::LegendAttributes ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::CurveAttributes ) + #endif diff --git a/libs/qwt/qwt_plot_dict.cpp b/libs/qwt/qwt_plot_dict.cpp index 2de1b4826d..17c61ed479 100644 --- a/libs/qwt/qwt_plot_dict.cpp +++ b/libs/qwt/qwt_plot_dict.cpp @@ -7,72 +7,52 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #include "qwt_plot_dict.h" class QwtPlotDict::PrivateData { public: -#if QT_VERSION < 0x040000 - class ItemList: public QValueList<QwtPlotItem *> -#else class ItemList: public QList<QwtPlotItem *> -#endif { public: - void insertItem(QwtPlotItem *item) { + void insertItem( QwtPlotItem *item ) + { if ( item == NULL ) return; - // Unfortunately there is no inSort operation - // for lists in Qt4. The implementation below - // is slow, but there shouldn't be many plot items. - -#ifdef __GNUC__ -#endif - -#if QT_VERSION < 0x040000 - QValueListIterator<QwtPlotItem *> it; -#else - QList<QwtPlotItem *>::Iterator it; -#endif - for ( it = begin(); it != end(); ++it ) { - if ( *it == item ) - return; - - if ( (*it)->z() > item->z() ) { - insert(it, item); - return; - } - } - append(item); + QList<QwtPlotItem *>::iterator it = + qUpperBound( begin(), end(), item, LessZThan() ); + insert( it, item ); } - void removeItem(QwtPlotItem *item) { + void removeItem( QwtPlotItem *item ) + { if ( item == NULL ) return; - int i = 0; - -#if QT_VERSION < 0x040000 - QValueListIterator<QwtPlotItem *> it; -#else - QList<QwtPlotItem *>::Iterator it; -#endif - for ( it = begin(); it != end(); ++it ) { - if ( item == *it ) { -#if QT_VERSION < 0x040000 - remove(it); -#else - removeAt(i); -#endif - return; + QList<QwtPlotItem *>::iterator it = + qLowerBound( begin(), end(), item, LessZThan() ); + + for ( ; it != end(); ++it ) + { + if ( item == *it ) + { + erase( it ); + break; } - i++; } } + private: + class LessZThan + { + public: + inline bool operator()( const QwtPlotItem *item1, + const QwtPlotItem *item2 ) const + { + return item1->z() < item2->z(); + } + }; }; ItemList itemList; @@ -83,7 +63,7 @@ public: Constructor Auto deletion is enabled. - \sa setAutoDelete, attachItem + \sa setAutoDelete(), QwtPlotItem::attach() */ QwtPlotDict::QwtPlotDict() { @@ -94,12 +74,12 @@ QwtPlotDict::QwtPlotDict() /*! Destructor - If autoDelete is on, all attached items will be deleted - \sa setAutoDelete, autoDelete, attachItem + If autoDelete() is on, all attached items will be deleted + \sa setAutoDelete(), autoDelete(), QwtPlotItem::attach() */ QwtPlotDict::~QwtPlotDict() { - detachItems(QwtPlotItem::Rtti_PlotItem, d_data->autoDelete); + detachItems( QwtPlotItem::Rtti_PlotItem, d_data->autoDelete ); delete d_data; } @@ -109,16 +89,16 @@ QwtPlotDict::~QwtPlotDict() If Auto deletion is on all attached plot items will be deleted in the destructor of QwtPlotDict. The default value is on. - \sa autoDelete, attachItem + \sa autoDelete(), insertItem() */ -void QwtPlotDict::setAutoDelete(bool autoDelete) +void QwtPlotDict::setAutoDelete( bool autoDelete ) { d_data->autoDelete = autoDelete; } /*! \return true if auto deletion is enabled - \sa setAutoDelete, attachItem + \sa setAutoDelete(), insertItem() */ bool QwtPlotDict::autoDelete() const { @@ -126,23 +106,25 @@ bool QwtPlotDict::autoDelete() const } /*! - Attach/Detach a plot item + Insert a plot item - Attached items will be deleted in the destructor, - if auto deletion is enabled (default). Manually detached - items are not deleted. + \param item PlotItem + \sa removeItem() + */ +void QwtPlotDict::insertItem( QwtPlotItem *item ) +{ + d_data->itemList.insertItem( item ); +} - \param item Plot item to attach/detach - \ on If true attach, else detach the item +/*! + Remove a plot item - \sa setAutoDelete, ~QwtPlotDict -*/ -void QwtPlotDict::attachItem(QwtPlotItem *item, bool on) + \param item PlotItem + \sa insertItem() + */ +void QwtPlotDict::removeItem( QwtPlotItem *item ) { - if ( on ) - d_data->itemList.insertItem(item); - else - d_data->itemList.removeItem(item); + d_data->itemList.removeItem( item ); } /*! @@ -152,30 +134,58 @@ void QwtPlotDict::attachItem(QwtPlotItem *item, bool on) otherwise only those items of the type rtti. \param autoDelete If true, delete all detached items */ -void QwtPlotDict::detachItems(int rtti, bool autoDelete) +void QwtPlotDict::detachItems( int rtti, bool autoDelete ) { PrivateData::ItemList list = d_data->itemList; QwtPlotItemIterator it = list.begin(); - while ( it != list.end() ) { + while ( it != list.end() ) + { QwtPlotItem *item = *it; ++it; // increment before removing item from the list - if ( rtti == QwtPlotItem::Rtti_PlotItem || item->rtti() == rtti ) { - item->attach(NULL); + if ( rtti == QwtPlotItem::Rtti_PlotItem || item->rtti() == rtti ) + { + item->attach( NULL ); if ( autoDelete ) delete item; } } } -//! \brief A QwtPlotItemList of all attached plot items. -/// -/// Use caution when iterating these lists, as removing/detaching an item will -/// invalidate the iterator. Instead you can place pointers to objects to be -/// removed in a removal list, and traverse that list later. -//! \return List of all attached plot items. +/*! + \brief A QwtPlotItemList of all attached plot items. + + Use caution when iterating these lists, as removing/detaching an item will + invalidate the iterator. Instead you can place pointers to objects to be + removed in a removal list, and traverse that list later. + + \return List of all attached plot items. +*/ const QwtPlotItemList &QwtPlotDict::itemList() const { return d_data->itemList; } + +/*! + \return List of all attached plot items of a specific type. + \param rtti See QwtPlotItem::RttiValues + \sa QwtPlotItem::rtti() +*/ +QwtPlotItemList QwtPlotDict::itemList( int rtti ) const +{ + if ( rtti == QwtPlotItem::Rtti_PlotItem ) + return d_data->itemList; + + QwtPlotItemList items; + + PrivateData::ItemList list = d_data->itemList; + for ( QwtPlotItemIterator it = list.begin(); it != list.end(); ++it ) + { + QwtPlotItem *item = *it; + if ( item->rtti() == rtti ) + items += item; + } + + return items; +} diff --git a/libs/qwt/qwt_plot_dict.h b/libs/qwt/qwt_plot_dict.h index f5640ad6b1..5d34f0c051 100644 --- a/libs/qwt/qwt_plot_dict.h +++ b/libs/qwt/qwt_plot_dict.h @@ -7,28 +7,18 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - /*! \file !*/ #ifndef QWT_PLOT_DICT #define QWT_PLOT_DICT #include "qwt_global.h" #include "qwt_plot_item.h" - -#if QT_VERSION < 0x040000 -#include <qvaluelist.h> -typedef QValueListConstIterator<QwtPlotItem *> QwtPlotItemIterator; -/// \var typedef QValueList< QwtPlotItem *> QwtPlotItemList -/// \brief See QT 3.x assistant documentation for QValueList -typedef QValueList<QwtPlotItem *> QwtPlotItemList; -#else #include <qlist.h> -typedef QList<QwtPlotItem *>::ConstIterator QwtPlotItemIterator; + /// \var typedef QList< QwtPlotItem *> QwtPlotItemList /// \brief See QT 4.x assistant documentation for QList typedef QList<QwtPlotItem *> QwtPlotItemList; -#endif +typedef QList<QwtPlotItem *>::ConstIterator QwtPlotItemIterator; /*! \brief A dictionary for plot items @@ -36,6 +26,8 @@ typedef QList<QwtPlotItem *> QwtPlotItemList; QwtPlotDict organizes plot items in increasing z-order. If autoDelete() is enabled, all attached items will be deleted in the destructor of the dictionary. + QwtPlotDict can be used to get access to all QwtPlotItem items - or all + items of a specific type - that are currently on the plot. \sa QwtPlotItem::attach(), QwtPlotItem::detach(), QwtPlotItem::z() */ @@ -43,21 +35,22 @@ class QWT_EXPORT QwtPlotDict { public: explicit QwtPlotDict(); - ~QwtPlotDict(); + virtual ~QwtPlotDict(); - void setAutoDelete(bool); + void setAutoDelete( bool ); bool autoDelete() const; const QwtPlotItemList& itemList() const; + QwtPlotItemList itemList( int rtti ) const; - void detachItems(int rtti = QwtPlotItem::Rtti_PlotItem, - bool autoDelete = true); - -private: - friend class QwtPlotItem; + void detachItems( int rtti = QwtPlotItem::Rtti_PlotItem, + bool autoDelete = true ); - void attachItem(QwtPlotItem *, bool); +protected: + void insertItem( QwtPlotItem * ); + void removeItem( QwtPlotItem * ); +private: class PrivateData; PrivateData *d_data; }; diff --git a/libs/qwt/qwt_plot_directpainter.cpp b/libs/qwt/qwt_plot_directpainter.cpp new file mode 100644 index 0000000000..d78352740c --- /dev/null +++ b/libs/qwt/qwt_plot_directpainter.cpp @@ -0,0 +1,317 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_directpainter.h" +#include "qwt_scale_map.h" +#include "qwt_plot.h" +#include "qwt_plot_canvas.h" +#include "qwt_plot_seriesitem.h" +#include <qpainter.h> +#include <qevent.h> +#include <qapplication.h> +#include <qpixmap.h> + +static inline void qwtRenderItem( + QPainter *painter, const QRect &canvasRect, + QwtPlotSeriesItem *seriesItem, int from, int to ) +{ + // A minor performance improvement is possible + // with caching the maps. TODO ... + + QwtPlot *plot = seriesItem->plot(); + const QwtScaleMap xMap = plot->canvasMap( seriesItem->xAxis() ); + const QwtScaleMap yMap = plot->canvasMap( seriesItem->yAxis() ); + + painter->setRenderHint( QPainter::Antialiasing, + seriesItem->testRenderHint( QwtPlotItem::RenderAntialiased ) ); + seriesItem->drawSeries( painter, xMap, yMap, canvasRect, from, to ); +} + +static inline bool qwtHasBackingStore( const QwtPlotCanvas *canvas ) +{ + return canvas->testPaintAttribute( QwtPlotCanvas::BackingStore ) + && canvas->backingStore() && !canvas->backingStore()->isNull(); +} + +class QwtPlotDirectPainter::PrivateData +{ +public: + PrivateData(): + attributes( 0 ), + hasClipping(false), + seriesItem( NULL ) + { + } + + QwtPlotDirectPainter::Attributes attributes; + + bool hasClipping; + QRegion clipRegion; + + QPainter painter; + + QwtPlotSeriesItem *seriesItem; + int from; + int to; +}; + +//! Constructor +QwtPlotDirectPainter::QwtPlotDirectPainter( QObject *parent ): + QObject( parent ) +{ + d_data = new PrivateData; +} + +//! Destructor +QwtPlotDirectPainter::~QwtPlotDirectPainter() +{ + delete d_data; +} + +/*! + Change an attribute + + \param attribute Attribute to change + \param on On/Off + + \sa Attribute, testAttribute() +*/ +void QwtPlotDirectPainter::setAttribute( Attribute attribute, bool on ) +{ + if ( bool( d_data->attributes & attribute ) != on ) + { + if ( on ) + d_data->attributes |= attribute; + else + d_data->attributes &= ~attribute; + + if ( ( attribute == AtomicPainter ) && on ) + reset(); + } +} + +/*! + \return True, when attribute is enabled + \param attribute Attribute to be tested + \sa Attribute, setAttribute() +*/ +bool QwtPlotDirectPainter::testAttribute( Attribute attribute ) const +{ + return d_data->attributes & attribute; +} + +/*! + En/Disables clipping + + \param enable Enables clipping is true, disable it otherwise + \sa hasClipping(), clipRegion(), setClipRegion() +*/ +void QwtPlotDirectPainter::setClipping( bool enable ) +{ + d_data->hasClipping = enable; +} + +/*! + \return true, when clipping is enabled + \sa setClipping(), clipRegion(), setClipRegion() +*/ +bool QwtPlotDirectPainter::hasClipping() const +{ + return d_data->hasClipping; +} + +/*! + \brief Assign a clip region and enable clipping + + Depending on the environment setting a proper clip region might improve + the performance heavily. F.e. on Qt embedded only the clipped part of + the backing store will be copied to a ( maybe unaccelerated ) frame buffer + device. + + \param region Clip region + \sa clipRegion(), hasClipping(), setClipping() +*/ +void QwtPlotDirectPainter::setClipRegion( const QRegion ®ion ) +{ + d_data->clipRegion = region; + d_data->hasClipping = true; +} + +/*! + \return Currently set clip region. + \sa setClipRegion(), setClipping(), hasClipping() +*/ +QRegion QwtPlotDirectPainter::clipRegion() const +{ + return d_data->clipRegion; +} + +/*! + \brief Draw a set of points of a seriesItem. + + When observing an measurement while it is running, new points have to be + added to an existing seriesItem. drawSeries() can be used to display them avoiding + a complete redraw of the canvas. + + Setting plot()->canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, true); + will result in faster painting, if the paint engine of the canvas widget + supports this feature. + + \param seriesItem Item to be painted + \param from Index of the first point to be painted + \param to Index of the last point to be painted. If to < 0 the + series will be painted to its last point. +*/ +void QwtPlotDirectPainter::drawSeries( + QwtPlotSeriesItem *seriesItem, int from, int to ) +{ + if ( seriesItem == NULL || seriesItem->plot() == NULL ) + return; + + QWidget *canvas = seriesItem->plot()->canvas(); + const QRect canvasRect = canvas->contentsRect(); + + QwtPlotCanvas *plotCanvas = qobject_cast<QwtPlotCanvas *>( canvas ); + + if ( plotCanvas && qwtHasBackingStore( plotCanvas ) ) + { + QPainter painter( const_cast<QPixmap *>( plotCanvas->backingStore() ) ); + + if ( d_data->hasClipping ) + painter.setClipRegion( d_data->clipRegion ); + + qwtRenderItem( &painter, canvasRect, seriesItem, from, to ); + + if ( testAttribute( QwtPlotDirectPainter::FullRepaint ) ) + { + plotCanvas->repaint(); + return; + } + } + + bool immediatePaint = true; + if ( !canvas->testAttribute( Qt::WA_WState_InPaintEvent ) ) + { +#if QT_VERSION < 0x050000 + if ( !canvas->testAttribute( Qt::WA_PaintOutsidePaintEvent ) ) +#endif + immediatePaint = false; + } + + if ( immediatePaint ) + { + if ( !d_data->painter.isActive() ) + { + reset(); + + d_data->painter.begin( canvas ); + canvas->installEventFilter( this ); + } + + if ( d_data->hasClipping ) + { + d_data->painter.setClipRegion( + QRegion( canvasRect ) & d_data->clipRegion ); + } + else + { + if ( !d_data->painter.hasClipping() ) + d_data->painter.setClipRect( canvasRect ); + } + + qwtRenderItem( &d_data->painter, canvasRect, seriesItem, from, to ); + + if ( d_data->attributes & QwtPlotDirectPainter::AtomicPainter ) + { + reset(); + } + else + { + if ( d_data->hasClipping ) + d_data->painter.setClipping( false ); + } + } + else + { + reset(); + + d_data->seriesItem = seriesItem; + d_data->from = from; + d_data->to = to; + + QRegion clipRegion = canvasRect; + if ( d_data->hasClipping ) + clipRegion &= d_data->clipRegion; + + canvas->installEventFilter( this ); + canvas->repaint(clipRegion); + canvas->removeEventFilter( this ); + + d_data->seriesItem = NULL; + } +} + +//! Close the internal QPainter +void QwtPlotDirectPainter::reset() +{ + if ( d_data->painter.isActive() ) + { + QWidget *w = static_cast<QWidget *>( d_data->painter.device() ); + if ( w ) + w->removeEventFilter( this ); + + d_data->painter.end(); + } +} + +//! Event filter +bool QwtPlotDirectPainter::eventFilter( QObject *, QEvent *event ) +{ + if ( event->type() == QEvent::Paint ) + { + reset(); + + if ( d_data->seriesItem ) + { + const QPaintEvent *pe = static_cast< QPaintEvent *>( event ); + + QWidget *canvas = d_data->seriesItem->plot()->canvas(); + + QPainter painter( canvas ); + painter.setClipRegion( pe->region() ); + + bool doCopyCache = testAttribute( CopyBackingStore ); + + if ( doCopyCache ) + { + QwtPlotCanvas *plotCanvas = + qobject_cast<QwtPlotCanvas *>( canvas ); + if ( plotCanvas ) + { + doCopyCache = qwtHasBackingStore( plotCanvas ); + if ( doCopyCache ) + { + painter.drawPixmap( plotCanvas->contentsRect().topLeft(), + *plotCanvas->backingStore() ); + } + } + } + + if ( !doCopyCache ) + { + qwtRenderItem( &painter, canvas->contentsRect(), + d_data->seriesItem, d_data->from, d_data->to ); + } + + return true; // don't call QwtPlotCanvas::paintEvent() + } + } + + return false; +} diff --git a/libs/qwt/qwt_plot_directpainter.h b/libs/qwt/qwt_plot_directpainter.h new file mode 100644 index 0000000000..b555c87c32 --- /dev/null +++ b/libs/qwt/qwt_plot_directpainter.h @@ -0,0 +1,100 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_DIRECT_PAINTER_H +#define QWT_PLOT_DIRECT_PAINTER_H + +#include "qwt_global.h" +#include <qobject.h> + +class QRegion; +class QwtPlotSeriesItem; + +/*! + \brief Painter object trying to paint incrementally + + Often applications want to display samples while they are + collected. When there are too many samples complete replots + will be expensive to be processed in a collection cycle. + + QwtPlotDirectPainter offers an API to paint + subsets ( f.e all additions points ) without erasing/repainting + the plot canvas. + + On certain environments it might be important to calculate a proper + clip region before painting. F.e. for Qt Embedded only the clipped part + of the backing store will be copied to a ( maybe unaccelerated ) + frame buffer. + + \warning Incremental painting will only help when no replot is triggered + by another operation ( like changing scales ) and nothing needs + to be erased. +*/ +class QWT_EXPORT QwtPlotDirectPainter: public QObject +{ +public: + /*! + \brief Paint attributes + \sa setAttribute(), testAttribute(), drawSeries() + */ + enum Attribute + { + /*! + Initializing a QPainter is an expensive operation. + When AtomicPainter is set each call of drawSeries() opens/closes + a temporary QPainter. Otherwise QwtPlotDirectPainter tries to + use the same QPainter as long as possible. + */ + AtomicPainter = 0x01, + + /*! + When FullRepaint is set the plot canvas is explicitly repainted + after the samples have been rendered. + */ + FullRepaint = 0x02, + + /*! + When QwtPlotCanvas::BackingStore is enabled the painter + has to paint to the backing store and the widget. In certain + situations/environments it might be faster to paint to + the backing store only and then copy the backing store to the canvas. + This flag can also be useful for settings, where Qt fills the + the clip region with the widget background. + */ + CopyBackingStore = 0x04 + }; + + //! Paint attributes + typedef QFlags<Attribute> Attributes; + + QwtPlotDirectPainter( QObject *parent = NULL ); + virtual ~QwtPlotDirectPainter(); + + void setAttribute( Attribute, bool on ); + bool testAttribute( Attribute ) const; + + void setClipping( bool ); + bool hasClipping() const; + + void setClipRegion( const QRegion & ); + QRegion clipRegion() const; + + void drawSeries( QwtPlotSeriesItem *, int from, int to ); + void reset(); + + virtual bool eventFilter( QObject *, QEvent * ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotDirectPainter::Attributes ) + +#endif diff --git a/libs/qwt/qwt_plot_glcanvas.cpp b/libs/qwt/qwt_plot_glcanvas.cpp new file mode 100644 index 0000000000..87a4cfde71 --- /dev/null +++ b/libs/qwt/qwt_plot_glcanvas.cpp @@ -0,0 +1,357 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_glcanvas.h" +#include "qwt_plot.h" +#include <qevent.h> +#include <qpainter.h> +#include <qdrawutil.h> +#include <qstyle.h> +#include <qstyleoption.h> +#include "qwt_painter.h" + +static QWidget *qwtBGWidget( QWidget *widget ) +{ + QWidget *w = widget; + + for ( ; w->parentWidget() != NULL; w = w->parentWidget() ) + { + if ( w->autoFillBackground() || + w->testAttribute( Qt::WA_StyledBackground ) ) + { + return w; + } + } + + return w; +} + +static void qwtUpdateContentsRect( QwtPlotGLCanvas *canvas ) +{ + const int fw = canvas->frameWidth(); + canvas->setContentsMargins( fw, fw, fw, fw ); +} + +class QwtPlotGLCanvas::PrivateData +{ +public: + PrivateData(): + frameStyle( QFrame::Panel | QFrame::Sunken), + lineWidth( 2 ), + midLineWidth( 0 ) + { + } + + int frameStyle; + int lineWidth; + int midLineWidth; +}; + +/*! + \brief Constructor + + \param plot Parent plot widget + \sa QwtPlot::setCanvas() +*/ +QwtPlotGLCanvas::QwtPlotGLCanvas( QwtPlot *plot ): + QGLWidget( plot ) +{ + d_data = new PrivateData; + +#ifndef QT_NO_CURSOR + setCursor( Qt::CrossCursor ); +#endif + + setAutoFillBackground( true ); + qwtUpdateContentsRect( this ); +} + +//! Destructor +QwtPlotGLCanvas::~QwtPlotGLCanvas() +{ + delete d_data; +} + +/*! + Set the frame style + + \param style The bitwise OR between a shape and a shadow. + + \sa frameStyle(), QFrame::setFrameStyle(), + setFrameShadow(), setFrameShape() + */ +void QwtPlotGLCanvas::setFrameStyle( int style ) +{ + if ( style != d_data->frameStyle ) + { + d_data->frameStyle = style; + qwtUpdateContentsRect( this ); + + update(); + } +} + +/*! + \return The bitwise OR between a frameShape() and a frameShadow() + \sa setFrameStyle(), QFrame::frameStyle() + */ +int QwtPlotGLCanvas::frameStyle() const +{ + return d_data->frameStyle; +} + +/*! + Set the frame shadow + + \param shadow Frame shadow + \sa frameShadow(), setFrameShape(), QFrame::setFrameShadow() + */ +void QwtPlotGLCanvas::setFrameShadow( Shadow shadow ) +{ + setFrameStyle(( d_data->frameStyle & QFrame::Shape_Mask ) | shadow ); +} + +/*! + \return Frame shadow + \sa setFrameShadow(), QFrame::setFrameShadow() + */ +QwtPlotGLCanvas::Shadow QwtPlotGLCanvas::frameShadow() const +{ + return (Shadow) ( d_data->frameStyle & QFrame::Shadow_Mask ); +} + +/*! + Set the frame shape + + \param shape Frame shape + \sa frameShape(), setFrameShadow(), QFrame::frameShape() + */ +void QwtPlotGLCanvas::setFrameShape( Shape shape ) +{ + setFrameStyle( ( d_data->frameStyle & QFrame::Shadow_Mask ) | shape ); +} + +/*! + \return Frame shape + \sa setFrameShape(), QFrame::frameShape() + */ +QwtPlotGLCanvas::Shape QwtPlotGLCanvas::frameShape() const +{ + return (Shape) ( d_data->frameStyle & QFrame::Shape_Mask ); +} + +/*! + Set the frame line width + + The default line width is 2 pixels. + + \param width Line width of the frame + \sa lineWidth(), setMidLineWidth() +*/ +void QwtPlotGLCanvas::setLineWidth( int width ) +{ + width = qMax( width, 0 ); + if ( width != d_data->lineWidth ) + { + d_data->lineWidth = qMax( width, 0 ); + qwtUpdateContentsRect( this ); + update(); + } +} + +/*! + \return Line width of the frame + \sa setLineWidth(), midLineWidth() + */ +int QwtPlotGLCanvas::lineWidth() const +{ + return d_data->lineWidth; +} + +/*! + Set the frame mid line width + + The default midline width is 0 pixels. + + \param width Midline width of the frame + \sa midLineWidth(), setLineWidth() +*/ +void QwtPlotGLCanvas::setMidLineWidth( int width ) +{ + width = qMax( width, 0 ); + if ( width != d_data->midLineWidth ) + { + d_data->midLineWidth = width; + qwtUpdateContentsRect( this ); + update(); + } +} + +/*! + \return Midline width of the frame + \sa setMidLineWidth(), lineWidth() + */ +int QwtPlotGLCanvas::midLineWidth() const +{ + return d_data->midLineWidth; +} + +/*! + \return Frame width depending on the style, line width and midline width. + */ +int QwtPlotGLCanvas::frameWidth() const +{ + return ( frameStyle() != NoFrame ) ? d_data->lineWidth : 0; +} + +/*! + Paint event + + \param event Paint event + \sa QwtPlot::drawCanvas() +*/ +void QwtPlotGLCanvas::paintEvent( QPaintEvent *event ) +{ + Q_UNUSED( event ); + + QPainter painter( this ); + + drawBackground( &painter ); + drawItems( &painter ); + + if ( !testAttribute( Qt::WA_StyledBackground ) ) + { + if ( frameWidth() > 0 ) + drawBorder( &painter ); + } +} +/*! + Qt event handler for QEvent::PolishRequest and QEvent::StyleChange + \param event Qt Event + \return See QGLWidget::event() +*/ +bool QwtPlotGLCanvas::event( QEvent *event ) +{ + const bool ok = QGLWidget::event( event ); + + if ( event->type() == QEvent::PolishRequest || + event->type() == QEvent::StyleChange ) + { + // assuming, that we always have a styled background + // when we have a style sheet + + setAttribute( Qt::WA_StyledBackground, + testAttribute( Qt::WA_StyleSheet ) ); + } + + return ok; +} + +/*! + Draw the plot items + \param painter Painter + + \sa QwtPlot::drawCanvas() +*/ +void QwtPlotGLCanvas::drawItems( QPainter *painter ) +{ + painter->save(); + + painter->setClipRect( contentsRect(), Qt::IntersectClip ); + + QwtPlot *plot = qobject_cast< QwtPlot *>( parent() ); + if ( plot ) + plot->drawCanvas( painter ); + + painter->restore(); +} + +/*! + Draw the background of the canvas + \param painter Painter +*/ +void QwtPlotGLCanvas::drawBackground( QPainter *painter ) +{ + painter->save(); + + QWidget *w = qwtBGWidget( this ); + + const QPoint off = mapTo( w, QPoint() ); + painter->translate( -off ); + + const QRect fillRect = rect().translated( off ); + + if ( w->testAttribute( Qt::WA_StyledBackground ) ) + { + painter->setClipRect( fillRect ); + + QStyleOption opt; + opt.initFrom( w ); + w->style()->drawPrimitive( QStyle::PE_Widget, &opt, painter, w); + } + else + { + painter->fillRect( fillRect, + w->palette().brush( w->backgroundRole() ) ); + } + + painter->restore(); +} + +/*! + Draw the border of the canvas + \param painter Painter +*/ +void QwtPlotGLCanvas::drawBorder( QPainter *painter ) +{ + const int fw = frameWidth(); + if ( fw <= 0 ) + return; + + if ( frameShadow() == QwtPlotGLCanvas::Plain ) + { + qDrawPlainRect( painter, frameRect(), + palette().shadow().color(), lineWidth() ); + } + else + { + if ( frameShape() == QwtPlotGLCanvas::Box ) + { + qDrawShadeRect( painter, frameRect(), palette(), + frameShadow() == Sunken, lineWidth(), midLineWidth() ); + } + else + { + qDrawShadePanel( painter, frameRect(), palette(), + frameShadow() == Sunken, lineWidth() ); + } + } +} + +//! Calls repaint() +void QwtPlotGLCanvas::replot() +{ + repaint(); +} + +/*! + \return Empty path +*/ +QPainterPath QwtPlotGLCanvas::borderPath( const QRect &rect ) const +{ + Q_UNUSED( rect ); + return QPainterPath(); +} + +//! \return The rectangle where the frame is drawn in. +QRect QwtPlotGLCanvas::frameRect() const +{ + const int fw = frameWidth(); + return contentsRect().adjusted( -fw, -fw, fw, fw ); +} diff --git a/libs/qwt/qwt_plot_glcanvas.h b/libs/qwt/qwt_plot_glcanvas.h new file mode 100644 index 0000000000..2ff1cf2e31 --- /dev/null +++ b/libs/qwt/qwt_plot_glcanvas.h @@ -0,0 +1,136 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_GLCANVAS_H +#define QWT_PLOT_GLCANVAS_H + +#include "qwt_global.h" +#include <qframe.h> +#include <qgl.h> + +class QwtPlot; + +/*! + \brief An alternative canvas for a QwtPlot derived from QGLWidget + + QwtPlotGLCanvas implements the very basics to act as canvas + inside of a QwtPlot widget. It might be extended to a full + featured alternative to QwtPlotCanvas in a future version of Qwt. + + Even if QwtPlotGLCanvas is not derived from QFrame it imitates + its API. When using style sheets it supports the box model - beside + backgrounds with rounded borders. + + \sa QwtPlot::setCanvas(), QwtPlotCanvas + + \note You might want to use the QPaintEngine::OpenGL paint engine + ( see QGL::setPreferredPaintEngine() ). On a Linux test system + QPaintEngine::OpenGL2 shows very basic problems ( wrong + geometries of rectangles ) but also more advanced stuff + like antialiasing doesn't work. + + \note Another way to introduce OpenGL rendering to Qwt + is to use QGLPixelBuffer or QGLFramebufferObject. Both + type of buffers can be converted into a QImage and + used in combination with a regular QwtPlotCanvas. +*/ +class QWT_EXPORT QwtPlotGLCanvas: public QGLWidget +{ + Q_OBJECT + + Q_ENUMS( Shape Shadow ) + + Q_PROPERTY( Shadow frameShadow READ frameShadow WRITE setFrameShadow ) + Q_PROPERTY( Shape frameShape READ frameShape WRITE setFrameShape ) + Q_PROPERTY( int lineWidth READ lineWidth WRITE setLineWidth ) + Q_PROPERTY( int midLineWidth READ midLineWidth WRITE setMidLineWidth ) + Q_PROPERTY( int frameWidth READ frameWidth ) + Q_PROPERTY( QRect frameRect READ frameRect DESIGNABLE false ) + +public: + /*! + \brief Frame shadow + + Unfortunately it is not possible to use QFrame::Shadow + as a property of a widget that is not derived from QFrame. + The following enum is made for the designer only. It is safe + to use QFrame::Shadow instead. + */ + enum Shadow + { + //! QFrame::Plain + Plain = QFrame::Plain, + + //! QFrame::Raised + Raised = QFrame::Raised, + + //! QFrame::Sunken + Sunken = QFrame::Sunken + }; + + /*! + \brief Frame shape + + Unfortunately it is not possible to use QFrame::Shape + as a property of a widget that is not derived from QFrame. + The following enum is made for the designer only. It is safe + to use QFrame::Shadow instead. + + \note QFrame::StyledPanel and QFrame::WinPanel are unsuported + and will be displayed as QFrame::Panel. + */ + enum Shape + { + NoFrame = QFrame::NoFrame, + + Box = QFrame::Box, + Panel = QFrame::Panel + }; + + explicit QwtPlotGLCanvas( QwtPlot * = NULL ); + virtual ~QwtPlotGLCanvas(); + + void setFrameStyle( int style ); + int frameStyle() const; + + void setFrameShadow( Shadow ); + Shadow frameShadow() const; + + void setFrameShape( Shape ); + Shape frameShape() const; + + void setLineWidth( int ); + int lineWidth() const; + + void setMidLineWidth( int ); + int midLineWidth() const; + + int frameWidth() const; + QRect frameRect() const; + + Q_INVOKABLE QPainterPath borderPath( const QRect & ) const; + + virtual bool event( QEvent * ); + +public Q_SLOTS: + void replot(); + +protected: + virtual void paintEvent( QPaintEvent * ); + + virtual void drawBackground( QPainter * ); + virtual void drawBorder( QPainter * ); + virtual void drawItems( QPainter * ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_grid.cpp b/libs/qwt/qwt_plot_grid.cpp index 0d512b4256..4375e53d7d 100644 --- a/libs/qwt/qwt_plot_grid.cpp +++ b/libs/qwt/qwt_plot_grid.cpp @@ -7,22 +7,24 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qpainter.h> -#include <qpen.h> +#include "qwt_plot_grid.h" #include "qwt_painter.h" #include "qwt_text.h" #include "qwt_scale_map.h" #include "qwt_scale_div.h" -#include "qwt_plot_grid.h" +#include "qwt_math.h" +#include <qpainter.h> +#include <qpen.h> class QwtPlotGrid::PrivateData { public: PrivateData(): - xEnabled(true), - yEnabled(true), - xMinEnabled(false), - yMinEnabled(false) { + xEnabled( true ), + yEnabled( true ), + xMinEnabled( false ), + yMinEnabled( false ) + { } bool xEnabled; @@ -33,16 +35,18 @@ public: QwtScaleDiv xScaleDiv; QwtScaleDiv yScaleDiv; - QPen majPen; - QPen minPen; + QPen majorPen; + QPen minorPen; }; //! Enables major grid, disables minor grid QwtPlotGrid::QwtPlotGrid(): - QwtPlotItem(QwtText("Grid")) + QwtPlotItem( QwtText( "Grid" ) ) { d_data = new PrivateData; - setZ(10.0); + + setItemInterest( QwtPlotItem::ScaleInterest, true ); + setZ( 10.0 ); } //! Destructor @@ -58,122 +62,201 @@ int QwtPlotGrid::rtti() const } /*! - \brief Enable or disable vertical gridlines - \param tf Enable (true) or disable + \brief Enable or disable vertical grid lines + \param on Enable (true) or disable - \sa Minor gridlines can be enabled or disabled with + \sa Minor grid lines can be enabled or disabled with enableXMin() */ -void QwtPlotGrid::enableX(bool tf) +void QwtPlotGrid::enableX( bool on ) { - if ( d_data->xEnabled != tf ) { - d_data->xEnabled = tf; + if ( d_data->xEnabled != on ) + { + d_data->xEnabled = on; + + legendChanged(); itemChanged(); } } /*! - \brief Enable or disable horizontal gridlines - \param tf Enable (true) or disable - \sa Minor gridlines can be enabled or disabled with enableYMin() + \brief Enable or disable horizontal grid lines + \param on Enable (true) or disable + \sa Minor grid lines can be enabled or disabled with enableYMin() */ -void QwtPlotGrid::enableY(bool tf) +void QwtPlotGrid::enableY( bool on ) { - if ( d_data->yEnabled != tf ) { - d_data->yEnabled = tf; + if ( d_data->yEnabled != on ) + { + d_data->yEnabled = on; + + legendChanged(); itemChanged(); } } /*! - \brief Enable or disable minor vertical gridlines. - \param tf Enable (true) or disable + \brief Enable or disable minor vertical grid lines. + \param on Enable (true) or disable \sa enableX() */ -void QwtPlotGrid::enableXMin(bool tf) +void QwtPlotGrid::enableXMin( bool on ) { - if ( d_data->xMinEnabled != tf ) { - d_data->xMinEnabled = tf; + if ( d_data->xMinEnabled != on ) + { + d_data->xMinEnabled = on; + + legendChanged(); itemChanged(); } } /*! - \brief Enable or disable minor horizontal gridlines - \param tf Enable (true) or disable + \brief Enable or disable minor horizontal grid lines + \param on Enable (true) or disable \sa enableY() */ -void QwtPlotGrid::enableYMin(bool tf) +void QwtPlotGrid::enableYMin( bool on ) { - if ( d_data->yMinEnabled != tf ) { - d_data->yMinEnabled = tf; + if ( d_data->yMinEnabled != on ) + { + d_data->yMinEnabled = on; + + legendChanged(); itemChanged(); } } /*! - \brief Assign an x axis scale division + Assign an x axis scale division + \param scaleDiv Scale division - \warning QwtPlotGrid uses implicit sharing (see Qt Manual) for - the scale divisions. */ -void QwtPlotGrid::setXDiv(const QwtScaleDiv &scaleDiv) +void QwtPlotGrid::setXDiv( const QwtScaleDiv &scaleDiv ) { - if ( d_data->xScaleDiv != scaleDiv ) { + if ( d_data->xScaleDiv != scaleDiv ) + { d_data->xScaleDiv = scaleDiv; itemChanged(); } } /*! - \brief Assign a y axis division - \param sy Scale division - \warning QwtPlotGrid uses implicit sharing (see Qt Manual) for - the scale divisions. + Assign a y axis division + + \param scaleDiv Scale division */ -void QwtPlotGrid::setYDiv(const QwtScaleDiv &sy) +void QwtPlotGrid::setYDiv( const QwtScaleDiv &scaleDiv ) { - if ( d_data->yScaleDiv != sy ) { - d_data->yScaleDiv = sy; + if ( d_data->yScaleDiv != scaleDiv ) + { + d_data->yScaleDiv = scaleDiv; itemChanged(); } } /*! - \brief Assign a pen for both major and minor gridlines - \param p Pen - \sa setMajPen(), setMinPen() + Build and assign a pen for both major and minor grid lines + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotGrid::setPen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setPen( QPen( color, width, style ) ); +} + +/*! + Assign a pen for both major and minor grid lines + + \param pen Pen + \sa setMajorPen(), setMinorPen() */ -void QwtPlotGrid::setPen(const QPen &p) +void QwtPlotGrid::setPen( const QPen &pen ) { - if ( d_data->majPen != p || d_data->minPen != p ) { - d_data->majPen = p; - d_data->minPen = p; + if ( d_data->majorPen != pen || d_data->minorPen != pen ) + { + d_data->majorPen = pen; + d_data->minorPen = pen; + + legendChanged(); itemChanged(); } } /*! - \brief Assign a pen for the major gridlines - \param p Pen - \sa majPen(), setMinPen(), setPen() + Build and assign a pen for both major grid lines + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotGrid::setMajorPen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setMajorPen( QPen( color, width, style ) ); +} + +/*! + Assign a pen for the major grid lines + + \param pen Pen + \sa majorPen(), setMinorPen(), setPen() */ -void QwtPlotGrid::setMajPen(const QPen &p) +void QwtPlotGrid::setMajorPen( const QPen &pen ) { - if ( d_data->majPen != p ) { - d_data->majPen = p; + if ( d_data->majorPen != pen ) + { + d_data->majorPen = pen; + + legendChanged(); itemChanged(); } } /*! - \brief Assign a pen for the minor gridlines - \param p Pen + Build and assign a pen for the minor grid lines + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotGrid::setMinorPen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setMinorPen( QPen( color, width, style ) ); +} + +/*! + Assign a pen for the minor grid lines + + \param pen Pen + \sa minorPen(), setMajorPen(), setPen() */ -void QwtPlotGrid::setMinPen(const QPen &p) +void QwtPlotGrid::setMinorPen( const QPen &pen ) { - if ( d_data->minPen != p ) { - d_data->minPen = p; + if ( d_data->minorPen != pen ) + { + d_data->minorPen = pen; + + legendChanged(); itemChanged(); } } @@ -182,90 +265,116 @@ void QwtPlotGrid::setMinPen(const QPen &p) \brief Draw the grid The grid is drawn into the bounding rectangle such that - gridlines begin and end at the rectangle's borders. The X and Y + grid lines begin and end at the rectangle's borders. The X and Y maps are used to map the scale divisions into the drawing region screen. + \param painter Painter \param xMap X axis map \param yMap Y axis - \param canvasRect Contents rect of the plot canvas + \param canvasRect Contents rectangle of the plot canvas */ -void QwtPlotGrid::draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &canvasRect) const +void QwtPlotGrid::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const { - // draw minor gridlines - painter->setPen(d_data->minPen); - - if (d_data->xEnabled && d_data->xMinEnabled) { - drawLines(painter, canvasRect, Qt::Vertical, xMap, - d_data->xScaleDiv.ticks(QwtScaleDiv::MinorTick)); - drawLines(painter, canvasRect, Qt::Vertical, xMap, - d_data->xScaleDiv.ticks(QwtScaleDiv::MediumTick)); + // draw minor grid lines + QPen minorPen = d_data->minorPen; + minorPen.setCapStyle( Qt::FlatCap ); + + painter->setPen( minorPen ); + + if ( d_data->xEnabled && d_data->xMinEnabled ) + { + drawLines( painter, canvasRect, Qt::Vertical, xMap, + d_data->xScaleDiv.ticks( QwtScaleDiv::MinorTick ) ); + drawLines( painter, canvasRect, Qt::Vertical, xMap, + d_data->xScaleDiv.ticks( QwtScaleDiv::MediumTick ) ); } - if (d_data->yEnabled && d_data->yMinEnabled) { - drawLines(painter, canvasRect, Qt::Horizontal, yMap, - d_data->yScaleDiv.ticks(QwtScaleDiv::MinorTick)); - drawLines(painter, canvasRect, Qt::Horizontal, yMap, - d_data->yScaleDiv.ticks(QwtScaleDiv::MediumTick)); + if ( d_data->yEnabled && d_data->yMinEnabled ) + { + drawLines( painter, canvasRect, Qt::Horizontal, yMap, + d_data->yScaleDiv.ticks( QwtScaleDiv::MinorTick ) ); + drawLines( painter, canvasRect, Qt::Horizontal, yMap, + d_data->yScaleDiv.ticks( QwtScaleDiv::MediumTick ) ); } - // draw major gridlines - painter->setPen(d_data->majPen); + // draw major grid lines + QPen majorPen = d_data->majorPen; + majorPen.setCapStyle( Qt::FlatCap ); - if (d_data->xEnabled) { - drawLines(painter, canvasRect, Qt::Vertical, xMap, - d_data->xScaleDiv.ticks(QwtScaleDiv::MajorTick)); + painter->setPen( majorPen ); + + if ( d_data->xEnabled ) + { + drawLines( painter, canvasRect, Qt::Vertical, xMap, + d_data->xScaleDiv.ticks( QwtScaleDiv::MajorTick ) ); } - if (d_data->yEnabled) { - drawLines(painter, canvasRect, Qt::Horizontal, yMap, - d_data->yScaleDiv.ticks(QwtScaleDiv::MajorTick)); + if ( d_data->yEnabled ) + { + drawLines( painter, canvasRect, Qt::Horizontal, yMap, + d_data->yScaleDiv.ticks( QwtScaleDiv::MajorTick ) ); } } -void QwtPlotGrid::drawLines(QPainter *painter, const QRect &canvasRect, - Qt::Orientation orientation, const QwtScaleMap &scaleMap, - const QwtValueList &values) const +void QwtPlotGrid::drawLines( QPainter *painter, const QRectF &canvasRect, + Qt::Orientation orientation, const QwtScaleMap &scaleMap, + const QList<double> &values ) const { - const int x1 = canvasRect.left(); - const int x2 = canvasRect.right(); - const int y1 = canvasRect.top(); - const int y2 = canvasRect.bottom(); - - for (uint i = 0; i < (uint)values.count(); i++) { - const int value = scaleMap.transform(values[i]); - if ( orientation == Qt::Horizontal ) { - if ((value >= y1) && (value <= y2)) - QwtPainter::drawLine(painter, x1, value, x2, value); - } else { - if ((value >= x1) && (value <= x2)) - QwtPainter::drawLine(painter, value, y1, value, y2); + const double x1 = canvasRect.left(); + const double x2 = canvasRect.right() - 1.0; + const double y1 = canvasRect.top(); + const double y2 = canvasRect.bottom() - 1.0; + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + for ( int i = 0; i < values.count(); i++ ) + { + double value = scaleMap.transform( values[i] ); + if ( doAlign ) + value = qRound( value ); + + if ( orientation == Qt::Horizontal ) + { + if ( qwtFuzzyGreaterOrEqual( value, y1 ) && + qwtFuzzyLessOrEqual( value, y2 ) ) + { + QwtPainter::drawLine( painter, x1, value, x2, value ); + } + } + else + { + if ( qwtFuzzyGreaterOrEqual( value, x1 ) && + qwtFuzzyLessOrEqual( value, x2 ) ) + { + QwtPainter::drawLine( painter, value, y1, value, y2 ); + } } } } /*! - \return the pen for the major gridlines - \sa setMajPen(), setMinPen(), setPen() + \return the pen for the major grid lines + \sa setMajorPen(), setMinorPen(), setPen() */ -const QPen &QwtPlotGrid::majPen() const +const QPen &QwtPlotGrid::majorPen() const { - return d_data->majPen; + return d_data->majorPen; } /*! - \return the pen for the minor gridlines - \sa setMinPen(), setMajPen(), setPen() + \return the pen for the minor grid lines + \sa setMinorPen(), setMajorPen(), setPen() */ -const QPen &QwtPlotGrid::minPen() const +const QPen &QwtPlotGrid::minorPen() const { - return d_data->minPen; + return d_data->minorPen; } /*! - \return true if vertical gridlines are enabled + \return true if vertical grid lines are enabled \sa enableX() */ bool QwtPlotGrid::xEnabled() const @@ -274,7 +383,7 @@ bool QwtPlotGrid::xEnabled() const } /*! - \return true if minor vertical gridlines are enabled + \return true if minor vertical grid lines are enabled \sa enableXMin() */ bool QwtPlotGrid::xMinEnabled() const @@ -283,7 +392,7 @@ bool QwtPlotGrid::xMinEnabled() const } /*! - \return true if horizontal gridlines are enabled + \return true if horizontal grid lines are enabled \sa enableY() */ bool QwtPlotGrid::yEnabled() const @@ -292,7 +401,7 @@ bool QwtPlotGrid::yEnabled() const } /*! - \return true if minor horizontal gridlines are enabled + \return true if minor horizontal grid lines are enabled \sa enableYMin() */ bool QwtPlotGrid::yMinEnabled() const @@ -313,9 +422,17 @@ const QwtScaleDiv &QwtPlotGrid::yScaleDiv() const return d_data->yScaleDiv; } -void QwtPlotGrid::updateScaleDiv(const QwtScaleDiv& xDiv, - const QwtScaleDiv& yDiv) +/*! + Update the grid to changes of the axes scale division + + \param xScaleDiv Scale division of the x-axis + \param yScaleDiv Scale division of the y-axis + + \sa QwtPlot::updateAxes() +*/ +void QwtPlotGrid::updateScaleDiv( const QwtScaleDiv& xScaleDiv, + const QwtScaleDiv& yScaleDiv ) { - setXDiv(xDiv); - setYDiv(yDiv); + setXDiv( xScaleDiv ); + setYDiv( yScaleDiv ); } diff --git a/libs/qwt/qwt_plot_grid.h b/libs/qwt/qwt_plot_grid.h index 4070353374..16d984c721 100644 --- a/libs/qwt/qwt_plot_grid.h +++ b/libs/qwt/qwt_plot_grid.h @@ -24,7 +24,7 @@ class QwtScaleDiv; The QwtPlotGrid class can be used to draw a coordinate grid. A coordinate grid consists of major and minor vertical - and horizontal gridlines. The locations of the gridlines + and horizontal grid lines. The locations of the grid lines are determined by the X and Y scale divisions which can be assigned with setXDiv() and setYDiv(). The draw() member draws the grid within a bounding @@ -39,43 +39,46 @@ public: virtual int rtti() const; - void enableX(bool tf); + void enableX( bool tf ); bool xEnabled() const; - void enableY(bool tf); + void enableY( bool tf ); bool yEnabled() const; - void enableXMin(bool tf); + void enableXMin( bool tf ); bool xMinEnabled() const; - void enableYMin(bool tf); + void enableYMin( bool tf ); bool yMinEnabled() const; - void setXDiv(const QwtScaleDiv &sx); + void setXDiv( const QwtScaleDiv &sx ); const QwtScaleDiv &xScaleDiv() const; - void setYDiv(const QwtScaleDiv &sy); + void setYDiv( const QwtScaleDiv &sy ); const QwtScaleDiv &yScaleDiv() const; - void setPen(const QPen &p); + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); - void setMajPen(const QPen &p); - const QPen& majPen() const; + void setMajorPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setMajorPen( const QPen & ); + const QPen& majorPen() const; - void setMinPen(const QPen &p); - const QPen& minPen() const; + void setMinorPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setMinorPen( const QPen &p ); + const QPen& minorPen() const; - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &rect) const; + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; - virtual void updateScaleDiv(const QwtScaleDiv &xMap, - const QwtScaleDiv &yMap); + virtual void updateScaleDiv( + const QwtScaleDiv &xMap, const QwtScaleDiv &yMap ); private: - void drawLines(QPainter *painter, const QRect &, - Qt::Orientation orientation, const QwtScaleMap &, - const QwtValueList &) const; + void drawLines( QPainter *painter, const QRectF &, + Qt::Orientation orientation, const QwtScaleMap &, + const QList<double> & ) const; class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_plot_histogram.cpp b/libs/qwt/qwt_plot_histogram.cpp new file mode 100644 index 0000000000..4464f03ff4 --- /dev/null +++ b/libs/qwt/qwt_plot_histogram.cpp @@ -0,0 +1,690 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_histogram.h" +#include "qwt_plot.h" +#include "qwt_painter.h" +#include "qwt_column_symbol.h" +#include "qwt_scale_map.h" +#include <qstring.h> +#include <qpainter.h> + +static inline bool qwtIsCombinable( const QwtInterval &d1, + const QwtInterval &d2 ) +{ + if ( d1.isValid() && d2.isValid() ) + { + if ( d1.maxValue() == d2.minValue() ) + { + if ( !( d1.borderFlags() & QwtInterval::ExcludeMaximum + && d2.borderFlags() & QwtInterval::ExcludeMinimum ) ) + { + return true; + } + } + } + + return false; +} + +class QwtPlotHistogram::PrivateData +{ +public: + PrivateData(): + baseline( 0.0 ), + style( Columns ), + symbol( NULL ) + { + } + + ~PrivateData() + { + delete symbol; + } + + double baseline; + + QPen pen; + QBrush brush; + QwtPlotHistogram::HistogramStyle style; + const QwtColumnSymbol *symbol; +}; + +/*! + Constructor + \param title Title of the histogram. +*/ +QwtPlotHistogram::QwtPlotHistogram( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the histogram. +*/ +QwtPlotHistogram::QwtPlotHistogram( const QString &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +//! Destructor +QwtPlotHistogram::~QwtPlotHistogram() +{ + delete d_data; +} + +//! Initialize data members +void QwtPlotHistogram::init() +{ + d_data = new PrivateData(); + setData( new QwtIntervalSeriesData() ); + + setItemAttribute( QwtPlotItem::AutoScale, true ); + setItemAttribute( QwtPlotItem::Legend, true ); + + setZ( 20.0 ); +} + +/*! + Set the histogram's drawing style + + \param style Histogram style + \sa HistogramStyle, style() +*/ +void QwtPlotHistogram::setStyle( HistogramStyle style ) +{ + if ( style != d_data->style ) + { + d_data->style = style; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Style of the histogram + \sa HistogramStyle, setStyle() +*/ +QwtPlotHistogram::HistogramStyle QwtPlotHistogram::style() const +{ + return d_data->style; +} + +/*! + Build and assign a pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotHistogram::setPen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setPen( QPen( color, width, style ) ); +} + +/*! + Assign a pen, that is used in a style() depending way. + + \param pen New pen + \sa pen(), brush() +*/ +void QwtPlotHistogram::setPen( const QPen &pen ) +{ + if ( pen != d_data->pen ) + { + d_data->pen = pen; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Pen used in a style() depending way. + \sa setPen(), brush() +*/ +const QPen &QwtPlotHistogram::pen() const +{ + return d_data->pen; +} + +/*! + Assign a brush, that is used in a style() depending way. + + \param brush New brush + \sa pen(), brush() +*/ +void QwtPlotHistogram::setBrush( const QBrush &brush ) +{ + if ( brush != d_data->brush ) + { + d_data->brush = brush; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Brush used in a style() depending way. + \sa setPen(), brush() +*/ +const QBrush &QwtPlotHistogram::brush() const +{ + return d_data->brush; +} + +/*! + \brief Assign a symbol + + In Column style an optional symbol can be assigned, that is responsible + for displaying the rectangle that is defined by the interval and + the distance between baseline() and value. When no symbol has been + defined the area is displayed as plain rectangle using pen() and brush(). + + \sa style(), symbol(), drawColumn(), pen(), brush() + + \note In applications, where different intervals need to be displayed + in a different way ( f.e different colors or even using different symbols) + it is recommended to overload drawColumn(). +*/ +void QwtPlotHistogram::setSymbol( const QwtColumnSymbol *symbol ) +{ + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Current symbol or NULL, when no symbol has been assigned + \sa setSymbol() +*/ +const QwtColumnSymbol *QwtPlotHistogram::symbol() const +{ + return d_data->symbol; +} + +/*! + \brief Set the value of the baseline + + Each column representing an QwtIntervalSample is defined by its + interval and the interval between baseline and the value of the sample. + + The default value of the baseline is 0.0. + + \param value Value of the baseline + \sa baseline() +*/ +void QwtPlotHistogram::setBaseline( double value ) +{ + if ( d_data->baseline != value ) + { + d_data->baseline = value; + itemChanged(); + } +} + +/*! + \return Value of the baseline + \sa setBaseline() +*/ +double QwtPlotHistogram::baseline() const +{ + return d_data->baseline; +} + +/*! + \return Bounding rectangle of all samples. + For an empty series the rectangle is invalid. +*/ +QRectF QwtPlotHistogram::boundingRect() const +{ + QRectF rect = data()->boundingRect(); + if ( !rect.isValid() ) + return rect; + + if ( orientation() == Qt::Horizontal ) + { + rect = QRectF( rect.y(), rect.x(), + rect.height(), rect.width() ); + + if ( rect.left() > d_data->baseline ) + rect.setLeft( d_data->baseline ); + else if ( rect.right() < d_data->baseline ) + rect.setRight( d_data->baseline ); + } + else + { + if ( rect.bottom() < d_data->baseline ) + rect.setBottom( d_data->baseline ); + else if ( rect.top() > d_data->baseline ) + rect.setTop( d_data->baseline ); + } + + return rect; +} + +//! \return QwtPlotItem::Rtti_PlotHistogram +int QwtPlotHistogram::rtti() const +{ + return QwtPlotItem::Rtti_PlotHistogram; +} + +/*! + Initialize data with an array of samples. + \param samples Vector of points +*/ +void QwtPlotHistogram::setSamples( + const QVector<QwtIntervalSample> &samples ) +{ + setData( new QwtIntervalSeriesData( samples ) ); +} + +/*! + Assign a series of samples + + setSamples() is just a wrapper for setData() without any additional + value - beside that it is easier to find for the developer. + + \param data Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. +*/ +void QwtPlotHistogram::setSamples( + QwtSeriesData<QwtIntervalSample> *data ) +{ + setData( data ); +} + +/*! + Draw a subset of the histogram samples + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawOutline(), drawLines(), drawColumns +*/ +void QwtPlotHistogram::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &, int from, int to ) const +{ + if ( !painter || dataSize() <= 0 ) + return; + + if ( to < 0 ) + to = dataSize() - 1; + + switch ( d_data->style ) + { + case Outline: + drawOutline( painter, xMap, yMap, from, to ); + break; + case Lines: + drawLines( painter, xMap, yMap, from, to ); + break; + case Columns: + drawColumns( painter, xMap, yMap, from, to ); + break; + default: + break; + } +} + +/*! + Draw a histogram in Outline style() + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + histogram will be painted to its last point. + + \sa setStyle(), style() + \warning The outline style requires, that the intervals are in increasing + order and not overlapping. +*/ +void QwtPlotHistogram::drawOutline( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double v0 = ( orientation() == Qt::Horizontal ) ? + xMap.transform( baseline() ) : yMap.transform( baseline() ); + if ( doAlign ) + v0 = qRound( v0 ); + + QwtIntervalSample previous; + + QPolygonF polygon; + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample sample = this->sample( i ); + + if ( !sample.interval.isValid() ) + { + flushPolygon( painter, v0, polygon ); + previous = sample; + continue; + } + + if ( previous.interval.isValid() ) + { + if ( !qwtIsCombinable( previous.interval, sample.interval ) ) + flushPolygon( painter, v0, polygon ); + } + + if ( orientation() == Qt::Vertical ) + { + double x1 = xMap.transform( sample.interval.minValue() ); + double x2 = xMap.transform( sample.interval.maxValue() ); + double y = yMap.transform( sample.value ); + if ( doAlign ) + { + x1 = qRound( x1 ); + x2 = qRound( x2 ); + y = qRound( y ); + } + + if ( polygon.size() == 0 ) + polygon += QPointF( x1, v0 ); + + polygon += QPointF( x1, y ); + polygon += QPointF( x2, y ); + } + else + { + double y1 = yMap.transform( sample.interval.minValue() ); + double y2 = yMap.transform( sample.interval.maxValue() ); + double x = xMap.transform( sample.value ); + if ( doAlign ) + { + y1 = qRound( y1 ); + y2 = qRound( y2 ); + x = qRound( x ); + } + + if ( polygon.size() == 0 ) + polygon += QPointF( v0, y1 ); + + polygon += QPointF( x, y1 ); + polygon += QPointF( x, y2 ); + } + previous = sample; + } + + flushPolygon( painter, v0, polygon ); +} + +/*! + Draw a histogram in Columns style() + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + histogram will be painted to its last point. + + \sa setStyle(), style(), setSymbol(), drawColumn() +*/ +void QwtPlotHistogram::drawColumns( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const +{ + painter->setPen( d_data->pen ); + painter->setBrush( d_data->brush ); + + const QwtSeriesData<QwtIntervalSample> *series = data(); + + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample sample = series->sample( i ); + if ( !sample.interval.isNull() ) + { + const QwtColumnRect rect = columnRect( sample, xMap, yMap ); + drawColumn( painter, rect, sample ); + } + } +} + +/*! + Draw a histogram in Lines style() + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + histogram will be painted to its last point. + + \sa setStyle(), style(), setPen() +*/ +void QwtPlotHistogram::drawLines( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + painter->setPen( d_data->pen ); + painter->setBrush( Qt::NoBrush ); + + const QwtSeriesData<QwtIntervalSample> *series = data(); + + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample sample = series->sample( i ); + if ( !sample.interval.isNull() ) + { + const QwtColumnRect rect = columnRect( sample, xMap, yMap ); + + QRectF r = rect.toRect(); + if ( doAlign ) + { + r.setLeft( qRound( r.left() ) ); + r.setRight( qRound( r.right() ) ); + r.setTop( qRound( r.top() ) ); + r.setBottom( qRound( r.bottom() ) ); + } + + switch ( rect.direction ) + { + case QwtColumnRect::LeftToRight: + { + QwtPainter::drawLine( painter, + r.topRight(), r.bottomRight() ); + break; + } + case QwtColumnRect::RightToLeft: + { + QwtPainter::drawLine( painter, + r.topLeft(), r.bottomLeft() ); + break; + } + case QwtColumnRect::TopToBottom: + { + QwtPainter::drawLine( painter, + r.bottomRight(), r.bottomLeft() ); + break; + } + case QwtColumnRect::BottomToTop: + { + QwtPainter::drawLine( painter, + r.topRight(), r.topLeft() ); + break; + } + } + } + } +} + +//! Internal, used by the Outline style. +void QwtPlotHistogram::flushPolygon( QPainter *painter, + double baseLine, QPolygonF &polygon ) const +{ + if ( polygon.size() == 0 ) + return; + + if ( orientation() == Qt::Horizontal ) + polygon += QPointF( baseLine, polygon.last().y() ); + else + polygon += QPointF( polygon.last().x(), baseLine ); + + if ( d_data->brush.style() != Qt::NoBrush ) + { + painter->setPen( Qt::NoPen ); + painter->setBrush( d_data->brush ); + + if ( orientation() == Qt::Horizontal ) + { + polygon += QPointF( polygon.last().x(), baseLine ); + polygon += QPointF( polygon.first().x(), baseLine ); + } + else + { + polygon += QPointF( baseLine, polygon.last().y() ); + polygon += QPointF( baseLine, polygon.first().y() ); + } + + QwtPainter::drawPolygon( painter, polygon ); + + polygon.pop_back(); + polygon.pop_back(); + } + if ( d_data->pen.style() != Qt::NoPen ) + { + painter->setBrush( Qt::NoBrush ); + painter->setPen( d_data->pen ); + QwtPainter::drawPolyline( painter, polygon ); + } + polygon.clear(); +} + +/*! + Calculate the area that is covered by a sample + + \param sample Sample + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + + \return Rectangle, that is covered by a sample +*/ +QwtColumnRect QwtPlotHistogram::columnRect( const QwtIntervalSample &sample, + const QwtScaleMap &xMap, const QwtScaleMap &yMap ) const +{ + QwtColumnRect rect; + + const QwtInterval &iv = sample.interval; + if ( !iv.isValid() ) + return rect; + + if ( orientation() == Qt::Horizontal ) + { + const double x0 = xMap.transform( baseline() ); + const double x = xMap.transform( sample.value ); + const double y1 = yMap.transform( iv.minValue() ); + const double y2 = yMap.transform( iv.maxValue() ); + + rect.hInterval.setInterval( x0, x ); + rect.vInterval.setInterval( y1, y2, iv.borderFlags() ); + rect.direction = ( x < x0 ) ? QwtColumnRect::RightToLeft : + QwtColumnRect::LeftToRight; + } + else + { + const double x1 = xMap.transform( iv.minValue() ); + const double x2 = xMap.transform( iv.maxValue() ); + const double y0 = yMap.transform( baseline() ); + const double y = yMap.transform( sample.value ); + + rect.hInterval.setInterval( x1, x2, iv.borderFlags() ); + rect.vInterval.setInterval( y0, y ); + rect.direction = ( y < y0 ) ? QwtColumnRect::BottomToTop : + QwtColumnRect::TopToBottom; + } + + return rect; +} + +/*! + Draw a column for a sample in Columns style(). + + When a symbol() has been set the symbol is used otherwise the + column is displayed as plain rectangle using pen() and brush(). + + \param painter Painter + \param rect Rectangle where to paint the column in paint device coordinates + \param sample Sample to be displayed + + \note In applications, where different intervals need to be displayed + in a different way ( f.e different colors or even using different symbols) + it is recommended to overload drawColumn(). +*/ +void QwtPlotHistogram::drawColumn( QPainter *painter, + const QwtColumnRect &rect, const QwtIntervalSample &sample ) const +{ + Q_UNUSED( sample ); + + if ( d_data->symbol && + ( d_data->symbol->style() != QwtColumnSymbol::NoStyle ) ) + { + d_data->symbol->draw( painter, rect ); + } + else + { + QRectF r = rect.toRect(); + if ( QwtPainter::roundingAlignment( painter ) ) + { + r.setLeft( qRound( r.left() ) ); + r.setRight( qRound( r.right() ) ); + r.setTop( qRound( r.top() ) ); + r.setBottom( qRound( r.bottom() ) ); + } + + QwtPainter::drawRect( painter, r ); + } +} + +/*! + A plain rectangle without pen using the brush() + + \param index Index of the legend entry + ( ignored as there is only one ) + \param size Icon size + \return A graphic displaying the icon + + \sa QwtPlotItem::setLegendIconSize(), QwtPlotItem::legendData() +*/ +QwtGraphic QwtPlotHistogram::legendIcon( int index, + const QSizeF &size ) const +{ + Q_UNUSED( index ); + return defaultIcon( d_data->brush, size ); +} diff --git a/libs/qwt/qwt_plot_histogram.h b/libs/qwt/qwt_plot_histogram.h new file mode 100644 index 0000000000..b96bdddc00 --- /dev/null +++ b/libs/qwt/qwt_plot_histogram.h @@ -0,0 +1,139 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_HISTOGRAM_H +#define QWT_PLOT_HISTOGRAM_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_column_symbol.h" +#include <qcolor.h> +#include <qvector.h> + +class QwtIntervalData; +class QString; +class QPolygonF; + +/*! + \brief QwtPlotHistogram represents a series of samples, where an interval + is associated with a value ( \f$y = f([x1,x2])\f$ ). + + The representation depends on the style() and an optional symbol() + that is displayed for each interval. + + \note The term "histogram" is used in a different way in the areas of + digital image processing and statistics. Wikipedia introduces the + terms "image histogram" and "color histogram" to avoid confusions. + While "image histograms" can be displayed by a QwtPlotCurve there + is no applicable plot item for a "color histogram" yet. + + \sa QwtPlotBarChart, QwtPlotMultiBarChart +*/ + +class QWT_EXPORT QwtPlotHistogram: + public QwtPlotSeriesItem, public QwtSeriesStore<QwtIntervalSample> +{ +public: + /*! + Histogram styles. + The default style is QwtPlotHistogram::Columns. + + \sa setStyle(), style(), setSymbol(), symbol(), setBaseline() + */ + enum HistogramStyle + { + /*! + Draw an outline around the area, that is build by all intervals + using the pen() and fill it with the brush(). The outline style + requires, that the intervals are in increasing order and + not overlapping. + */ + Outline, + + /*! + Draw a column for each interval. When a symbol() has been set + the symbol is used otherwise the column is displayed as + plain rectangle using pen() and brush(). + */ + Columns, + + /*! + Draw a simple line using the pen() for each interval. + */ + Lines, + + /*! + Styles >= UserStyle are reserved for derived + classes that overload drawSeries() with + additional application specific ways to display a histogram. + */ + UserStyle = 100 + }; + + explicit QwtPlotHistogram( const QString &title = QString::null ); + explicit QwtPlotHistogram( const QwtText &title ); + virtual ~QwtPlotHistogram(); + + virtual int rtti() const; + + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); + const QPen &pen() const; + + void setBrush( const QBrush & ); + const QBrush &brush() const; + + void setSamples( const QVector<QwtIntervalSample> & ); + void setSamples( QwtSeriesData<QwtIntervalSample> * ); + + void setBaseline( double reference ); + double baseline() const; + + void setStyle( HistogramStyle style ); + HistogramStyle style() const; + + void setSymbol( const QwtColumnSymbol * ); + const QwtColumnSymbol *symbol() const; + + virtual void drawSeries( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual QRectF boundingRect() const; + + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; + +protected: + virtual QwtColumnRect columnRect( const QwtIntervalSample &, + const QwtScaleMap &, const QwtScaleMap & ) const; + + virtual void drawColumn( QPainter *, const QwtColumnRect &, + const QwtIntervalSample & ) const; + + void drawColumns( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const; + + void drawOutline( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const; + + void drawLines( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const; + +private: + void init(); + void flushPolygon( QPainter *, double baseLine, QPolygonF & ) const; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_intervalcurve.cpp b/libs/qwt/qwt_plot_intervalcurve.cpp new file mode 100644 index 0000000000..200ea39b51 --- /dev/null +++ b/libs/qwt/qwt_plot_intervalcurve.cpp @@ -0,0 +1,603 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_intervalcurve.h" +#include "qwt_interval_symbol.h" +#include "qwt_scale_map.h" +#include "qwt_clipper.h" +#include "qwt_painter.h" +#include <string.h> + +#include <qpainter.h> + +static inline bool qwtIsHSampleInside( const QwtIntervalSample &sample, + double xMin, double xMax, double yMin, double yMax ) +{ + const double y = sample.value; + const double x1 = sample.interval.minValue(); + const double x2 = sample.interval.maxValue(); + + const bool isOffScreen = ( y < yMin ) || ( y > yMax ) + || ( x1 < xMin && x2 < xMin ) || ( x1 > xMax && x2 > xMax ); + + return !isOffScreen; +} + +static inline bool qwtIsVSampleInside( const QwtIntervalSample &sample, + double xMin, double xMax, double yMin, double yMax ) +{ + const double x = sample.value; + const double y1 = sample.interval.minValue(); + const double y2 = sample.interval.maxValue(); + + const bool isOffScreen = ( x < xMin ) || ( x > xMax ) + || ( y1 < yMin && y2 < yMin ) || ( y1 > yMax && y2 > yMax ); + + return !isOffScreen; +} + +class QwtPlotIntervalCurve::PrivateData +{ +public: + PrivateData(): + style( QwtPlotIntervalCurve::Tube ), + symbol( NULL ), + pen( Qt::black ), + brush( Qt::white ) + { + paintAttributes = QwtPlotIntervalCurve::ClipPolygons; + paintAttributes |= QwtPlotIntervalCurve::ClipSymbol; + + pen.setCapStyle( Qt::FlatCap ); + } + + ~PrivateData() + { + delete symbol; + } + + QwtPlotIntervalCurve::CurveStyle style; + const QwtIntervalSymbol *symbol; + + QPen pen; + QBrush brush; + + QwtPlotIntervalCurve::PaintAttributes paintAttributes; +}; + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotIntervalCurve::QwtPlotIntervalCurve( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotIntervalCurve::QwtPlotIntervalCurve( const QString &title ): + QwtPlotSeriesItem( QwtText( title ) ) +{ + init(); +} + +//! Destructor +QwtPlotIntervalCurve::~QwtPlotIntervalCurve() +{ + delete d_data; +} + +//! Initialize internal members +void QwtPlotIntervalCurve::init() +{ + setItemAttribute( QwtPlotItem::Legend, true ); + setItemAttribute( QwtPlotItem::AutoScale, true ); + + d_data = new PrivateData; + setData( new QwtIntervalSeriesData() ); + + setZ( 19.0 ); +} + +//! \return QwtPlotItem::Rtti_PlotIntervalCurve +int QwtPlotIntervalCurve::rtti() const +{ + return QwtPlotIntervalCurve::Rtti_PlotIntervalCurve; +} + +/*! + Specify an attribute how to draw the curve + + \param attribute Paint attribute + \param on On/Off + \sa testPaintAttribute() +*/ +void QwtPlotIntervalCurve::setPaintAttribute( + PaintAttribute attribute, bool on ) +{ + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; +} + +/*! + \return True, when attribute is enabled + \sa PaintAttribute, setPaintAttribute() +*/ +bool QwtPlotIntervalCurve::testPaintAttribute( + PaintAttribute attribute ) const +{ + return ( d_data->paintAttributes & attribute ); +} + +/*! + Initialize data with an array of samples. + \param samples Vector of samples +*/ +void QwtPlotIntervalCurve::setSamples( + const QVector<QwtIntervalSample> &samples ) +{ + setData( new QwtIntervalSeriesData( samples ) ); +} + +/*! + Assign a series of samples + + setSamples() is just a wrapper for setData() without any additional + value - beside that it is easier to find for the developer. + + \param data Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. +*/ +void QwtPlotIntervalCurve::setSamples( + QwtSeriesData<QwtIntervalSample> *data ) +{ + setData( data ); +} + +/*! + Set the curve's drawing style + + \param style Curve style + \sa CurveStyle, style() +*/ +void QwtPlotIntervalCurve::setStyle( CurveStyle style ) +{ + if ( style != d_data->style ) + { + d_data->style = style; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Style of the curve + \sa setStyle() +*/ +QwtPlotIntervalCurve::CurveStyle QwtPlotIntervalCurve::style() const +{ + return d_data->style; +} + +/*! + Assign a symbol. + + \param symbol Symbol + \sa symbol() +*/ +void QwtPlotIntervalCurve::setSymbol( const QwtIntervalSymbol *symbol ) +{ + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Current symbol or NULL, when no symbol has been assigned + \sa setSymbol() +*/ +const QwtIntervalSymbol *QwtPlotIntervalCurve::symbol() const +{ + return d_data->symbol; +} + +/*! + Build and assign a pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotIntervalCurve::setPen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setPen( QPen( color, width, style ) ); +} + +/*! + \brief Assign a pen + \param pen New pen + \sa pen(), brush() +*/ +void QwtPlotIntervalCurve::setPen( const QPen &pen ) +{ + if ( pen != d_data->pen ) + { + d_data->pen = pen; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Pen used to draw the lines + \sa setPen(), brush() +*/ +const QPen& QwtPlotIntervalCurve::pen() const +{ + return d_data->pen; +} + +/*! + Assign a brush. + + The brush is used to fill the area in Tube style(). + + \param brush Brush + \sa brush(), pen(), setStyle(), CurveStyle +*/ +void QwtPlotIntervalCurve::setBrush( const QBrush &brush ) +{ + if ( brush != d_data->brush ) + { + d_data->brush = brush; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Brush used to fill the area in Tube style() + \sa setBrush(), setStyle(), CurveStyle +*/ +const QBrush& QwtPlotIntervalCurve::brush() const +{ + return d_data->brush; +} + +/*! + \return Bounding rectangle of all samples. + For an empty series the rectangle is invalid. +*/ +QRectF QwtPlotIntervalCurve::boundingRect() const +{ + QRectF rect = QwtPlotSeriesItem::boundingRect(); + if ( rect.isValid() && orientation() == Qt::Vertical ) + rect.setRect( rect.y(), rect.x(), rect.height(), rect.width() ); + + return rect; +} + +/*! + Draw a subset of the samples + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawTube(), drawSymbols() +*/ +void QwtPlotIntervalCurve::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( to < 0 ) + to = dataSize() - 1; + + if ( from < 0 ) + from = 0; + + if ( from > to ) + return; + + switch ( d_data->style ) + { + case Tube: + drawTube( painter, xMap, yMap, canvasRect, from, to ); + break; + + case NoCurve: + default: + break; + } + + if ( d_data->symbol && + ( d_data->symbol->style() != QwtIntervalSymbol::NoSymbol ) ) + { + drawSymbols( painter, *d_data->symbol, + xMap, yMap, canvasRect, from, to ); + } +} + +/*! + Draw a tube + + Builds 2 curves from the upper and lower limits of the intervals + and draws them with the pen(). The area between the curves is + filled with the brush(). + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawSeries(), drawSymbols() +*/ +void QwtPlotIntervalCurve::drawTube( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + painter->save(); + + const size_t size = to - from + 1; + QPolygonF polygon( 2 * size ); + QPointF *points = polygon.data(); + + for ( uint i = 0; i < size; i++ ) + { + QPointF &minValue = points[i]; + QPointF &maxValue = points[2 * size - 1 - i]; + + const QwtIntervalSample intervalSample = sample( from + i ); + if ( orientation() == Qt::Vertical ) + { + double x = xMap.transform( intervalSample.value ); + double y1 = yMap.transform( intervalSample.interval.minValue() ); + double y2 = yMap.transform( intervalSample.interval.maxValue() ); + if ( doAlign ) + { + x = qRound( x ); + y1 = qRound( y1 ); + y2 = qRound( y2 ); + } + + minValue.rx() = x; + minValue.ry() = y1; + maxValue.rx() = x; + maxValue.ry() = y2; + } + else + { + double y = yMap.transform( intervalSample.value ); + double x1 = xMap.transform( intervalSample.interval.minValue() ); + double x2 = xMap.transform( intervalSample.interval.maxValue() ); + if ( doAlign ) + { + y = qRound( y ); + x1 = qRound( x1 ); + x2 = qRound( x2 ); + } + + minValue.rx() = x1; + minValue.ry() = y; + maxValue.rx() = x2; + maxValue.ry() = y; + } + } + + if ( d_data->brush.style() != Qt::NoBrush ) + { + painter->setPen( QPen( Qt::NoPen ) ); + painter->setBrush( d_data->brush ); + + if ( d_data->paintAttributes & ClipPolygons ) + { + const qreal m = 1.0; + const QPolygonF p = QwtClipper::clipPolygonF( + canvasRect.adjusted( -m, -m, m, m ), polygon, true ); + + QwtPainter::drawPolygon( painter, p ); + } + else + { + QwtPainter::drawPolygon( painter, polygon ); + } + } + + if ( d_data->pen.style() != Qt::NoPen ) + { + painter->setPen( d_data->pen ); + painter->setBrush( Qt::NoBrush ); + + if ( d_data->paintAttributes & ClipPolygons ) + { + qreal pw = qMax( qreal( 1.0 ), painter->pen().widthF() ); + const QRectF clipRect = canvasRect.adjusted( -pw, -pw, pw, pw ); + + QPolygonF p; + + p.resize( size ); + ::memcpy( p.data(), points, size * sizeof( QPointF ) ); + p = QwtClipper::clipPolygonF( clipRect, p ); + QwtPainter::drawPolyline( painter, p ); + + p.resize( size ); + ::memcpy( p.data(), points + size, size * sizeof( QPointF ) ); + p = QwtClipper::clipPolygonF( clipRect, p ); + QwtPainter::drawPolyline( painter, p ); + } + else + { + QwtPainter::drawPolyline( painter, points, size ); + QwtPainter::drawPolyline( painter, points + size, size ); + } + } + + painter->restore(); +} + +/*! + Draw symbols for a subset of the samples + + \param painter Painter + \param symbol Interval symbol + \param xMap x map + \param yMap y map + \param canvasRect Contents rectangle of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted + + \sa setSymbol(), drawSeries(), drawTube() +*/ +void QwtPlotIntervalCurve::drawSymbols( + QPainter *painter, const QwtIntervalSymbol &symbol, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + painter->save(); + + QPen pen = symbol.pen(); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + painter->setBrush( symbol.brush() ); + + const QRectF tr = QwtScaleMap::invTransform( xMap, yMap, canvasRect ); + + const double xMin = tr.left(); + const double xMax = tr.right(); + const double yMin = tr.top(); + const double yMax = tr.bottom(); + + const bool doClip = d_data->paintAttributes & ClipSymbol; + + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample s = sample( i ); + + if ( orientation() == Qt::Vertical ) + { + if ( !doClip || qwtIsVSampleInside( s, xMin, xMax, yMin, yMax ) ) + { + const double x = xMap.transform( s.value ); + const double y1 = yMap.transform( s.interval.minValue() ); + const double y2 = yMap.transform( s.interval.maxValue() ); + + symbol.draw( painter, orientation(), + QPointF( x, y1 ), QPointF( x, y2 ) ); + } + } + else + { + if ( !doClip || qwtIsHSampleInside( s, xMin, xMax, yMin, yMax ) ) + { + const double y = yMap.transform( s.value ); + const double x1 = xMap.transform( s.interval.minValue() ); + const double x2 = xMap.transform( s.interval.maxValue() ); + + symbol.draw( painter, orientation(), + QPointF( x1, y ), QPointF( x2, y ) ); + } + } + } + + painter->restore(); +} + +/*! + \return Icon for the legend + + In case of Tube style() the icon is a plain rectangle filled with the brush(). + If a symbol is assigned it is scaled to size. + + \param index Index of the legend entry + ( ignored as there is only one ) + \param size Icon size + + \sa QwtPlotItem::setLegendIconSize(), QwtPlotItem::legendData() +*/ +QwtGraphic QwtPlotIntervalCurve::legendIcon( + int index, const QSizeF &size ) const +{ + Q_UNUSED( index ); + + if ( size.isEmpty() ) + return QwtGraphic(); + + QwtGraphic icon; + icon.setDefaultSize( size ); + icon.setRenderHint( QwtGraphic::RenderPensUnscaled, true ); + + QPainter painter( &icon ); + painter.setRenderHint( QPainter::Antialiasing, + testRenderHint( QwtPlotItem::RenderAntialiased ) ); + + if ( d_data->style == Tube ) + { + QRectF r( 0, 0, size.width(), size.height() ); + painter.fillRect( r, d_data->brush ); + } + + if ( d_data->symbol && + ( d_data->symbol->style() != QwtIntervalSymbol::NoSymbol ) ) + { + QPen pen = d_data->symbol->pen(); + pen.setWidthF( pen.widthF() ); + pen.setCapStyle( Qt::FlatCap ); + + painter.setPen( pen ); + painter.setBrush( d_data->symbol->brush() ); + + if ( orientation() == Qt::Vertical ) + { + const double x = 0.5 * size.width(); + + d_data->symbol->draw( &painter, orientation(), + QPointF( x, 0 ), QPointF( x, size.height() - 1.0 ) ); + } + else + { + const double y = 0.5 * size.height(); + + d_data->symbol->draw( &painter, orientation(), + QPointF( 0.0, y ), QPointF( size.width() - 1.0, y ) ); + } + } + + return icon; +} diff --git a/libs/qwt/qwt_plot_intervalcurve.h b/libs/qwt/qwt_plot_intervalcurve.h new file mode 100644 index 0000000000..624d82f1b0 --- /dev/null +++ b/libs/qwt/qwt_plot_intervalcurve.h @@ -0,0 +1,132 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_INTERVAL_CURVE_H +#define QWT_PLOT_INTERVAL_CURVE_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_series_data.h" + +class QwtIntervalSymbol; + +/*! + \brief QwtPlotIntervalCurve represents a series of samples, where each value + is associated with an interval ( \f$[y1,y2] = f(x)\f$ ). + + The representation depends on the style() and an optional symbol() + that is displayed for each interval. QwtPlotIntervalCurve might be used + to display error bars or the area between 2 curves. +*/ +class QWT_EXPORT QwtPlotIntervalCurve: + public QwtPlotSeriesItem, public QwtSeriesStore<QwtIntervalSample> +{ +public: + /*! + \brief Curve styles. + The default setting is QwtPlotIntervalCurve::Tube. + + \sa setStyle(), style() + */ + enum CurveStyle + { + /*! + Don't draw a curve. Note: This doesn't affect the symbols. + */ + NoCurve, + + /*! + Build 2 curves from the upper and lower limits of the intervals + and draw them with the pen(). The area between the curves is + filled with the brush(). + */ + Tube, + + /*! + Styles >= QwtPlotIntervalCurve::UserCurve are reserved for derived + classes that overload drawSeries() with + additional application specific curve types. + */ + UserCurve = 100 + }; + + /*! + Attributes to modify the drawing algorithm. + \sa setPaintAttribute(), testPaintAttribute() + */ + enum PaintAttribute + { + /*! + Clip polygons before painting them. In situations, where points + are far outside the visible area (f.e when zooming deep) this + might be a substantial improvement for the painting performance. + */ + ClipPolygons = 0x01, + + //! Check if a symbol is on the plot canvas before painting it. + ClipSymbol = 0x02 + }; + + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + + explicit QwtPlotIntervalCurve( const QString &title = QString::null ); + explicit QwtPlotIntervalCurve( const QwtText &title ); + + virtual ~QwtPlotIntervalCurve(); + + virtual int rtti() const; + + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + void setSamples( const QVector<QwtIntervalSample> & ); + void setSamples( QwtSeriesData<QwtIntervalSample> * ); + + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); + const QPen &pen() const; + + void setBrush( const QBrush & ); + const QBrush &brush() const; + + void setStyle( CurveStyle style ); + CurveStyle style() const; + + void setSymbol( const QwtIntervalSymbol * ); + const QwtIntervalSymbol *symbol() const; + + virtual void drawSeries( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual QRectF boundingRect() const; + + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; + +protected: + + void init(); + + virtual void drawTube( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void drawSymbols( QPainter *, const QwtIntervalSymbol &, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotIntervalCurve::PaintAttributes ) + +#endif diff --git a/libs/qwt/qwt_plot_item.cpp b/libs/qwt/qwt_plot_item.cpp index 953449eb56..4cb03bbb2e 100644 --- a/libs/qwt/qwt_plot_item.cpp +++ b/libs/qwt/qwt_plot_item.cpp @@ -7,44 +7,55 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_plot_item.h" #include "qwt_text.h" #include "qwt_plot.h" -#include "qwt_legend.h" -#include "qwt_legend_item.h" -#include "qwt_plot_item.h" +#include "qwt_legend_data.h" +#include "qwt_scale_div.h" +#include "qwt_graphic.h" +#include <qpainter.h> class QwtPlotItem::PrivateData { public: PrivateData(): - plot(NULL), - isVisible(true), - attributes(0), -#if QT_VERSION >= 0x040000 - renderHints(0), -#endif - z(0.0), - xAxis(QwtPlot::xBottom), - yAxis(QwtPlot::yLeft) { + plot( NULL ), + isVisible( true ), + attributes( 0 ), + interests( 0 ), + renderHints( 0 ), + renderThreadCount( 1 ), + z( 0.0 ), + xAxis( QwtPlot::xBottom ), + yAxis( QwtPlot::yLeft ), + legendIconSize( 8, 8 ) + { } mutable QwtPlot *plot; bool isVisible; - int attributes; -#if QT_VERSION >= 0x040000 - int renderHints; -#endif + + QwtPlotItem::ItemAttributes attributes; + QwtPlotItem::ItemInterests interests; + + QwtPlotItem::RenderHints renderHints; + uint renderThreadCount; + double z; int xAxis; int yAxis; QwtText title; + QSize legendIconSize; }; -//! Constructor -QwtPlotItem::QwtPlotItem(const QwtText &title) +/*! + Constructor + \param title Title of the item +*/ +QwtPlotItem::QwtPlotItem( const QwtText &title ) { d_data = new PrivateData; d_data->title = title; @@ -53,7 +64,7 @@ QwtPlotItem::QwtPlotItem(const QwtText &title) //! Destroy the QwtPlotItem QwtPlotItem::~QwtPlotItem() { - attach(NULL); + attach( NULL ); delete d_data; } @@ -65,36 +76,33 @@ QwtPlotItem::~QwtPlotItem() necessary). If a NULL argument is passed, it will detach from any QwtPlot it was attached to. - \sa QwtPlotItem::detach() + \param plot Plot widget + \sa detach() */ -void QwtPlotItem::attach(QwtPlot *plot) +void QwtPlotItem::attach( QwtPlot *plot ) { if ( plot == d_data->plot ) return; - // remove the item from the previous plot - - if ( d_data->plot ) { - if ( d_data->plot->legend() ) { - QWidget *legendItem = d_data->plot->legend()->find(this); - if ( legendItem ) - delete legendItem; - } - - d_data->plot->attachItem(this, false); - - if ( d_data->plot->autoReplot() ) - d_data->plot->update(); - } + if ( d_data->plot ) + d_data->plot->attachItem( this, false ); d_data->plot = plot; - if ( d_data->plot ) { - // insert the item into the current plot + if ( d_data->plot ) + d_data->plot->attachItem( this, true ); +} - d_data->plot->attachItem(this, true); - itemChanged(); - } +/*! + \brief This method detaches a QwtPlotItem from any + QwtPlot it has been associated with. + + detach() is equivalent to calling attach( NULL ) + \sa attach() +*/ +void QwtPlotItem::detach() +{ + attach( NULL ); } /*! @@ -138,15 +146,18 @@ double QwtPlotItem::z() const \param z Z-value \sa z(), QwtPlotDict::itemList() */ -void QwtPlotItem::setZ(double z) +void QwtPlotItem::setZ( double z ) { - if ( d_data->z != z ) { + if ( d_data->z != z ) + { + if ( d_data->plot ) // update the z order + d_data->plot->attachItem( this, false ); + d_data->z = z; - if ( d_data->plot ) { - // update the z order - d_data->plot->attachItem(this, false); - d_data->plot->attachItem(this, true); - } + + if ( d_data->plot ) + d_data->plot->attachItem( this, true ); + itemChanged(); } } @@ -157,9 +168,9 @@ void QwtPlotItem::setZ(double z) \param title Title \sa title() */ -void QwtPlotItem::setTitle(const QString &title) +void QwtPlotItem::setTitle( const QString &title ) { - setTitle(QwtText(title)); + setTitle( QwtText( title ) ); } /*! @@ -168,11 +179,16 @@ void QwtPlotItem::setTitle(const QString &title) \param title Title \sa title() */ -void QwtPlotItem::setTitle(const QwtText &title) +void QwtPlotItem::setTitle( const QwtText &title ) { - if ( d_data->title != title ) { + if ( d_data->title != title ) + { d_data->title = title; + + legendChanged(); +#if 0 itemChanged(); +#endif } } @@ -191,16 +207,20 @@ const QwtText &QwtPlotItem::title() const \param attribute Attribute type \param on true/false - \sa testItemAttribute(), ItemAttribute + \sa testItemAttribute(), ItemInterest */ -void QwtPlotItem::setItemAttribute(ItemAttribute attribute, bool on) +void QwtPlotItem::setItemAttribute( ItemAttribute attribute, bool on ) { - if ( bool(d_data->attributes & attribute) != on ) { + if ( d_data->attributes.testFlag( attribute ) != on ) + { if ( on ) d_data->attributes |= attribute; else d_data->attributes &= ~attribute; + if ( attribute == QwtPlotItem::Legend ) + legendChanged(); + itemChanged(); } } @@ -208,16 +228,47 @@ void QwtPlotItem::setItemAttribute(ItemAttribute attribute, bool on) /*! Test an item attribute - \param ItemAttribute Attribute type + \param attribute Attribute type \return true/false - \sa setItemAttribute(), ItemAttribute + \sa setItemAttribute(), ItemInterest */ -bool QwtPlotItem::testItemAttribute(ItemAttribute attribute) const +bool QwtPlotItem::testItemAttribute( ItemAttribute attribute ) const { - return d_data->attributes & attribute; + return d_data->attributes.testFlag( attribute ); } -#if QT_VERSION >= 0x040000 +/*! + Toggle an item interest + + \param interest Interest type + \param on true/false + + \sa testItemInterest(), ItemAttribute +*/ +void QwtPlotItem::setItemInterest( ItemInterest interest, bool on ) +{ + if ( d_data->interests.testFlag( interest ) != on ) + { + if ( on ) + d_data->interests |= interest; + else + d_data->interests &= ~interest; + + itemChanged(); + } +} + +/*! + Test an item interest + + \param interest Interest type + \return true/false + \sa setItemInterest(), ItemAttribute +*/ +bool QwtPlotItem::testItemInterest( ItemInterest interest ) const +{ + return d_data->interests.testFlag( interest ); +} /*! Toggle an render hint @@ -227,9 +278,10 @@ bool QwtPlotItem::testItemAttribute(ItemAttribute attribute) const \sa testRenderHint(), RenderHint */ -void QwtPlotItem::setRenderHint(RenderHint hint, bool on) +void QwtPlotItem::setRenderHint( RenderHint hint, bool on ) { - if ( ((d_data->renderHints & hint) != 0) != on ) { + if ( d_data->renderHints.testFlag( hint ) != on ) + { if ( on ) d_data->renderHints |= hint; else @@ -246,23 +298,123 @@ void QwtPlotItem::setRenderHint(RenderHint hint, bool on) \return true/false \sa setRenderHint(), RenderHint */ -bool QwtPlotItem::testRenderHint(RenderHint hint) const +bool QwtPlotItem::testRenderHint( RenderHint hint ) const { - return (d_data->renderHints & hint); + return d_data->renderHints.testFlag( hint ); } -#endif +/*! + On multi core systems rendering of certain plot item + ( f.e QwtPlotRasterItem ) can be done in parallel in + several threads. + + The default setting is set to 1. + + \param numThreads Number of threads to be used for rendering. + If numThreads is set to 0, the system specific + ideal thread count is used. + + The default thread count is 1 ( = no additional threads ) +*/ +void QwtPlotItem::setRenderThreadCount( uint numThreads ) +{ + d_data->renderThreadCount = numThreads; +} + +/*! + \return Number of threads to be used for rendering. + If numThreads() is set to 0, the system specific + ideal thread count is used. +*/ +uint QwtPlotItem::renderThreadCount() const +{ + return d_data->renderThreadCount; +} + +/*! + Set the size of the legend icon + + The default setting is 8x8 pixels + + \param size Size + \sa legendIconSize(), legendIcon() +*/ +void QwtPlotItem::setLegendIconSize( const QSize &size ) +{ + if ( d_data->legendIconSize != size ) + { + d_data->legendIconSize = size; + legendChanged(); + } +} + +/*! + \return Legend icon size + \sa setLegendIconSize(), legendIcon() +*/ +QSize QwtPlotItem::legendIconSize() const +{ + return d_data->legendIconSize; +} + +/*! + \return Icon representing the item on the legend + + The default implementation returns an invalid icon + + \param index Index of the legend entry + ( usually there is only one ) + \param size Icon size + + \sa setLegendIconSize(), legendData() + */ +QwtGraphic QwtPlotItem::legendIcon( + int index, const QSizeF &size ) const +{ + Q_UNUSED( index ) + Q_UNUSED( size ) + + return QwtGraphic(); +} + +/*! + \brief Return a default icon from a brush + + The default icon is a filled rectangle used + in several derived classes as legendIcon(). + + \param brush Fill brush + \param size Icon size + + \return A filled rectangle + */ +QwtGraphic QwtPlotItem::defaultIcon( + const QBrush &brush, const QSizeF &size ) const +{ + QwtGraphic icon; + if ( !size.isEmpty() ) + { + icon.setDefaultSize( size ); + + QRectF r( 0, 0, size.width(), size.height() ); + + QPainter painter( &icon ); + painter.fillRect( r, brush ); + } + + return icon; +} //! Show the item void QwtPlotItem::show() { - setVisible(true); + setVisible( true ); } //! Hide the item void QwtPlotItem::hide() { - setVisible(false); + setVisible( false ); } /*! @@ -271,9 +423,10 @@ void QwtPlotItem::hide() \param on Show if true, otherwise hide \sa isVisible(), show(), hide() */ -void QwtPlotItem::setVisible(bool on) +void QwtPlotItem::setVisible( bool on ) { - if ( on != d_data->isVisible ) { + if ( on != d_data->isVisible ) + { d_data->isVisible = on; itemChanged(); } @@ -289,37 +442,43 @@ bool QwtPlotItem::isVisible() const } /*! - Update the legend and call QwtPlot::autoRefresh for the + Update the legend and call QwtPlot::autoRefresh() for the parent plot. - \sa updateLegend() + \sa QwtPlot::legendChanged(), QwtPlot::autoRefresh() */ void QwtPlotItem::itemChanged() { - if ( d_data->plot ) { - if ( d_data->plot->legend() ) - updateLegend(d_data->plot->legend()); - + if ( d_data->plot ) d_data->plot->autoRefresh(); - } +} + +/*! + Update the legend of the parent plot. + \sa QwtPlot::updateLegend(), itemChanged() +*/ +void QwtPlotItem::legendChanged() +{ + if ( testItemAttribute( QwtPlotItem::Legend ) && d_data->plot ) + d_data->plot->updateLegend( this ); } /*! Set X and Y axis - The item will painted according to the coordinates its Axes. + The item will painted according to the coordinates of its Axes. - \param xAxis X Axis - \param yAxis Y Axis + \param xAxis X Axis ( QwtPlot::xBottom or QwtPlot::xTop ) + \param yAxis Y Axis ( QwtPlot::yLeft or QwtPlot::yRight ) - \sa setXAxis(), setYAxis(), xAxis(), yAxis() + \sa setXAxis(), setYAxis(), xAxis(), yAxis(), QwtPlot::Axis */ -void QwtPlotItem::setAxis(int xAxis, int yAxis) +void QwtPlotItem::setAxes( int xAxis, int yAxis ) { - if (xAxis == QwtPlot::xBottom || xAxis == QwtPlot::xTop ) + if ( xAxis == QwtPlot::xBottom || xAxis == QwtPlot::xTop ) d_data->xAxis = xAxis; - if (yAxis == QwtPlot::yLeft || yAxis == QwtPlot::yRight ) + if ( yAxis == QwtPlot::yLeft || yAxis == QwtPlot::yRight ) d_data->yAxis = yAxis; itemChanged(); @@ -330,12 +489,13 @@ void QwtPlotItem::setAxis(int xAxis, int yAxis) The item will painted according to the coordinates its Axes. - \param axis X Axis - \sa setAxis(), setYAxis(), xAxis() + \param axis X Axis ( QwtPlot::xBottom or QwtPlot::xTop ) + \sa setAxes(), setYAxis(), xAxis(), QwtPlot::Axis */ -void QwtPlotItem::setXAxis(int axis) +void QwtPlotItem::setXAxis( int axis ) { - if (axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) { + if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) + { d_data->xAxis = axis; itemChanged(); } @@ -346,12 +506,13 @@ void QwtPlotItem::setXAxis(int axis) The item will painted according to the coordinates its Axes. - \param axis Y Axis - \sa setAxis(), setXAxis(), yAxis() + \param axis Y Axis ( QwtPlot::yLeft or QwtPlot::yRight ) + \sa setAxes(), setXAxis(), yAxis(), QwtPlot::Axis */ -void QwtPlotItem::setYAxis(int axis) +void QwtPlotItem::setYAxis( int axis ) { - if (axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) { + if ( axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) + { d_data->yAxis = axis; itemChanged(); } @@ -370,72 +531,90 @@ int QwtPlotItem::yAxis() const } /*! - \return An invalid bounding rect: QwtDoubleRect(1.0, 1.0, -2.0, -2.0) + \return An invalid bounding rect: QRectF(1.0, 1.0, -2.0, -2.0) + \note A width or height < 0.0 is ignored by the autoscaler */ -QwtDoubleRect QwtPlotItem::boundingRect() const +QRectF QwtPlotItem::boundingRect() const { - return QwtDoubleRect(1.0, 1.0, -2.0, -2.0); // invalid + return QRectF( 1.0, 1.0, -2.0, -2.0 ); // invalid } /*! - \brief Allocate the widget that represents the item on the legend + \brief Calculate a hint for the canvas margin - The default implementation is made for QwtPlotCurve and returns a - QwtLegendItem(), but an item could be represented by any type of widget, - by overloading legendItem() and updateLegend(). - - \return QwtLegendItem() - \sa updateLegend() QwtLegend() -*/ -QWidget *QwtPlotItem::legendItem() const -{ - return new QwtLegendItem; -} + When the QwtPlotItem::Margins flag is enabled the plot item + indicates, that it needs some margins at the borders of the canvas. + This is f.e. used by bar charts to reserve space for displaying + the bars. -/*! - \brief Update the widget that represents the item on the legend + The margins are in target device coordinates ( pixels on screen ) - updateLegend() is called from itemChanged() to adopt the widget - representing the item on the legend to its new configuration. + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas in painter coordinates + \param left Returns the left margin + \param top Returns the top margin + \param right Returns the right margin + \param bottom Returns the bottom margin - The default implementation is made for QwtPlotCurve and updates a - QwtLegendItem(), but an item could be represented by any type of widget, - by overloading legendItem() and updateLegend(). + \return The default implementation returns 0 for all margins - \sa legendItem(), itemChanged(), QwtLegend() -*/ -void QwtPlotItem::updateLegend(QwtLegend *legend) const + \sa QwtPlot::getCanvasMarginsHint(), QwtPlot::updateCanvasMargins() + */ +void QwtPlotItem::getCanvasMarginHint( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QRectF &canvasRect, + double &left, double &top, double &right, double &bottom ) const { - if ( !legend ) - return; + Q_UNUSED( xMap ); + Q_UNUSED( yMap ); + Q_UNUSED( canvasRect ); - QWidget *lgdItem = legend->find(this); - if ( testItemAttribute(QwtPlotItem::Legend) ) { - if ( lgdItem == NULL ) { - lgdItem = legendItem(); - if ( lgdItem ) { - if ( lgdItem->inherits("QwtLegendItem") ) { - QwtLegendItem *label = (QwtLegendItem *)lgdItem; - label->setItemMode(legend->itemMode()); - - if ( d_data->plot ) { - QObject::connect(label, SIGNAL(clicked()), - d_data->plot, SLOT(legendItemClicked())); - QObject::connect(label, SIGNAL(checked(bool)), - d_data->plot, SLOT(legendItemChecked(bool))); - } - } - legend->insert(this, lgdItem); - } - } - if ( lgdItem && lgdItem->inherits("QwtLegendItem") ) { - QwtLegendItem* label = (QwtLegendItem*)lgdItem; - if ( label ) - label->setText(d_data->title); - } - } else { - delete lgdItem; - } + // use QMargins, when we don't need to support Qt < 4.6 anymore + left = top = right = bottom = 0.0; +} + +/*! + \brief Return all information, that is needed to represent + the item on the legend + + Most items are represented by one entry on the legend + showing an icon and a text, but f.e. QwtPlotMultiBarChart + displays one entry for each bar. + + QwtLegendData is basically a list of QVariants that makes it + possible to overload and reimplement legendData() to + return almost any type of information, that is understood + by the receiver that acts as the legend. + + The default implementation returns one entry with + the title() of the item and the legendIcon(). + + \return Data, that is needed to represent the item on the legend + \sa title(), legendIcon(), QwtLegend, QwtPlotLegendItem + */ +QList<QwtLegendData> QwtPlotItem::legendData() const +{ + QwtLegendData data; + + QwtText label = title(); + label.setRenderFlags( label.renderFlags() & Qt::AlignLeft ); + + QVariant titleValue; + qVariantSetValue( titleValue, label ); + data.setValue( QwtLegendData::TitleRole, titleValue ); + + const QwtGraphic graphic = legendIcon( 0, legendIconSize() ); + if ( !graphic.isNull() ) + { + QVariant iconValue; + qVariantSetValue( iconValue, graphic ); + data.setValue( QwtLegendData::IconRole, iconValue ); + } + + QList<QwtLegendData> list; + list += data; + + return list; } /*! @@ -446,92 +625,74 @@ void QwtPlotItem::updateLegend(QwtLegend *legend) const on the scale division (like QwtPlotGrid()) have to reimplement updateScaleDiv() + updateScaleDiv() is only called when the ScaleInterest interest + is enabled. The default implementation does nothing. + \param xScaleDiv Scale division of the x-axis \param yScaleDiv Scale division of the y-axis - \sa QwtPlot::updateAxes() + \sa QwtPlot::updateAxes(), ScaleInterest */ -void QwtPlotItem::updateScaleDiv(const QwtScaleDiv &, - const QwtScaleDiv &) +void QwtPlotItem::updateScaleDiv( const QwtScaleDiv &xScaleDiv, + const QwtScaleDiv &yScaleDiv ) { + Q_UNUSED( xScaleDiv ); + Q_UNUSED( yScaleDiv ); } /*! - \brief Calculate the bounding scale rect of 2 maps + \brief Update the item to changes of the legend info - \param xMap X map - \param yMap X map + Plot items that want to display a legend ( not those, that want to + be displayed on a legend ! ) will have to implement updateLegend(). - \return Bounding rect of the scale maps -*/ -QwtDoubleRect QwtPlotItem::scaleRect(const QwtScaleMap &xMap, - const QwtScaleMap &yMap) const -{ - return QwtDoubleRect(xMap.s1(), yMap.s1(), - xMap.sDist(), yMap.sDist() ); -} + updateLegend() is only called when the LegendInterest interest + is enabled. The default implementation does nothing. -/*! - \brief Calculate the bounding paint rect of 2 maps + \param item Plot item to be displayed on a legend + \param data Attributes how to display item on the legend - \param xMap X map - \param yMap X map + \sa QwtPlotLegendItem - \return Bounding rect of the scale maps -*/ -QRect QwtPlotItem::paintRect(const QwtScaleMap &xMap, - const QwtScaleMap &yMap) const + \note Plot items, that want to be displayed on a legend + need to enable the QwtPlotItem::Legend flag and to implement + legendData() and legendIcon() + */ +void QwtPlotItem::updateLegend( const QwtPlotItem *item, + const QList<QwtLegendData> &data ) { - const QRect rect( qRound(xMap.p1()), qRound(yMap.p1()), - qRound(xMap.pDist()), qRound(yMap.pDist()) ); - - return rect; + Q_UNUSED( item ); + Q_UNUSED( data ); } /*! - Transform a rectangle + \brief Calculate the bounding scale rectangle of 2 maps - \param xMap X map - \param yMap Y map - \param rect Rectangle in scale coordinates - \return Rectangle in paint coordinates + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. - \sa invTransform() + \return Bounding scale rect of the scale maps, not normalized */ -QRect QwtPlotItem::transform(const QwtScaleMap &xMap, - const QwtScaleMap &yMap, const QwtDoubleRect& rect) const +QRectF QwtPlotItem::scaleRect( const QwtScaleMap &xMap, + const QwtScaleMap &yMap ) const { - int x1 = qRound(xMap.transform(rect.left())); - int x2 = qRound(xMap.transform(rect.right())); - int y1 = qRound(yMap.transform(rect.top())); - int y2 = qRound(yMap.transform(rect.bottom())); - - if ( x2 < x1 ) - qSwap(x1, x2); - if ( y2 < y1 ) - qSwap(y1, y2); - - return QRect(x1, y1, x2 - x1 + 1, y2 - y1 + 1); + return QRectF( xMap.s1(), yMap.s1(), + xMap.sDist(), yMap.sDist() ); } /*! - Transform a rectangle from paint to scale coordinates + \brief Calculate the bounding paint rectangle of 2 maps - \param xMap X map - \param yMap Y map - \param rect Rectangle in paint coordinates - \return Rectangle in scale coordinates - \sa transform() + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + + \return Bounding paint rectangle of the scale maps, not normalized */ -QwtDoubleRect QwtPlotItem::invTransform(const QwtScaleMap &xMap, - const QwtScaleMap &yMap, const QRect& rect) const +QRectF QwtPlotItem::paintRect( const QwtScaleMap &xMap, + const QwtScaleMap &yMap ) const { - const double x1 = xMap.invTransform(rect.left()); - const double x2 = xMap.invTransform(rect.right()); - const double y1 = yMap.invTransform(rect.top()); - const double y2 = yMap.invTransform(rect.bottom()); - - const QwtDoubleRect r(x1, y1, x2 - x1, y2 - y1); + const QRectF rect( xMap.p1(), yMap.p1(), + xMap.pDist(), yMap.pDist() ); - return r.normalized(); + return rect; } diff --git a/libs/qwt/qwt_plot_item.h b/libs/qwt/qwt_plot_item.h index 8d1397e23e..c76634e748 100644 --- a/libs/qwt/qwt_plot_item.h +++ b/libs/qwt/qwt_plot_item.h @@ -11,100 +11,248 @@ #define QWT_PLOT_ITEM_H #include "qwt_global.h" -#include "qwt_legend_itemmanager.h" #include "qwt_text.h" -#include "qwt_double_rect.h" +#include "qwt_legend_data.h" +#include "qwt_graphic.h" +#include <qrect.h> +#include <qlist.h> +#include <qmetatype.h> -class QString; -class QRect; class QPainter; -class QWidget; -class QwtPlot; -class QwtLegend; class QwtScaleMap; class QwtScaleDiv; +class QwtPlot; /*! \brief Base class for items on the plot canvas + + A plot item is "something", that can be painted on the plot canvas, + or only affects the scales of the plot widget. They can be categorized as: + + - Representator\n + A "Representator" is an item that represents some sort of data + on the plot canvas. The different representator classes are organized + according to the characteristics of the data: + - QwtPlotMarker + Represents a point or a horizontal/vertical coordinate + - QwtPlotCurve + Represents a series of points + - QwtPlotSpectrogram ( QwtPlotRasterItem ) + Represents raster data + - ... + + - Decorators\n + A "Decorator" is an item, that displays additional information, that + is not related to any data: + - QwtPlotGrid + - QwtPlotScaleItem + - QwtPlotSvgItem + - ... + + Depending on the QwtPlotItem::ItemAttribute flags, an item is included + into autoscaling or has an entry on the legend. + + Before misusing the existing item classes it might be better to + implement a new type of plot item + ( don't implement a watermark as spectrogram ). + Deriving a new type of QwtPlotItem primarily means to implement + the YourPlotItem::draw() method. + + \sa The cpuplot example shows the implementation of additional plot items. */ -class QWT_EXPORT QwtPlotItem: public QwtLegendItemManager +class QWT_EXPORT QwtPlotItem { public: - enum RttiValues { + /*! + \brief Runtime type information + + RttiValues is used to cast plot items, without + having to enable runtime type information of the compiler. + */ + enum RttiValues + { + //! Unspecific value, that can be used, when it doesn't matter Rtti_PlotItem = 0, + //! For QwtPlotGrid Rtti_PlotGrid, + + //! For QwtPlotScaleItem Rtti_PlotScale, + + //! For QwtPlotLegendItem + Rtti_PlotLegend, + + //! For QwtPlotMarker Rtti_PlotMarker, + + //! For QwtPlotCurve Rtti_PlotCurve, + + //! For QwtPlotSpectroCurve + Rtti_PlotSpectroCurve, + + //! For QwtPlotIntervalCurve + Rtti_PlotIntervalCurve, + + //! For QwtPlotHistogram Rtti_PlotHistogram, + + //! For QwtPlotSpectrogram Rtti_PlotSpectrogram, + + //! For QwtPlotSvgItem Rtti_PlotSVG, + //! For QwtPlotTradingCurve + Rtti_PlotTradingCurve, + + //! For QwtPlotBarChart + Rtti_PlotBarChart, + + //! For QwtPlotMultiBarChart + Rtti_PlotMultiBarChart, + + //! For QwtPlotShapeItem + Rtti_PlotShape, + + //! For QwtPlotTextLabel + Rtti_PlotTextLabel, + + //! For QwtPlotZoneItem + Rtti_PlotZone, + + /*! + Values >= Rtti_PlotUserItem are reserved for plot items + not implemented in the Qwt library. + */ Rtti_PlotUserItem = 1000 }; - enum ItemAttribute { - Legend = 1, - AutoScale = 2 + /*! + \brief Plot Item Attributes + + Various aspects of a plot widget depend on the attributes of + the attached plot items. If and how a single plot item + participates in these updates depends on its attributes. + + \sa setItemAttribute(), testItemAttribute(), ItemInterest + */ + enum ItemAttribute + { + //! The item is represented on the legend. + Legend = 0x01, + + /*! + The boundingRect() of the item is included in the + autoscaling calculation as long as its width or height + is >= 0.0. + */ + AutoScale = 0x02, + + /*! + The item needs extra space to display something outside + its bounding rectangle. + \sa getCanvasMarginHint() + */ + Margins = 0x04 }; -#if QT_VERSION >= 0x040000 - enum RenderHint { - RenderAntialiased = 1 + //! Plot Item Attributes + typedef QFlags<ItemAttribute> ItemAttributes; + + /*! + \brief Plot Item Interests + + Plot items might depend on the situation of the corresponding + plot widget. By enabling an interest the plot item will be + notified, when the corresponding attribute of the plot widgets + has changed. + + \sa setItemAttribute(), testItemAttribute(), ItemInterest + */ + enum ItemInterest + { + /*! + The item is interested in updates of the scales + \sa updateScaleDiv() + */ + ScaleInterest = 0x01, + + /*! + The item is interested in updates of the legend ( of other items ) + This flag is intended for items, that want to implement a legend + for displaying entries of other plot item. + + \note If the plot item wants to be represented on a legend + enable QwtPlotItem::Legend instead. + + \sa updateLegend() + */ + LegendInterest = 0x02 }; -#endif - explicit QwtPlotItem(const QwtText &title = QwtText()); - virtual ~QwtPlotItem(); + //! Plot Item Interests + typedef QFlags<ItemInterest> ItemInterests; - void attach(QwtPlot *plot); + //! Render hints + enum RenderHint + { + //! Enable antialiasing + RenderAntialiased = 0x1 + }; - /*! - \brief This method detaches a QwtPlotItem from any QwtPlot it has been - associated with. + //! Render hints + typedef QFlags<RenderHint> RenderHints; - detach() is equivalent to calling attach( NULL ) - \sa attach( QwtPlot* plot ) - */ - void detach() { - attach(NULL); - } + explicit QwtPlotItem( const QwtText &title = QwtText() ); + virtual ~QwtPlotItem(); + + void attach( QwtPlot *plot ); + void detach(); QwtPlot *plot() const; - void setTitle(const QString &title); - void setTitle(const QwtText &title); + void setTitle( const QString &title ); + void setTitle( const QwtText &title ); const QwtText &title() const; virtual int rtti() const; - void setItemAttribute(ItemAttribute, bool on = true); - bool testItemAttribute(ItemAttribute) const; + void setItemAttribute( ItemAttribute, bool on = true ); + bool testItemAttribute( ItemAttribute ) const; -#if QT_VERSION >= 0x040000 - void setRenderHint(RenderHint, bool on = true); - bool testRenderHint(RenderHint) const; -#endif + void setItemInterest( ItemInterest, bool on = true ); + bool testItemInterest( ItemInterest ) const; + + void setRenderHint( RenderHint, bool on = true ); + bool testRenderHint( RenderHint ) const; + + void setRenderThreadCount( uint numThreads ); + uint renderThreadCount() const; + + void setLegendIconSize( const QSize & ); + QSize legendIconSize() const; double z() const; - void setZ(double z); + void setZ( double z ); void show(); void hide(); - virtual void setVisible(bool); + virtual void setVisible( bool ); bool isVisible () const; - void setAxis(int xAxis, int yAxis); + void setAxes( int xAxis, int yAxis ); - void setXAxis(int axis); + void setXAxis( int axis ); int xAxis() const; - void setYAxis(int axis); + void setYAxis( int axis ); int yAxis() const; virtual void itemChanged(); + virtual void legendChanged(); /*! \brief Draw the item @@ -114,25 +262,32 @@ public: \param yMap Maps y-values into pixel coordinates. \param canvasRect Contents rect of the canvas in painter coordinates */ - virtual void draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &canvasRect) const = 0; + virtual void draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const = 0; + + virtual QRectF boundingRect() const; - virtual QwtDoubleRect boundingRect() const; + virtual void getCanvasMarginHint( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasSize, + double &left, double &top, double &right, double &bottom) const; - virtual void updateLegend(QwtLegend *) const; - virtual void updateScaleDiv(const QwtScaleDiv&, - const QwtScaleDiv&); + virtual void updateScaleDiv( + const QwtScaleDiv&, const QwtScaleDiv& ); - virtual QWidget *legendItem() const; + virtual void updateLegend( const QwtPlotItem *, + const QList<QwtLegendData> & ); - QwtDoubleRect scaleRect(const QwtScaleMap &, const QwtScaleMap &) const; - QRect paintRect(const QwtScaleMap &, const QwtScaleMap &) const; + QRectF scaleRect( const QwtScaleMap &, const QwtScaleMap & ) const; + QRectF paintRect( const QwtScaleMap &, const QwtScaleMap & ) const; - QRect transform(const QwtScaleMap &, const QwtScaleMap &, - const QwtDoubleRect&) const; - QwtDoubleRect invTransform(const QwtScaleMap &, const QwtScaleMap &, - const QRect&) const; + virtual QList<QwtLegendData> legendData() const; + + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; + +protected: + QwtGraphic defaultIcon( const QBrush &, const QSizeF & ) const; private: // Disabled copy constructor and operator= @@ -143,4 +298,10 @@ private: PrivateData *d_data; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotItem::ItemAttributes ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotItem::ItemInterests ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotItem::RenderHints ) + +Q_DECLARE_METATYPE( QwtPlotItem * ) + #endif diff --git a/libs/qwt/qwt_plot_layout.cpp b/libs/qwt/qwt_plot_layout.cpp index 364bd7e860..1c143e2376 100644 --- a/libs/qwt/qwt_plot_layout.cpp +++ b/libs/qwt/qwt_plot_layout.cpp @@ -7,76 +7,84 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <qscrollbar.h> +#include "qwt_plot_layout.h" #include "qwt_text.h" #include "qwt_text_label.h" -#include "qwt_plot_canvas.h" #include "qwt_scale_widget.h" -#include "qwt_legend.h" -#include "qwt_plot_layout.h" +#include "qwt_abstract_legend.h" +#include <qscrollbar.h> +#include <qmath.h> class QwtPlotLayout::LayoutData { public: - void init(const QwtPlot *, const QRect &rect); + void init( const QwtPlot *, const QRectF &rect ); - struct t_legendData { + struct t_legendData + { int frameWidth; - int vScrollBarWidth; - int hScrollBarHeight; + int hScrollExtent; + int vScrollExtent; QSize hint; } legend; - struct t_titleData { + struct t_titleData + { QwtText text; int frameWidth; } title; - struct t_scaleData { + struct t_footerData + { + QwtText text; + int frameWidth; + } footer; + + struct t_scaleData + { bool isEnabled; const QwtScaleWidget *scaleWidget; QFont scaleFont; int start; int end; int baseLineOffset; - int tickOffset; + double tickOffset; int dimWithoutTitle; } scale[QwtPlot::axisCnt]; - struct t_canvasData { - int frameWidth; + struct t_canvasData + { + int contentsMargins[ QwtPlot::axisCnt ]; + } canvas; }; /* Extract all layout relevant data from the plot components */ - -void QwtPlotLayout::LayoutData::init(const QwtPlot *plot, const QRect &rect) +void QwtPlotLayout::LayoutData::init( const QwtPlot *plot, const QRectF &rect ) { // legend - if ( plot->plotLayout()->legendPosition() != QwtPlot::ExternalLegend - && plot->legend() ) { + if ( plot->legend() ) + { legend.frameWidth = plot->legend()->frameWidth(); - legend.vScrollBarWidth = - plot->legend()->verticalScrollBar()->sizeHint().width(); - legend.hScrollBarHeight = - plot->legend()->horizontalScrollBar()->sizeHint().height(); + legend.hScrollExtent = + plot->legend()->scrollExtent( Qt::Horizontal ); + legend.vScrollExtent = + plot->legend()->scrollExtent( Qt::Vertical ); const QSize hint = plot->legend()->sizeHint(); - int w = qwtMin(hint.width(), rect.width()); - int h = plot->legend()->heightForWidth(w); - if ( h == 0 ) + int w = qMin( hint.width(), qFloor( rect.width() ) ); + int h = plot->legend()->heightForWidth( w ); + if ( h <= 0 ) h = hint.height(); if ( h > rect.height() ) - w += legend.vScrollBarWidth; + w += legend.hScrollExtent; - legend.hint = QSize(w, h); + legend.hint = QSize( w, h ); } // title @@ -84,20 +92,38 @@ void QwtPlotLayout::LayoutData::init(const QwtPlot *plot, const QRect &rect) title.frameWidth = 0; title.text = QwtText(); - if (plot->titleLabel() ) { + if ( plot->titleLabel() ) + { const QwtTextLabel *label = plot->titleLabel(); title.text = label->text(); - if ( !(title.text.testPaintAttribute(QwtText::PaintUsingTextFont)) ) - title.text.setFont(label->font()); + if ( !( title.text.testPaintAttribute( QwtText::PaintUsingTextFont ) ) ) + title.text.setFont( label->font() ); title.frameWidth = plot->titleLabel()->frameWidth(); } + // footer + + footer.frameWidth = 0; + footer.text = QwtText(); + + if ( plot->footerLabel() ) + { + const QwtTextLabel *label = plot->footerLabel(); + footer.text = label->text(); + if ( !( footer.text.testPaintAttribute( QwtText::PaintUsingTextFont ) ) ) + footer.text.setFont( label->font() ); + + footer.frameWidth = plot->footerLabel()->frameWidth(); + } + // scales - for (int axis = 0; axis < QwtPlot::axisCnt; axis++ ) { - if ( plot->axisEnabled(axis) ) { - const QwtScaleWidget *scaleWidget = plot->axisWidget(axis); + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( plot->axisEnabled( axis ) ) + { + const QwtScaleWidget *scaleWidget = plot->axisWidget( axis ); scale[axis].isEnabled = true; @@ -111,55 +137,62 @@ void QwtPlotLayout::LayoutData::init(const QwtPlot *plot, const QRect &rect) scale[axis].baseLineOffset = scaleWidget->margin(); scale[axis].tickOffset = scaleWidget->margin(); if ( scaleWidget->scaleDraw()->hasComponent( - QwtAbstractScaleDraw::Ticks) ) { + QwtAbstractScaleDraw::Ticks ) ) + { scale[axis].tickOffset += - (int)scaleWidget->scaleDraw()->majTickLength(); + scaleWidget->scaleDraw()->maxTickLength(); } scale[axis].dimWithoutTitle = scaleWidget->dimForLength( - QWIDGETSIZE_MAX, scale[axis].scaleFont); + QWIDGETSIZE_MAX, scale[axis].scaleFont ); - if ( !scaleWidget->title().isEmpty() ) { + if ( !scaleWidget->title().isEmpty() ) + { scale[axis].dimWithoutTitle -= - scaleWidget->titleHeightForWidth(QWIDGETSIZE_MAX); + scaleWidget->titleHeightForWidth( QWIDGETSIZE_MAX ); } - } else { + } + else + { scale[axis].isEnabled = false; scale[axis].start = 0; scale[axis].end = 0; scale[axis].baseLineOffset = 0; - scale[axis].tickOffset = 0; + scale[axis].tickOffset = 0.0; scale[axis].dimWithoutTitle = 0; } } // canvas - canvas.frameWidth = plot->canvas()->frameWidth(); + plot->canvas()->getContentsMargins( + &canvas.contentsMargins[ QwtPlot::yLeft ], + &canvas.contentsMargins[ QwtPlot::xTop ], + &canvas.contentsMargins[ QwtPlot::yRight ], + &canvas.contentsMargins[ QwtPlot::xBottom ] ); } class QwtPlotLayout::PrivateData { public: PrivateData(): - margin(0), - spacing(5), - alignCanvasToScales(false) { + spacing( 5 ) + { } - QRect titleRect; - QRect legendRect; - QRect scaleRect[QwtPlot::axisCnt]; - QRect canvasRect; + QRectF titleRect; + QRectF footerRect; + QRectF legendRect; + QRectF scaleRect[QwtPlot::axisCnt]; + QRectF canvasRect; QwtPlotLayout::LayoutData layoutData; QwtPlot::LegendPosition legendPos; double legendRatio; - unsigned int margin; unsigned int spacing; unsigned int canvasMargin[QwtPlot::axisCnt]; - bool alignCanvasToScales; + bool alignCanvasToScales[QwtPlot::axisCnt]; }; /*! @@ -170,8 +203,9 @@ QwtPlotLayout::QwtPlotLayout() { d_data = new PrivateData; - setLegendPosition(QwtPlot::BottomLegend); - setCanvasMargin(4); + setLegendPosition( QwtPlot::BottomLegend ); + setCanvasMargin( 4 ); + setAlignCanvasToScales( false ); invalidate(); } @@ -182,30 +216,6 @@ QwtPlotLayout::~QwtPlotLayout() delete d_data; } -/*! - Change the margin of the plot. The margin is the space - around all components. - - \param margin new margin - \sa margin(), setSpacing(), - QwtPlot::setMargin() -*/ -void QwtPlotLayout::setMargin(int margin) -{ - if ( margin < 0 ) - margin = 0; - d_data->margin = margin; -} - -/*! - \return margin - \sa setMargin(), spacing(), QwtPlot::margin() -*/ -int QwtPlotLayout::margin() const -{ - return d_data->margin; -} - /*! Change a margin of the canvas. The margin is the space above/below the scale ticks. A negative margin will @@ -216,48 +226,69 @@ int QwtPlotLayout::margin() const -1 means margin at all borders. \sa canvasMargin() - \warning The margin will have no effect when alignCanvasToScales is true + \warning The margin will have no effect when alignCanvasToScale() is true */ -void QwtPlotLayout::setCanvasMargin(int margin, int axis) +void QwtPlotLayout::setCanvasMargin( int margin, int axis ) { if ( margin < -1 ) margin = -1; - if ( axis == -1 ) { - for (axis = 0; axis < QwtPlot::axisCnt; axis++) + if ( axis == -1 ) + { + for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) d_data->canvasMargin[axis] = margin; - } else if ( axis >= 0 && axis < QwtPlot::axisCnt ) + } + else if ( axis >= 0 && axis < QwtPlot::axisCnt ) d_data->canvasMargin[axis] = margin; } /*! + \param axisId Axis index \return Margin around the scale tick borders \sa setCanvasMargin() */ -int QwtPlotLayout::canvasMargin(int axis) const +int QwtPlotLayout::canvasMargin( int axisId ) const { - if ( axis < 0 || axis >= QwtPlot::axisCnt ) + if ( axisId < 0 || axisId >= QwtPlot::axisCnt ) return 0; - return d_data->canvasMargin[axis]; + return d_data->canvasMargin[axisId]; +} + +/*! + \brief Set the align-canvas-to-axis-scales flag for all axes + + \param on True/False + \sa setAlignCanvasToScale(), alignCanvasToScale() +*/ +void QwtPlotLayout::setAlignCanvasToScales( bool on ) +{ + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + d_data->alignCanvasToScales[axis] = on; } /*! Change the align-canvas-to-axis-scales setting. The canvas may: + - extend beyond the axis scale ends to maximize its size, - align with the axis scale ends to control its size. - \param alignCanvasToScales New align-canvas-to-axis-scales setting + The axisId parameter is somehow confusing as it identifies a border + of the plot and not the axes, that are aligned. F.e when QwtPlot::yLeft + is set, the left end of the the x-axes ( QwtPlot::xTop, QwtPlot::xBottom ) + is aligned. + + \param axisId Axis index + \param on New align-canvas-to-axis-scales setting - \sa setCanvasMargin() - \note In this context the term 'scale' means the backbone of a scale. - \warning In case of alignCanvasToScales == true canvasMargin will have - no effect + \sa setCanvasMargin(), alignCanvasToScale(), setAlignCanvasToScales() + \warning In case of on == true canvasMargin() will have no effect */ -void QwtPlotLayout::setAlignCanvasToScales(bool alignCanvasToScales) +void QwtPlotLayout::setAlignCanvasToScale( int axisId, bool on ) { - d_data->alignCanvasToScales = alignCanvasToScales; + if ( axisId >= 0 && axisId < QwtPlot::axisCnt ) + d_data->alignCanvasToScales[axisId] = on; } /*! @@ -265,29 +296,32 @@ void QwtPlotLayout::setAlignCanvasToScales(bool alignCanvasToScales) - extend beyond the axis scale ends to maximize its size - align with the axis scale ends to control its size. + \param axisId Axis index \return align-canvas-to-axis-scales setting - \sa setAlignCanvasToScales, setCanvasMargin() - \note In this context the term 'scale' means the backbone of a scale. + \sa setAlignCanvasToScale(), setAlignCanvasToScale(), setCanvasMargin() */ -bool QwtPlotLayout::alignCanvasToScales() const +bool QwtPlotLayout::alignCanvasToScale( int axisId ) const { - return d_data->alignCanvasToScales; + if ( axisId < 0 || axisId >= QwtPlot::axisCnt ) + return false; + + return d_data->alignCanvasToScales[ axisId ]; } /*! Change the spacing of the plot. The spacing is the distance between the plot components. - \param spacing new spacing - \sa setMargin(), spacing() + \param spacing New spacing + \sa setCanvasMargin(), spacing() */ -void QwtPlotLayout::setSpacing(int spacing) +void QwtPlotLayout::setSpacing( int spacing ) { - d_data->spacing = qwtMax(0, spacing); + d_data->spacing = qMax( 0, spacing ); } /*! - \return spacing + \return Spacing \sa margin(), setSpacing() */ int QwtPlotLayout::spacing() const @@ -298,8 +332,8 @@ int QwtPlotLayout::spacing() const /*! \brief Specify the position of the legend \param pos The legend's position. - \param ratio Ratio between legend and the bounding rect - of title, canvas and axes. The legend will be shrinked + \param ratio Ratio between legend and the bounding rectangle + of title, footer, canvas and axes. The legend will be shrunk if it would need more space than the given ratio. The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 it will be reset to the default ratio. @@ -308,31 +342,29 @@ int QwtPlotLayout::spacing() const \sa QwtPlot::setLegendPosition() */ -void QwtPlotLayout::setLegendPosition(QwtPlot::LegendPosition pos, double ratio) +void QwtPlotLayout::setLegendPosition( QwtPlot::LegendPosition pos, double ratio ) { if ( ratio > 1.0 ) ratio = 1.0; - switch(pos) { - case QwtPlot::TopLegend: - case QwtPlot::BottomLegend: - if ( ratio <= 0.0 ) - ratio = 0.33; - d_data->legendRatio = ratio; - d_data->legendPos = pos; - break; - case QwtPlot::LeftLegend: - case QwtPlot::RightLegend: - if ( ratio <= 0.0 ) - ratio = 0.5; - d_data->legendRatio = ratio; - d_data->legendPos = pos; - break; - case QwtPlot::ExternalLegend: - d_data->legendRatio = ratio; // meaningless - d_data->legendPos = pos; - default: - break; + switch ( pos ) + { + case QwtPlot::TopLegend: + case QwtPlot::BottomLegend: + if ( ratio <= 0.0 ) + ratio = 0.33; + d_data->legendRatio = ratio; + d_data->legendPos = pos; + break; + case QwtPlot::LeftLegend: + case QwtPlot::RightLegend: + if ( ratio <= 0.0 ) + ratio = 0.5; + d_data->legendRatio = ratio; + d_data->legendPos = pos; + break; + default: + break; } } @@ -344,9 +376,9 @@ void QwtPlotLayout::setLegendPosition(QwtPlot::LegendPosition pos, double ratio) \sa QwtPlot::setLegendPosition() */ -void QwtPlotLayout::setLegendPosition(QwtPlot::LegendPosition pos) +void QwtPlotLayout::setLegendPosition( QwtPlot::LegendPosition pos ) { - setLegendPosition(pos, 0.0); + setLegendPosition( pos, 0.0 ); } /*! @@ -361,16 +393,16 @@ QwtPlot::LegendPosition QwtPlotLayout::legendPosition() const /*! Specify the relative size of the legend in the plot - \param ratio Ratio between legend and the bounding rect - of title, canvas and axes. The legend will be shrinked + \param ratio Ratio between legend and the bounding rectangle + of title, footer, canvas and axes. The legend will be shrunk if it would need more space than the given ratio. The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 it will be reset to the default ratio. The default vertical/horizontal ratio is 0.33/0.5. */ -void QwtPlotLayout::setLegendRatio(double ratio) +void QwtPlotLayout::setLegendRatio( double ratio ) { - setLegendPosition(legendPosition(), ratio); + setLegendPosition( legendPosition(), ratio ); } /*! @@ -382,47 +414,124 @@ double QwtPlotLayout::legendRatio() const return d_data->legendRatio; } +/*! + \brief Set the geometry for the title + + This method is intended to be used from derived layouts + overloading activate() + + \sa titleRect(), activate() + */ +void QwtPlotLayout::setTitleRect( const QRectF &rect ) +{ + d_data->titleRect = rect; +} + /*! \return Geometry for the title \sa activate(), invalidate() */ - -const QRect &QwtPlotLayout::titleRect() const +QRectF QwtPlotLayout::titleRect() const { return d_data->titleRect; } /*! - \return Geometry for the legend + \brief Set the geometry for the footer + + This method is intended to be used from derived layouts + overloading activate() + + \sa footerRect(), activate() + */ +void QwtPlotLayout::setFooterRect( const QRectF &rect ) +{ + d_data->footerRect = rect; +} + +/*! + \return Geometry for the footer \sa activate(), invalidate() */ +QRectF QwtPlotLayout::footerRect() const +{ + return d_data->footerRect; +} + +/*! + \brief Set the geometry for the legend + + This method is intended to be used from derived layouts + overloading activate() + + \param rect Rectangle for the legend -const QRect &QwtPlotLayout::legendRect() const + \sa legendRect(), activate() + */ +void QwtPlotLayout::setLegendRect( const QRectF &rect ) +{ + d_data->legendRect = rect; +} + +/*! + \return Geometry for the legend + \sa activate(), invalidate() +*/ +QRectF QwtPlotLayout::legendRect() const { return d_data->legendRect; } +/*! + \brief Set the geometry for an axis + + This method is intended to be used from derived layouts + overloading activate() + + \param axis Axis index + \param rect Rectangle for the scale + + \sa scaleRect(), activate() + */ +void QwtPlotLayout::setScaleRect( int axis, const QRectF &rect ) +{ + if ( axis >= 0 && axis < QwtPlot::axisCnt ) + d_data->scaleRect[axis] = rect; +} + /*! \param axis Axis index \return Geometry for the scale \sa activate(), invalidate() */ - -const QRect &QwtPlotLayout::scaleRect(int axis) const +QRectF QwtPlotLayout::scaleRect( int axis ) const { - if ( axis < 0 || axis >= QwtPlot::axisCnt ) { - static QRect dummyRect; + if ( axis < 0 || axis >= QwtPlot::axisCnt ) + { + static QRectF dummyRect; return dummyRect; } return d_data->scaleRect[axis]; } +/*! + \brief Set the geometry for the canvas + + This method is intended to be used from derived layouts + overloading activate() + + \sa canvasRect(), activate() + */ +void QwtPlotLayout::setCanvasRect( const QRectF &rect ) +{ + d_data->canvasRect = rect; +} + /*! \return Geometry for the canvas \sa activate(), invalidate() */ - -const QRect &QwtPlotLayout::canvasRect() const +QRectF QwtPlotLayout::canvasRect() const { return d_data->canvasRect; } @@ -433,22 +542,27 @@ const QRect &QwtPlotLayout::canvasRect() const */ void QwtPlotLayout::invalidate() { - d_data->titleRect = d_data->legendRect = d_data->canvasRect = QRect(); - for (int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + d_data->titleRect = d_data->footerRect + = d_data->legendRect = d_data->canvasRect = QRect(); + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) d_data->scaleRect[axis] = QRect(); } /*! - \brief Return a minimum size hint + \return Minimum size hint + \param plot Plot widget + \sa QwtPlot::minimumSizeHint() */ -QSize QwtPlotLayout::minimumSizeHint(const QwtPlot *plot) const +QSize QwtPlotLayout::minimumSizeHint( const QwtPlot *plot ) const { class ScaleData { public: - ScaleData() { + ScaleData() + { w = h = minLeft = minRight = tickOffset = 0; } @@ -461,40 +575,47 @@ QSize QwtPlotLayout::minimumSizeHint(const QwtPlot *plot) const int canvasBorder[QwtPlot::axisCnt]; + int fw; + plot->canvas()->getContentsMargins( &fw, NULL, NULL, NULL ); + int axis; - for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) { - if ( plot->axisEnabled(axis) ) { - const QwtScaleWidget *scl = plot->axisWidget(axis); + for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( plot->axisEnabled( axis ) ) + { + const QwtScaleWidget *scl = plot->axisWidget( axis ); ScaleData &sd = scaleData[axis]; const QSize hint = scl->minimumSizeHint(); sd.w = hint.width(); sd.h = hint.height(); - scl->getBorderDistHint(sd.minLeft, sd.minRight); + scl->getBorderDistHint( sd.minLeft, sd.minRight ); sd.tickOffset = scl->margin(); - if ( scl->scaleDraw()->hasComponent(QwtAbstractScaleDraw::Ticks) ) - sd.tickOffset += scl->scaleDraw()->majTickLength(); + if ( scl->scaleDraw()->hasComponent( QwtAbstractScaleDraw::Ticks ) ) + sd.tickOffset += qCeil( scl->scaleDraw()->maxTickLength() ); } - canvasBorder[axis] = plot->canvas()->frameWidth() + - d_data->canvasMargin[axis] + 1; - + canvasBorder[axis] = fw + d_data->canvasMargin[axis] + 1; } - for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) { + for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { ScaleData &sd = scaleData[axis]; - if ( sd.w && (axis == QwtPlot::xBottom || axis == QwtPlot::xTop) ) { - if ( (sd.minLeft > canvasBorder[QwtPlot::yLeft]) - && scaleData[QwtPlot::yLeft].w ) { + if ( sd.w && ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) ) + { + if ( ( sd.minLeft > canvasBorder[QwtPlot::yLeft] ) + && scaleData[QwtPlot::yLeft].w ) + { int shiftLeft = sd.minLeft - canvasBorder[QwtPlot::yLeft]; if ( shiftLeft > scaleData[QwtPlot::yLeft].w ) shiftLeft = scaleData[QwtPlot::yLeft].w; sd.w -= shiftLeft; } - if ( (sd.minRight > canvasBorder[QwtPlot::yRight]) - && scaleData[QwtPlot::yRight].w ) { + if ( ( sd.minRight > canvasBorder[QwtPlot::yRight] ) + && scaleData[QwtPlot::yRight].w ) + { int shiftRight = sd.minRight - canvasBorder[QwtPlot::yRight]; if ( shiftRight > scaleData[QwtPlot::yRight].w ) shiftRight = scaleData[QwtPlot::yRight].w; @@ -503,17 +624,20 @@ QSize QwtPlotLayout::minimumSizeHint(const QwtPlot *plot) const } } - if ( sd.h && (axis == QwtPlot::yLeft || axis == QwtPlot::yRight) ) { - if ( (sd.minLeft > canvasBorder[QwtPlot::xBottom]) && - scaleData[QwtPlot::xBottom].h ) { + if ( sd.h && ( axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) ) + { + if ( ( sd.minLeft > canvasBorder[QwtPlot::xBottom] ) && + scaleData[QwtPlot::xBottom].h ) + { int shiftBottom = sd.minLeft - canvasBorder[QwtPlot::xBottom]; if ( shiftBottom > scaleData[QwtPlot::xBottom].tickOffset ) shiftBottom = scaleData[QwtPlot::xBottom].tickOffset; sd.h -= shiftBottom; } - if ( (sd.minLeft > canvasBorder[QwtPlot::xTop]) && - scaleData[QwtPlot::xTop].h ) { + if ( ( sd.minLeft > canvasBorder[QwtPlot::xTop] ) && + scaleData[QwtPlot::xTop].h ) + { int shiftTop = sd.minRight - canvasBorder[QwtPlot::xTop]; if ( shiftTop > scaleData[QwtPlot::xTop].tickOffset ) shiftTop = scaleData[QwtPlot::xTop].tickOffset; @@ -523,136 +647,158 @@ QSize QwtPlotLayout::minimumSizeHint(const QwtPlot *plot) const } } - const QwtPlotCanvas *canvas = plot->canvas(); + const QWidget *canvas = plot->canvas(); + + int left, top, right, bottom; + canvas->getContentsMargins( &left, &top, &right, &bottom ); + const QSize minCanvasSize = canvas->minimumSize(); int w = scaleData[QwtPlot::yLeft].w + scaleData[QwtPlot::yRight].w; - int cw = qwtMax(scaleData[QwtPlot::xBottom].w, scaleData[QwtPlot::xTop].w) - + 2 * (canvas->frameWidth() + 1); - w += qwtMax(cw, minCanvasSize.width()); + int cw = qMax( scaleData[QwtPlot::xBottom].w, scaleData[QwtPlot::xTop].w ) + + left + 1 + right + 1; + w += qMax( cw, minCanvasSize.width() ); int h = scaleData[QwtPlot::xBottom].h + scaleData[QwtPlot::xTop].h; - int ch = qwtMax(scaleData[QwtPlot::yLeft].h, scaleData[QwtPlot::yRight].h) - + 2 * (canvas->frameWidth() + 1); - h += qwtMax(ch, minCanvasSize.height()); - - const QwtTextLabel *title = plot->titleLabel(); - if (title && !title->text().isEmpty()) { - // If only QwtPlot::yLeft or QwtPlot::yRight is showing, - // we center on the plot canvas. - const bool centerOnCanvas = !(plot->axisEnabled(QwtPlot::yLeft) - && plot->axisEnabled(QwtPlot::yRight)); - - int titleW = w; - if ( centerOnCanvas ) { - titleW -= scaleData[QwtPlot::yLeft].w - + scaleData[QwtPlot::yRight].w; - } + int ch = qMax( scaleData[QwtPlot::yLeft].h, scaleData[QwtPlot::yRight].h ) + + top + 1 + bottom + 1; + h += qMax( ch, minCanvasSize.height() ); + + const QwtTextLabel *labels[2]; + labels[0] = plot->titleLabel(); + labels[1] = plot->footerLabel(); - int titleH = title->heightForWidth(titleW); - if ( titleH > titleW ) { // Compensate for a long title - w = titleW = titleH; - if ( centerOnCanvas ) { - w += scaleData[QwtPlot::yLeft].w - + scaleData[QwtPlot::yRight].w; + for ( int i = 0; i < 2; i++ ) + { + const QwtTextLabel *label = labels[i]; + if ( label && !label->text().isEmpty() ) + { + // If only QwtPlot::yLeft or QwtPlot::yRight is showing, + // we center on the plot canvas. + const bool centerOnCanvas = !( plot->axisEnabled( QwtPlot::yLeft ) + && plot->axisEnabled( QwtPlot::yRight ) ); + + int labelW = w; + if ( centerOnCanvas ) + { + labelW -= scaleData[QwtPlot::yLeft].w + + scaleData[QwtPlot::yRight].w; } - titleH = title->heightForWidth(titleW); + int labelH = label->heightForWidth( labelW ); + if ( labelH > labelW ) // Compensate for a long title + { + w = labelW = labelH; + if ( centerOnCanvas ) + { + w += scaleData[QwtPlot::yLeft].w + + scaleData[QwtPlot::yRight].w; + } + + labelH = label->heightForWidth( labelW ); + } + h += labelH + d_data->spacing; } - h += titleH + d_data->spacing; } // Compute the legend contribution - const QwtLegend *legend = plot->legend(); - if ( d_data->legendPos != QwtPlot::ExternalLegend - && legend && !legend->isEmpty() ) { + const QwtAbstractLegend *legend = plot->legend(); + if ( legend && !legend->isEmpty() ) + { if ( d_data->legendPos == QwtPlot::LeftLegend - || d_data->legendPos == QwtPlot::RightLegend ) { + || d_data->legendPos == QwtPlot::RightLegend ) + { int legendW = legend->sizeHint().width(); - int legendH = legend->heightForWidth(legendW); + int legendH = legend->heightForWidth( legendW ); if ( legend->frameWidth() > 0 ) w += d_data->spacing; if ( legendH > h ) - legendW += legend->verticalScrollBar()->sizeHint().height(); + legendW += legend->scrollExtent( Qt::Horizontal ); if ( d_data->legendRatio < 1.0 ) - legendW = qwtMin(legendW, int(w / (1.0 - d_data->legendRatio))); + legendW = qMin( legendW, int( w / ( 1.0 - d_data->legendRatio ) ) ); - w += legendW; - } else { // QwtPlot::Top, QwtPlot::Bottom - int legendW = qwtMin(legend->sizeHint().width(), w); - int legendH = legend->heightForWidth(legendW); + w += legendW + d_data->spacing; + } + else // QwtPlot::Top, QwtPlot::Bottom + { + int legendW = qMin( legend->sizeHint().width(), w ); + int legendH = legend->heightForWidth( legendW ); if ( legend->frameWidth() > 0 ) h += d_data->spacing; if ( d_data->legendRatio < 1.0 ) - legendH = qwtMin(legendH, int(h / (1.0 - d_data->legendRatio))); + legendH = qMin( legendH, int( h / ( 1.0 - d_data->legendRatio ) ) ); - h += legendH; + h += legendH + d_data->spacing; } } - w += 2 * d_data->margin; - h += 2 * d_data->margin; - return QSize( w, h ); } /*! Find the geometry for the legend + \param options Options how to layout the legend \param rect Rectangle where to place the legend + \return Geometry for the legend + \sa Options */ -QRect QwtPlotLayout::layoutLegend(int options, - const QRect &rect) const +QRectF QwtPlotLayout::layoutLegend( Options options, + const QRectF &rect ) const { - const QSize hint(d_data->layoutData.legend.hint); + const QSize hint( d_data->layoutData.legend.hint ); int dim; if ( d_data->legendPos == QwtPlot::LeftLegend - || d_data->legendPos == QwtPlot::RightLegend ) { + || d_data->legendPos == QwtPlot::RightLegend ) + { // We don't allow vertical legends to take more than // half of the available space. - dim = qwtMin(hint.width(), int(rect.width() * d_data->legendRatio)); + dim = qMin( hint.width(), int( rect.width() * d_data->legendRatio ) ); - if ( !(options & IgnoreScrollbars) ) { - if ( hint.height() > rect.height() ) { + if ( !( options & IgnoreScrollbars ) ) + { + if ( hint.height() > rect.height() ) + { // The legend will need additional // space for the vertical scrollbar. - dim += d_data->layoutData.legend.vScrollBarWidth; + dim += d_data->layoutData.legend.hScrollExtent; } } - } else { - dim = qwtMin(hint.height(), int(rect.height() * d_data->legendRatio)); - dim = qwtMax(dim, d_data->layoutData.legend.hScrollBarHeight); + } + else + { + dim = qMin( hint.height(), int( rect.height() * d_data->legendRatio ) ); + dim = qMax( dim, d_data->layoutData.legend.vScrollExtent ); } - QRect legendRect = rect; - switch(d_data->legendPos) { - case QwtPlot::LeftLegend: - legendRect.setWidth(dim); - break; - case QwtPlot::RightLegend: - legendRect.setX(rect.right() - dim + 1); - legendRect.setWidth(dim); - break; - case QwtPlot::TopLegend: - legendRect.setHeight(dim); - break; - case QwtPlot::BottomLegend: - legendRect.setY(rect.bottom() - dim + 1); - legendRect.setHeight(dim); - break; - case QwtPlot::ExternalLegend: - break; + QRectF legendRect = rect; + switch ( d_data->legendPos ) + { + case QwtPlot::LeftLegend: + legendRect.setWidth( dim ); + break; + case QwtPlot::RightLegend: + legendRect.setX( rect.right() - dim ); + legendRect.setWidth( dim ); + break; + case QwtPlot::TopLegend: + legendRect.setHeight( dim ); + break; + case QwtPlot::BottomLegend: + legendRect.setY( rect.bottom() - dim ); + legendRect.setHeight( dim ); + break; } return legendRect; @@ -660,25 +806,32 @@ QRect QwtPlotLayout::layoutLegend(int options, /*! Align the legend to the canvas + \param canvasRect Geometry of the canvas \param legendRect Maximum geometry for the legend + \return Geometry for the aligned legend */ -QRect QwtPlotLayout::alignLegend(const QRect &canvasRect, - const QRect &legendRect) const +QRectF QwtPlotLayout::alignLegend( const QRectF &canvasRect, + const QRectF &legendRect ) const { - QRect alignedRect = legendRect; + QRectF alignedRect = legendRect; if ( d_data->legendPos == QwtPlot::BottomLegend - || d_data->legendPos == QwtPlot::TopLegend ) { - if ( d_data->layoutData.legend.hint.width() < canvasRect.width() ) { - alignedRect.setX(canvasRect.x()); - alignedRect.setWidth(canvasRect.width()); + || d_data->legendPos == QwtPlot::TopLegend ) + { + if ( d_data->layoutData.legend.hint.width() < canvasRect.width() ) + { + alignedRect.setX( canvasRect.x() ); + alignedRect.setWidth( canvasRect.width() ); } - } else { - if ( d_data->layoutData.legend.hint.height() < canvasRect.height() ) { - alignedRect.setY(canvasRect.y()); - alignedRect.setHeight(canvasRect.height()); + } + else + { + if ( d_data->layoutData.legend.hint.height() < canvasRect.height() ) + { + alignedRect.setY( canvasRect.y() ); + alignedRect.setHeight( canvasRect.height() ); } } @@ -690,28 +843,34 @@ QRect QwtPlotLayout::alignLegend(const QRect &canvasRect, of their widgets in orientation of the text. \param options Options how to layout the legend - \param rect Bounding rect for title, axes and canvas. + \param rect Bounding rectangle for title, footer, axes and canvas. \param dimTitle Expanded height of the title widget + \param dimFooter Expanded height of the footer widget \param dimAxis Expanded heights of the axis in axis orientation. + + \sa Options */ -void QwtPlotLayout::expandLineBreaks(int options, const QRect &rect, - int &dimTitle, int dimAxis[QwtPlot::axisCnt]) const +void QwtPlotLayout::expandLineBreaks( Options options, const QRectF &rect, + int &dimTitle, int &dimFooter, int dimAxis[QwtPlot::axisCnt] ) const { - dimTitle = 0; + dimTitle = dimFooter = 0; for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) dimAxis[axis] = 0; int backboneOffset[QwtPlot::axisCnt]; - for (int axis = 0; axis < QwtPlot::axisCnt; axis++ ) { + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { backboneOffset[axis] = 0; - if ( !d_data->alignCanvasToScales ) + if ( !( options & IgnoreFrames ) ) + backboneOffset[axis] += d_data->layoutData.canvas.contentsMargins[ axis ]; + + if ( !d_data->alignCanvasToScales[axis] ) backboneOffset[axis] += d_data->canvasMargin[axis]; - if ( !(options & IgnoreFrames) ) - backboneOffset[axis] += d_data->layoutData.canvas.frameWidth; } bool done = false; - while (!done) { + while ( !done ) + { done = true; // the size for the 4 axis depend on each other. Expanding @@ -722,46 +881,78 @@ void QwtPlotLayout::expandLineBreaks(int options, const QRect &rect, // axis what might result in a line break of a horizontal // axis ... . So we loop as long until no size changes. - if ( !d_data->layoutData.title.text.isEmpty() ) { - int w = rect.width(); + if ( !( ( options & IgnoreTitle ) || + d_data->layoutData.title.text.isEmpty() ) ) + { + double w = rect.width(); if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled - != d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) { + != d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) + { // center to the canvas w -= dimAxis[QwtPlot::yLeft] + dimAxis[QwtPlot::yRight]; } - int d = d_data->layoutData.title.text.heightForWidth(w); - if ( !(options & IgnoreFrames) ) + int d = qCeil( d_data->layoutData.title.text.heightForWidth( w ) ); + if ( !( options & IgnoreFrames ) ) d += 2 * d_data->layoutData.title.frameWidth; - if ( d > dimTitle ) { + if ( d > dimTitle ) + { dimTitle = d; done = false; } } - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) { + if ( !( ( options & IgnoreFooter ) || + d_data->layoutData.footer.text.isEmpty() ) ) + { + double w = rect.width(); + + if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled + != d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) + { + // center to the canvas + w -= dimAxis[QwtPlot::yLeft] + dimAxis[QwtPlot::yRight]; + } + + int d = qCeil( d_data->layoutData.footer.text.heightForWidth( w ) ); + if ( !( options & IgnoreFrames ) ) + d += 2 * d_data->layoutData.footer.frameWidth; + + if ( d > dimFooter ) + { + dimFooter = d; + done = false; + } + } + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { const struct LayoutData::t_scaleData &scaleData = - d_data->layoutData.scale[axis]; + d_data->layoutData.scale[axis]; - if (scaleData.isEnabled) { - int length; - if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) { + if ( scaleData.isEnabled ) + { + double length; + if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) + { length = rect.width() - dimAxis[QwtPlot::yLeft] - - dimAxis[QwtPlot::yRight]; + - dimAxis[QwtPlot::yRight]; length -= scaleData.start + scaleData.end; if ( dimAxis[QwtPlot::yRight] > 0 ) length -= 1; - length += qwtMin(dimAxis[QwtPlot::yLeft], - scaleData.start - backboneOffset[QwtPlot::yLeft]); - length += qwtMin(dimAxis[QwtPlot::yRight], - scaleData.end - backboneOffset[QwtPlot::yRight]); - } else { // QwtPlot::yLeft, QwtPlot::yRight + length += qMin( dimAxis[QwtPlot::yLeft], + scaleData.start - backboneOffset[QwtPlot::yLeft] ); + length += qMin( dimAxis[QwtPlot::yRight], + scaleData.end - backboneOffset[QwtPlot::yRight] ); + } + else // QwtPlot::yLeft, QwtPlot::yRight + { length = rect.height() - dimAxis[QwtPlot::xTop] - - dimAxis[QwtPlot::xBottom]; + - dimAxis[QwtPlot::xBottom]; length -= scaleData.start + scaleData.end; length -= 1; @@ -770,15 +961,17 @@ void QwtPlotLayout::expandLineBreaks(int options, const QRect &rect, if ( dimAxis[QwtPlot::xTop] <= 0 ) length -= 1; - if ( dimAxis[QwtPlot::xBottom] > 0 ) { - length += qwtMin( - d_data->layoutData.scale[QwtPlot::xBottom].tickOffset, - scaleData.start - backboneOffset[QwtPlot::xBottom]); + if ( dimAxis[QwtPlot::xBottom] > 0 ) + { + length += qMin( + d_data->layoutData.scale[QwtPlot::xBottom].tickOffset, + double( scaleData.start - backboneOffset[QwtPlot::xBottom] ) ); } - if ( dimAxis[QwtPlot::xTop] > 0 ) { - length += qwtMin( - d_data->layoutData.scale[QwtPlot::xTop].tickOffset, - scaleData.end - backboneOffset[QwtPlot::xTop]); + if ( dimAxis[QwtPlot::xTop] > 0 ) + { + length += qMin( + d_data->layoutData.scale[QwtPlot::xTop].tickOffset, + double( scaleData.end - backboneOffset[QwtPlot::xTop] ) ); } if ( dimTitle > 0 ) @@ -786,12 +979,14 @@ void QwtPlotLayout::expandLineBreaks(int options, const QRect &rect, } int d = scaleData.dimWithoutTitle; - if ( !scaleData.scaleWidget->title().isEmpty() ) { - d += scaleData.scaleWidget->titleHeightForWidth(length); + if ( !scaleData.scaleWidget->title().isEmpty() ) + { + d += scaleData.scaleWidget->titleHeightForWidth( qFloor( length ) ); } - if ( d > dimAxis[axis] ) { + if ( d > dimAxis[axis] ) + { dimAxis[axis] = d; done = false; } @@ -803,132 +998,262 @@ void QwtPlotLayout::expandLineBreaks(int options, const QRect &rect, /*! Align the ticks of the axis to the canvas borders using the empty corners. + + \param options Layout options + \param canvasRect Geometry of the canvas ( IN/OUT ) + \param scaleRect Geometries of the scales ( IN/OUT ) + + \sa Options */ -void QwtPlotLayout::alignScales(int options, - QRect &canvasRect, QRect scaleRect[QwtPlot::axisCnt]) const +void QwtPlotLayout::alignScales( Options options, + QRectF &canvasRect, QRectF scaleRect[QwtPlot::axisCnt] ) const { - int axis; - int backboneOffset[QwtPlot::axisCnt]; - for (axis = 0; axis < QwtPlot::axisCnt; axis++ ) { + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { backboneOffset[axis] = 0; - if ( !d_data->alignCanvasToScales ) + + if ( !d_data->alignCanvasToScales[axis] ) + { backboneOffset[axis] += d_data->canvasMargin[axis]; - if ( !(options & IgnoreFrames) ) - backboneOffset[axis] += d_data->layoutData.canvas.frameWidth; + } + + if ( !( options & IgnoreFrames ) ) + { + backboneOffset[axis] += + d_data->layoutData.canvas.contentsMargins[axis]; + } } - for (axis = 0; axis < QwtPlot::axisCnt; axis++ ) { + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { if ( !scaleRect[axis].isValid() ) continue; const int startDist = d_data->layoutData.scale[axis].start; const int endDist = d_data->layoutData.scale[axis].end; - QRect &axisRect = scaleRect[axis]; + QRectF &axisRect = scaleRect[axis]; - if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) { + if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) + { + const QRectF &leftScaleRect = scaleRect[QwtPlot::yLeft]; const int leftOffset = backboneOffset[QwtPlot::yLeft] - startDist; - if ( scaleRect[QwtPlot::yLeft].isValid() ) { - int minLeft = scaleRect[QwtPlot::yLeft].left(); - int left = axisRect.left() + leftOffset; - axisRect.setLeft(qwtMax(left, minLeft)); - } else { - if ( d_data->alignCanvasToScales && leftOffset < 0 ) { - canvasRect.setLeft(qwtMax(canvasRect.left(), - axisRect.left() - leftOffset)); - } else { + if ( leftScaleRect.isValid() ) + { + const double dx = leftOffset + leftScaleRect.width(); + if ( d_data->alignCanvasToScales[QwtPlot::yLeft] && dx < 0.0 ) + { + /* + The axis needs more space than the width + of the left scale. + */ + const double cLeft = canvasRect.left(); // qreal -> double + canvasRect.setLeft( qMax( cLeft, axisRect.left() - dx ) ); + } + else + { + const double minLeft = leftScaleRect.left(); + const double left = axisRect.left() + leftOffset; + axisRect.setLeft( qMax( left, minLeft ) ); + } + } + else + { + if ( d_data->alignCanvasToScales[QwtPlot::yLeft] && leftOffset < 0 ) + { + canvasRect.setLeft( qMax( canvasRect.left(), + axisRect.left() - leftOffset ) ); + } + else + { if ( leftOffset > 0 ) - axisRect.setLeft(axisRect.left() + leftOffset); + axisRect.setLeft( axisRect.left() + leftOffset ); } } + const QRectF &rightScaleRect = scaleRect[QwtPlot::yRight]; const int rightOffset = backboneOffset[QwtPlot::yRight] - endDist + 1; - if ( scaleRect[QwtPlot::yRight].isValid() ) { - int maxRight = scaleRect[QwtPlot::yRight].right(); - int right = axisRect.right() - rightOffset; - axisRect.setRight(qwtMin(right, maxRight)); - } else { - if ( d_data->alignCanvasToScales && rightOffset < 0 ) { - canvasRect.setRight( qwtMin(canvasRect.right(), - axisRect.right() + rightOffset) ); - } else { + if ( rightScaleRect.isValid() ) + { + const double dx = rightOffset + rightScaleRect.width(); + if ( d_data->alignCanvasToScales[QwtPlot::yRight] && dx < 0 ) + { + /* + The axis needs more space than the width + of the right scale. + */ + const double cRight = canvasRect.right(); // qreal -> double + canvasRect.setRight( qMin( cRight, axisRect.right() + dx ) ); + } + + const double maxRight = rightScaleRect.right(); + const double right = axisRect.right() - rightOffset; + axisRect.setRight( qMin( right, maxRight ) ); + } + else + { + if ( d_data->alignCanvasToScales[QwtPlot::yRight] && rightOffset < 0 ) + { + canvasRect.setRight( qMin( canvasRect.right(), + axisRect.right() + rightOffset ) ); + } + else + { if ( rightOffset > 0 ) - axisRect.setRight(axisRect.right() - rightOffset); + axisRect.setRight( axisRect.right() - rightOffset ); } } - } else { // QwtPlot::yLeft, QwtPlot::yRight + } + else // QwtPlot::yLeft, QwtPlot::yRight + { + const QRectF &bottomScaleRect = scaleRect[QwtPlot::xBottom]; const int bottomOffset = backboneOffset[QwtPlot::xBottom] - endDist + 1; - if ( scaleRect[QwtPlot::xBottom].isValid() ) { - int maxBottom = scaleRect[QwtPlot::xBottom].top() + - d_data->layoutData.scale[QwtPlot::xBottom].tickOffset; - - int bottom = axisRect.bottom() - bottomOffset; - axisRect.setBottom(qwtMin(bottom, maxBottom)); - } else { - if ( d_data->alignCanvasToScales && bottomOffset < 0 ) { - canvasRect.setBottom(qwtMin(canvasRect.bottom(), - axisRect.bottom() + bottomOffset)); - } else { + if ( bottomScaleRect.isValid() ) + { + const double dy = bottomOffset + bottomScaleRect.height(); + if ( d_data->alignCanvasToScales[QwtPlot::xBottom] && dy < 0 ) + { + /* + The axis needs more space than the height + of the bottom scale. + */ + const double cBottom = canvasRect.bottom(); // qreal -> double + canvasRect.setBottom( qMin( cBottom, axisRect.bottom() + dy ) ); + } + else + { + const double maxBottom = bottomScaleRect.top() + + d_data->layoutData.scale[QwtPlot::xBottom].tickOffset; + const double bottom = axisRect.bottom() - bottomOffset; + axisRect.setBottom( qMin( bottom, maxBottom ) ); + } + } + else + { + if ( d_data->alignCanvasToScales[QwtPlot::xBottom] && bottomOffset < 0 ) + { + canvasRect.setBottom( qMin( canvasRect.bottom(), + axisRect.bottom() + bottomOffset ) ); + } + else + { if ( bottomOffset > 0 ) - axisRect.setBottom(axisRect.bottom() - bottomOffset); + axisRect.setBottom( axisRect.bottom() - bottomOffset ); } } + const QRectF &topScaleRect = scaleRect[QwtPlot::xTop]; const int topOffset = backboneOffset[QwtPlot::xTop] - startDist; - if ( scaleRect[QwtPlot::xTop].isValid() ) { - int minTop = scaleRect[QwtPlot::xTop].bottom() - - d_data->layoutData.scale[QwtPlot::xTop].tickOffset; - - int top = axisRect.top() + topOffset; - axisRect.setTop(qwtMax(top, minTop)); - } else { - if ( d_data->alignCanvasToScales && topOffset < 0 ) { - canvasRect.setTop(qwtMax(canvasRect.top(), - axisRect.top() - topOffset)); - } else { + if ( topScaleRect.isValid() ) + { + const double dy = topOffset + topScaleRect.height(); + if ( d_data->alignCanvasToScales[QwtPlot::xTop] && dy < 0 ) + { + /* + The axis needs more space than the height + of the top scale. + */ + const double cTop = canvasRect.top(); // qreal -> double + canvasRect.setTop( qMax( cTop, axisRect.top() - dy ) ); + } + else + { + const double minTop = topScaleRect.bottom() - + d_data->layoutData.scale[QwtPlot::xTop].tickOffset; + const double top = axisRect.top() + topOffset; + axisRect.setTop( qMax( top, minTop ) ); + } + } + else + { + if ( d_data->alignCanvasToScales[QwtPlot::xTop] && topOffset < 0 ) + { + canvasRect.setTop( qMax( canvasRect.top(), + axisRect.top() - topOffset ) ); + } + else + { if ( topOffset > 0 ) - axisRect.setTop(axisRect.top() + topOffset); + axisRect.setTop( axisRect.top() + topOffset ); } } } } - if ( d_data->alignCanvasToScales ) { - /* - The canvas has been aligned to the scale with largest - border distances. Now we have to realign the other scale. - */ - - int fw = 0; - if ( !(options & IgnoreFrames) ) - fw = d_data->layoutData.canvas.frameWidth; - - if ( scaleRect[QwtPlot::xBottom].isValid() && - scaleRect[QwtPlot::xTop].isValid() ) { - for ( int axis = QwtPlot::xBottom; axis <= QwtPlot::xTop; axis++ ) { - scaleRect[axis].setLeft(canvasRect.left() + fw - - d_data->layoutData.scale[axis].start); - scaleRect[axis].setRight(canvasRect.right() - fw - 1 - + d_data->layoutData.scale[axis].end); + /* + The canvas has been aligned to the scale with largest + border distances. Now we have to realign the other scale. + */ + + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + QRectF &sRect = scaleRect[axis]; + + if ( !sRect.isValid() ) + continue; + + if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) + { + if ( d_data->alignCanvasToScales[QwtPlot::yLeft] ) + { + double y = canvasRect.left() - d_data->layoutData.scale[axis].start; + if ( !( options & IgnoreFrames ) ) + y += d_data->layoutData.canvas.contentsMargins[ QwtPlot::yLeft ]; + + sRect.setLeft( y ); + } + if ( d_data->alignCanvasToScales[QwtPlot::yRight] ) + { + double y = canvasRect.right() - 1 + d_data->layoutData.scale[axis].end; + if ( !( options & IgnoreFrames ) ) + y -= d_data->layoutData.canvas.contentsMargins[ QwtPlot::yRight ]; + + sRect.setRight( y ); + } + + if ( d_data->alignCanvasToScales[ axis ] ) + { + if ( axis == QwtPlot::xTop ) + sRect.setBottom( canvasRect.top() ); + else + sRect.setTop( canvasRect.bottom() ); } } + else + { + if ( d_data->alignCanvasToScales[QwtPlot::xTop] ) + { + double x = canvasRect.top() - d_data->layoutData.scale[axis].start; + if ( !( options & IgnoreFrames ) ) + x += d_data->layoutData.canvas.contentsMargins[ QwtPlot::xTop ]; + + sRect.setTop( x ); + } + if ( d_data->alignCanvasToScales[QwtPlot::xBottom] ) + { + double x = canvasRect.bottom() - 1 + d_data->layoutData.scale[axis].end; + if ( !( options & IgnoreFrames ) ) + x -= d_data->layoutData.canvas.contentsMargins[ QwtPlot::xBottom ]; + + sRect.setBottom( x ); + } - if ( scaleRect[QwtPlot::yLeft].isValid() && - scaleRect[QwtPlot::yRight].isValid() ) { - for ( int axis = QwtPlot::yLeft; axis <= QwtPlot::yRight; axis++ ) { - scaleRect[axis].setTop(canvasRect.top() + fw - - d_data->layoutData.scale[axis].start); - scaleRect[axis].setBottom(canvasRect.bottom() - fw - 1 - + d_data->layoutData.scale[axis].end); + if ( d_data->alignCanvasToScales[ axis ] ) + { + if ( axis == QwtPlot::yLeft ) + sRect.setRight( canvasRect.left() ); + else + sRect.setLeft( canvasRect.right() ); } } } @@ -938,72 +1263,51 @@ void QwtPlotLayout::alignScales(int options, \brief Recalculate the geometry of all components. \param plot Plot to be layout - \param plotRect Rect where to place the components - \param options Options + \param plotRect Rectangle where to place the components + \param options Layout options - \sa invalidate(), titleRect(), + \sa invalidate(), titleRect(), footerRect() legendRect(), scaleRect(), canvasRect() */ -void QwtPlotLayout::activate(const QwtPlot *plot, - const QRect &plotRect, int options) +void QwtPlotLayout::activate( const QwtPlot *plot, + const QRectF &plotRect, Options options ) { invalidate(); - QRect rect(plotRect); // undistributed rest of the plot rect + QRectF rect( plotRect ); // undistributed rest of the plot rect - if ( !(options & IgnoreMargin) ) { - // subtract the margin + // We extract all layout relevant parameters from the widgets, + // and save them to d_data->layoutData. - rect.setRect( - rect.x() + d_data->margin, - rect.y() + d_data->margin, - rect.width() - 2 * d_data->margin, - rect.height() - 2 * d_data->margin - ); - } + d_data->layoutData.init( plot, rect ); - // We extract all layout relevant data from the widgets, - // filter them through pfilter and save them to d_data->layoutData. - - d_data->layoutData.init(plot, rect); - - if (!(options & IgnoreLegend) - && d_data->legendPos != QwtPlot::ExternalLegend - && plot->legend() && !plot->legend()->isEmpty() ) { - d_data->legendRect = layoutLegend(options, rect); + if ( !( options & IgnoreLegend ) + && plot->legend() && !plot->legend()->isEmpty() ) + { + d_data->legendRect = layoutLegend( options, rect ); // subtract d_data->legendRect from rect - const QRegion region(rect); - rect = region.subtract(d_data->legendRect).boundingRect(); + const QRegion region( rect.toRect() ); + rect = region.subtracted( d_data->legendRect.toRect() ).boundingRect(); - if ( d_data->layoutData.legend.frameWidth && - !(options & IgnoreFrames ) ) { - // In case of a frame we have to insert a spacing. - // Otherwise the leading of the font separates - // legend and scale/canvas - - switch(d_data->legendPos) { + switch ( d_data->legendPos ) + { case QwtPlot::LeftLegend: - rect.setLeft(rect.left() + d_data->spacing); + rect.setLeft( rect.left() + d_data->spacing ); break; case QwtPlot::RightLegend: - rect.setRight(rect.right() - d_data->spacing); + rect.setRight( rect.right() - d_data->spacing ); break; case QwtPlot::TopLegend: - rect.setTop(rect.top() + d_data->spacing); + rect.setTop( rect.top() + d_data->spacing ); break; case QwtPlot::BottomLegend: - rect.setBottom(rect.bottom() - d_data->spacing); + rect.setBottom( rect.bottom() - d_data->spacing ); break; - case QwtPlot::ExternalLegend: - break; // suppress compiler warning - } } } -#ifdef __GNUC__ -#endif /* +---+-----------+---+ | Title | @@ -1017,73 +1321,94 @@ void QwtPlotLayout::activate(const QwtPlot *plot, +---+-----------+---+ | | Axis | | +---+-----------+---+ + | Footer | + +---+-----------+---+ */ - // axes and title include text labels. The height of each + // title, footer and axes include text labels. The height of each // label depends on its line breaks, that depend on the width // for the label. A line break in a horizontal text will reduce // the available width for vertical texts and vice versa. - // expandLineBreaks finds the height/width for title and axes + // expandLineBreaks finds the height/width for title, footer and axes // including all line breaks. - int dimTitle, dimAxes[QwtPlot::axisCnt]; - expandLineBreaks(options, rect, dimTitle, dimAxes); + int dimTitle, dimFooter, dimAxes[QwtPlot::axisCnt]; + expandLineBreaks( options, rect, dimTitle, dimFooter, dimAxes ); - if (dimTitle > 0 ) { - d_data->titleRect = QRect(rect.x(), rect.y(), - rect.width(), dimTitle); + if ( dimTitle > 0 ) + { + d_data->titleRect.setRect( + rect.left(), rect.top(), rect.width(), dimTitle ); + + rect.setTop( d_data->titleRect.bottom() + d_data->spacing ); if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled != - d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) { + d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) + { // if only one of the y axes is missing we align // the title centered to the canvas - d_data->titleRect.setX(rect.x() + dimAxes[QwtPlot::yLeft]); - d_data->titleRect.setWidth(rect.width() - - dimAxes[QwtPlot::yLeft] - dimAxes[QwtPlot::yRight]); + d_data->titleRect.setX( rect.left() + dimAxes[QwtPlot::yLeft] ); + d_data->titleRect.setWidth( rect.width() + - dimAxes[QwtPlot::yLeft] - dimAxes[QwtPlot::yRight] ); } + } - // subtract title - rect.setTop(rect.top() + dimTitle + d_data->spacing); + if ( dimFooter > 0 ) + { + d_data->footerRect.setRect( + rect.left(), rect.bottom() - dimFooter, rect.width(), dimFooter ); + + rect.setBottom( d_data->footerRect.top() - d_data->spacing ); + + if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled != + d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) + { + // if only one of the y axes is missing we align + // the footer centered to the canvas + + d_data->footerRect.setX( rect.left() + dimAxes[QwtPlot::yLeft] ); + d_data->footerRect.setWidth( rect.width() + - dimAxes[QwtPlot::yLeft] - dimAxes[QwtPlot::yRight] ); + } } d_data->canvasRect.setRect( rect.x() + dimAxes[QwtPlot::yLeft], rect.y() + dimAxes[QwtPlot::xTop], rect.width() - dimAxes[QwtPlot::yRight] - dimAxes[QwtPlot::yLeft], - rect.height() - dimAxes[QwtPlot::xBottom] - dimAxes[QwtPlot::xTop]); + rect.height() - dimAxes[QwtPlot::xBottom] - dimAxes[QwtPlot::xTop] ); - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) { + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { // set the rects for the axes - if ( dimAxes[axis] ) { + if ( dimAxes[axis] ) + { int dim = dimAxes[axis]; - QRect &scaleRect = d_data->scaleRect[axis]; + QRectF &scaleRect = d_data->scaleRect[axis]; scaleRect = d_data->canvasRect; - switch(axis) { - case QwtPlot::yLeft: - scaleRect.setX(d_data->canvasRect.left() - dim); - scaleRect.setWidth(dim); - break; - case QwtPlot::yRight: - scaleRect.setX(d_data->canvasRect.right() + 1); - scaleRect.setWidth(dim); - break; - case QwtPlot::xBottom: - scaleRect.setY(d_data->canvasRect.bottom() + 1); - scaleRect.setHeight(dim); - break; - case QwtPlot::xTop: - scaleRect.setY(d_data->canvasRect.top() - dim); - scaleRect.setHeight(dim); - break; + switch ( axis ) + { + case QwtPlot::yLeft: + scaleRect.setX( d_data->canvasRect.left() - dim ); + scaleRect.setWidth( dim ); + break; + case QwtPlot::yRight: + scaleRect.setX( d_data->canvasRect.right() ); + scaleRect.setWidth( dim ); + break; + case QwtPlot::xBottom: + scaleRect.setY( d_data->canvasRect.bottom() ); + scaleRect.setHeight( dim ); + break; + case QwtPlot::xTop: + scaleRect.setY( d_data->canvasRect.top() - dim ); + scaleRect.setHeight( dim ); + break; } -#if QT_VERSION < 0x040000 - scaleRect = scaleRect.normalize(); -#else scaleRect = scaleRect.normalized(); -#endif } } @@ -1107,12 +1432,13 @@ void QwtPlotLayout::activate(const QwtPlot *plot, // corners to extend the axes, so that the label texts // left/right of the min/max ticks are moved into them. - alignScales(options, d_data->canvasRect, d_data->scaleRect); + alignScales( options, d_data->canvasRect, d_data->scaleRect ); - if (!d_data->legendRect.isEmpty() ) { + if ( !d_data->legendRect.isEmpty() ) + { // We prefer to align the legend to the canvas - not to // the complete plot - if possible. - d_data->legendRect = alignLegend(d_data->canvasRect, d_data->legendRect); + d_data->legendRect = alignLegend( d_data->canvasRect, d_data->legendRect ); } } diff --git a/libs/qwt/qwt_plot_layout.h b/libs/qwt/qwt_plot_layout.h index 0ade70c5ea..c72c04fc3f 100644 --- a/libs/qwt/qwt_plot_layout.h +++ b/libs/qwt/qwt_plot_layout.h @@ -14,69 +14,102 @@ #include "qwt_plot.h" /*! - \brief Layout class for QwtPlot. + \brief Layout engine for QwtPlot. - Organizes the geometry for the different QwtPlot components. + It is used by the QwtPlot widget to organize its internal widgets + or by QwtPlot::print() to render its content to a QPaintDevice like + a QPrinter, QPixmap/QImage or QSvgRenderer. + + \sa QwtPlot::setPlotLayout() */ class QWT_EXPORT QwtPlotLayout { public: - enum Options { - AlignScales = 1, - IgnoreScrollbars = 2, - IgnoreFrames = 4, - IgnoreMargin = 8, - IgnoreLegend = 16 + /*! + Options to configure the plot layout engine + \sa activate(), QwtPlotRenderer + */ + enum Option + { + //! Unused + AlignScales = 0x01, + + /*! + Ignore the dimension of the scrollbars. There are no + scrollbars, when the plot is not rendered to widgets. + */ + IgnoreScrollbars = 0x02, + + //! Ignore all frames. + IgnoreFrames = 0x04, + + //! Ignore the legend. + IgnoreLegend = 0x08, + + //! Ignore the title. + IgnoreTitle = 0x10, + + //! Ignore the footer. + IgnoreFooter = 0x20 }; + //! Layout options + typedef QFlags<Option> Options; + explicit QwtPlotLayout(); virtual ~QwtPlotLayout(); - void setMargin(int); - int margin() const; + void setCanvasMargin( int margin, int axis = -1 ); + int canvasMargin( int axis ) const; - void setCanvasMargin(int margin, int axis = -1); - int canvasMargin(int axis) const; + void setAlignCanvasToScales( bool ); - void setAlignCanvasToScales(bool); - bool alignCanvasToScales() const; + void setAlignCanvasToScale( int axisId, bool ); + bool alignCanvasToScale( int axisId ) const; - void setSpacing(int); + void setSpacing( int ); int spacing() const; - void setLegendPosition(QwtPlot::LegendPosition pos, double ratio); - void setLegendPosition(QwtPlot::LegendPosition pos); + void setLegendPosition( QwtPlot::LegendPosition pos, double ratio ); + void setLegendPosition( QwtPlot::LegendPosition pos ); QwtPlot::LegendPosition legendPosition() const; - void setLegendRatio(double ratio); + void setLegendRatio( double ratio ); double legendRatio() const; - virtual QSize minimumSizeHint(const QwtPlot *) const; + virtual QSize minimumSizeHint( const QwtPlot * ) const; - virtual void activate(const QwtPlot *, - const QRect &rect, int options = 0); + virtual void activate( const QwtPlot *, + const QRectF &rect, Options options = 0x00 ); virtual void invalidate(); - const QRect &titleRect() const; - const QRect &legendRect() const; - const QRect &scaleRect(int axis) const; - const QRect &canvasRect() const; + QRectF titleRect() const; + QRectF footerRect() const; + QRectF legendRect() const; + QRectF scaleRect( int axis ) const; + QRectF canvasRect() const; class LayoutData; protected: - QRect layoutLegend(int options, const QRect &) const; - QRect alignLegend(const QRect &canvasRect, - const QRect &legendRect) const; + void setTitleRect( const QRectF & ); + void setFooterRect( const QRectF & ); + void setLegendRect( const QRectF & ); + void setScaleRect( int axis, const QRectF & ); + void setCanvasRect( const QRectF & ); - void expandLineBreaks(int options, const QRect &rect, - int &dimTitle, int dimAxes[QwtPlot::axisCnt]) const; + QRectF layoutLegend( Options options, const QRectF & ) const; + QRectF alignLegend( const QRectF &canvasRect, + const QRectF &legendRect ) const; - void alignScales(int options, QRect &canvasRect, - QRect scaleRect[QwtPlot::axisCnt]) const; + void expandLineBreaks( Options options, const QRectF &rect, + int &dimTitle, int &dimFooter, int dimAxes[QwtPlot::axisCnt] ) const; + + void alignScales( Options options, QRectF &canvasRect, + QRectF scaleRect[QwtPlot::axisCnt] ) const; private: class PrivateData; @@ -84,4 +117,6 @@ private: PrivateData *d_data; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotLayout::Options ) + #endif diff --git a/libs/qwt/qwt_plot_legenditem.cpp b/libs/qwt/qwt_plot_legenditem.cpp new file mode 100644 index 0000000000..5bb8e4c12d --- /dev/null +++ b/libs/qwt/qwt_plot_legenditem.cpp @@ -0,0 +1,865 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_legenditem.h" +#include "qwt_dyngrid_layout.h" +#include "qwt_scale_map.h" +#include "qwt_painter.h" +#include <qlayoutitem.h> +#include <qpen.h> +#include <qbrush.h> +#include <qpainter.h> +#include <qmath.h> + +class QwtLegendLayoutItem: public QLayoutItem +{ +public: + QwtLegendLayoutItem( const QwtPlotLegendItem *, const QwtPlotItem * ); + virtual ~QwtLegendLayoutItem(); + + const QwtPlotItem *plotItem() const; + + void setData( const QwtLegendData & ); + const QwtLegendData &data() const; + + virtual Qt::Orientations expandingDirections() const; + virtual QRect geometry() const; + virtual bool hasHeightForWidth() const; + virtual int heightForWidth( int w ) const; + virtual bool isEmpty() const; + virtual QSize maximumSize() const; + virtual int minimumHeightForWidth( int w ) const; + virtual QSize minimumSize() const; + virtual void setGeometry( const QRect & r ); + virtual QSize sizeHint() const; + +private: + + const QwtPlotLegendItem *d_legendItem; + const QwtPlotItem *d_plotItem; + QwtLegendData d_data; + + QRect d_rect; +}; + +QwtLegendLayoutItem::QwtLegendLayoutItem( + const QwtPlotLegendItem *legendItem, const QwtPlotItem *plotItem ): + d_legendItem( legendItem ), + d_plotItem( plotItem) +{ +} + +QwtLegendLayoutItem::~QwtLegendLayoutItem() +{ +} + +const QwtPlotItem *QwtLegendLayoutItem::plotItem() const +{ + return d_plotItem; +} + +void QwtLegendLayoutItem::setData( const QwtLegendData &data ) +{ + d_data = data; +} + +const QwtLegendData &QwtLegendLayoutItem::data() const +{ + return d_data; +} + +Qt::Orientations QwtLegendLayoutItem::expandingDirections() const +{ + return Qt::Horizontal; +} + +bool QwtLegendLayoutItem::hasHeightForWidth() const +{ + return !d_data.title().isEmpty(); +} + +int QwtLegendLayoutItem::minimumHeightForWidth( int w ) const +{ + return d_legendItem->heightForWidth( d_data, w ); +} + +int QwtLegendLayoutItem::heightForWidth( int w ) const +{ + return d_legendItem->heightForWidth( d_data, w ); +} + +bool QwtLegendLayoutItem::isEmpty() const +{ + return false; +} + +QSize QwtLegendLayoutItem::maximumSize() const +{ + return QSize( QLAYOUTSIZE_MAX, QLAYOUTSIZE_MAX ); +} + +QSize QwtLegendLayoutItem::minimumSize() const +{ + return d_legendItem->minimumSize( d_data ); +} + +QSize QwtLegendLayoutItem::sizeHint() const +{ + return minimumSize(); +} + +void QwtLegendLayoutItem::setGeometry( const QRect &rect ) +{ + d_rect = rect; +} + +QRect QwtLegendLayoutItem::geometry() const +{ + return d_rect; +} + +class QwtPlotLegendItem::PrivateData +{ +public: + PrivateData(): + itemMargin( 4 ), + itemSpacing( 4 ), + borderRadius( 0.0 ), + borderPen( Qt::NoPen ), + backgroundBrush( Qt::NoBrush ), + backgroundMode( QwtPlotLegendItem::LegendBackground ), + borderDistance( 10 ), + alignment( Qt::AlignRight | Qt::AlignBottom ) + { + layout = new QwtDynGridLayout(); + layout->setMaxColumns( 2 ); + + layout->setSpacing( 0 ); + layout->setContentsMargins( 0, 0, 0, 0 ); + } + + ~PrivateData() + { + delete layout; + } + + QFont font; + QPen textPen; + int itemMargin; + int itemSpacing; + + double borderRadius; + QPen borderPen; + QBrush backgroundBrush; + QwtPlotLegendItem::BackgroundMode backgroundMode; + + int borderDistance; + Qt::Alignment alignment; + + QMap< const QwtPlotItem *, QList<QwtLegendLayoutItem *> > map; + QwtDynGridLayout *layout; +}; + +//! Constructor +QwtPlotLegendItem::QwtPlotLegendItem(): + QwtPlotItem( QwtText( "Legend" ) ) +{ + d_data = new PrivateData; + + setItemInterest( QwtPlotItem::LegendInterest, true ); + setZ( 100.0 ); +} + +//! Destructor +QwtPlotLegendItem::~QwtPlotLegendItem() +{ + clearLegend(); + delete d_data; +} + +//! \return QwtPlotItem::Rtti_PlotLegend +int QwtPlotLegendItem::rtti() const +{ + return QwtPlotItem::Rtti_PlotLegend; +} + +/*! + \brief Set the alignmnet + + Alignment means the position of the legend relative + to the geometry of the plot canvas. + + \param alignment Alignment flags + + \sa alignment(), setMaxColumns() + + \note To align a legend with many items horizontally + the number of columns need to be limited + */ +void QwtPlotLegendItem::setAlignment( Qt::Alignment alignment ) +{ + if ( d_data->alignment != alignment ) + { + d_data->alignment = alignment; + itemChanged(); + } +} + +/*! + \return Alignment flags + \sa setAlignment() + */ +Qt::Alignment QwtPlotLegendItem::alignment() const +{ + return d_data->alignment; +} + +/*! + \brief Limit the number of columns + + When aligning the legend horizontally ( Qt::AlignLeft, Qt::AlignRight ) + the number of columns needs to be limited to avoid, that + the width of the legend grows with an increasing number of entries. + + \param maxColumns Maximum number of columns. 0 means unlimited. + \sa maxColumns(), QwtDynGridLayout::setMaxColumns() + */ +void QwtPlotLegendItem::setMaxColumns( uint maxColumns ) +{ + if ( maxColumns != d_data->layout->maxColumns() ) + { + d_data->layout->setMaxColumns( maxColumns ); + itemChanged(); + } +} + +/*! + \return Maximum number of columns + \sa maxColumns(), QwtDynGridLayout::maxColumns() + */ +uint QwtPlotLegendItem::maxColumns() const +{ + return d_data->layout->maxColumns(); +} + +/*! + \brief Set the margin around legend items + + The default setting for the margin is 0. + + \param margin Margin in pixels + \sa margin(), setSpacing(), setItemMargin(), setItemSpacing + */ +void QwtPlotLegendItem::setMargin( int margin ) +{ + margin = qMax( margin, 0 ); + if ( margin != this->margin() ) + { + d_data->layout->setContentsMargins( + margin, margin, margin, margin ); + + itemChanged(); + } +} + +/*! + \return Margin around the legend items + \sa setMargin(), spacing(), itemMargin(), itemSpacing() + */ +int QwtPlotLegendItem::margin() const +{ + int left; + d_data->layout->getContentsMargins( &left, NULL, NULL, NULL ); + + return left; +} + +/*! + \brief Set the spacing between the legend items + + \param spacing Spacing in pixels + \sa spacing(), setMargin() +*/ +void QwtPlotLegendItem::setSpacing( int spacing ) +{ + spacing = qMax( spacing, 0 ); + if ( spacing != d_data->layout->spacing() ) + { + d_data->layout->setSpacing( spacing ); + itemChanged(); + } +} + +/*! + \return Spacing between the legend items + \sa setSpacing(), margin(), itemSpacing(), itemMargin() + */ +int QwtPlotLegendItem::spacing() const +{ + return d_data->layout->spacing(); +} + +/*! + Set the margin around each item + + \param margin Margin + \sa itemMargin(), setItemSpacing(), setMargin(), setSpacing() + */ +void QwtPlotLegendItem::setItemMargin( int margin ) +{ + margin = qMax( margin, 0 ); + if ( margin != d_data->itemMargin ) + { + d_data->itemMargin = margin; + + d_data->layout->invalidate(); + itemChanged(); + } +} + +/*! + \return Margin around each item + \sa setItemMargin(), itemSpacing(), margin(), spacing() +*/ +int QwtPlotLegendItem::itemMargin() const +{ + return d_data->itemMargin; +} + +/*! + Set the spacing inside of each item + + \param spacing Spacing + \sa itemSpacing(), setItemMargin(), setMargin(), setSpacing() + */ +void QwtPlotLegendItem::setItemSpacing( int spacing ) +{ + spacing = qMax( spacing, 0 ); + if ( spacing != d_data->itemSpacing ) + { + d_data->itemSpacing = spacing; + + d_data->layout->invalidate(); + itemChanged(); + } + +} + +/*! + \return Spacing inside of each item + \sa setItemSpacing(), itemMargin(), margin(), spacing() +*/ +int QwtPlotLegendItem::itemSpacing() const +{ + return d_data->itemSpacing; +} + +/*! + Change the font used for drawing the text label + + \param font Legend font + \sa font() +*/ +void QwtPlotLegendItem::setFont( const QFont &font ) +{ + if ( font != d_data->font ) + { + d_data->font = font; + + d_data->layout->invalidate(); + itemChanged(); + } +} + +/*! + \return Font used for drawing the text label + \sa setFont() +*/ +QFont QwtPlotLegendItem::font() const +{ + return d_data->font; +} + +/*! + \brief Set the margin between the legend and the canvas border + + The default setting for the margin is 10 pixels. + + \param distance Margin in pixels + \sa setMargin() + */ +void QwtPlotLegendItem::setBorderDistance( int distance ) +{ + if ( distance < 0 ) + distance = -1; + + if ( distance != d_data->borderDistance ) + { + d_data->borderDistance = distance; + itemChanged(); + } +} + +/*! + \return Margin between the legend and the canvas border + \sa margin() + */ +int QwtPlotLegendItem::borderDistance() const +{ + return d_data->borderDistance; +} + +/*! + Set the radius for the border + + \param radius A value <= 0 defines a rectangular border + \sa borderRadius(), setBorderPen() + */ +void QwtPlotLegendItem::setBorderRadius( double radius ) +{ + radius = qMax( 0.0, radius ); + + if ( radius != d_data->borderRadius ) + { + d_data->borderRadius = radius; + itemChanged(); + } +} + +/*! + \return Radius of the border + \sa setBorderRadius(), setBorderPen() + */ +double QwtPlotLegendItem::borderRadius() const +{ + return d_data->borderRadius; +} + +/*! + Set the pen for drawing the border + + \param pen Border pen + \sa borderPen(), setBackgroundBrush() + */ +void QwtPlotLegendItem::setBorderPen( const QPen &pen ) +{ + if ( d_data->borderPen != pen ) + { + d_data->borderPen = pen; + itemChanged(); + } +} + +/*! + \return Pen for drawing the border + \sa setBorderPen(), backgroundBrush() + */ +QPen QwtPlotLegendItem::borderPen() const +{ + return d_data->borderPen; +} + +/*! + \brief Set the background brush + + The brush is used to fill the background + + \param brush Brush + \sa backgroundBrush(), setBackgroundMode(), drawBackground() + */ +void QwtPlotLegendItem::setBackgroundBrush( const QBrush &brush ) +{ + if ( d_data->backgroundBrush != brush ) + { + d_data->backgroundBrush = brush; + itemChanged(); + } +} + +/*! + \return Brush is used to fill the background + \sa setBackgroundBrush(), backgroundMode(), drawBackground() + */ +QBrush QwtPlotLegendItem::backgroundBrush() const +{ + return d_data->backgroundBrush; +} + +/*! + \brief Set the background mode + + Depending on the mode the complete legend or each item + might have an background. + + The default setting is LegendBackground. + + \sa backgroundMode(), setBackgroundBrush(), drawBackground() + */ +void QwtPlotLegendItem::setBackgroundMode( BackgroundMode mode ) +{ + if ( mode != d_data->backgroundMode ) + { + d_data->backgroundMode = mode; + itemChanged(); + } +} + +/*! + \return backgroundMode + \sa setBackgroundMode(), backgroundBrush(), drawBackground() + */ +QwtPlotLegendItem::BackgroundMode QwtPlotLegendItem::backgroundMode() const +{ + return d_data->backgroundMode; +} + +/*! + \brief Set the pen for drawing text labels + + \param pen Text pen + \sa textPen(), setFont() + */ +void QwtPlotLegendItem::setTextPen( const QPen &pen ) +{ + if ( d_data->textPen != pen ) + { + d_data->textPen = pen; + itemChanged(); + } +} + +/*! + \return Pen for drawing text labels + \sa setTextPen(), font() + */ +QPen QwtPlotLegendItem::textPen() const +{ + return d_data->textPen; +} + +/*! + Draw the legend + + \param painter Painter + \param xMap x Scale Map + \param yMap y Scale Map + \param canvasRect Contents rectangle of the canvas in painter coordinates +*/ +void QwtPlotLegendItem::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const +{ + Q_UNUSED( xMap ); + Q_UNUSED( yMap ); + + d_data->layout->setGeometry( geometry( canvasRect ) ); + + if ( d_data->backgroundMode == QwtPlotLegendItem::LegendBackground ) + drawBackground( painter, d_data->layout->geometry() ); + + for ( int i = 0; i < d_data->layout->count(); i++ ) + { + const QwtLegendLayoutItem *layoutItem = + static_cast<QwtLegendLayoutItem *>( d_data->layout->itemAt( i ) ); + + if ( d_data->backgroundMode == QwtPlotLegendItem::ItemBackground ) + drawBackground( painter, layoutItem->geometry() ); + + painter->save(); + + drawLegendData( painter, layoutItem->plotItem(), + layoutItem->data(), layoutItem->geometry() ); + + painter->restore(); + } +} + +/*! + Draw a rounded rect + + \param painter Painter + \param rect Bounding rectangle + + \sa setBorderRadius(), setBorderPen(), + setBackgroundBrush(), setBackgroundMode() + */ +void QwtPlotLegendItem::drawBackground( + QPainter *painter, const QRectF &rect ) const +{ + painter->save(); + + painter->setPen( d_data->borderPen ); + painter->setBrush( d_data->backgroundBrush ); + + const double radius = d_data->borderRadius; + painter->drawRoundedRect( rect, radius, radius ); + + painter->restore(); +} + +/*! + Calculate the geometry of the legend on the canvas + + \param canvasRect Geometry of the canvas + \return Geometry of the legend +*/ +QRect QwtPlotLegendItem::geometry( const QRectF &canvasRect ) const +{ + QRect rect; + rect.setSize( d_data->layout->sizeHint() ); + + int margin = d_data->borderDistance; + if ( d_data->alignment & Qt::AlignHCenter ) + { + int x = qRound( canvasRect.center().x() ); + rect.moveCenter( QPoint( x, rect.center().y() ) ); + } + else if ( d_data->alignment & Qt::AlignRight ) + { + rect.moveRight( qFloor( canvasRect.right() - margin ) ); + } + else + { + rect.moveLeft( qCeil( canvasRect.left() + margin ) ); + } + + if ( d_data->alignment & Qt::AlignVCenter ) + { + int y = qRound( canvasRect.center().y() ); + rect.moveCenter( QPoint( rect.center().x(), y ) ); + } + else if ( d_data->alignment & Qt::AlignBottom ) + { + rect.moveBottom( qFloor( canvasRect.bottom() - margin ) ); + } + else + { + rect.moveTop( qCeil( canvasRect.top() + margin ) ); + } + + return rect; +} + +/*! + Update the legend items according to modifications of a + plot item + + \param plotItem Plot item + \param data Attributes of the legend entries + */ +void QwtPlotLegendItem::updateLegend( const QwtPlotItem *plotItem, + const QList<QwtLegendData> &data ) +{ + if ( plotItem == NULL ) + return; + + QList<QwtLegendLayoutItem *> layoutItems; + + QMap<const QwtPlotItem *, QList<QwtLegendLayoutItem *> >::iterator it = + d_data->map.find( plotItem ); + if ( it != d_data->map.end() ) + layoutItems = it.value(); + + bool changed = false; + + if ( data.size() != layoutItems.size() ) + { + changed = true; + + for ( int i = 0; i < layoutItems.size(); i++ ) + { + d_data->layout->removeItem( layoutItems[i] ); + delete layoutItems[i]; + } + if ( it != d_data->map.end() ) + d_data->map.remove( plotItem ); + + if ( !data.isEmpty() ) + { + for ( int i = 0; i < data.size(); i++ ) + { + QwtLegendLayoutItem *layoutItem = + new QwtLegendLayoutItem( this, plotItem ); + d_data->layout->addItem( layoutItem ); + layoutItems += layoutItem; + } + + d_data->map.insert( plotItem, layoutItems ); + } + } + + for ( int i = 0; i < data.size(); i++ ) + { + if ( layoutItems[i]->data().values() != data[i].values() ) + { + layoutItems[i]->setData( data[i] ); + changed = true; + } + } + + if ( changed ) + { + d_data->layout->invalidate(); + itemChanged(); + } +} + +//! Remove all items from the legend +void QwtPlotLegendItem::clearLegend() +{ + if ( !d_data->map.isEmpty() ) + { + d_data->map.clear(); + + for ( int i = d_data->layout->count() - 1; i >= 0; i-- ) + delete d_data->layout->takeAt( i ); + + itemChanged(); + } +} + +/*! + Draw an entry on the legend + + \param painter Qt Painter + \param plotItem Plot item, represented by the entry + \param data Attributes of the legend entry + \param rect Bounding rectangle for the entry + */ +void QwtPlotLegendItem::drawLegendData( QPainter *painter, + const QwtPlotItem *plotItem, const QwtLegendData &data, + const QRectF &rect ) const +{ + Q_UNUSED( plotItem ); + + const int m = d_data->itemMargin; + const QRectF r = rect.toRect().adjusted( m, m, -m, -m ); + + painter->setClipRect( r, Qt::IntersectClip ); + + int titleOff = 0; + + const QwtGraphic graphic = data.icon(); + if ( !graphic.isEmpty() ) + { + QRectF iconRect( r.topLeft(), graphic.defaultSize() ); + + iconRect.moveCenter( + QPoint( iconRect.center().x(), rect.center().y() ) ); + + graphic.render( painter, iconRect, Qt::KeepAspectRatio ); + + titleOff += iconRect.width() + d_data->itemSpacing; + } + + const QwtText text = data.title(); + if ( !text.isEmpty() ) + { + painter->setPen( textPen() ); + painter->setFont( font() ); + + const QRectF textRect = r.adjusted( titleOff, 0, 0, 0 ); + text.draw( painter, textRect ); + } +} + +/*! + Minimum size hint needed to display an entry + + \param data Attributes of the legend entry + \return Minimum size + */ +QSize QwtPlotLegendItem::minimumSize( const QwtLegendData &data ) const +{ + QSize size( 2 * d_data->itemMargin, 2 * d_data->itemMargin ); + + if ( !data.isValid() ) + return size; + + const QwtGraphic graphic = data.icon(); + const QwtText text = data.title(); + + int w = 0; + int h = 0; + + if ( !graphic.isNull() ) + { + w = graphic.width(); + h = graphic.height(); + } + + if ( !text.isEmpty() ) + { + const QSizeF sz = text.textSize( font() ); + + w += qCeil( sz.width() ); + h = qMax( h, qCeil( sz.height() ) ); + } + + if ( graphic.width() > 0 && !text.isEmpty() ) + w += d_data->itemSpacing; + + size += QSize( w, h ); + return size; +} + +/*! + \return The preferred height, for a width. + \param data Attributes of the legend entry + \param width Width +*/ +int QwtPlotLegendItem::heightForWidth( + const QwtLegendData &data, int width ) const +{ + width -= 2 * d_data->itemMargin; + + const QwtGraphic graphic = data.icon(); + const QwtText text = data.title(); + + if ( text.isEmpty() ) + return graphic.height(); + + if ( graphic.width() > 0 ) + width -= graphic.width() + d_data->itemSpacing; + + int h = text.heightForWidth( width, font() ); + h += 2 * d_data->itemMargin; + + return qMax( graphic.height(), h ); +} + +/*! + \return All plot items with an entry on the legend + \note A plot item might have more than one entry on the legend + */ +QList< const QwtPlotItem * > QwtPlotLegendItem::plotItems() const +{ + return d_data->map.keys(); +} + +/*! + \return Geometries of the items of a plot item + \note Usually a plot item has only one entry on the legend +*/ +QList< QRect > QwtPlotLegendItem::legendGeometries( + const QwtPlotItem *plotItem ) const +{ + QList<QwtLegendLayoutItem *> layoutItems; + + QMap<const QwtPlotItem *, QList<QwtLegendLayoutItem *> >::iterator it = + d_data->map.find( plotItem ); + if ( it != d_data->map.end() ) + layoutItems = it.value(); + + QList<QRect> geometries; + for ( int i = 0; i < layoutItems.size(); i++ ) + geometries += layoutItems[i]->geometry(); + + return geometries; +} diff --git a/libs/qwt/qwt_plot_legenditem.h b/libs/qwt/qwt_plot_legenditem.h new file mode 100644 index 0000000000..378551e1f8 --- /dev/null +++ b/libs/qwt/qwt_plot_legenditem.h @@ -0,0 +1,136 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_LEGEND_ITEM_H +#define QWT_PLOT_LEGEND_ITEM_H + +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include "qwt_legend_data.h" + +class QFont; + +/*! + \brief A class which draws a legend inside the plot canvas + + QwtPlotLegendItem can be used to draw a inside the plot canvas. + It can be used together with a QwtLegend or instead of it + to have more space for the plot canvas. + + In opposite to QwtLegend the legend item is not interactive. + To identify mouse clicks on a legend item an event filter + needs to be installed catching mouse events ob the plot canvas. + The geometries of the legend items are available using + legendGeometries(). + + The legend item is aligned to plot canvas according to + its alignment() flags. It might have a background for the + complete legend ( usually semi transparent ) or for + each legend item. + + \note An external QwtLegend with a transparent background + on top the plot canvas might be another option + with a similar effect. +*/ + +class QWT_EXPORT QwtPlotLegendItem: public QwtPlotItem +{ +public: + /*! + \brief Background mode + + Depending on the mode the complete legend or each item + might have an background. + + The default setting is LegendBackground. + + \sa setBackgroundMode(), setBackgroundBrush(), drawBackground() + */ + enum BackgroundMode + { + //! The legend has a background + LegendBackground, + + //! Each item has a background + ItemBackground + }; + + explicit QwtPlotLegendItem(); + virtual ~QwtPlotLegendItem(); + + virtual int rtti() const; + + void setAlignment( Qt::Alignment ); + Qt::Alignment alignment() const; + + void setMaxColumns( uint ); + uint maxColumns() const; + + void setMargin( int ); + int margin() const; + + void setSpacing( int ); + int spacing() const; + + void setItemMargin( int ); + int itemMargin() const; + + void setItemSpacing( int ); + int itemSpacing() const; + + void setFont( const QFont& ); + QFont font() const; + + void setBorderDistance( int numPixels ); + int borderDistance() const; + + void setBorderRadius( double ); + double borderRadius() const; + + void setBorderPen( const QPen & ); + QPen borderPen() const; + + void setBackgroundBrush( const QBrush & ); + QBrush backgroundBrush() const; + + void setBackgroundMode( BackgroundMode ); + BackgroundMode backgroundMode() const; + + void setTextPen( const QPen & ); + QPen textPen() const; + + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; + + void clearLegend(); + + virtual void updateLegend( const QwtPlotItem *, + const QList<QwtLegendData> & ); + + virtual QRect geometry( const QRectF &canvasRect ) const; + + virtual QSize minimumSize( const QwtLegendData & ) const; + virtual int heightForWidth( const QwtLegendData &, int w ) const; + + QList< const QwtPlotItem * > plotItems() const; + QList< QRect > legendGeometries( const QwtPlotItem * ) const; + +protected: + virtual void drawLegendData( QPainter *painter, + const QwtPlotItem *, const QwtLegendData &, const QRectF & ) const; + + virtual void drawBackground( QPainter *, const QRectF &rect ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_magnifier.cpp b/libs/qwt/qwt_plot_magnifier.cpp index e13a441658..43a6b9a3b4 100644 --- a/libs/qwt/qwt_plot_magnifier.cpp +++ b/libs/qwt/qwt_plot_magnifier.cpp @@ -7,19 +7,16 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <math.h> -#include <qevent.h> #include "qwt_plot.h" -#include "qwt_plot_canvas.h" #include "qwt_scale_div.h" #include "qwt_plot_magnifier.h" +#include <qevent.h> class QwtPlotMagnifier::PrivateData { public: - PrivateData() { + PrivateData() + { for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) isAxisEnabled[axis] = true; } @@ -31,8 +28,8 @@ public: Constructor \param canvas Plot canvas to be magnified */ -QwtPlotMagnifier::QwtPlotMagnifier(QwtPlotCanvas *canvas): - QwtMagnifier(canvas) +QwtPlotMagnifier::QwtPlotMagnifier( QWidget *canvas ): + QwtMagnifier( canvas ) { d_data = new PrivateData(); } @@ -46,15 +43,15 @@ QwtPlotMagnifier::~QwtPlotMagnifier() /*! \brief En/Disable an axis - Axes that are enabled will be synchronized to the - result of panning. All other axes will remain unchanged. + Only Axes that are enabled will be zoomed. + All other axes will remain unchanged. \param axis Axis, see QwtPlot::Axis \param on On/Off - \sa isAxisEnabled + \sa isAxisEnabled() */ -void QwtPlotMagnifier::setAxisEnabled(int axis, bool on) +void QwtPlotMagnifier::setAxisEnabled( int axis, bool on ) { if ( axis >= 0 && axis < QwtPlot::axisCnt ) d_data->isAxisEnabled[axis] = on; @@ -66,9 +63,9 @@ void QwtPlotMagnifier::setAxisEnabled(int axis, bool on) \param axis Axis, see QwtPlot::Axis \return True, if the axis is enabled - \sa setAxisEnabled + \sa setAxisEnabled() */ -bool QwtPlotMagnifier::isAxisEnabled(int axis) const +bool QwtPlotMagnifier::isAxisEnabled( int axis ) const { if ( axis >= 0 && axis < QwtPlot::axisCnt ) return d_data->isAxisEnabled[axis]; @@ -77,69 +74,71 @@ bool QwtPlotMagnifier::isAxisEnabled(int axis) const } //! Return observed plot canvas -QwtPlotCanvas *QwtPlotMagnifier::canvas() +QWidget *QwtPlotMagnifier::canvas() { - QObject *w = parent(); - if ( w && w->inherits("QwtPlotCanvas") ) - return (QwtPlotCanvas *)w; - - return NULL; + return parentWidget(); } //! Return Observed plot canvas -const QwtPlotCanvas *QwtPlotMagnifier::canvas() const +const QWidget *QwtPlotMagnifier::canvas() const { - return ((QwtPlotMagnifier *)this)->canvas(); + return parentWidget(); } //! Return plot widget, containing the observed plot canvas QwtPlot *QwtPlotMagnifier::plot() { - QObject *w = canvas(); - if ( w ) { - w = w->parent(); - if ( w && w->inherits("QwtPlot") ) - return (QwtPlot *)w; - } + QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); - return NULL; + return qobject_cast<QwtPlot *>( w ); } //! Return plot widget, containing the observed plot canvas const QwtPlot *QwtPlotMagnifier::plot() const { - return ((QwtPlotMagnifier *)this)->plot(); + const QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); + + return qobject_cast<const QwtPlot *>( w ); } /*! Zoom in/out the axes scales \param factor A value < 1.0 zooms in, a value > 1.0 zooms out. */ -void QwtPlotMagnifier::rescale(double factor) +void QwtPlotMagnifier::rescale( double factor ) { - factor = qwtAbs(factor); + QwtPlot* plt = plot(); + if ( plt == NULL ) + return; + + factor = qAbs( factor ); if ( factor == 1.0 || factor == 0.0 ) return; bool doReplot = false; - QwtPlot* plt = plot(); const bool autoReplot = plt->autoReplot(); - plt->setAutoReplot(false); + plt->setAutoReplot( false ); - for ( int axisId = 0; axisId < QwtPlot::axisCnt; axisId++ ) { - const QwtScaleDiv *scaleDiv = plt->axisScaleDiv(axisId); - if ( isAxisEnabled(axisId) && scaleDiv->isValid() ) { + for ( int axisId = 0; axisId < QwtPlot::axisCnt; axisId++ ) + { + const QwtScaleDiv &scaleDiv = plt->axisScaleDiv( axisId ); + if ( isAxisEnabled( axisId ) ) + { const double center = - scaleDiv->lBound() + scaleDiv->range() / 2; - const double width_2 = scaleDiv->range() / 2 * factor; + scaleDiv.lowerBound() + scaleDiv.range() / 2; + const double width_2 = scaleDiv.range() / 2 * factor; - plt->setAxisScale(axisId, center - width_2, center + width_2); + plt->setAxisScale( axisId, center - width_2, center + width_2 ); doReplot = true; } } - plt->setAutoReplot(autoReplot); + plt->setAutoReplot( autoReplot ); if ( doReplot ) plt->replot(); diff --git a/libs/qwt/qwt_plot_magnifier.h b/libs/qwt/qwt_plot_magnifier.h index 05f2afa612..7bce3fa9af 100644 --- a/libs/qwt/qwt_plot_magnifier.h +++ b/libs/qwt/qwt_plot_magnifier.h @@ -13,7 +13,6 @@ #include "qwt_global.h" #include "qwt_magnifier.h" -class QwtPlotCanvas; class QwtPlot; /*! @@ -32,20 +31,20 @@ class QWT_EXPORT QwtPlotMagnifier: public QwtMagnifier Q_OBJECT public: - explicit QwtPlotMagnifier(QwtPlotCanvas *); + explicit QwtPlotMagnifier( QWidget * ); virtual ~QwtPlotMagnifier(); - void setAxisEnabled(int axis, bool on); - bool isAxisEnabled(int axis) const; + void setAxisEnabled( int axis, bool on ); + bool isAxisEnabled( int axis ) const; - QwtPlotCanvas *canvas(); - const QwtPlotCanvas *canvas() const; + QWidget *canvas(); + const QWidget *canvas() const; QwtPlot *plot(); const QwtPlot *plot() const; protected: - virtual void rescale(double factor); + virtual void rescale( double factor ); private: class PrivateData; diff --git a/libs/qwt/qwt_plot_marker.cpp b/libs/qwt/qwt_plot_marker.cpp index ea39ccdf81..d88debfcde 100644 --- a/libs/qwt/qwt_plot_marker.cpp +++ b/libs/qwt/qwt_plot_marker.cpp @@ -7,53 +7,60 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <qpainter.h> +#include "qwt_plot_marker.h" #include "qwt_painter.h" #include "qwt_scale_map.h" -#include "qwt_plot_marker.h" #include "qwt_symbol.h" #include "qwt_text.h" #include "qwt_math.h" - -static const int LabelDist = 2; +#include <qpainter.h> class QwtPlotMarker::PrivateData { public: PrivateData(): - align(Qt::AlignCenter), - style(NoLine), - xValue(0.0), - yValue(0.0) { - symbol = new QwtSymbol(); + labelAlignment( Qt::AlignCenter ), + labelOrientation( Qt::Horizontal ), + spacing( 2 ), + symbol( NULL ), + style( QwtPlotMarker::NoLine ), + xValue( 0.0 ), + yValue( 0.0 ) + { } - ~PrivateData() { + ~PrivateData() + { delete symbol; } QwtText label; -#if QT_VERSION < 0x040000 - int align; -#else - Qt::Alignment align; -#endif + Qt::Alignment labelAlignment; + Qt::Orientation labelOrientation; + int spacing; + QPen pen; - QwtSymbol *symbol; + const QwtSymbol *symbol; LineStyle style; double xValue; double yValue; }; -//! Sets alignment to Qt::AlignCenter, and style to NoLine -QwtPlotMarker::QwtPlotMarker(): - QwtPlotItem(QwtText("Marker")) +//! Sets alignment to Qt::AlignCenter, and style to QwtPlotMarker::NoLine +QwtPlotMarker::QwtPlotMarker( const QString &title ): + QwtPlotItem( QwtText( title ) ) { d_data = new PrivateData; - setZ(30.0); + setZ( 30.0 ); +} + +//! Sets alignment to Qt::AlignCenter, and style to QwtPlotMarker::NoLine +QwtPlotMarker::QwtPlotMarker( const QwtText &title ): + QwtPlotItem( title ) +{ + d_data = new PrivateData; + setZ( 30.0 ); } //! Destructor @@ -69,9 +76,9 @@ int QwtPlotMarker::rtti() const } //! Return Value -QwtDoublePoint QwtPlotMarker::value() const +QPointF QwtPlotMarker::value() const { - return QwtDoublePoint(d_data->xValue, d_data->yValue); + return QPointF( d_data->xValue, d_data->yValue ); } //! Return x Value @@ -87,15 +94,16 @@ double QwtPlotMarker::yValue() const } //! Set Value -void QwtPlotMarker::setValue(const QwtDoublePoint& pos) +void QwtPlotMarker::setValue( const QPointF& pos ) { - setValue(pos.x(), pos.y()); + setValue( pos.x(), pos.y() ); } //! Set Value -void QwtPlotMarker::setValue(double x, double y) +void QwtPlotMarker::setValue( double x, double y ) { - if ( x != d_data->xValue || y != d_data->yValue ) { + if ( x != d_data->xValue || y != d_data->yValue ) + { d_data->xValue = x; d_data->yValue = y; itemChanged(); @@ -103,132 +111,249 @@ void QwtPlotMarker::setValue(double x, double y) } //! Set X Value -void QwtPlotMarker::setXValue(double x) +void QwtPlotMarker::setXValue( double x ) { - setValue(x, d_data->yValue); + setValue( x, d_data->yValue ); } //! Set Y Value -void QwtPlotMarker::setYValue(double y) +void QwtPlotMarker::setYValue( double y ) { - setValue(d_data->xValue, y); + setValue( d_data->xValue, y ); } /*! - \brief Draw the marker - \param p Painter + Draw the marker + + \param painter Painter \param xMap x Scale Map \param yMap y Scale Map - \param r Bounding rect, where to paint + \param canvasRect Contents rectangle of the canvas in painter coordinates */ -void QwtPlotMarker::draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &r) const +void QwtPlotMarker::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const { - const int x = xMap.transform(d_data->xValue); - const int y = yMap.transform(d_data->yValue); + const QPointF pos( xMap.transform( d_data->xValue ), + yMap.transform( d_data->yValue ) ); // draw lines - if (d_data->style != NoLine) { - p->setPen(d_data->pen); - if ((d_data->style == HLine) || (d_data->style == Cross)) - QwtPainter::drawLine(p, r.left(), y, r.right(), y); - if ((d_data->style == VLine)||(d_data->style == Cross)) - QwtPainter::drawLine(p, x, r.top(), x, r.bottom()); - } + + drawLines( painter, canvasRect, pos ); // draw symbol - QSize sSym(0, 0); - if (d_data->symbol->style() != QwtSymbol::NoSymbol) { - sSym = d_data->symbol->size(); - d_data->symbol->draw(p, x, y); + if ( d_data->symbol && + ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) + { + const QSizeF sz = d_data->symbol->size(); + + const QRectF clipRect = canvasRect.adjusted( + -sz.width(), -sz.height(), sz.width(), sz.height() ); + + if ( clipRect.contains( pos ) ) + d_data->symbol->drawSymbol( painter, pos ); } - // draw label - if (!d_data->label.isEmpty()) { - int xlw = qwtMax(int(d_data->pen.width()), 1); - int ylw = xlw; - int xlw1; - int ylw1; - - const int xLabelDist = - QwtPainter::metricsMap().screenToLayoutX(LabelDist); - const int yLabelDist = - QwtPainter::metricsMap().screenToLayoutY(LabelDist); - - if ((d_data->style == VLine) || (d_data->style == HLine)) { - xlw1 = (xlw + 1) / 2 + xLabelDist; - xlw = xlw / 2 + xLabelDist; - ylw1 = (ylw + 1) / 2 + yLabelDist; - ylw = ylw / 2 + yLabelDist; - } else { - xlw1 = qwtMax((xlw + 1) / 2, (sSym.width() + 1) / 2) + xLabelDist; - xlw = qwtMax(xlw / 2, (sSym.width() + 1) / 2) + xLabelDist; - ylw1 = qwtMax((ylw + 1) / 2, (sSym.height() + 1) / 2) + yLabelDist; - ylw = qwtMax(ylw / 2, (sSym. height() + 1) / 2) + yLabelDist; - } + drawLabel( painter, canvasRect, pos ); +} - QRect tr(QPoint(0, 0), d_data->label.textSize(p->font())); - tr.moveCenter(QPoint(0, 0)); +/*! + Draw the lines marker - int dx = x; - int dy = y; + \param painter Painter + \param canvasRect Contents rectangle of the canvas in painter coordinates + \param pos Position of the marker, translated into widget coordinates - if (d_data->style == VLine) { - if (d_data->align & (int) Qt::AlignTop) - dy = r.top() + yLabelDist - tr.y(); - else if (d_data->align & (int) Qt::AlignBottom) - dy = r.bottom() - yLabelDist + tr.y(); - else - dy = r.top() + r.height() / 2; - } else { - if (d_data->align & (int) Qt::AlignTop) - dy += tr.y() - ylw1; - else if (d_data->align & (int) Qt::AlignBottom) - dy -= tr.y() - ylw1; - } + \sa drawLabel(), QwtSymbol::drawSymbol() +*/ +void QwtPlotMarker::drawLines( QPainter *painter, + const QRectF &canvasRect, const QPointF &pos ) const +{ + if ( d_data->style == NoLine ) + return; + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + painter->setPen( d_data->pen ); + if ( d_data->style == QwtPlotMarker::HLine || + d_data->style == QwtPlotMarker::Cross ) + { + double y = pos.y(); + if ( doAlign ) + y = qRound( y ); + + QwtPainter::drawLine( painter, canvasRect.left(), + y, canvasRect.right() - 1.0, y ); + } + if ( d_data->style == QwtPlotMarker::VLine || + d_data->style == QwtPlotMarker::Cross ) + { + double x = pos.x(); + if ( doAlign ) + x = qRound( x ); + + QwtPainter::drawLine( painter, x, + canvasRect.top(), x, canvasRect.bottom() - 1.0 ); + } +} +/*! + Align and draw the text label of the marker + + \param painter Painter + \param canvasRect Contents rectangle of the canvas in painter coordinates + \param pos Position of the marker, translated into widget coordinates + + \sa drawLabel(), QwtSymbol::drawSymbol() +*/ +void QwtPlotMarker::drawLabel( QPainter *painter, + const QRectF &canvasRect, const QPointF &pos ) const +{ + if ( d_data->label.isEmpty() ) + return; - if (d_data->style == HLine) { - if (d_data->align & (int) Qt::AlignLeft) - dx = r.left() + xLabelDist - tr.x(); - else if (d_data->align & (int) Qt::AlignRight) - dx = r.right() - xLabelDist + tr.x(); + Qt::Alignment align = d_data->labelAlignment; + QPointF alignPos = pos; + + QSizeF symbolOff( 0, 0 ); + + switch ( d_data->style ) + { + case QwtPlotMarker::VLine: + { + // In VLine-style the y-position is pointless and + // the alignment flags are relative to the canvas + + if ( d_data->labelAlignment & Qt::AlignTop ) + { + alignPos.setY( canvasRect.top() ); + align &= ~Qt::AlignTop; + align |= Qt::AlignBottom; + } + else if ( d_data->labelAlignment & Qt::AlignBottom ) + { + // In HLine-style the x-position is pointless and + // the alignment flags are relative to the canvas + + alignPos.setY( canvasRect.bottom() - 1 ); + align &= ~Qt::AlignBottom; + align |= Qt::AlignTop; + } + else + { + alignPos.setY( canvasRect.center().y() ); + } + break; + } + case QwtPlotMarker::HLine: + { + if ( d_data->labelAlignment & Qt::AlignLeft ) + { + alignPos.setX( canvasRect.left() ); + align &= ~Qt::AlignLeft; + align |= Qt::AlignRight; + } + else if ( d_data->labelAlignment & Qt::AlignRight ) + { + alignPos.setX( canvasRect.right() - 1 ); + align &= ~Qt::AlignRight; + align |= Qt::AlignLeft; + } else - dx = r.left() + r.width() / 2; - } else { - if (d_data->align & (int) Qt::AlignLeft) - dx += tr.x() - xlw1; - else if (d_data->align & (int) Qt::AlignRight) - dx -= tr.x() - xlw1; + { + alignPos.setX( canvasRect.center().x() ); + } + break; } + default: + { + if ( d_data->symbol && + ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) + { + symbolOff = d_data->symbol->size() + QSizeF( 1, 1 ); + symbolOff /= 2; + } + } + } + + qreal pw2 = d_data->pen.widthF() / 2.0; + if ( pw2 == 0.0 ) + pw2 = 0.5; + + const int spacing = d_data->spacing; + + const qreal xOff = qMax( pw2, symbolOff.width() ); + const qreal yOff = qMax( pw2, symbolOff.height() ); + + const QSizeF textSize = d_data->label.textSize( painter->font() ); + + if ( align & Qt::AlignLeft ) + { + alignPos.rx() -= xOff + spacing; + if ( d_data->labelOrientation == Qt::Vertical ) + alignPos.rx() -= textSize.height(); + else + alignPos.rx() -= textSize.width(); + } + else if ( align & Qt::AlignRight ) + { + alignPos.rx() += xOff + spacing; + } + else + { + if ( d_data->labelOrientation == Qt::Vertical ) + alignPos.rx() -= textSize.height() / 2; + else + alignPos.rx() -= textSize.width() / 2; + } -#if QT_VERSION < 0x040000 - tr.moveBy(dx, dy); -#else - tr.translate(dx, dy); -#endif - d_data->label.draw(p, tr); + if ( align & Qt::AlignTop ) + { + alignPos.ry() -= yOff + spacing; + if ( d_data->labelOrientation != Qt::Vertical ) + alignPos.ry() -= textSize.height(); + } + else if ( align & Qt::AlignBottom ) + { + alignPos.ry() += yOff + spacing; + if ( d_data->labelOrientation == Qt::Vertical ) + alignPos.ry() += textSize.width(); } + else + { + if ( d_data->labelOrientation == Qt::Vertical ) + alignPos.ry() += textSize.width() / 2; + else + alignPos.ry() -= textSize.height() / 2; + } + + painter->translate( alignPos.x(), alignPos.y() ); + if ( d_data->labelOrientation == Qt::Vertical ) + painter->rotate( -90.0 ); + + const QRectF textRect( 0, 0, textSize.width(), textSize.height() ); + d_data->label.draw( painter, textRect ); } /*! \brief Set the line style - \param st Line style. Can be one of QwtPlotMarker::NoLine, - HLine, VLine or Cross + \param style Line style. \sa lineStyle() */ -void QwtPlotMarker::setLineStyle(QwtPlotMarker::LineStyle st) +void QwtPlotMarker::setLineStyle( LineStyle style ) { - if ( st != d_data->style ) { - d_data->style = st; + if ( style != d_data->style ) + { + d_data->style = style; + + legendChanged(); itemChanged(); } } /*! \return the line style - \sa For a description of line styles, see QwtPlotMarker::setLineStyle() + \sa setLineStyle() */ QwtPlotMarker::LineStyle QwtPlotMarker::lineStyle() const { @@ -237,33 +362,42 @@ QwtPlotMarker::LineStyle QwtPlotMarker::lineStyle() const /*! \brief Assign a symbol - \param s New symbol + \param symbol New symbol \sa symbol() */ -void QwtPlotMarker::setSymbol(const QwtSymbol &s) +void QwtPlotMarker::setSymbol( const QwtSymbol *symbol ) { - delete d_data->symbol; - d_data->symbol = s.clone(); - itemChanged(); + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + + if ( symbol ) + setLegendIconSize( symbol->boundingRect().size() ); + + legendChanged(); + itemChanged(); + } } /*! \return the symbol \sa setSymbol(), QwtSymbol */ -const QwtSymbol &QwtPlotMarker::symbol() const +const QwtSymbol *QwtPlotMarker::symbol() const { - return *d_data->symbol; + return d_data->symbol; } /*! \brief Set the label - \param label label text + \param label Label text \sa label() */ -void QwtPlotMarker::setLabel(const QwtText& label) +void QwtPlotMarker::setLabel( const QwtText& label ) { - if ( label != d_data->label ) { + if ( label != d_data->label ) + { d_data->label = label; itemChanged(); } @@ -281,49 +415,124 @@ QwtText QwtPlotMarker::label() const /*! \brief Set the alignment of the label - The alignment determines where the label is drawn relative to - the marker's position. + In case of QwtPlotMarker::HLine the alignment is relative to the + y position of the marker, but the horizontal flags correspond to the + canvas rectangle. In case of QwtPlotMarker::VLine the alignment is + relative to the x position of the marker, but the vertical flags + correspond to the canvas rectangle. + + In all other styles the alignment is relative to the marker's position. - \param align Alignment. A combination of AlignTop, AlignBottom, - AlignLeft, AlignRight, AlignCenter, AlgnHCenter, - AlignVCenter. - \sa labelAlignment() + \param align Alignment. + \sa labelAlignment(), labelOrientation() */ -#if QT_VERSION < 0x040000 -void QwtPlotMarker::setLabelAlignment(int align) -#else -void QwtPlotMarker::setLabelAlignment(Qt::Alignment align) -#endif +void QwtPlotMarker::setLabelAlignment( Qt::Alignment align ) { - if ( align == d_data->align ) + if ( align != d_data->labelAlignment ) + { + d_data->labelAlignment = align; + itemChanged(); + } +} + +/*! + \return the label alignment + \sa setLabelAlignment(), setLabelOrientation() +*/ +Qt::Alignment QwtPlotMarker::labelAlignment() const +{ + return d_data->labelAlignment; +} + +/*! + \brief Set the orientation of the label + + When orientation is Qt::Vertical the label is rotated by 90.0 degrees + ( from bottom to top ). + + \param orientation Orientation of the label + + \sa labelOrientation(), setLabelAlignment() +*/ +void QwtPlotMarker::setLabelOrientation( Qt::Orientation orientation ) +{ + if ( orientation != d_data->labelOrientation ) + { + d_data->labelOrientation = orientation; + itemChanged(); + } +} + +/*! + \return the label orientation + \sa setLabelOrientation(), labelAlignment() +*/ +Qt::Orientation QwtPlotMarker::labelOrientation() const +{ + return d_data->labelOrientation; +} + +/*! + \brief Set the spacing + + When the label is not centered on the marker position, the spacing + is the distance between the position and the label. + + \param spacing Spacing + \sa spacing(), setLabelAlignment() +*/ +void QwtPlotMarker::setSpacing( int spacing ) +{ + if ( spacing < 0 ) + spacing = 0; + + if ( spacing == d_data->spacing ) return; - d_data->align = align; + d_data->spacing = spacing; itemChanged(); } /*! - \return the label alignment - \sa setLabelAlignment() + \return the spacing + \sa setSpacing() */ -#if QT_VERSION < 0x040000 -int QwtPlotMarker::labelAlignment() const -#else -Qt::Alignment QwtPlotMarker::labelAlignment() const -#endif +int QwtPlotMarker::spacing() const { - return d_data->align; + return d_data->spacing; +} + +/*! + Build and assign a line pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotMarker::setLinePen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setLinePen( QPen( color, width, style ) ); } /*! - \brief Specify a pen for the line. - \param p New pen + Specify a pen for the line. + + \param pen New pen \sa linePen() */ -void QwtPlotMarker::setLinePen(const QPen &p) +void QwtPlotMarker::setLinePen( const QPen &pen ) { - if ( p != d_data->pen ) { - d_data->pen = p; + if ( pen != d_data->pen ) + { + d_data->pen = pen; + + legendChanged(); itemChanged(); } } @@ -337,7 +546,65 @@ const QPen &QwtPlotMarker::linePen() const return d_data->pen; } -QwtDoubleRect QwtPlotMarker::boundingRect() const +QRectF QwtPlotMarker::boundingRect() const { - return QwtDoubleRect(d_data->xValue, d_data->yValue, 0.0, 0.0); + return QRectF( d_data->xValue, d_data->yValue, 0.0, 0.0 ); } + +/*! + \return Icon representing the marker on the legend + + \param index Index of the legend entry + ( usually there is only one ) + \param size Icon size + + \sa setLegendIconSize(), legendData() +*/ +QwtGraphic QwtPlotMarker::legendIcon( int index, + const QSizeF &size ) const +{ + Q_UNUSED( index ); + + if ( size.isEmpty() ) + return QwtGraphic(); + + QwtGraphic icon; + icon.setDefaultSize( size ); + icon.setRenderHint( QwtGraphic::RenderPensUnscaled, true ); + + QPainter painter( &icon ); + painter.setRenderHint( QPainter::Antialiasing, + testRenderHint( QwtPlotItem::RenderAntialiased ) ); + + if ( d_data->style != QwtPlotMarker::NoLine ) + { + painter.setPen( d_data->pen ); + + if ( d_data->style == QwtPlotMarker::HLine || + d_data->style == QwtPlotMarker::Cross ) + { + const double y = 0.5 * size.height(); + + QwtPainter::drawLine( &painter, + 0.0, y, size.width(), y ); + } + + if ( d_data->style == QwtPlotMarker::VLine || + d_data->style == QwtPlotMarker::Cross ) + { + const double x = 0.5 * size.width(); + + QwtPainter::drawLine( &painter, + x, 0.0, x, size.height() ); + } + } + + if ( d_data->symbol ) + { + const QRect r( 0.0, 0.0, size.width(), size.height() ); + d_data->symbol->drawSymbol( &painter, r ); + } + + return icon; +} + diff --git a/libs/qwt/qwt_plot_marker.h b/libs/qwt/qwt_plot_marker.h index d09522e375..2c726ce544 100644 --- a/libs/qwt/qwt_plot_marker.h +++ b/libs/qwt/qwt_plot_marker.h @@ -7,8 +7,6 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_PLOT_MARKER_H #define QWT_PLOT_MARKER_H @@ -19,7 +17,7 @@ #include "qwt_global.h" #include "qwt_plot_item.h" -class QRect; +class QRectF; class QwtText; class QwtSymbol; @@ -30,16 +28,21 @@ class QwtSymbol; a symbol, a label or any combination of them, which can be drawn around a center point inside a bounding rectangle. - The QwtPlotMarker::setSymbol() member assigns a symbol to the marker. + The setSymbol() member assigns a symbol to the marker. The symbol is drawn at the specified point. - With QwtPlotMarker::setLabel(), a label can be assigned to the marker. - The QwtPlotMarker::setLabelAlignment() member specifies where the label is + With setLabel(), a label can be assigned to the marker. + The setLabelAlignment() member specifies where the label is drawn. All the Align*-constants in Qt::AlignmentFlags (see Qt documentation) are valid. The interpretation of the alignment depends on the marker's line style. The alignment refers to the center point of the marker, which means, for example, that the label would be printed - left above the center point if the alignment was set to AlignLeft|AlignTop. + left above the center point if the alignment was set to + Qt::AlignLeft | Qt::AlignTop. + + \note QwtPlotTextLabel is intended to align a text label + according to the geometry of canvas + ( unrelated to plot coordinates ) */ class QWT_EXPORT QwtPlotMarker: public QwtPlotItem @@ -48,51 +51,78 @@ public: /*! Line styles. - \sa QwtPlotMarker::setLineStyle, QwtPlotMarker::lineStyle + \sa setLineStyle(), lineStyle() */ - enum LineStyle {NoLine, HLine, VLine, Cross}; + enum LineStyle + { + //! No line + NoLine, + + //! A horizontal line + HLine, + + //! A vertical line + VLine, + + //! A crosshair + Cross + }; + + explicit QwtPlotMarker( const QString &title = QString::null ); + explicit QwtPlotMarker( const QwtText &title ); - explicit QwtPlotMarker(); virtual ~QwtPlotMarker(); virtual int rtti() const; double xValue() const; double yValue() const; - QwtDoublePoint value() const; + QPointF value() const; - void setXValue(double); - void setYValue(double); - void setValue(double, double); - void setValue(const QwtDoublePoint &); + void setXValue( double ); + void setYValue( double ); + void setValue( double, double ); + void setValue( const QPointF & ); - void setLineStyle(LineStyle st); + void setLineStyle( LineStyle st ); LineStyle lineStyle() const; - void setLinePen(const QPen &p); + void setLinePen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setLinePen( const QPen &p ); const QPen &linePen() const; - void setSymbol(const QwtSymbol &s); - const QwtSymbol &symbol() const; + void setSymbol( const QwtSymbol * ); + const QwtSymbol *symbol() const; - void setLabel(const QwtText&); + void setLabel( const QwtText& ); QwtText label() const; -#if QT_VERSION < 0x040000 - void setLabelAlignment(int align); - int labelAlignment() const; -#else - void setLabelAlignment(Qt::Alignment); + void setLabelAlignment( Qt::Alignment ); Qt::Alignment labelAlignment() const; -#endif - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &) const; + void setLabelOrientation( Qt::Orientation ); + Qt::Orientation labelOrientation() const; - virtual QwtDoubleRect boundingRect() const; + void setSpacing( int ); + int spacing() const; + + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF & ) const; + + virtual QRectF boundingRect() const; + + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; + +protected: + virtual void drawLines( QPainter *, + const QRectF &, const QPointF & ) const; + + virtual void drawLabel( QPainter *, + const QRectF &, const QPointF & ) const; private: + class PrivateData; PrivateData *d_data; }; diff --git a/libs/qwt/qwt_plot_multi_barchart.cpp b/libs/qwt/qwt_plot_multi_barchart.cpp new file mode 100644 index 0000000000..7ee61666f4 --- /dev/null +++ b/libs/qwt/qwt_plot_multi_barchart.cpp @@ -0,0 +1,744 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_multi_barchart.h" +#include "qwt_scale_map.h" +#include "qwt_column_symbol.h" +#include "qwt_painter.h" +#include <qpainter.h> +#include <qpalette.h> +#include <qmap.h> + +inline static bool qwtIsIncreasing( + const QwtScaleMap &map, const QVector<double> &values ) +{ + bool isInverting = map.isInverting(); + + for ( int i = 0; i < values.size(); i++ ) + { + const double y = values[ i ]; + if ( y != 0.0 ) + return ( map.isInverting() != ( y > 0.0 ) ); + } + + return !isInverting; +} + +class QwtPlotMultiBarChart::PrivateData +{ +public: + PrivateData(): + style( QwtPlotMultiBarChart::Grouped ) + { + } + + QwtPlotMultiBarChart::ChartStyle style; + QList<QwtText> barTitles; + QMap<int, QwtColumnSymbol *> symbolMap; +}; + +/*! + Constructor + \param title Title of the chart +*/ +QwtPlotMultiBarChart::QwtPlotMultiBarChart( const QwtText &title ): + QwtPlotAbstractBarChart( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the chart +*/ +QwtPlotMultiBarChart::QwtPlotMultiBarChart( const QString &title ): + QwtPlotAbstractBarChart( QwtText( title ) ) +{ + init(); +} + +//! Destructor +QwtPlotMultiBarChart::~QwtPlotMultiBarChart() +{ + resetSymbolMap(); + delete d_data; +} + +void QwtPlotMultiBarChart::init() +{ + d_data = new PrivateData; + setData( new QwtSetSeriesData() ); +} + +//! \return QwtPlotItem::Rtti_PlotBarChart +int QwtPlotMultiBarChart::rtti() const +{ + return QwtPlotItem::Rtti_PlotMultiBarChart; +} + +/*! + Initialize data with an array of samples. + \param samples Vector of points +*/ +void QwtPlotMultiBarChart::setSamples( + const QVector<QwtSetSample> &samples ) +{ + setData( new QwtSetSeriesData( samples ) ); +} + +/*! + Initialize data with an array of samples. + \param samples Vector of points +*/ +void QwtPlotMultiBarChart::setSamples( + const QVector< QVector<double> > &samples ) +{ + QVector<QwtSetSample> s; + for ( int i = 0; i < samples.size(); i++ ) + s += QwtSetSample( i, samples[ i ] ); + + setData( new QwtSetSeriesData( s ) ); +} + +/*! + Assign a series of samples + + setSamples() is just a wrapper for setData() without any additional + value - beside that it is easier to find for the developer. + + \param data Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. +*/ +void QwtPlotMultiBarChart::setSamples( + QwtSeriesData<QwtSetSample> *data ) +{ + setData( data ); +} + +/*! + \brief Set the titles for the bars + + The titles are used for the legend. + + \param titles Bar titles + + \sa barTitles(), legendData() + */ +void QwtPlotMultiBarChart::setBarTitles( const QList<QwtText> &titles ) +{ + d_data->barTitles = titles; + itemChanged(); +} + +/*! + \return Bar titles + \sa setBarTitles(), legendData() + */ +QList<QwtText> QwtPlotMultiBarChart::barTitles() const +{ + return d_data->barTitles; +} + +/*! + \brief Add a symbol to the symbol map + + Assign a default symbol for drawing the bar representing all values + with the same index in a set. + + \param valueIndex Index of a value in a set + \param symbol Symbol used for drawing a bar + + \sa symbol(), resetSymbolMap(), specialSymbol() +*/ +void QwtPlotMultiBarChart::setSymbol( int valueIndex, QwtColumnSymbol *symbol ) +{ + if ( valueIndex < 0 ) + return; + + QMap<int, QwtColumnSymbol *>::iterator it = + d_data->symbolMap.find(valueIndex); + if ( it == d_data->symbolMap.end() ) + { + if ( symbol != NULL ) + { + d_data->symbolMap.insert( valueIndex, symbol ); + + legendChanged(); + itemChanged(); + } + } + else + { + if ( symbol != it.value() ) + { + delete it.value(); + + if ( symbol == NULL ) + { + d_data->symbolMap.remove( valueIndex ); + } + else + { + it.value() = symbol; + } + + legendChanged(); + itemChanged(); + } + } +} + +/*! + Find a symbol in the symbol map + + \param valueIndex Index of a value in a set + \return The symbol, that had been set by setSymbol() or NULL. + + \sa setSymbol(), specialSymbol(), drawBar() +*/ +const QwtColumnSymbol *QwtPlotMultiBarChart::symbol( int valueIndex ) const +{ + QMap<int, QwtColumnSymbol *>::const_iterator it = + d_data->symbolMap.find( valueIndex ); + + return ( it == d_data->symbolMap.end() ) ? NULL : it.value(); +} + +/*! + Find a symbol in the symbol map + + \param valueIndex Index of a value in a set + \return The symbol, that had been set by setSymbol() or NULL. + + \sa setSymbol(), specialSymbol(), drawBar() +*/ +QwtColumnSymbol *QwtPlotMultiBarChart::symbol( int valueIndex ) +{ + QMap<int, QwtColumnSymbol *>::iterator it = + d_data->symbolMap.find( valueIndex ); + + return ( it == d_data->symbolMap.end() ) ? NULL : it.value(); +} + +/*! + Remove all symbols from the symbol map + */ +void QwtPlotMultiBarChart::resetSymbolMap() +{ + for ( QMap<int, QwtColumnSymbol *>::iterator it + = d_data->symbolMap.begin(); it != d_data->symbolMap.end(); ++it ) + { + delete it.value(); + } + + d_data->symbolMap.clear(); +} + +/*! + \brief Create a symbol for special values + + Usually the symbols for displaying a bar are set by setSymbols() and + common for all sets. By overloading specialSymbol() it is possible to + create a temporary symbol() for displaying a special value. + + The symbol has to be created by new each time specialSymbol() is + called. As soon as the symbol is painted this symbol gets deleted. + + When no symbol ( NULL ) is returned, the value will be displayed + with the standard symbol that is used for all symbols with the same + valueIndex. + + \param sampleIndex Index of the sample + \param valueIndex Index of the value in the set + + \return NULL, meaning that the value is not special + + */ +QwtColumnSymbol *QwtPlotMultiBarChart::specialSymbol( + int sampleIndex, int valueIndex ) const +{ + Q_UNUSED( sampleIndex ); + Q_UNUSED( valueIndex ); + + return NULL; +} + +/*! + Set the style of the chart + + \param style Chart style + \sa style() + */ +void QwtPlotMultiBarChart::setStyle( ChartStyle style ) +{ + if ( style != d_data->style ) + { + d_data->style = style; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Style of the chart + \sa setStyle() + */ +QwtPlotMultiBarChart::ChartStyle QwtPlotMultiBarChart::style() const +{ + return d_data->style; +} + +/*! + \return Bounding rectangle of all samples. + For an empty series the rectangle is invalid. +*/ +QRectF QwtPlotMultiBarChart::boundingRect() const +{ + const size_t numSamples = dataSize(); + + if ( numSamples == 0 ) + return QwtPlotSeriesItem::boundingRect(); + + const double baseLine = baseline(); + + QRectF rect; + + if ( d_data->style != QwtPlotMultiBarChart::Stacked ) + { + rect = QwtPlotSeriesItem::boundingRect(); + + if ( rect.height() >= 0 ) + { + if ( rect.bottom() < baseLine ) + rect.setBottom( baseLine ); + if ( rect.top() > baseLine ) + rect.setTop( baseLine ); + } + } + else + { + double xMin, xMax, yMin, yMax; + + xMin = xMax = 0.0; + yMin = yMax = baseLine; + + const QwtSeriesData<QwtSetSample> *series = data(); + + for ( size_t i = 0; i < numSamples; i++ ) + { + const QwtSetSample sample = series->sample( i ); + if ( i == 0 ) + { + xMin = xMax = sample.value; + } + else + { + xMin = qMin( xMin, sample.value ); + xMax = qMax( xMax, sample.value ); + } + + const double y = baseLine + sample.added(); + + yMin = qMin( yMin, y ); + yMax = qMax( yMax, y ); + } + rect.setRect( xMin, yMin, xMax - xMin, yMax - yMin ); + } + + if ( orientation() == Qt::Horizontal ) + rect.setRect( rect.y(), rect.x(), rect.height(), rect.width() ); + + return rect; +} + +/*! + Draw an interval of the bar chart + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted. If to < 0 the + curve will be painted to its last point. + + \sa drawSymbols() +*/ +void QwtPlotMultiBarChart::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( to < 0 ) + to = dataSize() - 1; + + if ( from < 0 ) + from = 0; + + if ( from > to ) + return; + + + const QRectF br = data()->boundingRect(); + const QwtInterval interval( br.left(), br.right() ); + + painter->save(); + + for ( int i = from; i <= to; i++ ) + { + drawSample( painter, xMap, yMap, + canvasRect, interval, i, sample( i ) ); + } + + painter->restore(); +} + +/*! + Draw a sample + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rectangle of the canvas + \param boundingInterval Bounding interval of sample values + \param index Index of the sample to be painted + \param sample Sample value + + \sa drawSeries() +*/ +void QwtPlotMultiBarChart::drawSample( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, const QwtInterval &boundingInterval, + int index, const QwtSetSample& sample ) const +{ + if ( sample.set.size() <= 0 ) + return; + + double sampleW; + + if ( orientation() == Qt::Horizontal ) + { + sampleW = sampleWidth( yMap, canvasRect.height(), + boundingInterval.width(), sample.value ); + } + else + { + sampleW = sampleWidth( xMap, canvasRect.width(), + boundingInterval.width(), sample.value ); + } + + if ( d_data->style == Stacked ) + { + drawStackedBars( painter, xMap, yMap, + canvasRect, index, sampleW, sample ); + } + else + { + drawGroupedBars( painter, xMap, yMap, + canvasRect, index, sampleW, sample ); + } +} + +/*! + Draw a grouped sample + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rectangle of the canvas + \param index Index of the sample to be painted + \param sampleWidth Boundng width for all bars of the smaple + \param sample Sample + + \sa drawSeries(), sampleWidth() +*/ +void QwtPlotMultiBarChart::drawGroupedBars( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int index, double sampleWidth, + const QwtSetSample& sample ) const +{ + Q_UNUSED( canvasRect ); + + const int numBars = sample.set.size(); + if ( numBars == 0 ) + return; + + if ( orientation() == Qt::Vertical ) + { + const double barWidth = sampleWidth / numBars; + + const double y1 = yMap.transform( baseline() ); + const double x0 = xMap.transform( sample.value ) - 0.5 * sampleWidth; + + for ( int i = 0; i < numBars; i++ ) + { + const double x1 = x0 + i * barWidth; + const double x2 = x1 + barWidth; + + const double y2 = yMap.transform( sample.set[i] ); + + QwtColumnRect barRect; + barRect.direction = ( y1 < y2 ) ? + QwtColumnRect::TopToBottom : QwtColumnRect::BottomToTop; + + barRect.hInterval = QwtInterval( x1, x2 ).normalized(); + if ( i != 0 ) + barRect.hInterval.setBorderFlags( QwtInterval::ExcludeMinimum ); + + barRect.vInterval = QwtInterval( y1, y2 ).normalized(); + + drawBar( painter, index, i, barRect ); + } + } + else + { + const double barHeight = sampleWidth / numBars; + + const double x1 = xMap.transform( baseline() ); + const double y0 = yMap.transform( sample.value ) - 0.5 * sampleWidth; + + for ( int i = 0; i < numBars; i++ ) + { + double y1 = y0 + i * barHeight; + double y2 = y1 + barHeight; + + double x2 = xMap.transform( sample.set[i] ); + + QwtColumnRect barRect; + barRect.direction = x1 < x2 ? + QwtColumnRect::LeftToRight : QwtColumnRect::RightToLeft; + + barRect.hInterval = QwtInterval( x1, x2 ).normalized(); + + barRect.vInterval = QwtInterval( y1, y2 ); + if ( i != 0 ) + barRect.vInterval.setBorderFlags( QwtInterval::ExcludeMinimum ); + + drawBar( painter, index, i, barRect ); + } + } +} + +/*! + Draw a stacked sample + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rectangle of the canvas + \param index Index of the sample to be painted + \param sampleWidth Width of the bars + \param sample Sample + + \sa drawSeries(), sampleWidth() +*/ +void QwtPlotMultiBarChart::drawStackedBars( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int index, + double sampleWidth, const QwtSetSample& sample ) const +{ + Q_UNUSED( canvasRect ); // clipping the bars ? + + const int numBars = sample.set.size(); + if ( numBars == 0 ) + return; + + QwtInterval::BorderFlag borderFlags = QwtInterval::IncludeBorders; + + if ( orientation() == Qt::Vertical ) + { + const double x1 = xMap.transform( sample.value ) - 0.5 * sampleWidth; + const double x2 = x1 + sampleWidth; + + const bool increasing = qwtIsIncreasing( yMap, sample.set ); + + QwtColumnRect bar; + bar.direction = increasing ? + QwtColumnRect::TopToBottom : QwtColumnRect::BottomToTop; + + bar.hInterval = QwtInterval( x1, x2 ).normalized(); + + double sum = baseline(); + + const int numBars = sample.set.size(); + for ( int i = 0; i < numBars; i++ ) + { + const double si = sample.set[ i ]; + if ( si == 0.0 ) + continue; + + const double y1 = yMap.transform( sum ); + const double y2 = yMap.transform( sum + si ); + + if ( ( y2 > y1 ) != increasing ) + { + // stacked bars need to be in the same direction + continue; + } + + bar.vInterval = QwtInterval( y1, y2 ).normalized(); + bar.vInterval.setBorderFlags( borderFlags ); + + drawBar( painter, index, i, bar ); + + sum += si; + + if ( increasing ) + borderFlags = QwtInterval::ExcludeMinimum; + else + borderFlags = QwtInterval::ExcludeMaximum; + } + } + else + { + const double y1 = yMap.transform( sample.value ) - 0.5 * sampleWidth; + const double y2 = y1 + sampleWidth; + + const bool increasing = qwtIsIncreasing( xMap, sample.set ); + + QwtColumnRect bar; + bar.direction = increasing ? + QwtColumnRect::LeftToRight : QwtColumnRect::RightToLeft; + bar.vInterval = QwtInterval( y1, y2 ).normalized(); + + double sum = baseline(); + + for ( int i = 0; i < sample.set.size(); i++ ) + { + const double si = sample.set[ i ]; + if ( si == 0.0 ) + continue; + + const double x1 = xMap.transform( sum ); + const double x2 = xMap.transform( sum + si ); + + if ( ( x2 > x1 ) != increasing ) + { + // stacked bars need to be in the same direction + continue; + } + + bar.hInterval = QwtInterval( x1, x2 ).normalized(); + bar.hInterval.setBorderFlags( borderFlags ); + + drawBar( painter, index, i, bar ); + + sum += si; + + if ( increasing ) + borderFlags = QwtInterval::ExcludeMinimum; + else + borderFlags = QwtInterval::ExcludeMaximum; + } + } +} + +/*! + Draw a bar + + \param painter Painter + \param sampleIndex Index of the sample - might be -1 when the + bar is painted for the legend + \param valueIndex Index of a value in a set + \param rect Directed target rectangle for the bar + + \sa drawSeries() +*/ +void QwtPlotMultiBarChart::drawBar( QPainter *painter, + int sampleIndex, int valueIndex, const QwtColumnRect &rect ) const +{ + const QwtColumnSymbol *specialSym = NULL; + if ( sampleIndex >= 0 ) + specialSym = specialSymbol( sampleIndex, valueIndex ); + + const QwtColumnSymbol *sym = specialSym; + if ( sym == NULL ) + sym = symbol( valueIndex ); + + if ( sym ) + { + sym->draw( painter, rect ); + } + else + { + // we build a temporary default symbol + QwtColumnSymbol sym( QwtColumnSymbol::Box ); + sym.setLineWidth( 1 ); + sym.setFrameStyle( QwtColumnSymbol::Plain ); + sym.draw( painter, rect ); + } + + delete specialSym; +} + +/*! + \return Information to be displayed on the legend + + The chart is represented by a list of entries - one for each bar title. + Each element contains a bar title and an icon showing its corresponding bar. + + \sa barTitles(), legendIcon(), legendIconSize() +*/ +QList<QwtLegendData> QwtPlotMultiBarChart::legendData() const +{ + QList<QwtLegendData> list; + + for ( int i = 0; i < d_data->barTitles.size(); i++ ) + { + QwtLegendData data; + + QVariant titleValue; + qVariantSetValue( titleValue, d_data->barTitles[i] ); + data.setValue( QwtLegendData::TitleRole, titleValue ); + + if ( !legendIconSize().isEmpty() ) + { + QVariant iconValue; + qVariantSetValue( iconValue, + legendIcon( i, legendIconSize() ) ); + + data.setValue( QwtLegendData::IconRole, iconValue ); + } + + list += data; + } + + return list; +} + +/*! + \return Icon for representing a bar on the legend + + \param index Index of the bar + \param size Icon size + + \return An icon showing a bar + \sa drawBar(), legendData() + */ +QwtGraphic QwtPlotMultiBarChart::legendIcon( int index, + const QSizeF &size ) const +{ + QwtColumnRect column; + column.hInterval = QwtInterval( 0.0, size.width() - 1.0 ); + column.vInterval = QwtInterval( 0.0, size.height() - 1.0 ); + + QwtGraphic icon; + icon.setDefaultSize( size ); + icon.setRenderHint( QwtGraphic::RenderPensUnscaled, true ); + + QPainter painter( &icon ); + painter.setRenderHint( QPainter::Antialiasing, + testRenderHint( QwtPlotItem::RenderAntialiased ) ); + + drawBar( &painter, -1, index, column ); + + return icon; +} + diff --git a/libs/qwt/qwt_plot_multi_barchart.h b/libs/qwt/qwt_plot_multi_barchart.h new file mode 100644 index 0000000000..834925522f --- /dev/null +++ b/libs/qwt/qwt_plot_multi_barchart.h @@ -0,0 +1,127 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_MULTI_BAR_CHART_H +#define QWT_PLOT_MULTI_BAR_CHART_H + +#include "qwt_global.h" +#include "qwt_plot_abstract_barchart.h" +#include "qwt_series_data.h" + +class QwtColumnRect; +class QwtColumnSymbol; + +/*! + \brief QwtPlotMultiBarChart displays a series of a samples that consist + each of a set of values. + + Each value is displayed as a bar, the bars of each set can be organized + side by side or accumulated. + + Each bar of a set is rendered by a QwtColumnSymbol, that is set by setSymbol(). + The bars of different sets use the same symbols. Exceptions are possible + by overloading specialSymbol() or overloading drawBar(). + + Depending on its orientation() the bars are displayed horizontally + or vertically. The bars cover the interval between the baseline() + and the value. + + In opposite to most other plot items, QwtPlotMultiBarChart returns more + than one entry for the legend - one for each symbol. + + \sa QwtPlotBarChart, QwtPlotHistogram + QwtPlotSeriesItem::orientation(), QwtPlotAbstractBarChart::baseline() + */ +class QWT_EXPORT QwtPlotMultiBarChart: + public QwtPlotAbstractBarChart, public QwtSeriesStore<QwtSetSample> +{ +public: + /*! + \brief Chart styles. + + The default setting is QwtPlotMultiBarChart::Grouped. + \sa setStyle(), style() + */ + enum ChartStyle + { + //! The bars of a set are displayed side by side + Grouped, + + /*! + The bars are displayed on top of each other accumulating + to a single bar. All values of a set need to have the same + sign. + */ + Stacked + }; + + explicit QwtPlotMultiBarChart( const QString &title = QString::null ); + explicit QwtPlotMultiBarChart( const QwtText &title ); + + virtual ~QwtPlotMultiBarChart(); + + virtual int rtti() const; + + void setBarTitles( const QList<QwtText> & ); + QList<QwtText> barTitles() const; + + void setSamples( const QVector<QwtSetSample> & ); + void setSamples( const QVector< QVector<double> > & ); + void setSamples( QwtSeriesData<QwtSetSample> * ); + + void setStyle( ChartStyle style ); + ChartStyle style() const; + + void setSymbol( int barIndex, QwtColumnSymbol *symbol ); + const QwtColumnSymbol *symbol( int barIndex ) const; + + void resetSymbolMap(); + + virtual void drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual QRectF boundingRect() const; + + virtual QList<QwtLegendData> legendData() const; + + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; + +protected: + QwtColumnSymbol *symbol( int barIndex ); + + virtual QwtColumnSymbol *specialSymbol( + int sampleIndex, int valueIndex ) const; + + virtual void drawSample( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, const QwtInterval &boundingInterval, + int index, const QwtSetSample& sample ) const; + + virtual void drawBar( QPainter *, int sampleIndex, + int barIndex, const QwtColumnRect & ) const; + + void drawStackedBars( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int index, + double sampleWidth, const QwtSetSample& sample ) const; + + void drawGroupedBars( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int index, + double sampleWidth, const QwtSetSample& sample ) const; + +private: + void init(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_panner.cpp b/libs/qwt/qwt_plot_panner.cpp index a706b14d05..62a75a2fb3 100644 --- a/libs/qwt/qwt_plot_panner.cpp +++ b/libs/qwt/qwt_plot_panner.cpp @@ -7,17 +7,91 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_plot_panner.h" #include "qwt_scale_div.h" #include "qwt_plot.h" -#include "qwt_plot_canvas.h" -#include "qwt_plot_panner.h" +#include "qwt_painter.h" +#include <qbitmap.h> +#include <qstyle.h> +#include <qstyleoption.h> + +static QBitmap qwtBorderMask( const QWidget *canvas, const QSize &size ) +{ + const QRect r( 0, 0, size.width(), size.height() ); + + QPainterPath borderPath; + + ( void )QMetaObject::invokeMethod( + const_cast< QWidget *>( canvas ), "borderPath", Qt::DirectConnection, + Q_RETURN_ARG( QPainterPath, borderPath ), Q_ARG( QRect, r ) ); + + if ( borderPath.isEmpty() ) + { + if ( canvas->contentsRect() == canvas->rect() ) + return QBitmap(); + + QBitmap mask( size ); + mask.fill( Qt::color0 ); + + QPainter painter( &mask ); + painter.fillRect( canvas->contentsRect(), Qt::color1 ); + + return mask; + } + + QImage image( size, QImage::Format_ARGB32_Premultiplied ); + image.fill( Qt::color0 ); + + QPainter painter( &image ); + painter.setClipPath( borderPath ); + painter.fillRect( r, Qt::color1 ); + + // now erase the frame + + painter.setCompositionMode( QPainter::CompositionMode_DestinationOut ); + + if ( canvas->testAttribute(Qt::WA_StyledBackground ) ) + { + QStyleOptionFrame opt; + opt.initFrom(canvas); + opt.rect = r; + canvas->style()->drawPrimitive( QStyle::PE_Frame, &opt, &painter, canvas ); + } + else + { + const QVariant borderRadius = canvas->property( "borderRadius" ); + const QVariant frameWidth = canvas->property( "frameWidth" ); + + if ( borderRadius.type() == QVariant::Double + && frameWidth.type() == QVariant::Int ) + { + const double br = borderRadius.toDouble(); + const int fw = frameWidth.toInt(); + + if ( br > 0.0 && fw > 0 ) + { + painter.setPen( QPen( Qt::color1, fw ) ); + painter.setBrush( Qt::NoBrush ); + painter.setRenderHint( QPainter::Antialiasing, true ); + + painter.drawPath( borderPath ); + } + } + } + + painter.end(); + + const QImage mask = image.createMaskFromColor( + QColor( Qt::color1 ).rgb(), Qt::MaskOutColor ); + + return QBitmap::fromImage( mask ); +} class QwtPlotPanner::PrivateData { public: - PrivateData() { + PrivateData() + { for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) isAxisEnabled[axis] = true; } @@ -26,21 +100,21 @@ public: }; /*! - \brief Create a plot panner + \brief A panner for the canvas of a QwtPlot The panner is enabled for all axes \param canvas Plot canvas to pan, also the parent object - \sa setAxisEnabled + \sa setAxisEnabled() */ -QwtPlotPanner::QwtPlotPanner(QwtPlotCanvas *canvas): - QwtPanner(canvas) +QwtPlotPanner::QwtPlotPanner( QWidget *canvas ): + QwtPanner( canvas ) { d_data = new PrivateData(); - connect(this, SIGNAL(panned(int, int)), - SLOT(moveCanvas(int, int))); + connect( this, SIGNAL( panned( int, int ) ), + SLOT( moveCanvas( int, int ) ) ); } //! Destructor @@ -58,9 +132,9 @@ QwtPlotPanner::~QwtPlotPanner() \param axis Axis, see QwtPlot::Axis \param on On/Off - \sa isAxisEnabled, moveCanvas + \sa isAxisEnabled(), moveCanvas() */ -void QwtPlotPanner::setAxisEnabled(int axis, bool on) +void QwtPlotPanner::setAxisEnabled( int axis, bool on ) { if ( axis >= 0 && axis < QwtPlot::axisCnt ) d_data->isAxisEnabled[axis] = on; @@ -72,9 +146,9 @@ void QwtPlotPanner::setAxisEnabled(int axis, bool on) \param axis Axis, see QwtPlot::Axis \return True, if the axis is enabled - \sa setAxisEnabled, moveCanvas + \sa setAxisEnabled(), moveCanvas() */ -bool QwtPlotPanner::isAxisEnabled(int axis) const +bool QwtPlotPanner::isAxisEnabled( int axis ) const { if ( axis >= 0 && axis < QwtPlot::axisCnt ) return d_data->isAxisEnabled[axis]; @@ -83,38 +157,35 @@ bool QwtPlotPanner::isAxisEnabled(int axis) const } //! Return observed plot canvas -QwtPlotCanvas *QwtPlotPanner::canvas() +QWidget *QwtPlotPanner::canvas() { - QWidget *w = parentWidget(); - if ( w && w->inherits("QwtPlotCanvas") ) - return (QwtPlotCanvas *)w; - - return NULL; + return parentWidget(); } //! Return Observed plot canvas -const QwtPlotCanvas *QwtPlotPanner::canvas() const +const QWidget *QwtPlotPanner::canvas() const { - return ((QwtPlotPanner *)this)->canvas(); + return parentWidget(); } //! Return plot widget, containing the observed plot canvas QwtPlot *QwtPlotPanner::plot() { - QObject *w = canvas(); - if ( w ) { - w = w->parent(); - if ( w && w->inherits("QwtPlot") ) - return (QwtPlot *)w; - } + QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); - return NULL; + return qobject_cast<QwtPlot *>( w ); } //! Return plot widget, containing the observed plot canvas const QwtPlot *QwtPlotPanner::plot() const { - return ((QwtPlotPanner *)this)->plot(); + const QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); + + return qobject_cast<const QwtPlot *>( w ); } /*! @@ -125,39 +196,80 @@ const QwtPlot *QwtPlotPanner::plot() const \sa QwtPanner::panned() */ -void QwtPlotPanner::moveCanvas(int dx, int dy) +void QwtPlotPanner::moveCanvas( int dx, int dy ) { if ( dx == 0 && dy == 0 ) return; - QwtPlot *plot = QwtPlotPanner::plot(); + QwtPlot *plot = this->plot(); if ( plot == NULL ) return; const bool doAutoReplot = plot->autoReplot(); - plot->setAutoReplot(false); + plot->setAutoReplot( false ); - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) { + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { if ( !d_data->isAxisEnabled[axis] ) continue; - const QwtScaleMap map = plot->canvasMap(axis); + const QwtScaleMap map = plot->canvasMap( axis ); - const int i1 = map.transform(plot->axisScaleDiv(axis)->lBound()); - const int i2 = map.transform(plot->axisScaleDiv(axis)->hBound()); + const double p1 = map.transform( plot->axisScaleDiv( axis ).lowerBound() ); + const double p2 = map.transform( plot->axisScaleDiv( axis ).upperBound() ); double d1, d2; - if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) { - d1 = map.invTransform(i1 - dx); - d2 = map.invTransform(i2 - dx); - } else { - d1 = map.invTransform(i1 - dy); - d2 = map.invTransform(i2 - dy); + if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) + { + d1 = map.invTransform( p1 - dx ); + d2 = map.invTransform( p2 - dx ); + } + else + { + d1 = map.invTransform( p1 - dy ); + d2 = map.invTransform( p2 - dy ); } - plot->setAxisScale(axis, d1, d2); + plot->setAxisScale( axis, d1, d2 ); } - plot->setAutoReplot(doAutoReplot); + plot->setAutoReplot( doAutoReplot ); plot->replot(); } + +/*! + Calculate a mask from the border path of the canvas + + \return Mask as bitmap + \sa QwtPlotCanvas::borderPath() +*/ +QBitmap QwtPlotPanner::contentsMask() const +{ + if ( canvas() ) + return qwtBorderMask( canvas(), size() ); + + return QwtPanner::contentsMask(); +} + +/*! + \return Pixmap with the content of the canvas + */ +QPixmap QwtPlotPanner::grab() const +{ + const QWidget *cv = canvas(); + if ( cv && cv->inherits( "QGLWidget" ) ) + { + // we can't grab from a QGLWidget + + QPixmap pm( cv->size() ); + QwtPainter::fillPixmap( cv, pm ); + + QPainter painter( &pm ); + const_cast<QwtPlot *>( plot() )->drawCanvas( &painter ); + + return pm; + } + + return QwtPanner::grab(); +} + diff --git a/libs/qwt/qwt_plot_panner.h b/libs/qwt/qwt_plot_panner.h index 224dc0fa08..517c23d23b 100644 --- a/libs/qwt/qwt_plot_panner.h +++ b/libs/qwt/qwt_plot_panner.h @@ -13,13 +13,12 @@ #include "qwt_global.h" #include "qwt_panner.h" -class QwtPlotCanvas; class QwtPlot; /*! \brief QwtPlotPanner provides panning of a plot canvas - QwtPlotPanner is a panner for a QwtPlotCanvas, that + QwtPlotPanner is a panner for a plot canvas, that adjusts the scales of the axes after dropping the canvas on its new position. @@ -34,20 +33,24 @@ class QWT_EXPORT QwtPlotPanner: public QwtPanner Q_OBJECT public: - explicit QwtPlotPanner(QwtPlotCanvas *); + explicit QwtPlotPanner( QWidget * ); virtual ~QwtPlotPanner(); - QwtPlotCanvas *canvas(); - const QwtPlotCanvas *canvas() const; + QWidget *canvas(); + const QWidget *canvas() const; QwtPlot *plot(); const QwtPlot *plot() const; - void setAxisEnabled(int axis, bool on); - bool isAxisEnabled(int axis) const; + void setAxisEnabled( int axis, bool on ); + bool isAxisEnabled( int axis ) const; -protected slots: - virtual void moveCanvas(int dx, int dy); +protected Q_SLOTS: + virtual void moveCanvas( int dx, int dy ); + +protected: + virtual QBitmap contentsMask() const; + virtual QPixmap grab() const; private: class PrivateData; diff --git a/libs/qwt/qwt_plot_picker.cpp b/libs/qwt/qwt_plot_picker.cpp index 1bbff38814..1c0733d1ab 100644 --- a/libs/qwt/qwt_plot_picker.cpp +++ b/libs/qwt/qwt_plot_picker.cpp @@ -7,14 +7,12 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_plot_picker.h" #include "qwt_plot.h" -#include "qwt_double_rect.h" #include "qwt_scale_div.h" #include "qwt_painter.h" #include "qwt_scale_map.h" -#include "qwt_plot_picker.h" +#include "qwt_picker_machine.h" /*! \brief Create a plot picker @@ -26,13 +24,13 @@ \param canvas Plot canvas to observe, also the parent object - \sa QwtPlot::autoReplot(), QwtPlot::replot(), QwtPlotPicker::scaleRect() + \sa QwtPlot::autoReplot(), QwtPlot::replot(), scaleRect() */ -QwtPlotPicker::QwtPlotPicker(QwtPlotCanvas *canvas): - QwtPicker(canvas), - d_xAxis(-1), - d_yAxis(-1) +QwtPlotPicker::QwtPlotPicker( QWidget *canvas ): + QwtPicker( canvas ), + d_xAxis( -1 ), + d_yAxis( -1 ) { if ( !canvas ) return; @@ -42,18 +40,20 @@ QwtPlotPicker::QwtPlotPicker(QwtPlotCanvas *canvas): int xAxis = QwtPlot::xBottom; const QwtPlot *plot = QwtPlotPicker::plot(); - if ( !plot->axisEnabled(QwtPlot::xBottom) && - plot->axisEnabled(QwtPlot::xTop) ) { + if ( !plot->axisEnabled( QwtPlot::xBottom ) && + plot->axisEnabled( QwtPlot::xTop ) ) + { xAxis = QwtPlot::xTop; } int yAxis = QwtPlot::yLeft; - if ( !plot->axisEnabled(QwtPlot::yLeft) && - plot->axisEnabled(QwtPlot::yRight) ) { + if ( !plot->axisEnabled( QwtPlot::yLeft ) && + plot->axisEnabled( QwtPlot::yRight ) ) + { yAxis = QwtPlot::yRight; } - setAxis(xAxis, yAxis); + setAxis( xAxis, yAxis ); } /*! @@ -63,12 +63,12 @@ QwtPlotPicker::QwtPlotPicker(QwtPlotCanvas *canvas): \param yAxis Set the y axis of the picker \param canvas Plot canvas to observe, also the parent object - \sa QwtPlot::autoReplot(), QwtPlot::replot(), QwtPlotPicker::scaleRect() + \sa QwtPlot::autoReplot(), QwtPlot::replot(), scaleRect() */ -QwtPlotPicker::QwtPlotPicker(int xAxis, int yAxis, QwtPlotCanvas *canvas): - QwtPicker(canvas), - d_xAxis(xAxis), - d_yAxis(yAxis) +QwtPlotPicker::QwtPlotPicker( int xAxis, int yAxis, QWidget *canvas ): + QwtPicker( canvas ), + d_xAxis( xAxis ), + d_yAxis( yAxis ) { } @@ -77,79 +77,77 @@ QwtPlotPicker::QwtPlotPicker(int xAxis, int yAxis, QwtPlotCanvas *canvas): \param xAxis X axis of the picker \param yAxis Y axis of the picker - \param selectionFlags Or'd value of SelectionType, RectSelectionType and - SelectionMode - \param rubberBand Rubberband style + \param rubberBand Rubber band style \param trackerMode Tracker mode \param canvas Plot canvas to observe, also the parent object \sa QwtPicker, QwtPicker::setSelectionFlags(), QwtPicker::setRubberBand(), QwtPicker::setTrackerMode - \sa QwtPlot::autoReplot(), QwtPlot::replot(), QwtPlotPicker::scaleRect() + \sa QwtPlot::autoReplot(), QwtPlot::replot(), scaleRect() */ -QwtPlotPicker::QwtPlotPicker(int xAxis, int yAxis, int selectionFlags, - RubberBand rubberBand, DisplayMode trackerMode, - QwtPlotCanvas *canvas): - QwtPicker(selectionFlags, rubberBand, trackerMode, canvas), - d_xAxis(xAxis), - d_yAxis(yAxis) +QwtPlotPicker::QwtPlotPicker( int xAxis, int yAxis, + RubberBand rubberBand, DisplayMode trackerMode, + QWidget *canvas ): + QwtPicker( rubberBand, trackerMode, canvas ), + d_xAxis( xAxis ), + d_yAxis( yAxis ) { } -//! Return observed plot canvas -QwtPlotCanvas *QwtPlotPicker::canvas() +//! Destructor +QwtPlotPicker::~QwtPlotPicker() { - QWidget *w = parentWidget(); - if ( w && w->inherits("QwtPlotCanvas") ) - return (QwtPlotCanvas *)w; +} - return NULL; +//! \return Observed plot canvas +QWidget *QwtPlotPicker::canvas() +{ + return parentWidget(); } -//! Return Observed plot canvas -const QwtPlotCanvas *QwtPlotPicker::canvas() const +//! \return Observed plot canvas +const QWidget *QwtPlotPicker::canvas() const { - return ((QwtPlotPicker *)this)->canvas(); + return parentWidget(); } -//! Return plot widget, containing the observed plot canvas +//! \return Plot widget, containing the observed plot canvas QwtPlot *QwtPlotPicker::plot() { - QObject *w = canvas(); - if ( w ) { - w = w->parent(); - if ( w && w->inherits("QwtPlot") ) - return (QwtPlot *)w; - } + QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); - return NULL; + return qobject_cast<QwtPlot *>( w ); } -//! Return plot widget, containing the observed plot canvas +//! \return Plot widget, containing the observed plot canvas const QwtPlot *QwtPlotPicker::plot() const { - return ((QwtPlotPicker *)this)->plot(); + const QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); + + return qobject_cast<const QwtPlot *>( w ); } /*! - Return normalized bounding rect of the axes - + \return Normalized bounding rectangle of the axes \sa QwtPlot::autoReplot(), QwtPlot::replot(). */ -QwtDoubleRect QwtPlotPicker::scaleRect() const +QRectF QwtPlotPicker::scaleRect() const { - QwtDoubleRect rect; + QRectF rect; - if ( plot() ) { - const QwtScaleDiv *xs = plot()->axisScaleDiv(xAxis()); - const QwtScaleDiv *ys = plot()->axisScaleDiv(yAxis()); + if ( plot() ) + { + const QwtScaleDiv &xs = plot()->axisScaleDiv( xAxis() ); + const QwtScaleDiv &ys = plot()->axisScaleDiv( yAxis() ); - if ( xs && ys ) { - rect = QwtDoubleRect( xs->lBound(), ys->lBound(), - xs->range(), ys->range() ); - rect = rect.normalized(); - } + rect = QRectF( xs.lowerBound(), ys.lowerBound(), + xs.range(), ys.range() ); + rect = rect.normalized(); } return rect; @@ -161,13 +159,14 @@ QwtDoubleRect QwtPlotPicker::scaleRect() const \param xAxis X axis \param yAxis Y axis */ -void QwtPlotPicker::setAxis(int xAxis, int yAxis) +void QwtPlotPicker::setAxis( int xAxis, int yAxis ) { const QwtPlot *plt = plot(); if ( !plt ) return; - if ( xAxis != d_xAxis || yAxis != d_yAxis ) { + if ( xAxis != d_xAxis || yAxis != d_yAxis ) + { d_xAxis = xAxis; d_yAxis = yAxis; } @@ -191,9 +190,9 @@ int QwtPlotPicker::yAxis() const \param pos Position in pixel coordinates \return Position string */ -QwtText QwtPlotPicker::trackerText(const QPoint &pos) const +QwtText QwtPlotPicker::trackerText( const QPoint &pos ) const { - return trackerText(invTransform(pos)); + return trackerTextF( invTransform( pos ) ); } /*! @@ -208,25 +207,26 @@ QwtText QwtPlotPicker::trackerText(const QPoint &pos) const \param pos Position \return Position string */ -QwtText QwtPlotPicker::trackerText(const QwtDoublePoint &pos) const +QwtText QwtPlotPicker::trackerTextF( const QPointF &pos ) const { QString text; - switch(rubberBand()) { - case HLineRubberBand: - text.sprintf("%.4f", pos.y()); - break; - case VLineRubberBand: - text.sprintf("%.4f", pos.x()); - break; - default: - text.sprintf("%.4f, %.4f", pos.x(), pos.y()); + switch ( rubberBand() ) + { + case HLineRubberBand: + text.sprintf( "%.4f", pos.y() ); + break; + case VLineRubberBand: + text.sprintf( "%.4f", pos.x() ); + break; + default: + text.sprintf( "%.4f, %.4f", pos.x(), pos.y() ); } - return QwtText(text); + return QwtText( text ); } /*! - Append a point to the selection and update rubberband and tracker. + Append a point to the selection and update rubber band and tracker. \param pos Additional point \sa isActive, begin(), end(), move(), appended() @@ -234,10 +234,10 @@ QwtText QwtPlotPicker::trackerText(const QwtDoublePoint &pos) const \note The appended(const QPoint &), appended(const QDoublePoint &) signals are emitted. */ -void QwtPlotPicker::append(const QPoint &pos) +void QwtPlotPicker::append( const QPoint &pos ) { - QwtPicker::append(pos); - emit appended(invTransform(pos)); + QwtPicker::append( pos ); + Q_EMIT appended( invTransform( pos ) ); } /*! @@ -249,10 +249,10 @@ void QwtPlotPicker::append(const QPoint &pos) \note The moved(const QPoint &), moved(const QDoublePoint &) signals are emitted. */ -void QwtPlotPicker::move(const QPoint &pos) +void QwtPlotPicker::move( const QPoint &pos ) { - QwtPicker::move(pos); - emit moved(invTransform(pos)); + QwtPicker::move( pos ); + Q_EMIT moved( invTransform( pos ) ); } /*! @@ -260,12 +260,12 @@ void QwtPlotPicker::move(const QPoint &pos) \param ok If true, complete the selection and emit selected signals otherwise discard the selection. - \return true if the selection is accepted, false otherwise + \return True if the selection has been accepted, false otherwise */ -bool QwtPlotPicker::end(bool ok) +bool QwtPlotPicker::end( bool ok ) { - ok = QwtPicker::end(ok); + ok = QwtPicker::end( ok ); if ( !ok ) return false; @@ -273,36 +273,46 @@ bool QwtPlotPicker::end(bool ok) if ( !plot ) return false; - const QwtPolygon &pa = selection(); - if ( pa.count() == 0 ) + const QPolygon points = selection(); + if ( points.count() == 0 ) return false; - if ( selectionFlags() & PointSelection ) { - const QwtDoublePoint pos = invTransform(pa[0]); - emit selected(pos); - } else if ( (selectionFlags() & RectSelection) && pa.count() >= 2 ) { - QPoint p1 = pa[0]; - QPoint p2 = pa[int(pa.count() - 1)]; - - if ( selectionFlags() & CenterToCorner ) { - p1.setX(p1.x() - (p2.x() - p1.x())); - p1.setY(p1.y() - (p2.y() - p1.y())); - } else if ( selectionFlags() & CenterToRadius ) { - const int radius = qwtMax(qwtAbs(p2.x() - p1.x()), - qwtAbs(p2.y() - p1.y())); - p2.setX(p1.x() + radius); - p2.setY(p1.y() + radius); - p1.setX(p1.x() - radius); - p1.setY(p1.y() - radius); - } + QwtPickerMachine::SelectionType selectionType = + QwtPickerMachine::NoSelection; + + if ( stateMachine() ) + selectionType = stateMachine()->selectionType(); - emit selected(invTransform(QRect(p1, p2)).normalized()); - } else { - QwtArray<QwtDoublePoint> dpa(pa.count()); - for ( int i = 0; i < int(pa.count()); i++ ) - dpa[i] = invTransform(pa[i]); + switch ( selectionType ) + { + case QwtPickerMachine::PointSelection: + { + const QPointF pos = invTransform( points.first() ); + Q_EMIT selected( pos ); + break; + } + case QwtPickerMachine::RectSelection: + { + if ( points.count() >= 2 ) + { + const QPoint p1 = points.first(); + const QPoint p2 = points.last(); + + const QRect rect = QRect( p1, p2 ).normalized(); + Q_EMIT selected( invTransform( rect ) ); + } + break; + } + case QwtPickerMachine::PolygonSelection: + { + QVector<QPointF> dpa( points.count() ); + for ( int i = 0; i < points.count(); i++ ) + dpa[i] = invTransform( points[i] ); - emit selected(dpa); + Q_EMIT selected( dpa ); + } + default: + break; } return true; @@ -312,68 +322,57 @@ bool QwtPlotPicker::end(bool ok) Translate a rectangle from pixel into plot coordinates \return Rectangle in plot coordinates - \sa QwtPlotPicker::transform() + \sa transform() */ -QwtDoubleRect QwtPlotPicker::invTransform(const QRect &rect) const +QRectF QwtPlotPicker::invTransform( const QRect &rect ) const { - QwtScaleMap xMap = plot()->canvasMap(d_xAxis); - QwtScaleMap yMap = plot()->canvasMap(d_yAxis); - - const double left = xMap.invTransform(rect.left()); - const double right = xMap.invTransform(rect.right()); - const double top = yMap.invTransform(rect.top()); - const double bottom = yMap.invTransform(rect.bottom()); + const QwtScaleMap xMap = plot()->canvasMap( d_xAxis ); + const QwtScaleMap yMap = plot()->canvasMap( d_yAxis ); - return QwtDoubleRect(left, top, - right - left, bottom - top); + return QwtScaleMap::invTransform( xMap, yMap, rect ); } /*! Translate a rectangle from plot into pixel coordinates \return Rectangle in pixel coordinates - \sa QwtPlotPicker::invTransform() + \sa invTransform() */ -QRect QwtPlotPicker::transform(const QwtDoubleRect &rect) const +QRect QwtPlotPicker::transform( const QRectF &rect ) const { - QwtScaleMap xMap = plot()->canvasMap(d_xAxis); - QwtScaleMap yMap = plot()->canvasMap(d_yAxis); + const QwtScaleMap xMap = plot()->canvasMap( d_xAxis ); + const QwtScaleMap yMap = plot()->canvasMap( d_yAxis ); - const int left = xMap.transform(rect.left()); - const int right = xMap.transform(rect.right()); - const int top = yMap.transform(rect.top()); - const int bottom = yMap.transform(rect.bottom()); - - return QRect(left, top, right - left, bottom - top); + return QwtScaleMap::transform( xMap, yMap, rect ).toRect(); } /*! Translate a point from pixel into plot coordinates \return Point in plot coordinates - \sa QwtPlotPicker::transform() + \sa transform() */ -QwtDoublePoint QwtPlotPicker::invTransform(const QPoint &pos) const +QPointF QwtPlotPicker::invTransform( const QPoint &pos ) const { - QwtScaleMap xMap = plot()->canvasMap(d_xAxis); - QwtScaleMap yMap = plot()->canvasMap(d_yAxis); + QwtScaleMap xMap = plot()->canvasMap( d_xAxis ); + QwtScaleMap yMap = plot()->canvasMap( d_yAxis ); - return QwtDoublePoint( - xMap.invTransform(pos.x()), - yMap.invTransform(pos.y()) - ); + return QPointF( + xMap.invTransform( pos.x() ), + yMap.invTransform( pos.y() ) + ); } /*! Translate a point from plot into pixel coordinates \return Point in pixel coordinates - \sa QwtPlotPicker::invTransform() + \sa invTransform() */ -QPoint QwtPlotPicker::transform(const QwtDoublePoint &pos) const +QPoint QwtPlotPicker::transform( const QPointF &pos ) const { - QwtScaleMap xMap = plot()->canvasMap(d_xAxis); - QwtScaleMap yMap = plot()->canvasMap(d_yAxis); + QwtScaleMap xMap = plot()->canvasMap( d_xAxis ); + QwtScaleMap yMap = plot()->canvasMap( d_yAxis ); + + const QPointF p( xMap.transform( pos.x() ), + yMap.transform( pos.y() ) ); - return QPoint( - xMap.transform(pos.x()), - yMap.transform(pos.y()) - ); + return p.toPoint(); } diff --git a/libs/qwt/qwt_plot_picker.h b/libs/qwt/qwt_plot_picker.h index d376e1f8dd..a6fe366107 100644 --- a/libs/qwt/qwt_plot_picker.h +++ b/libs/qwt/qwt_plot_picker.h @@ -7,14 +7,12 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_PLOT_PICKER_H #define QWT_PLOT_PICKER_H -#include "qwt_double_rect.h" -#include "qwt_plot_canvas.h" +#include "qwt_global.h" #include "qwt_picker.h" +#include <qvector.h> class QwtPlot; @@ -23,7 +21,7 @@ class QwtPlot; QwtPlotPicker is a QwtPicker tailored for selections on a plot canvas. It is set to a x-Axis and y-Axis and - translates all pixel coordinates into this coodinate system. + translates all pixel coordinates into this coordinate system. */ class QWT_EXPORT QwtPlotPicker: public QwtPicker @@ -31,16 +29,15 @@ class QWT_EXPORT QwtPlotPicker: public QwtPicker Q_OBJECT public: - explicit QwtPlotPicker(QwtPlotCanvas *); + explicit QwtPlotPicker( QWidget *canvas ); + virtual ~QwtPlotPicker(); - explicit QwtPlotPicker(int xAxis, int yAxis, - QwtPlotCanvas *); + explicit QwtPlotPicker( int xAxis, int yAxis, QWidget * ); - explicit QwtPlotPicker(int xAxis, int yAxis, int selectionFlags, - RubberBand rubberBand, DisplayMode trackerMode, - QwtPlotCanvas *); + explicit QwtPlotPicker( int xAxis, int yAxis, + RubberBand rubberBand, DisplayMode trackerMode, QWidget * ); - virtual void setAxis(int xAxis, int yAxis); + virtual void setAxis( int xAxis, int yAxis ); int xAxis() const; int yAxis() const; @@ -48,22 +45,22 @@ public: QwtPlot *plot(); const QwtPlot *plot() const; - QwtPlotCanvas *canvas(); - const QwtPlotCanvas *canvas() const; + QWidget *canvas(); + const QWidget *canvas() const; -signals: +Q_SIGNALS: /*! - A signal emitted in case of selectionFlags() & PointSelection. + A signal emitted in case of QwtPickerMachine::PointSelection. \param pos Selected point */ - void selected(const QwtDoublePoint &pos); + void selected( const QPointF &pos ); /*! - A signal emitted in case of selectionFlags() & RectSelection. + A signal emitted in case of QwtPickerMachine::RectSelection. \param rect Selected rectangle */ - void selected(const QwtDoubleRect &rect); + void selected( const QRectF &rect ); /*! A signal emitting the selected points, @@ -71,7 +68,7 @@ signals: \param pa Selected points */ - void selected(const QwtArray<QwtDoublePoint> &pa); + void selected( const QVector<QPointF> &pa ); /*! A signal emitted when a point has been appended to the selection @@ -79,7 +76,7 @@ signals: \param pos Position of the appended point. \sa append(). moved() */ - void appended(const QwtDoublePoint &pos); + void appended( const QPointF &pos ); /*! A signal emitted whenever the last appended point of the @@ -88,23 +85,23 @@ signals: \param pos Position of the moved last point of the selection. \sa move(), appended() */ - void moved(const QwtDoublePoint &pos); + void moved( const QPointF &pos ); protected: - QwtDoubleRect scaleRect() const; + QRectF scaleRect() const; - QwtDoubleRect invTransform(const QRect &) const; - QRect transform(const QwtDoubleRect &) const; + QRectF invTransform( const QRect & ) const; + QRect transform( const QRectF & ) const; - QwtDoublePoint invTransform(const QPoint &) const; - QPoint transform(const QwtDoublePoint &) const; + QPointF invTransform( const QPoint & ) const; + QPoint transform( const QPointF & ) const; - virtual QwtText trackerText(const QPoint &) const; - virtual QwtText trackerText(const QwtDoublePoint &) const; + virtual QwtText trackerText( const QPoint & ) const; + virtual QwtText trackerTextF( const QPointF & ) const; - virtual void move(const QPoint &); - virtual void append(const QPoint &); - virtual bool end(bool ok = true); + virtual void move( const QPoint & ); + virtual void append( const QPoint & ); + virtual bool end( bool ok = true ); private: int d_xAxis; diff --git a/libs/qwt/qwt_plot_rasteritem.cpp b/libs/qwt/qwt_plot_rasteritem.cpp index 2f8fc0c678..e12d7c762e 100644 --- a/libs/qwt/qwt_plot_rasteritem.cpp +++ b/libs/qwt/qwt_plot_rasteritem.cpp @@ -7,88 +7,435 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_plot_rasteritem.h" +#include "qwt_scale_map.h" +#include "qwt_painter.h" #include <qapplication.h> #include <qdesktopwidget.h> -#include <qpaintdevice.h> #include <qpainter.h> -#include "qwt_legend.h" -#include "qwt_legend_item.h" -#include "qwt_scale_map.h" -#include "qwt_plot_rasteritem.h" +#include <qpaintengine.h> +#include <qmath.h> +#if QT_VERSION >= 0x040400 +#include <qthread.h> +#include <qfuture.h> +#include <qtconcurrentrun.h> +#endif +#include <float.h> class QwtPlotRasterItem::PrivateData { public: PrivateData(): - alpha(-1) { + alpha( -1 ), + paintAttributes( QwtPlotRasterItem::PaintInDeviceResolution ) + { cache.policy = QwtPlotRasterItem::NoCache; } int alpha; - struct ImageCache { + QwtPlotRasterItem::PaintAttributes paintAttributes; + + struct ImageCache + { QwtPlotRasterItem::CachePolicy policy; - QwtDoubleRect rect; - QSize size; + QRectF area; + QSizeF size; QImage image; } cache; }; -static QImage toRgba(const QImage& image, int alpha) + +static QRectF qwtAlignRect(const QRectF &rect) { - if ( alpha < 0 || alpha >= 255 ) - return image; + QRectF r; + r.setLeft( qRound( rect.left() ) ); + r.setRight( qRound( rect.right() ) ); + r.setTop( qRound( rect.top() ) ); + r.setBottom( qRound( rect.bottom() ) ); -#if QT_VERSION < 0x040000 - QImage alphaImage(image.size(), 32); - alphaImage.setAlphaBuffer(true); -#else - QImage alphaImage(image.size(), QImage::Format_ARGB32); -#endif + return r; +} - const QRgb mask1 = qRgba(0, 0, 0, alpha); - const QRgb mask2 = qRgba(255, 255, 255, 0); - const QRgb mask3 = qRgba(0, 0, 0, 255); +static QRectF qwtStripRect(const QRectF &rect, const QRectF &area, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtInterval &xInterval, const QwtInterval &yInterval) +{ + QRectF r = rect; + if ( xInterval.borderFlags() & QwtInterval::ExcludeMinimum ) + { + if ( area.left() <= xInterval.minValue() ) + { + if ( xMap.isInverting() ) + r.adjust(0, 0, -1, 0); + else + r.adjust(1, 0, 0, 0); + } + } - const int w = image.size().width(); - const int h = image.size().height(); + if ( xInterval.borderFlags() & QwtInterval::ExcludeMaximum ) + { + if ( area.right() >= xInterval.maxValue() ) + { + if ( xMap.isInverting() ) + r.adjust(1, 0, 0, 0); + else + r.adjust(0, 0, -1, 0); + } + } - if ( image.depth() == 8 ) { - for ( int y = 0; y < h; y++ ) { - QRgb* alphaLine = (QRgb*)alphaImage.scanLine(y); - const unsigned char *line = image.scanLine(y); + if ( yInterval.borderFlags() & QwtInterval::ExcludeMinimum ) + { + if ( area.top() <= yInterval.minValue() ) + { + if ( yMap.isInverting() ) + r.adjust(0, 0, 0, -1); + else + r.adjust(0, 1, 0, 0); + } + } - for ( int x = 0; x < w; x++ ) - *alphaLine++ = (image.color(*line++) & mask2) | mask1; + if ( yInterval.borderFlags() & QwtInterval::ExcludeMaximum ) + { + if ( area.bottom() >= yInterval.maxValue() ) + { + if ( yMap.isInverting() ) + r.adjust(0, 1, 0, 0); + else + r.adjust(0, 0, 0, -1); } - } else if ( image.depth() == 32 ) { - for ( int y = 0; y < h; y++ ) { - QRgb* alphaLine = (QRgb*)alphaImage.scanLine(y); - const QRgb* line = (const QRgb*) image.scanLine(y); + } + + return r; +} + +static QImage qwtExpandImage(const QImage &image, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &area, const QRectF &area2, const QRectF &paintRect, + const QwtInterval &xInterval, const QwtInterval &yInterval ) +{ + const QRectF strippedRect = qwtStripRect(paintRect, area2, + xMap, yMap, xInterval, yInterval); + const QSize sz = strippedRect.toRect().size(); + + const int w = image.width(); + const int h = image.height(); + + const QRectF r = QwtScaleMap::transform(xMap, yMap, area).normalized(); + const double pw = ( r.width() - 1) / w; + const double ph = ( r.height() - 1) / h; + + double px0, py0; + if ( !xMap.isInverting() ) + { + px0 = xMap.transform( area2.left() ); + px0 = qRound( px0 ); + px0 = px0 - xMap.transform( area.left() ); + } + else + { + px0 = xMap.transform( area2.right() ); + px0 = qRound( px0 ); + px0 -= xMap.transform( area.right() ); + + px0 -= 1.0; + } + px0 += strippedRect.left() - paintRect.left(); + + if ( !yMap.isInverting() ) + { + py0 = yMap.transform( area2.top() ); + py0 = qRound( py0 ); + py0 -= yMap.transform( area.top() ); + } + else + { + py0 = yMap.transform( area2.bottom() ); + py0 = qRound( py0 ); + py0 -= yMap.transform( area.bottom() ); + + py0 -= 1.0; + } + py0 += strippedRect.top() - paintRect.top(); + + QImage expanded(sz, image.format()); + + switch( image.depth() ) + { + case 32: + { + for ( int y1 = 0; y1 < h; y1++ ) + { + int yy1; + if ( y1 == 0 ) + { + yy1 = 0; + } + else + { + yy1 = qRound( y1 * ph - py0 ); + if ( yy1 < 0 ) + yy1 = 0; + } + + int yy2; + if ( y1 == h - 1 ) + { + yy2 = sz.height(); + } + else + { + yy2 = qRound( ( y1 + 1 ) * ph - py0 ); + if ( yy2 > sz.height() ) + yy2 = sz.height(); + } + + const quint32 *line1 = + reinterpret_cast<const quint32 *>( image.scanLine( y1 ) ); + + for ( int x1 = 0; x1 < w; x1++ ) + { + int xx1; + if ( x1 == 0 ) + { + xx1 = 0; + } + else + { + xx1 = qRound( x1 * pw - px0 ); + if ( xx1 < 0 ) + xx1 = 0; + } + + int xx2; + if ( x1 == w - 1 ) + { + xx2 = sz.width(); + } + else + { + xx2 = qRound( ( x1 + 1 ) * pw - px0 ); + if ( xx2 > sz.width() ) + xx2 = sz.width(); + } + + const quint32 rgb( line1[x1] ); + for ( int y2 = yy1; y2 < yy2; y2++ ) + { + quint32 *line2 = reinterpret_cast<quint32 *>( + expanded.scanLine( y2 ) ); + + for ( int x2 = xx1; x2 < xx2; x2++ ) + line2[x2] = rgb; + } + } + } + break; + } + case 8: + { + for ( int y1 = 0; y1 < h; y1++ ) + { + int yy1; + if ( y1 == 0 ) + { + yy1 = 0; + } + else + { + yy1 = qRound( y1 * ph - py0 ); + if ( yy1 < 0 ) + yy1 = 0; + } + + int yy2; + if ( y1 == h - 1 ) + { + yy2 = sz.height(); + } + else + { + yy2 = qRound( ( y1 + 1 ) * ph - py0 ); + if ( yy2 > sz.height() ) + yy2 = sz.height(); + } + + const uchar *line1 = image.scanLine( y1 ); + + for ( int x1 = 0; x1 < w; x1++ ) + { + int xx1; + if ( x1 == 0 ) + { + xx1 = 0; + } + else + { + xx1 = qRound( x1 * pw - px0 ); + if ( xx1 < 0 ) + xx1 = 0; + } + + int xx2; + if ( x1 == w - 1 ) + { + xx2 = sz.width(); + } + else + { + xx2 = qRound( ( x1 + 1 ) * pw - px0 ); + if ( xx2 > sz.width() ) + xx2 = sz.width(); + } + + for ( int y2 = yy1; y2 < yy2; y2++ ) + { + uchar *line2 = expanded.scanLine( y2 ); + memset( line2 + xx1, line1[x1], xx2 - xx1 ); + } + } + } + break; + } + default: + expanded = image; + } + + return expanded; +} + +static QRectF qwtExpandToPixels(const QRectF &rect, const QRectF &pixelRect) +{ + const double pw = pixelRect.width(); + const double ph = pixelRect.height(); + + const double dx1 = pixelRect.left() - rect.left(); + const double dx2 = pixelRect.right() - rect.right(); + const double dy1 = pixelRect.top() - rect.top(); + const double dy2 = pixelRect.bottom() - rect.bottom(); - for ( int x = 0; x < w; x++ ) { + QRectF r; + r.setLeft( pixelRect.left() - qCeil( dx1 / pw ) * pw ); + r.setTop( pixelRect.top() - qCeil( dy1 / ph ) * ph ); + r.setRight( pixelRect.right() - qFloor( dx2 / pw ) * pw ); + r.setBottom( pixelRect.bottom() - qFloor( dy2 / ph ) * ph ); + + return r; +} + +static void qwtTransformMaps( const QTransform &tr, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + QwtScaleMap &xxMap, QwtScaleMap &yyMap ) +{ + const QPointF p1 = tr.map( QPointF( xMap.p1(), yMap.p1() ) ); + const QPointF p2 = tr.map( QPointF( xMap.p2(), yMap.p2() ) ); + + xxMap = xMap; + xxMap.setPaintInterval( p1.x(), p2.x() ); + + yyMap = yMap; + yyMap.setPaintInterval( p1.y(), p2.y() ); +} + +static void qwtAdjustMaps( QwtScaleMap &xMap, QwtScaleMap &yMap, + const QRectF &area, const QRectF &paintRect) +{ + double sx1 = area.left(); + double sx2 = area.right(); + if ( xMap.isInverting() ) + qSwap(sx1, sx2); + + double sy1 = area.top(); + double sy2 = area.bottom(); + + if ( yMap.isInverting() ) + qSwap(sy1, sy2); + + xMap.setPaintInterval(paintRect.left(), paintRect.right()); + xMap.setScaleInterval(sx1, sx2); + + yMap.setPaintInterval(paintRect.top(), paintRect.bottom()); + yMap.setScaleInterval(sy1, sy2); +} + +static bool qwtUseCache( QwtPlotRasterItem::CachePolicy policy, + const QPainter *painter ) +{ + bool doCache = false; + + if ( policy == QwtPlotRasterItem::PaintCache ) + { + // Caching doesn't make sense, when the item is + // not painted to screen + + switch ( painter->paintEngine()->type() ) + { + case QPaintEngine::SVG: + case QPaintEngine::Pdf: + case QPaintEngine::PostScript: + case QPaintEngine::MacPrinter: + case QPaintEngine::Picture: + break; + default:; + doCache = true; + } + } + + return doCache; +} + +static void qwtToRgba( const QImage* from, QImage* to, + const QRect& tile, int alpha ) +{ + const QRgb mask1 = qRgba( 0, 0, 0, alpha ); + const QRgb mask2 = qRgba( 255, 255, 255, 0 ); + const QRgb mask3 = qRgba( 0, 0, 0, 255 ); + + const int y0 = tile.top(); + const int y1 = tile.bottom(); + const int x0 = tile.left(); + const int x1 = tile.right(); + + if ( from->depth() == 8 ) + { + for ( int y = y0; y <= y1; y++ ) + { + QRgb *alphaLine = reinterpret_cast<QRgb *>( to->scanLine( y ) ); + const unsigned char *line = from->scanLine( y ); + + for ( int x = x0; x <= x1; x++ ) + *alphaLine++ = ( from->color( *line++ ) & mask2 ) | mask1; + } + } + else if ( from->depth() == 32 ) + { + for ( int y = y0; y <= y1; y++ ) + { + QRgb *alphaLine = reinterpret_cast<QRgb *>( to->scanLine( y ) ); + const QRgb *line = reinterpret_cast<const QRgb *>( from->scanLine( y ) ); + + for ( int x = x0; x <= x1; x++ ) + { const QRgb rgb = *line++; if ( rgb & mask3 ) // alpha != 0 - *alphaLine++ = (rgb & mask2) | mask1; + *alphaLine++ = ( rgb & mask2 ) | mask1; else *alphaLine++ = rgb; } } } - - return alphaImage; } //! Constructor -QwtPlotRasterItem::QwtPlotRasterItem(const QString& title): - QwtPlotItem(QwtText(title)) +QwtPlotRasterItem::QwtPlotRasterItem( const QString& title ): + QwtPlotItem( QwtText( title ) ) { init(); } //! Constructor -QwtPlotRasterItem::QwtPlotRasterItem(const QwtText& title): - QwtPlotItem(title) +QwtPlotRasterItem::QwtPlotRasterItem( const QwtText& title ): + QwtPlotItem( title ) { init(); } @@ -103,10 +450,34 @@ void QwtPlotRasterItem::init() { d_data = new PrivateData(); - setItemAttribute(QwtPlotItem::AutoScale, true); - setItemAttribute(QwtPlotItem::Legend, false); + setItemAttribute( QwtPlotItem::AutoScale, true ); + setItemAttribute( QwtPlotItem::Legend, false ); + + setZ( 8.0 ); +} + +/*! + Specify an attribute how to draw the raster item + + \param attribute Paint attribute + \param on On/Off + /sa PaintAttribute, testPaintAttribute() +*/ +void QwtPlotRasterItem::setPaintAttribute( PaintAttribute attribute, bool on ) +{ + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; +} - setZ(8.0); +/*! + \return True, when attribute is enabled + \sa PaintAttribute, setPaintAttribute() +*/ +bool QwtPlotRasterItem::testPaintAttribute( PaintAttribute attribute ) const +{ + return ( d_data->paintAttributes & attribute ); } /*! @@ -132,7 +503,7 @@ void QwtPlotRasterItem::init() \sa alpha() */ -void QwtPlotRasterItem::setAlpha(int alpha) +void QwtPlotRasterItem::setAlpha( int alpha ) { if ( alpha < 0 ) alpha = -1; @@ -140,7 +511,8 @@ void QwtPlotRasterItem::setAlpha(int alpha) if ( alpha > 255 ) alpha = 255; - if ( alpha != d_data->alpha ) { + if ( alpha != d_data->alpha ) + { d_data->alpha = alpha; itemChanged(); @@ -165,9 +537,10 @@ int QwtPlotRasterItem::alpha() const \sa CachePolicy, cachePolicy() */ void QwtPlotRasterItem::setCachePolicy( - QwtPlotRasterItem::CachePolicy policy) + QwtPlotRasterItem::CachePolicy policy ) { - if ( d_data->cache.policy != policy ) { + if ( d_data->cache.policy != policy ) + { d_data->cache.policy = policy; invalidateCache(); @@ -186,27 +559,45 @@ QwtPlotRasterItem::CachePolicy QwtPlotRasterItem::cachePolicy() const /*! Invalidate the paint cache - \sa setCachePolicy + \sa setCachePolicy() */ void QwtPlotRasterItem::invalidateCache() { d_data->cache.image = QImage(); - d_data->cache.rect = QwtDoubleRect(); + d_data->cache.area = QRect(); d_data->cache.size = QSize(); } /*! - \brief Returns the recommended raster for a given rect. + \brief Pixel hint + + The geometry of a pixel is used to calculated the resolution and + alignment of the rendered image. + + Width and height of the hint need to be the horizontal + and vertical distances between 2 neighbored points. + The center of the hint has to be the position of any point + ( it doesn't matter which one ). + + Limiting the resolution of the image might significantly improve + the performance and heavily reduce the amount of memory when rendering + a QImage from the raster data. + + The default implementation returns an empty rectangle (QRectF()), + meaning, that the image will be rendered in target device ( f.e screen ) + resolution. - F.e the raster hint can be used to limit the resolution of - the image that is rendered. + \param area In most implementations the resolution of the data doesn't + depend on the requested area. - The default implementation returns an invalid size (QSize()), - what means: no hint. + \return Bounding rectangle of a pixel + + \sa render(), renderImage() */ -QSize QwtPlotRasterItem::rasterHint(const QwtDoubleRect &) const +QRectF QwtPlotRasterItem::pixelHint( const QRectF &area ) const { - return QSize(); + Q_UNUSED( area ); + return QRectF(); } /*! @@ -214,72 +605,342 @@ QSize QwtPlotRasterItem::rasterHint(const QwtDoubleRect &) const \param painter Painter \param xMap X-Scale Map \param yMap Y-Scale Map - \param canvasRect Contents rect of the plot canvas + \param canvasRect Contents rectangle of the plot canvas */ -void QwtPlotRasterItem::draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &canvasRect) const +void QwtPlotRasterItem::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const { if ( canvasRect.isEmpty() || d_data->alpha == 0 ) return; - QwtDoubleRect area = invTransform(xMap, yMap, canvasRect); - if ( boundingRect().isValid() ) - area &= boundingRect(); + const bool doCache = qwtUseCache( d_data->cache.policy, painter ); - const QRect paintRect = transform(xMap, yMap, area); - if ( !paintRect.isValid() ) - return; + const QwtInterval xInterval = interval( Qt::XAxis ); + const QwtInterval yInterval = interval( Qt::YAxis ); + + /* + Scaling an image always results in a loss of + precision/quality. So we always render the image in + paint device resolution. + */ + + QwtScaleMap xxMap, yyMap; + qwtTransformMaps( painter->transform(), xMap, yMap, xxMap, yyMap ); + + QRectF paintRect = painter->transform().mapRect( canvasRect ); + QRectF area = QwtScaleMap::invTransform( xxMap, yyMap, paintRect ); + const QRectF br = boundingRect(); + if ( br.isValid() && !br.contains( area ) ) + { + area &= br; + if ( !area.isValid() ) + return; + + paintRect = QwtScaleMap::transform( xxMap, yyMap, area ); + } + + QRectF imageRect; QImage image; - bool doCache = true; - if ( painter->device()->devType() == QInternal::Printer - || painter->device()->devType() == QInternal::Picture ) { - doCache = false; + QRectF pixelRect = pixelHint(area); + if ( !pixelRect.isEmpty() ) + { + // pixel in target device resolution + const double dx = qAbs( xxMap.invTransform( 1 ) - xxMap.invTransform( 0 ) ); + const double dy = qAbs( yyMap.invTransform( 1 ) - yyMap.invTransform( 0 ) ); + + if ( dx > pixelRect.width() && dy > pixelRect.height() ) + { + /* + When the resolution of the data pixels is higher than + the resolution of the target device we render in + target device resolution. + */ + pixelRect = QRectF(); + } } - if ( !doCache || d_data->cache.policy == NoCache ) { - image = renderImage(xMap, yMap, area); - if ( d_data->alpha >= 0 && d_data->alpha < 255 ) - image = toRgba(image, d_data->alpha); + if ( pixelRect.isEmpty() ) + { + if ( QwtPainter::roundingAlignment( painter ) ) + { + // we want to have maps, where the boundaries of + // the aligned paint rectangle exactly match the area - } else if ( d_data->cache.policy == PaintCache ) { - if ( d_data->cache.image.isNull() || d_data->cache.rect != area - || d_data->cache.size != paintRect.size() ) { - d_data->cache.image = renderImage(xMap, yMap, area); - d_data->cache.rect = area; - d_data->cache.size = paintRect.size(); + paintRect = qwtAlignRect(paintRect); + qwtAdjustMaps(xxMap, yyMap, area, paintRect); } - image = d_data->cache.image; - if ( d_data->alpha >= 0 && d_data->alpha < 255 ) - image = toRgba(image, d_data->alpha); - } else if ( d_data->cache.policy == ScreenCache ) { - const QSize screenSize = - QApplication::desktop()->screenGeometry().size(); - - if ( paintRect.width() > screenSize.width() || - paintRect.height() > screenSize.height() ) { - image = renderImage(xMap, yMap, area); - } else { - if ( d_data->cache.image.isNull() || d_data->cache.rect != area ) { - QwtScaleMap cacheXMap = xMap; - cacheXMap.setPaintInterval( 0, screenSize.width()); - - QwtScaleMap cacheYMap = yMap; - cacheYMap.setPaintInterval(screenSize.height(), 0); - - d_data->cache.image = renderImage( - cacheXMap, cacheYMap, area); - d_data->cache.rect = area; - d_data->cache.size = paintRect.size(); - } + // When we have no information about position and size of + // data pixels we render in resolution of the paint device. + + image = compose(xxMap, yyMap, + area, paintRect, paintRect.size().toSize(), doCache); + if ( image.isNull() ) + return; + + // Remove pixels at the boundaries, when explicitly + // excluded in the intervals + + imageRect = qwtStripRect(paintRect, area, + xxMap, yyMap, xInterval, yInterval); + + if ( imageRect != paintRect ) + { + const QRect r( + qRound( imageRect.x() - paintRect.x()), + qRound( imageRect.y() - paintRect.y() ), + qRound( imageRect.width() ), + qRound( imageRect.height() ) ); + + image = image.copy(r); + } + } + else + { + if ( QwtPainter::roundingAlignment( painter ) ) + paintRect = qwtAlignRect(paintRect); + + // align the area to the data pixels + QRectF imageArea = qwtExpandToPixels(area, pixelRect); + + if ( imageArea.right() == xInterval.maxValue() && + !( xInterval.borderFlags() & QwtInterval::ExcludeMaximum ) ) + { + imageArea.adjust(0, 0, pixelRect.width(), 0); + } + if ( imageArea.bottom() == yInterval.maxValue() && + !( yInterval.borderFlags() & QwtInterval::ExcludeMaximum ) ) + { + imageArea.adjust(0, 0, 0, pixelRect.height() ); + } + + QSize imageSize; + imageSize.setWidth( qRound( imageArea.width() / pixelRect.width() ) ); + imageSize.setHeight( qRound( imageArea.height() / pixelRect.height() ) ); + image = compose(xxMap, yyMap, + imageArea, paintRect, imageSize, doCache ); + if ( image.isNull() ) + return; + + imageRect = qwtStripRect(paintRect, area, + xxMap, yyMap, xInterval, yInterval); + + if ( ( image.width() > 1 || image.height() > 1 ) && + testPaintAttribute( PaintInDeviceResolution ) ) + { + // Because of rounding errors the pixels + // need to be expanded manually to rectangles of + // different sizes + + image = qwtExpandImage(image, xxMap, yyMap, + imageArea, area, paintRect, xInterval, yInterval ); + } + } + + painter->save(); + painter->setWorldTransform( QTransform() ); + + QwtPainter::drawImage( painter, imageRect, image ); + + painter->restore(); +} + +/*! + \return Bounding interval for an axis + + This method is intended to be reimplemented by derived classes. + The default implementation returns an invalid interval. + + \param axis X, Y, or Z axis +*/ +QwtInterval QwtPlotRasterItem::interval(Qt::Axis axis) const +{ + Q_UNUSED( axis ); + return QwtInterval(); +} + +/*! + \return Bounding rectangle of the data + \sa QwtPlotRasterItem::interval() +*/ +QRectF QwtPlotRasterItem::boundingRect() const +{ + const QwtInterval intervalX = interval( Qt::XAxis ); + const QwtInterval intervalY = interval( Qt::YAxis ); + + if ( !intervalX.isValid() && !intervalY.isValid() ) + return QRectF(); // no bounding rect + + QRectF r; + + if ( intervalX.isValid() ) + { + r.setLeft( intervalX.minValue() ); + r.setRight( intervalX.maxValue() ); + } + else + { + r.setLeft(-0.5 * FLT_MAX); + r.setWidth(FLT_MAX); + } + + if ( intervalY.isValid() ) + { + r.setTop( intervalY.minValue() ); + r.setBottom( intervalY.maxValue() ); + } + else + { + r.setTop(-0.5 * FLT_MAX); + r.setHeight(FLT_MAX); + } + + return r.normalized(); +} +QImage QwtPlotRasterItem::compose( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &imageArea, const QRectF &paintRect, + const QSize &imageSize, bool doCache) const +{ + QImage image; + if ( imageArea.isEmpty() || paintRect.isEmpty() || imageSize.isEmpty() ) + return image; + + if ( doCache ) + { + if ( !d_data->cache.image.isNull() + && d_data->cache.area == imageArea + && d_data->cache.size == paintRect.size() ) + { image = d_data->cache.image; } - image = toRgba(image, d_data->alpha); } - painter->drawImage(paintRect, image); + if ( image.isNull() ) + { + double dx = 0.0; + if ( paintRect.toRect().width() > imageSize.width() ) + dx = imageArea.width() / imageSize.width(); + + const QwtScaleMap xxMap = + imageMap(Qt::Horizontal, xMap, imageArea, imageSize, dx); + + double dy = 0.0; + if ( paintRect.toRect().height() > imageSize.height() ) + dy = imageArea.height() / imageSize.height(); + + const QwtScaleMap yyMap = + imageMap(Qt::Vertical, yMap, imageArea, imageSize, dy); + + image = renderImage( xxMap, yyMap, imageArea, imageSize ); + + if ( doCache ) + { + d_data->cache.area = imageArea; + d_data->cache.size = paintRect.size(); + d_data->cache.image = image; + } + } + + if ( d_data->alpha >= 0 && d_data->alpha < 255 ) + { + QImage alphaImage( image.size(), QImage::Format_ARGB32 ); + +#if QT_VERSION >= 0x040400 && !defined(QT_NO_QFUTURE) + uint numThreads = renderThreadCount(); + + if ( numThreads <= 0 ) + numThreads = QThread::idealThreadCount(); + + if ( numThreads <= 0 ) + numThreads = 1; + + const int numRows = image.height() / numThreads; + + QList< QFuture<void> > futures; + for ( uint i = 0; i < numThreads; i++ ) + { + QRect tile( 0, i * numRows, image.width(), numRows ); + if ( i == numThreads - 1 ) + { + tile.setHeight( image.height() - i * numRows ); + qwtToRgba( &image, &alphaImage, tile, d_data->alpha ); + } + else + { + futures += QtConcurrent::run( + &qwtToRgba, &image, &alphaImage, tile, d_data->alpha ); + } + } + for ( int i = 0; i < futures.size(); i++ ) + futures[i].waitForFinished(); +#else + const QRect tile( 0, 0, image.width(), image.height() ); + qwtToRgba( &image, &alphaImage, tile, d_data->alpha ); +#endif + image = alphaImage; + } + + return image; +} + +/*! + \brief Calculate a scale map for painting to an image + + \param orientation Orientation, Qt::Horizontal means a X axis + \param map Scale map for rendering the plot item + \param area Area to be painted on the image + \param imageSize Image size + \param pixelSize Width/Height of a data pixel + + \return Calculated scale map +*/ +QwtScaleMap QwtPlotRasterItem::imageMap( + Qt::Orientation orientation, + const QwtScaleMap &map, const QRectF &area, + const QSize &imageSize, double pixelSize) const +{ + double p1, p2, s1, s2; + + if ( orientation == Qt::Horizontal ) + { + p1 = 0.0; + p2 = imageSize.width(); + s1 = area.left(); + s2 = area.right(); + } + else + { + p1 = 0.0; + p2 = imageSize.height(); + s1 = area.top(); + s2 = area.bottom(); + } + + if ( pixelSize > 0.0 ) + { + double off = 0.5 * pixelSize; + if ( map.isInverting() ) + off = -off; + + s1 += off; + s2 += off; + } + else + { + p2--; + } + + if ( map.isInverting() && ( s1 < s2 ) ) + qSwap( s1, s2 ); + + QwtScaleMap newMap = map; + newMap.setPaintInterval( p1, p2 ); + newMap.setScaleInterval( s1, s2 ); + + return newMap; } diff --git a/libs/qwt/qwt_plot_rasteritem.h b/libs/qwt/qwt_plot_rasteritem.h index 22b2df7ec6..f411816ea3 100644 --- a/libs/qwt/qwt_plot_rasteritem.h +++ b/libs/qwt/qwt_plot_rasteritem.h @@ -10,12 +10,13 @@ #ifndef QWT_PLOT_RASTERITEM_H #define QWT_PLOT_RASTERITEM_H +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include "qwt_interval.h" #include <qglobal.h> #include <qstring.h> #include <qimage.h> -#include "qwt_plot_item.h" - /*! \brief A class, which displays raster data @@ -37,61 +38,99 @@ class QWT_EXPORT QwtPlotRasterItem: public QwtPlotItem { public: /*! - - NoCache\n - renderImage() is called, whenever the item has to be repainted - - PaintCache\n - renderImage() is called, whenever the image cache is not valid, - or the scales, or the size of the canvas has changed. This type - of cache is only useful for improving the performance of hide/show - operations. All other situations are already handled by the - plot canvas cache. - - ScreenCache\n - The screen cache is an image in size of the screen. As long as - the scales don't change the target image is scaled from the cache. - This might improve the performance - when resizing the plot widget, but suffers from scaling effects. - + \brief Cache policy The default policy is NoCache */ - enum CachePolicy { + enum CachePolicy + { + /*! + renderImage() is called each time the item has to be repainted + */ NoCache, - PaintCache, - ScreenCache + + /*! + renderImage() is called, whenever the image cache is not valid, + or the scales, or the size of the canvas has changed. + + This type of cache is useful for improving the performance + of hide/show operations or manipulations of the alpha value. + All other situations are handled by the canvas backing store. + */ + PaintCache + }; + + /*! + Attributes to modify the drawing algorithm. + \sa setPaintAttribute(), testPaintAttribute() + */ + enum PaintAttribute + { + /*! + When the image is rendered according to the data pixels + ( QwtRasterData::pixelHint() ) it can be expanded to paint + device resolution before it is passed to QPainter. + The expansion algorithm rounds the pixel borders in the same + way as the axis ticks, what is usually better than the + scaling algorithm implemented in Qt. + Disabling this flag might make sense, to reduce the size of a + document/file. If this is possible for a document format + depends on the implementation of the specific QPaintEngine. + */ + + PaintInDeviceResolution = 1 }; - explicit QwtPlotRasterItem(const QString& title = QString::null); - explicit QwtPlotRasterItem(const QwtText& title); + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + + explicit QwtPlotRasterItem( const QString& title = QString::null ); + explicit QwtPlotRasterItem( const QwtText& title ); virtual ~QwtPlotRasterItem(); - void setAlpha(int alpha); + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + void setAlpha( int alpha ); int alpha() const; - void setCachePolicy(CachePolicy); + void setCachePolicy( CachePolicy ); CachePolicy cachePolicy() const; void invalidateCache(); - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &rect) const; + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; - virtual QSize rasterHint(const QwtDoubleRect &) const; + virtual QRectF pixelHint( const QRectF & ) const; -protected: + virtual QwtInterval interval(Qt::Axis) const; + virtual QRectF boundingRect() const; +protected: /*! - Renders an image for an area - - The format of the image must be QImage::Format_Indexed8, - QImage::Format_RGB32 or QImage::Format_ARGB32 + \brief Render an image + + An implementation of render() might iterate over all + pixels of imageRect. Each pixel has to be translated into + the corresponding position in scale coordinates using the maps. + This position can be used to look up a value in a implementation + specific way and to map it into a color. + + \param xMap X-Scale Map + \param yMap Y-Scale Map + \param area Requested area for the image in scale coordinates + \param imageSize Requested size of the image + + \return Rendered image + */ + virtual QImage renderImage( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QRectF &area, + const QSize &imageSize ) const = 0; - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param area Requested area for the image in scale coordinates - */ - virtual QImage renderImage(const QwtScaleMap &xMap, - const QwtScaleMap &yMap, const QwtDoubleRect &area - ) const = 0; + virtual QwtScaleMap imageMap( Qt::Orientation, + const QwtScaleMap &map, const QRectF &area, + const QSize &imageSize, double pixelSize) const; private: QwtPlotRasterItem( const QwtPlotRasterItem & ); @@ -99,8 +138,15 @@ private: void init(); + QImage compose( const QwtScaleMap &, const QwtScaleMap &, + const QRectF &imageArea, const QRectF &paintRect, + const QSize &imageSize, bool doCache) const; + + class PrivateData; PrivateData *d_data; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotRasterItem::PaintAttributes ) + #endif diff --git a/libs/qwt/qwt_plot_renderer.cpp b/libs/qwt/qwt_plot_renderer.cpp new file mode 100644 index 0000000000..3416f98062 --- /dev/null +++ b/libs/qwt/qwt_plot_renderer.cpp @@ -0,0 +1,1014 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_renderer.h" +#include "qwt_plot.h" +#include "qwt_painter.h" +#include "qwt_plot_layout.h" +#include "qwt_abstract_legend.h" +#include "qwt_scale_widget.h" +#include "qwt_scale_engine.h" +#include "qwt_text.h" +#include "qwt_text_label.h" +#include "qwt_math.h" +#include <qpainter.h> +#include <qpaintengine.h> +#include <qtransform.h> +#include <qprinter.h> +#include <qprintdialog.h> +#include <qfiledialog.h> +#include <qfileinfo.h> +#include <qstyle.h> +#include <qstyleoption.h> +#include <qimagewriter.h> +#ifndef QWT_NO_SVG +#ifdef QT_SVG_LIB +#include <qsvggenerator.h> +#endif +#endif + +static QPainterPath qwtCanvasClip( + const QWidget* canvas, const QRectF &canvasRect ) +{ + // The clip region is calculated in integers + // To avoid too much rounding errors better + // calculate it in target device resolution + + int x1 = qCeil( canvasRect.left() ); + int x2 = qFloor( canvasRect.right() ); + int y1 = qCeil( canvasRect.top() ); + int y2 = qFloor( canvasRect.bottom() ); + + const QRect r( x1, y1, x2 - x1 - 1, y2 - y1 - 1 ); + + QPainterPath clipPath; + + ( void ) QMetaObject::invokeMethod( + const_cast< QWidget *>( canvas ), "borderPath", + Qt::DirectConnection, + Q_RETURN_ARG( QPainterPath, clipPath ), Q_ARG( QRect, r ) ); + + return clipPath; +} + +class QwtPlotRenderer::PrivateData +{ +public: + PrivateData(): + discardFlags( QwtPlotRenderer::DiscardNone ), + layoutFlags( QwtPlotRenderer::DefaultLayout ) + { + } + + QwtPlotRenderer::DiscardFlags discardFlags; + QwtPlotRenderer::LayoutFlags layoutFlags; +}; + +/*! + Constructor + \param parent Parent object +*/ +QwtPlotRenderer::QwtPlotRenderer( QObject *parent ): + QObject( parent ) +{ + d_data = new PrivateData; +} + +//! Destructor +QwtPlotRenderer::~QwtPlotRenderer() +{ + delete d_data; +} + +/*! + Change a flag, indicating what to discard from rendering + + \param flag Flag to change + \param on On/Off + + \sa DiscardFlag, testDiscardFlag(), setDiscardFlags(), discardFlags() +*/ +void QwtPlotRenderer::setDiscardFlag( DiscardFlag flag, bool on ) +{ + if ( on ) + d_data->discardFlags |= flag; + else + d_data->discardFlags &= ~flag; +} + +/*! + \return True, if flag is enabled. + \param flag Flag to be tested + \sa DiscardFlag, setDiscardFlag(), setDiscardFlags(), discardFlags() +*/ +bool QwtPlotRenderer::testDiscardFlag( DiscardFlag flag ) const +{ + return d_data->discardFlags & flag; +} + +/*! + Set the flags, indicating what to discard from rendering + + \param flags Flags + \sa DiscardFlag, setDiscardFlag(), testDiscardFlag(), discardFlags() +*/ +void QwtPlotRenderer::setDiscardFlags( DiscardFlags flags ) +{ + d_data->discardFlags = flags; +} + +/*! + \return Flags, indicating what to discard from rendering + \sa DiscardFlag, setDiscardFlags(), setDiscardFlag(), testDiscardFlag() +*/ +QwtPlotRenderer::DiscardFlags QwtPlotRenderer::discardFlags() const +{ + return d_data->discardFlags; +} + +/*! + Change a layout flag + + \param flag Flag to change + \param on On/Off + + \sa LayoutFlag, testLayoutFlag(), setLayoutFlags(), layoutFlags() +*/ +void QwtPlotRenderer::setLayoutFlag( LayoutFlag flag, bool on ) +{ + if ( on ) + d_data->layoutFlags |= flag; + else + d_data->layoutFlags &= ~flag; +} + +/*! + \return True, if flag is enabled. + \param flag Flag to be tested + \sa LayoutFlag, setLayoutFlag(), setLayoutFlags(), layoutFlags() +*/ +bool QwtPlotRenderer::testLayoutFlag( LayoutFlag flag ) const +{ + return d_data->layoutFlags & flag; +} + +/*! + Set the layout flags + + \param flags Flags + \sa LayoutFlag, setLayoutFlag(), testLayoutFlag(), layoutFlags() +*/ +void QwtPlotRenderer::setLayoutFlags( LayoutFlags flags ) +{ + d_data->layoutFlags = flags; +} + +/*! + \return Layout flags + \sa LayoutFlag, setLayoutFlags(), setLayoutFlag(), testLayoutFlag() +*/ +QwtPlotRenderer::LayoutFlags QwtPlotRenderer::layoutFlags() const +{ + return d_data->layoutFlags; +} + +/*! + Render a plot to a file + + The format of the document will be auto-detected from the + suffix of the file name. + + \param plot Plot widget + \param fileName Path of the file, where the document will be stored + \param sizeMM Size for the document in millimeters. + \param resolution Resolution in dots per Inch (dpi) +*/ +void QwtPlotRenderer::renderDocument( QwtPlot *plot, + const QString &fileName, const QSizeF &sizeMM, int resolution ) +{ + renderDocument( plot, fileName, + QFileInfo( fileName ).suffix(), sizeMM, resolution ); +} + +/*! + Render a plot to a file + + Supported formats are: + + - pdf\n + Portable Document Format PDF + - ps\n + Postcript + - svg\n + Scalable Vector Graphics SVG + - all image formats supported by Qt\n + see QImageWriter::supportedImageFormats() + + Scalable vector graphic formats like PDF or SVG are superior to + raster graphics formats. + + \param plot Plot widget + \param fileName Path of the file, where the document will be stored + \param format Format for the document + \param sizeMM Size for the document in millimeters. + \param resolution Resolution in dots per Inch (dpi) + + \sa renderTo(), render(), QwtPainter::setRoundingAlignment() +*/ +void QwtPlotRenderer::renderDocument( QwtPlot *plot, + const QString &fileName, const QString &format, + const QSizeF &sizeMM, int resolution ) +{ + if ( plot == NULL || sizeMM.isEmpty() || resolution <= 0 ) + return; + + QString title = plot->title().text(); + if ( title.isEmpty() ) + title = "Plot Document"; + + const double mmToInch = 1.0 / 25.4; + const QSizeF size = sizeMM * mmToInch * resolution; + + const QRectF documentRect( 0.0, 0.0, size.width(), size.height() ); + + const QString fmt = format.toLower(); + if ( fmt == "pdf" ) + { +#ifndef QT_NO_PRINTER + QPrinter printer; + printer.setOutputFormat( QPrinter::PdfFormat ); + printer.setColorMode( QPrinter::Color ); + printer.setFullPage( true ); + printer.setPaperSize( sizeMM, QPrinter::Millimeter ); + printer.setDocName( title ); + printer.setOutputFileName( fileName ); + printer.setResolution( resolution ); + + QPainter painter( &printer ); + render( plot, &painter, documentRect ); +#endif + } + else if ( fmt == "ps" ) + { +#if QT_VERSION < 0x050000 +#ifndef QT_NO_PRINTER + QPrinter printer; + printer.setOutputFormat( QPrinter::PostScriptFormat ); + printer.setColorMode( QPrinter::Color ); + printer.setFullPage( true ); + printer.setPaperSize( sizeMM, QPrinter::Millimeter ); + printer.setDocName( title ); + printer.setOutputFileName( fileName ); + printer.setResolution( resolution ); + + QPainter painter( &printer ); + render( plot, &painter, documentRect ); +#endif +#endif + } + else if ( fmt == "svg" ) + { +#ifndef QWT_NO_SVG +#ifdef QT_SVG_LIB +#if QT_VERSION >= 0x040500 + QSvgGenerator generator; + generator.setTitle( title ); + generator.setFileName( fileName ); + generator.setResolution( resolution ); + generator.setViewBox( documentRect ); + + QPainter painter( &generator ); + render( plot, &painter, documentRect ); +#endif +#endif +#endif + } + else + { + if ( QImageWriter::supportedImageFormats().indexOf( + format.toLatin1() ) >= 0 ) + { + const QRect imageRect = documentRect.toRect(); + const int dotsPerMeter = qRound( resolution * mmToInch * 1000.0 ); + + QImage image( imageRect.size(), QImage::Format_ARGB32 ); + image.setDotsPerMeterX( dotsPerMeter ); + image.setDotsPerMeterY( dotsPerMeter ); + image.fill( QColor( Qt::white ).rgb() ); + + QPainter painter( &image ); + render( plot, &painter, imageRect ); + painter.end(); + + image.save( fileName, format.toLatin1() ); + } + } +} + +/*! + \brief Render the plot to a \c QPaintDevice + + This function renders the contents of a QwtPlot instance to + \c QPaintDevice object. The target rectangle is derived from + its device metrics. + + \param plot Plot to be rendered + \param paintDevice device to paint on, f.e a QImage + + \sa renderDocument(), render(), QwtPainter::setRoundingAlignment() +*/ + +void QwtPlotRenderer::renderTo( + QwtPlot *plot, QPaintDevice &paintDevice ) const +{ + int w = paintDevice.width(); + int h = paintDevice.height(); + + QPainter p( &paintDevice ); + render( plot, &p, QRectF( 0, 0, w, h ) ); +} + +/*! + \brief Render the plot to a QPrinter + + This function renders the contents of a QwtPlot instance to + \c QPaintDevice object. The size is derived from the printer + metrics. + + \param plot Plot to be rendered + \param printer Printer to paint on + + \sa renderDocument(), render(), QwtPainter::setRoundingAlignment() +*/ + +#ifndef QT_NO_PRINTER + +void QwtPlotRenderer::renderTo( + QwtPlot *plot, QPrinter &printer ) const +{ + int w = printer.width(); + int h = printer.height(); + + QRectF rect( 0, 0, w, h ); + double aspect = rect.width() / rect.height(); + if ( ( aspect < 1.0 ) ) + rect.setHeight( aspect * rect.width() ); + + QPainter p( &printer ); + render( plot, &p, rect ); +} + +#endif + +#ifndef QWT_NO_SVG +#ifdef QT_SVG_LIB +#if QT_VERSION >= 0x040500 + +/*! + \brief Render the plot to a QSvgGenerator + + If the generator has a view box, the plot will be rendered into it. + If it has no viewBox but a valid size the target coordinates + will be (0, 0, generator.width(), generator.height()). Otherwise + the target rectangle will be QRectF(0, 0, 800, 600); + + \param plot Plot to be rendered + \param generator SVG generator +*/ +void QwtPlotRenderer::renderTo( + QwtPlot *plot, QSvgGenerator &generator ) const +{ + QRectF rect = generator.viewBoxF(); + if ( rect.isEmpty() ) + rect.setRect( 0, 0, generator.width(), generator.height() ); + + if ( rect.isEmpty() ) + rect.setRect( 0, 0, 800, 600 ); // something + + QPainter p( &generator ); + render( plot, &p, rect ); +} +#endif +#endif +#endif + +/*! + Paint the contents of a QwtPlot instance into a given rectangle. + + \param plot Plot to be rendered + \param painter Painter + \param plotRect Bounding rectangle + + \sa renderDocument(), renderTo(), QwtPainter::setRoundingAlignment() +*/ +void QwtPlotRenderer::render( QwtPlot *plot, + QPainter *painter, const QRectF &plotRect ) const +{ + if ( painter == 0 || !painter->isActive() || + !plotRect.isValid() || plot->size().isNull() ) + { + return; + } + + if ( !( d_data->discardFlags & DiscardBackground ) ) + QwtPainter::drawBackgound( painter, plotRect, plot ); + + /* + The layout engine uses the same methods as they are used + by the Qt layout system. Therefore we need to calculate the + layout in screen coordinates and paint with a scaled painter. + */ + QTransform transform; + transform.scale( + double( painter->device()->logicalDpiX() ) / plot->logicalDpiX(), + double( painter->device()->logicalDpiY() ) / plot->logicalDpiY() ); + + QRectF layoutRect = transform.inverted().mapRect( plotRect ); + + if ( !( d_data->discardFlags & DiscardBackground ) ) + { + // subtract the contents margins + + int left, top, right, bottom; + plot->getContentsMargins( &left, &top, &right, &bottom ); + layoutRect.adjust( left, top, -right, -bottom ); + } + + QwtPlotLayout *layout = plot->plotLayout(); + + int baseLineDists[QwtPlot::axisCnt]; + int canvasMargins[QwtPlot::axisCnt]; + + for ( int axisId = 0; axisId < QwtPlot::axisCnt; axisId++ ) + { + canvasMargins[ axisId ] = layout->canvasMargin( axisId ); + + if ( d_data->layoutFlags & FrameWithScales ) + { + QwtScaleWidget *scaleWidget = plot->axisWidget( axisId ); + if ( scaleWidget ) + { + baseLineDists[axisId] = scaleWidget->margin(); + scaleWidget->setMargin( 0 ); + } + + if ( !plot->axisEnabled( axisId ) ) + { + int left = 0; + int right = 0; + int top = 0; + int bottom = 0; + + // When we have a scale the frame is painted on + // the position of the backbone - otherwise we + // need to introduce a margin around the canvas + + switch( axisId ) + { + case QwtPlot::yLeft: + layoutRect.adjust( 1, 0, 0, 0 ); + break; + case QwtPlot::yRight: + layoutRect.adjust( 0, 0, -1, 0 ); + break; + case QwtPlot::xTop: + layoutRect.adjust( 0, 1, 0, 0 ); + break; + case QwtPlot::xBottom: + layoutRect.adjust( 0, 0, 0, -1 ); + break; + default: + break; + } + layoutRect.adjust( left, top, right, bottom ); + } + } + } + + // Calculate the layout for the document. + + QwtPlotLayout::Options layoutOptions = QwtPlotLayout::IgnoreScrollbars; + + if ( ( d_data->layoutFlags & FrameWithScales ) || + ( d_data->discardFlags & DiscardCanvasFrame ) ) + { + layoutOptions |= QwtPlotLayout::IgnoreFrames; + } + + + if ( d_data->discardFlags & DiscardLegend ) + layoutOptions |= QwtPlotLayout::IgnoreLegend; + + if ( d_data->discardFlags & DiscardTitle ) + layoutOptions |= QwtPlotLayout::IgnoreTitle; + + if ( d_data->discardFlags & DiscardFooter ) + layoutOptions |= QwtPlotLayout::IgnoreFooter; + + layout->activate( plot, layoutRect, layoutOptions ); + + // canvas + + QwtScaleMap maps[QwtPlot::axisCnt]; + buildCanvasMaps( plot, layout->canvasRect(), maps ); + if ( updateCanvasMargins( plot, layout->canvasRect(), maps ) ) + { + // recalculate maps and layout, when the margins + // have been changed + + layout->activate( plot, layoutRect, layoutOptions ); + buildCanvasMaps( plot, layout->canvasRect(), maps ); + } + + // now start painting + + painter->save(); + painter->setWorldTransform( transform, true ); + + renderCanvas( plot, painter, layout->canvasRect(), maps ); + + if ( !( d_data->discardFlags & DiscardTitle ) + && ( !plot->titleLabel()->text().isEmpty() ) ) + { + renderTitle( plot, painter, layout->titleRect() ); + } + + if ( !( d_data->discardFlags & DiscardFooter ) + && ( !plot->footerLabel()->text().isEmpty() ) ) + { + renderFooter( plot, painter, layout->footerRect() ); + } + + if ( !( d_data->discardFlags & DiscardLegend ) + && plot->legend() && !plot->legend()->isEmpty() ) + { + renderLegend( plot, painter, layout->legendRect() ); + } + + for ( int axisId = 0; axisId < QwtPlot::axisCnt; axisId++ ) + { + QwtScaleWidget *scaleWidget = plot->axisWidget( axisId ); + if ( scaleWidget ) + { + int baseDist = scaleWidget->margin(); + + int startDist, endDist; + scaleWidget->getBorderDistHint( startDist, endDist ); + + renderScale( plot, painter, axisId, startDist, endDist, + baseDist, layout->scaleRect( axisId ) ); + } + } + + painter->restore(); + + // restore all setting to their original attributes. + for ( int axisId = 0; axisId < QwtPlot::axisCnt; axisId++ ) + { + if ( d_data->layoutFlags & FrameWithScales ) + { + QwtScaleWidget *scaleWidget = plot->axisWidget( axisId ); + if ( scaleWidget ) + scaleWidget->setMargin( baseLineDists[axisId] ); + } + + layout->setCanvasMargin( canvasMargins[axisId] ); + } + + layout->invalidate(); + +} + +/*! + Render the title into a given rectangle. + + \param plot Plot widget + \param painter Painter + \param rect Bounding rectangle +*/ +void QwtPlotRenderer::renderTitle( const QwtPlot *plot, + QPainter *painter, const QRectF &rect ) const +{ + painter->setFont( plot->titleLabel()->font() ); + + const QColor color = plot->titleLabel()->palette().color( + QPalette::Active, QPalette::Text ); + + painter->setPen( color ); + plot->titleLabel()->text().draw( painter, rect ); +} + +/*! + Render the footer into a given rectangle. + + \param plot Plot widget + \param painter Painter + \param rect Bounding rectangle +*/ +void QwtPlotRenderer::renderFooter( const QwtPlot *plot, + QPainter *painter, const QRectF &rect ) const +{ + painter->setFont( plot->footerLabel()->font() ); + + const QColor color = plot->footerLabel()->palette().color( + QPalette::Active, QPalette::Text ); + + painter->setPen( color ); + plot->footerLabel()->text().draw( painter, rect ); +} + + +/*! + Render the legend into a given rectangle. + + \param plot Plot widget + \param painter Painter + \param rect Bounding rectangle +*/ +void QwtPlotRenderer::renderLegend( const QwtPlot *plot, + QPainter *painter, const QRectF &rect ) const +{ + if ( plot->legend() ) + { + bool fillBackground = !( d_data->discardFlags & DiscardBackground ); + plot->legend()->renderLegend( painter, rect, fillBackground ); + } +} + +/*! + \brief Paint a scale into a given rectangle. + Paint the scale into a given rectangle. + + \param plot Plot widget + \param painter Painter + \param axisId Axis + \param startDist Start border distance + \param endDist End border distance + \param baseDist Base distance + \param rect Bounding rectangle +*/ +void QwtPlotRenderer::renderScale( const QwtPlot *plot, + QPainter *painter, + int axisId, int startDist, int endDist, int baseDist, + const QRectF &rect ) const +{ + if ( !plot->axisEnabled( axisId ) ) + return; + + const QwtScaleWidget *scaleWidget = plot->axisWidget( axisId ); + if ( scaleWidget->isColorBarEnabled() + && scaleWidget->colorBarWidth() > 0 ) + { + scaleWidget->drawColorBar( painter, scaleWidget->colorBarRect( rect ) ); + baseDist += scaleWidget->colorBarWidth() + scaleWidget->spacing(); + } + + painter->save(); + + QwtScaleDraw::Alignment align; + double x, y, w; + + switch ( axisId ) + { + case QwtPlot::yLeft: + { + x = rect.right() - 1.0 - baseDist; + y = rect.y() + startDist; + w = rect.height() - startDist - endDist; + align = QwtScaleDraw::LeftScale; + break; + } + case QwtPlot::yRight: + { + x = rect.left() + baseDist; + y = rect.y() + startDist; + w = rect.height() - startDist - endDist; + align = QwtScaleDraw::RightScale; + break; + } + case QwtPlot::xTop: + { + x = rect.left() + startDist; + y = rect.bottom() - 1.0 - baseDist; + w = rect.width() - startDist - endDist; + align = QwtScaleDraw::TopScale; + break; + } + case QwtPlot::xBottom: + { + x = rect.left() + startDist; + y = rect.top() + baseDist; + w = rect.width() - startDist - endDist; + align = QwtScaleDraw::BottomScale; + break; + } + default: + return; + } + + scaleWidget->drawTitle( painter, align, rect ); + + painter->setFont( scaleWidget->font() ); + + QwtScaleDraw *sd = const_cast<QwtScaleDraw *>( scaleWidget->scaleDraw() ); + const QPointF sdPos = sd->pos(); + const double sdLength = sd->length(); + + sd->move( x, y ); + sd->setLength( w ); + + QPalette palette = scaleWidget->palette(); + palette.setCurrentColorGroup( QPalette::Active ); + sd->draw( painter, palette ); + + // reset previous values + sd->move( sdPos ); + sd->setLength( sdLength ); + + painter->restore(); +} + +/*! + Render the canvas into a given rectangle. + + \param plot Plot widget + \param painter Painter + \param map Maps mapping between plot and paint device coordinates + \param canvasRect Canvas rectangle +*/ +void QwtPlotRenderer::renderCanvas( const QwtPlot *plot, + QPainter *painter, const QRectF &canvasRect, + const QwtScaleMap *map ) const +{ + const QWidget *canvas = plot->canvas(); + + QRectF r = canvasRect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + + if ( d_data->layoutFlags & FrameWithScales ) + { + painter->save(); + + r.adjust( -1.0, -1.0, 1.0, 1.0 ); + painter->setPen( QPen( Qt::black ) ); + + if ( !( d_data->discardFlags & DiscardCanvasBackground ) ) + { + const QBrush bgBrush = + canvas->palette().brush( plot->backgroundRole() ); + painter->setBrush( bgBrush ); + } + + QwtPainter::drawRect( painter, r ); + + painter->restore(); + painter->save(); + + painter->setClipRect( canvasRect ); + plot->drawItems( painter, canvasRect, map ); + + painter->restore(); + } + else if ( canvas->testAttribute( Qt::WA_StyledBackground ) ) + { + QPainterPath clipPath; + + painter->save(); + + if ( !( d_data->discardFlags & DiscardCanvasBackground ) ) + { + QwtPainter::drawBackgound( painter, r, canvas ); + clipPath = qwtCanvasClip( canvas, canvasRect ); + } + + painter->restore(); + painter->save(); + + if ( clipPath.isEmpty() ) + painter->setClipRect( canvasRect ); + else + painter->setClipPath( clipPath ); + + plot->drawItems( painter, canvasRect, map ); + + painter->restore(); + } + else + { + QPainterPath clipPath; + + int frameWidth = 0; + + if ( !( d_data->discardFlags & DiscardCanvasFrame ) ) + { + const QVariant fw = canvas->property( "frameWidth" ); + if ( fw.type() == QVariant::Int ) + frameWidth = fw.toInt(); + + clipPath = qwtCanvasClip( canvas, canvasRect ); + } + + QRectF innerRect = canvasRect.adjusted( + frameWidth, frameWidth, -frameWidth, -frameWidth ); + + painter->save(); + + if ( clipPath.isEmpty() ) + { + painter->setClipRect( innerRect ); + } + else + { + painter->setClipPath( clipPath ); + } + + if ( !( d_data->discardFlags & DiscardCanvasBackground ) ) + { + QwtPainter::drawBackgound( painter, innerRect, canvas ); + } + + plot->drawItems( painter, innerRect, map ); + + painter->restore(); + + if ( frameWidth > 0 ) + { + painter->save(); + + const int frameStyle = + canvas->property( "frameShadow" ).toInt() | + canvas->property( "frameShape" ).toInt(); + + const int frameWidth = canvas->property( "frameWidth" ).toInt(); + + + const QVariant borderRadius = canvas->property( "borderRadius" ); + if ( borderRadius.type() == QVariant::Double + && borderRadius.toDouble() > 0.0 ) + { + const double r = borderRadius.toDouble(); + + QwtPainter::drawRoundedFrame( painter, canvasRect, + r, r, canvas->palette(), frameWidth, frameStyle ); + } + else + { + const int midLineWidth = canvas->property( "midLineWidth" ).toInt(); + + QwtPainter::drawFrame( painter, canvasRect, + canvas->palette(), canvas->foregroundRole(), + frameWidth, midLineWidth, frameStyle ); + } + painter->restore(); + } + } +} + +/*! + Calculated the scale maps for rendering the canvas + + \param plot Plot widget + \param canvasRect Target rectangle + \param maps Scale maps to be calculated +*/ +void QwtPlotRenderer::buildCanvasMaps( const QwtPlot *plot, + const QRectF &canvasRect, QwtScaleMap maps[] ) const +{ + for ( int axisId = 0; axisId < QwtPlot::axisCnt; axisId++ ) + { + maps[axisId].setTransformation( + plot->axisScaleEngine( axisId )->transformation() ); + + const QwtScaleDiv &scaleDiv = plot->axisScaleDiv( axisId ); + maps[axisId].setScaleInterval( + scaleDiv.lowerBound(), scaleDiv.upperBound() ); + + double from, to; + if ( plot->axisEnabled( axisId ) ) + { + const int sDist = plot->axisWidget( axisId )->startBorderDist(); + const int eDist = plot->axisWidget( axisId )->endBorderDist(); + const QRectF scaleRect = plot->plotLayout()->scaleRect( axisId ); + + if ( axisId == QwtPlot::xTop || axisId == QwtPlot::xBottom ) + { + from = scaleRect.left() + sDist; + to = scaleRect.right() - eDist; + } + else + { + from = scaleRect.bottom() - eDist; + to = scaleRect.top() + sDist; + } + } + else + { + int margin = 0; + if ( !plot->plotLayout()->alignCanvasToScale( axisId ) ) + margin = plot->plotLayout()->canvasMargin( axisId ); + + if ( axisId == QwtPlot::yLeft || axisId == QwtPlot::yRight ) + { + from = canvasRect.bottom() - margin; + to = canvasRect.top() + margin; + } + else + { + from = canvasRect.left() + margin; + to = canvasRect.right() - margin; + } + } + maps[axisId].setPaintInterval( from, to ); + } +} + +bool QwtPlotRenderer::updateCanvasMargins( QwtPlot *plot, + const QRectF &canvasRect, const QwtScaleMap maps[] ) const +{ + double margins[QwtPlot::axisCnt]; + plot->getCanvasMarginsHint( maps, canvasRect, + margins[QwtPlot::yLeft], margins[QwtPlot::xTop], + margins[QwtPlot::yRight], margins[QwtPlot::xBottom] ); + + bool marginsChanged = false; + for ( int axisId = 0; axisId < QwtPlot::axisCnt; axisId++ ) + { + if ( margins[axisId] >= 0.0 ) + { + const int m = qCeil( margins[axisId] ); + plot->plotLayout()->setCanvasMargin( m, axisId); + marginsChanged = true; + } + } + + return marginsChanged; +} + +/*! + \brief Execute a file dialog and render the plot to the selected file + + \param plot Plot widget + \param documentName Default document name + \param sizeMM Size for the document in millimeters. + \param resolution Resolution in dots per Inch (dpi) + + \return True, when exporting was successful + \sa renderDocument() +*/ +bool QwtPlotRenderer::exportTo( QwtPlot *plot, const QString &documentName, + const QSizeF &sizeMM, int resolution ) +{ + if ( plot == NULL ) + return false; + + QString fileName = documentName; + + // What about translation + +#ifndef QT_NO_FILEDIALOG + const QList<QByteArray> imageFormats = + QImageWriter::supportedImageFormats(); + + QStringList filter; +#ifndef QT_NO_PRINTER + filter += QString( "PDF " ) + tr( "Documents" ) + " (*.pdf)"; +#endif +#ifndef QWT_NO_SVG + filter += QString( "SVG " ) + tr( "Documents" ) + " (*.svg)"; +#endif +#ifndef QT_NO_PRINTER + filter += QString( "Postscript " ) + tr( "Documents" ) + " (*.ps)"; +#endif + + if ( imageFormats.size() > 0 ) + { + QString imageFilter( tr( "Images" ) ); + imageFilter += " ("; + for ( int i = 0; i < imageFormats.size(); i++ ) + { + if ( i > 0 ) + imageFilter += " "; + imageFilter += "*."; + imageFilter += imageFormats[i]; + } + imageFilter += ")"; + + filter += imageFilter; + } + + fileName = QFileDialog::getSaveFileName( + NULL, tr( "Export File Name" ), fileName, + filter.join( ";;" ), NULL, QFileDialog::DontConfirmOverwrite ); +#endif + if ( fileName.isEmpty() ) + return false; + + renderDocument( plot, fileName, sizeMM, resolution ); + + return true; +} diff --git a/libs/qwt/qwt_plot_renderer.h b/libs/qwt/qwt_plot_renderer.h new file mode 100644 index 0000000000..68ffcd1a97 --- /dev/null +++ b/libs/qwt/qwt_plot_renderer.h @@ -0,0 +1,170 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_RENDERER_H +#define QWT_PLOT_RENDERER_H + +#include "qwt_global.h" +#include <qobject.h> +#include <qsize.h> + +class QwtPlot; +class QwtScaleMap; +class QRectF; +class QPainter; +class QPaintDevice; + +#ifndef QT_NO_PRINTER +class QPrinter; +#endif + +#ifndef QWT_NO_SVG +#ifdef QT_SVG_LIB +class QSvgGenerator; +#endif +#endif + +/*! + \brief Renderer for exporting a plot to a document, a printer + or anything else, that is supported by QPainter/QPaintDevice +*/ +class QWT_EXPORT QwtPlotRenderer: public QObject +{ + Q_OBJECT + +public: + //! Disard flags + enum DiscardFlag + { + //! Render all components of the plot + DiscardNone = 0x00, + + //! Don't render the background of the plot + DiscardBackground = 0x01, + + //! Don't render the title of the plot + DiscardTitle = 0x02, + + //! Don't render the legend of the plot + DiscardLegend = 0x04, + + //! Don't render the background of the canvas + DiscardCanvasBackground = 0x08, + + //! Don't render the footer of the plot + DiscardFooter = 0x10, + + /*! + Don't render the frame of the canvas + + \note This flag has no effect when using + style sheets, where the frame is part + of the background + */ + DiscardCanvasFrame = 0x20 + + }; + + //! Disard flags + typedef QFlags<DiscardFlag> DiscardFlags; + + /*! + \brief Layout flags + \sa setLayoutFlag(), testLayoutFlag() + */ + enum LayoutFlag + { + //! Use the default layout as on screen + DefaultLayout = 0x00, + + /*! + Instead of the scales a box is painted around the plot canvas, + where the scale ticks are aligned to. + */ + FrameWithScales = 0x01 + }; + + //! Layout flags + typedef QFlags<LayoutFlag> LayoutFlags; + + explicit QwtPlotRenderer( QObject * = NULL ); + virtual ~QwtPlotRenderer(); + + void setDiscardFlag( DiscardFlag flag, bool on = true ); + bool testDiscardFlag( DiscardFlag flag ) const; + + void setDiscardFlags( DiscardFlags flags ); + DiscardFlags discardFlags() const; + + void setLayoutFlag( LayoutFlag flag, bool on = true ); + bool testLayoutFlag( LayoutFlag flag ) const; + + void setLayoutFlags( LayoutFlags flags ); + LayoutFlags layoutFlags() const; + + void renderDocument( QwtPlot *, const QString &fileName, + const QSizeF &sizeMM, int resolution = 85 ); + + void renderDocument( QwtPlot *, + const QString &fileName, const QString &format, + const QSizeF &sizeMM, int resolution = 85 ); + +#ifndef QWT_NO_SVG +#ifdef QT_SVG_LIB +#if QT_VERSION >= 0x040500 + void renderTo( QwtPlot *, QSvgGenerator & ) const; +#endif +#endif +#endif + +#ifndef QT_NO_PRINTER + void renderTo( QwtPlot *, QPrinter & ) const; +#endif + + void renderTo( QwtPlot *, QPaintDevice &p ) const; + + virtual void render( QwtPlot *, + QPainter *, const QRectF &rect ) const; + + virtual void renderTitle( const QwtPlot *, + QPainter *, const QRectF & ) const; + + virtual void renderFooter( const QwtPlot *, + QPainter *, const QRectF & ) const; + + virtual void renderScale( const QwtPlot *, QPainter *, + int axisId, int startDist, int endDist, + int baseDist, const QRectF & ) const; + + virtual void renderCanvas( const QwtPlot *, + QPainter *, const QRectF &canvasRect, + const QwtScaleMap* maps ) const; + + virtual void renderLegend( + const QwtPlot *, QPainter *, const QRectF & ) const; + + bool exportTo( QwtPlot *, const QString &documentName, + const QSizeF &sizeMM = QSizeF( 300, 200 ), int resolution = 85 ); + +private: + void buildCanvasMaps( const QwtPlot *, + const QRectF &, QwtScaleMap maps[] ) const; + + bool updateCanvasMargins( QwtPlot *, + const QRectF &, const QwtScaleMap maps[] ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotRenderer::DiscardFlags ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotRenderer::LayoutFlags ) + +#endif diff --git a/libs/qwt/qwt_plot_rescaler.cpp b/libs/qwt/qwt_plot_rescaler.cpp new file mode 100644 index 0000000000..54843faa87 --- /dev/null +++ b/libs/qwt/qwt_plot_rescaler.cpp @@ -0,0 +1,631 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_rescaler.h" +#include "qwt_plot.h" +#include "qwt_scale_div.h" +#include "qwt_interval.h" +#include "qwt_plot_canvas.h" +#include <qevent.h> +#include <qalgorithms.h> + +class QwtPlotRescaler::AxisData +{ +public: + AxisData(): + aspectRatio( 1.0 ), + expandingDirection( QwtPlotRescaler::ExpandUp ) + { + } + + double aspectRatio; + QwtInterval intervalHint; + QwtPlotRescaler::ExpandingDirection expandingDirection; + mutable QwtScaleDiv scaleDiv; +}; + +class QwtPlotRescaler::PrivateData +{ +public: + PrivateData(): + referenceAxis( QwtPlot::xBottom ), + rescalePolicy( QwtPlotRescaler::Expanding ), + isEnabled( false ), + inReplot( 0 ) + { + } + + int referenceAxis; + RescalePolicy rescalePolicy; + QwtPlotRescaler::AxisData axisData[QwtPlot::axisCnt]; + bool isEnabled; + + mutable int inReplot; +}; + +/*! + Constructor + + \param canvas Canvas + \param referenceAxis Reference axis, see RescalePolicy + \param policy Rescale policy + + \sa setRescalePolicy(), setReferenceAxis() +*/ +QwtPlotRescaler::QwtPlotRescaler( QWidget *canvas, + int referenceAxis, RescalePolicy policy ): + QObject( canvas ) +{ + d_data = new PrivateData; + d_data->referenceAxis = referenceAxis; + d_data->rescalePolicy = policy; + + setEnabled( true ); +} + +//! Destructor +QwtPlotRescaler::~QwtPlotRescaler() +{ + delete d_data; +} + +/*! + \brief En/disable the rescaler + + When enabled is true an event filter is installed for + the canvas, otherwise the event filter is removed. + + \param on true or false + \sa isEnabled(), eventFilter() +*/ +void QwtPlotRescaler::setEnabled( bool on ) +{ + if ( d_data->isEnabled != on ) + { + d_data->isEnabled = on; + + QWidget *w = canvas(); + if ( w ) + { + if ( d_data->isEnabled ) + w->installEventFilter( this ); + else + w->removeEventFilter( this ); + } + } +} + +/*! + \return true when enabled, false otherwise + \sa setEnabled, eventFilter() +*/ +bool QwtPlotRescaler::isEnabled() const +{ + return d_data->isEnabled; +} + +/*! + Change the rescale policy + + \param policy Rescale policy + \sa rescalePolicy() +*/ +void QwtPlotRescaler::setRescalePolicy( RescalePolicy policy ) +{ + d_data->rescalePolicy = policy; +} + +/*! + \return Rescale policy + \sa setRescalePolicy() +*/ +QwtPlotRescaler::RescalePolicy QwtPlotRescaler::rescalePolicy() const +{ + return d_data->rescalePolicy; +} + +/*! + Set the reference axis ( see RescalePolicy ) + + \param axis Axis index ( QwtPlot::Axis ) + \sa referenceAxis() +*/ +void QwtPlotRescaler::setReferenceAxis( int axis ) +{ + d_data->referenceAxis = axis; +} + +/*! + \return Reference axis ( see RescalePolicy ) + \sa setReferenceAxis() +*/ +int QwtPlotRescaler::referenceAxis() const +{ + return d_data->referenceAxis; +} + +/*! + Set the direction in which all axis should be expanded + + \param direction Direction + \sa expandingDirection() +*/ +void QwtPlotRescaler::setExpandingDirection( + ExpandingDirection direction ) +{ + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + setExpandingDirection( axis, direction ); +} + +/*! + Set the direction in which an axis should be expanded + + \param axis Axis index ( see QwtPlot::AxisId ) + \param direction Direction + \sa expandingDirection() +*/ +void QwtPlotRescaler::setExpandingDirection( + int axis, ExpandingDirection direction ) +{ + if ( axis >= 0 && axis < QwtPlot::axisCnt ) + d_data->axisData[axis].expandingDirection = direction; +} + +/*! + \return Direction in which an axis should be expanded + + \param axis Axis index ( see QwtPlot::AxisId ) + \sa setExpandingDirection() +*/ +QwtPlotRescaler::ExpandingDirection +QwtPlotRescaler::expandingDirection( int axis ) const +{ + if ( axis >= 0 && axis < QwtPlot::axisCnt ) + return d_data->axisData[axis].expandingDirection; + + return ExpandBoth; +} + +/*! + Set the aspect ratio between the scale of the reference axis + and the other scales. The default ratio is 1.0 + + \param ratio Aspect ratio + \sa aspectRatio() +*/ +void QwtPlotRescaler::setAspectRatio( double ratio ) +{ + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + setAspectRatio( axis, ratio ); +} + +/*! + Set the aspect ratio between the scale of the reference axis + and another scale. The default ratio is 1.0 + + \param axis Axis index ( see QwtPlot::AxisId ) + \param ratio Aspect ratio + \sa aspectRatio() +*/ +void QwtPlotRescaler::setAspectRatio( int axis, double ratio ) +{ + if ( ratio < 0.0 ) + ratio = 0.0; + + if ( axis >= 0 && axis < QwtPlot::axisCnt ) + d_data->axisData[axis].aspectRatio = ratio; +} + +/*! + \return Aspect ratio between an axis and the reference axis. + + \param axis Axis index ( see QwtPlot::AxisId ) + \sa setAspectRatio() +*/ +double QwtPlotRescaler::aspectRatio( int axis ) const +{ + if ( axis >= 0 && axis < QwtPlot::axisCnt ) + return d_data->axisData[axis].aspectRatio; + + return 0.0; +} + +/*! + Set an interval hint for an axis + + In Fitting mode, the hint is used as minimal interval + that always needs to be displayed. + + \param axis Axis, see QwtPlot::Axis + \param interval Axis + \sa intervalHint(), RescalePolicy +*/ +void QwtPlotRescaler::setIntervalHint( int axis, + const QwtInterval &interval ) +{ + if ( axis >= 0 && axis < QwtPlot::axisCnt ) + d_data->axisData[axis].intervalHint = interval; +} + +/*! + \param axis Axis, see QwtPlot::Axis + \return Interval hint + \sa setIntervalHint(), RescalePolicy +*/ +QwtInterval QwtPlotRescaler::intervalHint( int axis ) const +{ + if ( axis >= 0 && axis < QwtPlot::axisCnt ) + return d_data->axisData[axis].intervalHint; + + return QwtInterval(); +} + +//! \return plot canvas +QWidget *QwtPlotRescaler::canvas() +{ + return qobject_cast<QWidget *>( parent() ); +} + +//! \return plot canvas +const QWidget *QwtPlotRescaler::canvas() const +{ + return qobject_cast<const QWidget *>( parent() ); +} + +//! \return plot widget +QwtPlot *QwtPlotRescaler::plot() +{ + QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); + + return qobject_cast<QwtPlot *>( w ); +} + +//! \return plot widget +const QwtPlot *QwtPlotRescaler::plot() const +{ + const QWidget *w = canvas(); + if ( w ) + w = w->parentWidget(); + + return qobject_cast<const QwtPlot *>( w ); +} + +//! Event filter for the plot canvas +bool QwtPlotRescaler::eventFilter( QObject *object, QEvent *event ) +{ + if ( object && object == canvas() ) + { + switch ( event->type() ) + { + case QEvent::Resize: + { + canvasResizeEvent( static_cast<QResizeEvent *>( event ) ); + break; + } + case QEvent::PolishRequest: + { + rescale(); + break; + } + default:; + } + } + + return false; +} + +/*! + Event handler for resize events of the plot canvas + + \param event Resize event + \sa rescale() +*/ +void QwtPlotRescaler::canvasResizeEvent( QResizeEvent* event ) +{ + int left, top, right, bottom; + canvas()->getContentsMargins( &left, &top, &right, &bottom ); + + const QSize marginSize( left + right, top + bottom ); + + const QSize newSize = event->size() - marginSize; + const QSize oldSize = event->oldSize() - marginSize; + + rescale( oldSize, newSize ); +} + +//! Adjust the plot axes scales +void QwtPlotRescaler::rescale() const +{ + const QSize size = canvas()->contentsRect().size(); + rescale( size, size ); +} + +/*! + Adjust the plot axes scales + + \param oldSize Previous size of the canvas + \param newSize New size of the canvas +*/ +void QwtPlotRescaler::rescale( + const QSize &oldSize, const QSize &newSize ) const +{ + if ( newSize.isEmpty() ) + return; + + QwtInterval intervals[QwtPlot::axisCnt]; + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + intervals[axis] = interval( axis ); + + const int refAxis = referenceAxis(); + intervals[refAxis] = expandScale( refAxis, oldSize, newSize ); + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( aspectRatio( axis ) > 0.0 && axis != refAxis ) + intervals[axis] = syncScale( axis, intervals[refAxis], newSize ); + } + + updateScales( intervals ); +} + +/*! + Calculate the new scale interval of a plot axis + + \param axis Axis index ( see QwtPlot::AxisId ) + \param oldSize Previous size of the canvas + \param newSize New size of the canvas + + \return Calculated new interval for the axis +*/ +QwtInterval QwtPlotRescaler::expandScale( int axis, + const QSize &oldSize, const QSize &newSize ) const +{ + const QwtInterval oldInterval = interval( axis ); + + QwtInterval expanded = oldInterval; + switch ( rescalePolicy() ) + { + case Fixed: + { + break; // do nothing + } + case Expanding: + { + if ( !oldSize.isEmpty() ) + { + double width = oldInterval.width(); + if ( orientation( axis ) == Qt::Horizontal ) + width *= double( newSize.width() ) / oldSize.width(); + else + width *= double( newSize.height() ) / oldSize.height(); + + expanded = expandInterval( oldInterval, + width, expandingDirection( axis ) ); + } + break; + } + case Fitting: + { + double dist = 0.0; + for ( int ax = 0; ax < QwtPlot::axisCnt; ax++ ) + { + const double d = pixelDist( ax, newSize ); + if ( d > dist ) + dist = d; + } + if ( dist > 0.0 ) + { + double width; + if ( orientation( axis ) == Qt::Horizontal ) + width = newSize.width() * dist; + else + width = newSize.height() * dist; + + expanded = expandInterval( intervalHint( axis ), + width, expandingDirection( axis ) ); + } + break; + } + } + + return expanded; +} + +/*! + Synchronize an axis scale according to the scale of the reference axis + + \param axis Axis index ( see QwtPlot::AxisId ) + \param reference Interval of the reference axis + \param size Size of the canvas + + \return New interval for axis +*/ +QwtInterval QwtPlotRescaler::syncScale( int axis, + const QwtInterval& reference, const QSize &size ) const +{ + double dist; + if ( orientation( referenceAxis() ) == Qt::Horizontal ) + dist = reference.width() / size.width(); + else + dist = reference.width() / size.height(); + + if ( orientation( axis ) == Qt::Horizontal ) + dist *= size.width(); + else + dist *= size.height(); + + dist /= aspectRatio( axis ); + + QwtInterval intv; + if ( rescalePolicy() == Fitting ) + intv = intervalHint( axis ); + else + intv = interval( axis ); + + intv = expandInterval( intv, dist, expandingDirection( axis ) ); + + return intv; +} + +/*! + \return Orientation of an axis + \param axis Axis index ( see QwtPlot::AxisId ) +*/ +Qt::Orientation QwtPlotRescaler::orientation( int axis ) const +{ + if ( axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) + return Qt::Vertical; + + return Qt::Horizontal; +} + +/*! + \param axis Axis index ( see QwtPlot::AxisId ) + \return Normalized interval of an axis +*/ +QwtInterval QwtPlotRescaler::interval( int axis ) const +{ + if ( axis < 0 || axis >= QwtPlot::axisCnt ) + return QwtInterval(); + + return plot()->axisScaleDiv( axis ).interval().normalized(); +} + +/*! + Expand the interval + + \param interval Interval to be expanded + \param width Distance to be added to the interval + \param direction Direction of the expand operation + + \return Expanded interval +*/ +QwtInterval QwtPlotRescaler::expandInterval( + const QwtInterval &interval, double width, + ExpandingDirection direction ) const +{ + QwtInterval expanded = interval; + + switch ( direction ) + { + case ExpandUp: + expanded.setMinValue( interval.minValue() ); + expanded.setMaxValue( interval.minValue() + width ); + break; + + case ExpandDown: + expanded.setMaxValue( interval.maxValue() ); + expanded.setMinValue( interval.maxValue() - width ); + break; + + case ExpandBoth: + default: + expanded.setMinValue( interval.minValue() + + interval.width() / 2.0 - width / 2.0 ); + expanded.setMaxValue( expanded.minValue() + width ); + } + return expanded; +} + +double QwtPlotRescaler::pixelDist( int axis, const QSize &size ) const +{ + const QwtInterval intv = intervalHint( axis ); + + double dist = 0.0; + if ( !intv.isNull() ) + { + if ( axis == referenceAxis() ) + dist = intv.width(); + else + { + const double r = aspectRatio( axis ); + if ( r > 0.0 ) + dist = intv.width() * r; + } + } + + if ( dist > 0.0 ) + { + if ( orientation( axis ) == Qt::Horizontal ) + dist /= size.width(); + else + dist /= size.height(); + } + + return dist; +} + +/*! + Update the axes scales + + \param intervals Scale intervals +*/ +void QwtPlotRescaler::updateScales( + QwtInterval intervals[QwtPlot::axisCnt] ) const +{ + if ( d_data->inReplot >= 5 ) + { + return; + } + + QwtPlot *plt = const_cast<QwtPlot *>( plot() ); + + const bool doReplot = plt->autoReplot(); + plt->setAutoReplot( false ); + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( axis == referenceAxis() || aspectRatio( axis ) > 0.0 ) + { + double v1 = intervals[axis].minValue(); + double v2 = intervals[axis].maxValue(); + + if ( !plt->axisScaleDiv( axis ).isIncreasing() ) + qSwap( v1, v2 ); + + if ( d_data->inReplot >= 1 ) + d_data->axisData[axis].scaleDiv = plt->axisScaleDiv( axis ); + + if ( d_data->inReplot >= 2 ) + { + QList<double> ticks[QwtScaleDiv::NTickTypes]; + for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) + ticks[i] = d_data->axisData[axis].scaleDiv.ticks( i ); + + plt->setAxisScaleDiv( axis, QwtScaleDiv( v1, v2, ticks ) ); + } + else + { + plt->setAxisScale( axis, v1, v2 ); + } + } + } + + QwtPlotCanvas *canvas = qobject_cast<QwtPlotCanvas *>( plt->canvas() ); + + bool immediatePaint = false; + if ( canvas ) + { + immediatePaint = canvas->testPaintAttribute( QwtPlotCanvas::ImmediatePaint ); + canvas->setPaintAttribute( QwtPlotCanvas::ImmediatePaint, false ); + } + + plt->setAutoReplot( doReplot ); + + d_data->inReplot++; + plt->replot(); + d_data->inReplot--; + + if ( canvas && immediatePaint ) + { + canvas->setPaintAttribute( QwtPlotCanvas::ImmediatePaint, true ); + } +} diff --git a/libs/qwt/qwt_plot_rescaler.h b/libs/qwt/qwt_plot_rescaler.h new file mode 100644 index 0000000000..0a4890fd45 --- /dev/null +++ b/libs/qwt/qwt_plot_rescaler.h @@ -0,0 +1,142 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_RESCALER_H +#define QWT_PLOT_RESCALER_H 1 + +#include "qwt_global.h" +#include "qwt_interval.h" +#include "qwt_plot.h" +#include <qobject.h> + +class QwtPlot; +class QResizeEvent; + +/*! + \brief QwtPlotRescaler takes care of fixed aspect ratios for plot scales + + QwtPlotRescaler auto adjusts the axes of a QwtPlot according + to fixed aspect ratios. +*/ + +class QWT_EXPORT QwtPlotRescaler: public QObject +{ +public: + /*! + The rescale policy defines how to rescale the reference axis and + their depending axes. + + \sa ExpandingDirection, setIntervalHint() + */ + enum RescalePolicy + { + /*! + The interval of the reference axis remains unchanged, when the + geometry of the canvas changes. All other axes + will be adjusted according to their aspect ratio. + */ + Fixed, + + /*! + The interval of the reference axis will be shrunk/expanded, + when the geometry of the canvas changes. All other axes + will be adjusted according to their aspect ratio. + + The interval, that is represented by one pixel is fixed. + + */ + Expanding, + + /*! + The intervals of the axes are calculated, so that all axes include + their interval hint. + */ + Fitting + }; + + /*! + When rescalePolicy() is set to Expanding its direction depends + on ExpandingDirection + */ + enum ExpandingDirection + { + //! The upper limit of the scale is adjusted + ExpandUp, + + //! The lower limit of the scale is adjusted + ExpandDown, + + //! Both limits of the scale are adjusted + ExpandBoth + }; + + explicit QwtPlotRescaler( QWidget *canvas, + int referenceAxis = QwtPlot::xBottom, + RescalePolicy = Expanding ); + + virtual ~QwtPlotRescaler(); + + void setEnabled( bool ); + bool isEnabled() const; + + void setRescalePolicy( RescalePolicy ); + RescalePolicy rescalePolicy() const; + + void setExpandingDirection( ExpandingDirection ); + void setExpandingDirection( int axis, ExpandingDirection ); + ExpandingDirection expandingDirection( int axis ) const; + + void setReferenceAxis( int axis ); + int referenceAxis() const; + + void setAspectRatio( double ratio ); + void setAspectRatio( int axis, double ratio ); + double aspectRatio( int axis ) const; + + void setIntervalHint( int axis, const QwtInterval& ); + QwtInterval intervalHint( int axis ) const; + + QWidget *canvas(); + const QWidget *canvas() const; + + QwtPlot *plot(); + const QwtPlot *plot() const; + + virtual bool eventFilter( QObject *, QEvent * ); + + void rescale() const; + +protected: + virtual void canvasResizeEvent( QResizeEvent * ); + + virtual void rescale( const QSize &oldSize, const QSize &newSize ) const; + virtual QwtInterval expandScale( + int axis, const QSize &oldSize, const QSize &newSize ) const; + + virtual QwtInterval syncScale( + int axis, const QwtInterval& reference, + const QSize &size ) const; + + virtual void updateScales( + QwtInterval intervals[QwtPlot::axisCnt] ) const; + + Qt::Orientation orientation( int axis ) const; + QwtInterval interval( int axis ) const; + QwtInterval expandInterval( const QwtInterval &, + double width, ExpandingDirection ) const; + +private: + double pixelDist( int axis, const QSize & ) const; + + class AxisData; + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_scaleitem.cpp b/libs/qwt/qwt_plot_scaleitem.cpp index ea6ec8b026..aeed6befb5 100644 --- a/libs/qwt/qwt_plot_scaleitem.cpp +++ b/libs/qwt/qwt_plot_scaleitem.cpp @@ -7,61 +7,82 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qpalette.h> -#include <qpainter.h> +#include "qwt_plot_scaleitem.h" #include "qwt_plot.h" -#include "qwt_plot_canvas.h" #include "qwt_scale_map.h" -#include "qwt_plot_scaleitem.h" -#include "qwt_double_interval.h" +#include "qwt_interval.h" +#include <qpalette.h> +#include <qpainter.h> class QwtPlotScaleItem::PrivateData { public: PrivateData(): - position(0.0), - borderDistance(-1), - scaleDivFromAxis(true), - scaleDraw(new QwtScaleDraw()) { + position( 0.0 ), + borderDistance( -1 ), + scaleDivFromAxis( true ), + scaleDraw( new QwtScaleDraw() ) + { } - ~PrivateData() { + ~PrivateData() + { delete scaleDraw; } -#if QT_VERSION < 0x040000 - QColorGroup colorGroup; -#else + void updateBorders( const QRectF &, + const QwtScaleMap &, const QwtScaleMap & ); + QPalette palette; -#endif QFont font; double position; int borderDistance; bool scaleDivFromAxis; QwtScaleDraw *scaleDraw; - QRect canvasRectCache; + QRectF canvasRectCache; }; +void QwtPlotScaleItem::PrivateData::updateBorders( const QRectF &canvasRect, + const QwtScaleMap &xMap, const QwtScaleMap &yMap ) +{ + QwtInterval interval; + if ( scaleDraw->orientation() == Qt::Horizontal ) + { + interval.setMinValue( xMap.invTransform( canvasRect.left() ) ); + interval.setMaxValue( xMap.invTransform( canvasRect.right() - 1 ) ); + } + else + { + interval.setMinValue( yMap.invTransform( canvasRect.bottom() - 1 ) ); + interval.setMaxValue( yMap.invTransform( canvasRect.top() ) ); + } + + QwtScaleDiv scaleDiv = scaleDraw->scaleDiv(); + scaleDiv.setInterval( interval ); + scaleDraw->setScaleDiv( scaleDiv ); +} + /*! \brief Constructor for scale item at the position pos. - \param alignment In case of QwtScaleDraw::BottomScale/QwtScaleDraw::TopScale + \param alignment In case of QwtScaleDraw::BottomScale or QwtScaleDraw::TopScale the scale item is corresponding to the xAxis(), otherwise it corresponds to the yAxis(). - \param position x or y position, depending on the corresponding axis. + \param pos x or y position, depending on the corresponding axis. \sa setPosition(), setAlignment() */ QwtPlotScaleItem::QwtPlotScaleItem( - QwtScaleDraw::Alignment alignment, const double pos): - QwtPlotItem(QwtText("Scale")) + QwtScaleDraw::Alignment alignment, const double pos ): + QwtPlotItem( QwtText( "Scale" ) ) { d_data = new PrivateData; d_data->position = pos; - d_data->scaleDraw->setAlignment(alignment); + d_data->scaleDraw->setAlignment( alignment ); - setZ(11.0); + setItemInterest( QwtPlotItem::ScaleInterest, true ); + setZ( 11.0 ); } //! Destructor @@ -85,10 +106,10 @@ int QwtPlotScaleItem::rtti() const \param scaleDiv Scale division \sa scaleDiv(), setScaleDivFromAxis(), isScaleDivFromAxis() */ -void QwtPlotScaleItem::setScaleDiv(const QwtScaleDiv& scaleDiv) +void QwtPlotScaleItem::setScaleDiv( const QwtScaleDiv& scaleDiv ) { d_data->scaleDivFromAxis = false; - d_data->scaleDraw->setScaleDiv(scaleDiv); + d_data->scaleDraw->setScaleDiv( scaleDiv ); } //! \return Scale division @@ -101,17 +122,21 @@ const QwtScaleDiv& QwtPlotScaleItem::scaleDiv() const Enable/Disable the synchronization of the scale division with the corresponding axis. + \param on true/false \sa isScaleDivFromAxis() */ -void QwtPlotScaleItem::setScaleDivFromAxis(bool on) +void QwtPlotScaleItem::setScaleDivFromAxis( bool on ) { - if ( on != d_data->scaleDivFromAxis ) { + if ( on != d_data->scaleDivFromAxis ) + { d_data->scaleDivFromAxis = on; - if ( on ) { + if ( on ) + { const QwtPlot *plt = plot(); - if ( plt ) { - updateScaleDiv( *plt->axisScaleDiv(xAxis()), - *plt->axisScaleDiv(yAxis()) ); + if ( plt ) + { + updateScaleDiv( plt->axisScaleDiv( xAxis() ), + plt->axisScaleDiv( yAxis() ) ); itemChanged(); } } @@ -128,39 +153,17 @@ bool QwtPlotScaleItem::isScaleDivFromAxis() const return d_data->scaleDivFromAxis; } -#if QT_VERSION < 0x040000 - -/*! - Set the color group - \sa QwtAbstractScaleDraw::draw(), colorGroup() -*/ -void QwtPlotScaleItem::setColorGroup(const QColorGroup &colorGroup) -{ - if ( colorGroup != d_data->colorGroup ) { - d_data->colorGroup = colorGroup; - itemChanged(); - } -} - -/*! - \return color group - \sa setColorGroup() -*/ -QColorGroup QwtPlotScaleItem::colorGroup() const -{ - return d_data->colorGroup; -} - -#else - /*! Set the palette \sa QwtAbstractScaleDraw::draw(), palette() */ -void QwtPlotScaleItem::setPalette(const QPalette &palette) +void QwtPlotScaleItem::setPalette( const QPalette &palette ) { - if ( palette != d_data->palette ) { + if ( palette != d_data->palette ) + { d_data->palette = palette; + + legendChanged(); itemChanged(); } } @@ -174,15 +177,14 @@ QPalette QwtPlotScaleItem::palette() const return d_data->palette; } -#endif - /*! Change the tick label font - \sa font + \sa font() */ -void QwtPlotScaleItem::setFont(const QFont &font) +void QwtPlotScaleItem::setFont( const QFont &font ) { - if ( font != d_data->font ) { + if ( font != d_data->font ) + { d_data->font = font; itemChanged(); } @@ -200,7 +202,6 @@ QFont QwtPlotScaleItem::font() const /*! \brief Set a scale draw - \param axisId axis index \param scaleDraw object responsible for drawing scales. The main use case for replacing the default QwtScaleDraw is @@ -209,7 +210,7 @@ QFont QwtPlotScaleItem::font() const \sa scaleDraw() */ -void QwtPlotScaleItem::setScaleDraw(QwtScaleDraw *scaleDraw) +void QwtPlotScaleItem::setScaleDraw( QwtScaleDraw *scaleDraw ) { if ( scaleDraw == NULL ) return; @@ -220,9 +221,10 @@ void QwtPlotScaleItem::setScaleDraw(QwtScaleDraw *scaleDraw) d_data->scaleDraw = scaleDraw; const QwtPlot *plt = plot(); - if ( plt ) { - updateScaleDiv( *plt->axisScaleDiv(xAxis()), - *plt->axisScaleDiv(yAxis()) ); + if ( plt ) + { + updateScaleDiv( plt->axisScaleDiv( xAxis() ), + plt->axisScaleDiv( yAxis() ) ); } itemChanged(); @@ -254,11 +256,13 @@ QwtScaleDraw *QwtPlotScaleItem::scaleDraw() The border distance is set to -1. + \param pos New position \sa position(), setAlignment() */ -void QwtPlotScaleItem::setPosition(double pos) +void QwtPlotScaleItem::setPosition( double pos ) { - if ( d_data->position != pos ) { + if ( d_data->position != pos ) + { d_data->position = pos; d_data->borderDistance = -1; itemChanged(); @@ -278,7 +282,7 @@ double QwtPlotScaleItem::position() const \brief Align the scale to the canvas If distance is >= 0 the scale will be aligned to a - border of the contents rect of the canvas. If + border of the contents rectangle of the canvas. If alignment() is QwtScaleDraw::LeftScale, the scale will be aligned to the right border, if it is QwtScaleDraw::TopScale it will be aligned to the bottom (and vice versa), @@ -290,12 +294,13 @@ double QwtPlotScaleItem::position() const \sa setPosition(), borderDistance() */ -void QwtPlotScaleItem::setBorderDistance(int distance) +void QwtPlotScaleItem::setBorderDistance( int distance ) { if ( distance < 0 ) distance = -1; - if ( distance != d_data->borderDistance ) { + if ( distance != d_data->borderDistance ) + { d_data->borderDistance = distance; itemChanged(); } @@ -326,11 +331,12 @@ int QwtPlotScaleItem::borderDistance() const \sa scaleDraw(), QwtScaleDraw::alignment(), setPosition() */ -void QwtPlotScaleItem::setAlignment(QwtScaleDraw::Alignment alignment) +void QwtPlotScaleItem::setAlignment( QwtScaleDraw::Alignment alignment ) { QwtScaleDraw *sd = d_data->scaleDraw; - if ( sd->alignment() != alignment ) { - sd->setAlignment(alignment); + if ( sd->alignment() != alignment ) + { + sd->setAlignment( alignment ); itemChanged(); } } @@ -338,70 +344,86 @@ void QwtPlotScaleItem::setAlignment(QwtScaleDraw::Alignment alignment) /*! \brief Draw the scale */ -void QwtPlotScaleItem::draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &canvasRect) const +void QwtPlotScaleItem::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const { - if ( canvasRect != d_data->canvasRectCache ) { - QwtPlotScaleItem* that = (QwtPlotScaleItem*)this; - that->updateBorders(); + if ( d_data->scaleDivFromAxis ) + { + if ( canvasRect != d_data->canvasRectCache ) + { + d_data->updateBorders( canvasRect, xMap, yMap ); + d_data->canvasRectCache = canvasRect; + } } QPen pen = painter->pen(); - pen.setStyle(Qt::SolidLine); - painter->setPen(pen); - - int pw = painter->pen().width(); - if ( pw == 0 ) - pw = 1; + pen.setStyle( Qt::SolidLine ); + painter->setPen( pen ); QwtScaleDraw *sd = d_data->scaleDraw; - if ( sd->orientation() == Qt::Horizontal ) { - int y; - if ( d_data->borderDistance >= 0 ) { + if ( sd->orientation() == Qt::Horizontal ) + { + double y; + if ( d_data->borderDistance >= 0 ) + { if ( sd->alignment() == QwtScaleDraw::BottomScale ) y = canvasRect.top() + d_data->borderDistance; - else { - y = canvasRect.bottom() - d_data->borderDistance - pw + 1; + else + { + y = canvasRect.bottom() - d_data->borderDistance; } - } else { - y = yMap.transform(d_data->position); + } + else + { + y = yMap.transform( d_data->position ); } if ( y < canvasRect.top() || y > canvasRect.bottom() ) return; - sd->move(canvasRect.left(), y); - sd->setLength(canvasRect.width() - 1); - sd->setTransformation(xMap.transformation()->copy()); - } else { // == Qt::Vertical - int x; - if ( d_data->borderDistance >= 0 ) { + sd->move( canvasRect.left(), y ); + sd->setLength( canvasRect.width() - 1 ); + + QwtTransform *transform = NULL; + if ( xMap.transformation() ) + transform = xMap.transformation()->copy(); + + sd->setTransformation( transform ); + } + else // == Qt::Vertical + { + double x; + if ( d_data->borderDistance >= 0 ) + { if ( sd->alignment() == QwtScaleDraw::RightScale ) x = canvasRect.left() + d_data->borderDistance; - else { - x = canvasRect.right() - d_data->borderDistance - pw + 1; + else + { + x = canvasRect.right() - d_data->borderDistance; } - } else { - x = xMap.transform(d_data->position); + } + else + { + x = xMap.transform( d_data->position ); } if ( x < canvasRect.left() || x > canvasRect.right() ) return; - sd->move(x, canvasRect.top()); - sd->setLength(canvasRect.height() - 1); - sd->setTransformation(yMap.transformation()->copy()); - } + sd->move( x, canvasRect.top() ); + sd->setLength( canvasRect.height() - 1 ); + + QwtTransform *transform = NULL; + if ( yMap.transformation() ) + transform = yMap.transformation()->copy(); - painter->setFont(d_data->font); + sd->setTransformation( transform ); + } -#if QT_VERSION < 0x040000 - sd->draw(painter, d_data->colorGroup); -#else - sd->draw(painter, d_data->palette); -#endif + painter->setFont( d_data->font ); + sd->draw( painter, d_data->palette ); } /*! @@ -416,38 +438,21 @@ void QwtPlotScaleItem::draw(QPainter *painter, \sa QwtPlot::updateAxes() */ -void QwtPlotScaleItem::updateScaleDiv(const QwtScaleDiv& xScaleDiv, - const QwtScaleDiv& yScaleDiv) +void QwtPlotScaleItem::updateScaleDiv( const QwtScaleDiv& xScaleDiv, + const QwtScaleDiv& yScaleDiv ) { QwtScaleDraw *sd = d_data->scaleDraw; - if ( d_data->scaleDivFromAxis && sd ) { + if ( d_data->scaleDivFromAxis && sd ) + { sd->setScaleDiv( - sd->orientation() == Qt::Horizontal ? xScaleDiv : yScaleDiv); - updateBorders(); - } -} - -void QwtPlotScaleItem::updateBorders() -{ - const QwtPlot *plt = plot(); - if ( plt == NULL || !d_data->scaleDivFromAxis ) - return; - - const QRect r = plt->canvas()->contentsRect(); - d_data->canvasRectCache = r; - - QwtDoubleInterval interval; - if ( d_data->scaleDraw->orientation() == Qt::Horizontal ) { - const QwtScaleMap map = plt->canvasMap(xAxis()); - interval.setMinValue(map.invTransform(r.left())); - interval.setMaxValue(map.invTransform(r.right())); - } else { - const QwtScaleMap map = plt->canvasMap(yAxis()); - interval.setMinValue(map.invTransform(r.bottom())); - interval.setMaxValue(map.invTransform(r.top())); + sd->orientation() == Qt::Horizontal ? xScaleDiv : yScaleDiv ); + + const QwtPlot *plt = plot(); + if ( plt != NULL ) + { + d_data->updateBorders( plt->canvas()->contentsRect(), + plt->canvasMap( xAxis() ), plt->canvasMap( yAxis() ) ); + d_data->canvasRectCache = QRect(); + } } - - QwtScaleDiv scaleDiv = d_data->scaleDraw->scaleDiv(); - scaleDiv.setInterval(interval); - d_data->scaleDraw->setScaleDiv(scaleDiv); } diff --git a/libs/qwt/qwt_plot_scaleitem.h b/libs/qwt/qwt_plot_scaleitem.h index c9c081dbf0..ead67a3761 100644 --- a/libs/qwt/qwt_plot_scaleitem.h +++ b/libs/qwt/qwt_plot_scaleitem.h @@ -14,11 +14,7 @@ #include "qwt_plot_item.h" #include "qwt_scale_draw.h" -#if QT_VERSION < 0x040000 -class QColorGroup; -#else class QPalette; -#endif /*! \brief A class which draws a scale inside the plot canvas @@ -53,51 +49,44 @@ class QWT_EXPORT QwtPlotScaleItem: public QwtPlotItem public: explicit QwtPlotScaleItem( QwtScaleDraw::Alignment = QwtScaleDraw::BottomScale, - const double pos = 0.0); + const double pos = 0.0 ); + virtual ~QwtPlotScaleItem(); virtual int rtti() const; - void setScaleDiv(const QwtScaleDiv& ); + void setScaleDiv( const QwtScaleDiv& ); const QwtScaleDiv& scaleDiv() const; - void setScaleDivFromAxis(bool on); + void setScaleDivFromAxis( bool on ); bool isScaleDivFromAxis() const; -#if QT_VERSION < 0x040000 - void setColorGroup(const QColorGroup &); - QColorGroup colorGroup() const; -#else - void setPalette(const QPalette &); + void setPalette( const QPalette & ); QPalette palette() const; -#endif - void setFont(const QFont&); + void setFont( const QFont& ); QFont font() const; - void setScaleDraw(QwtScaleDraw *); + void setScaleDraw( QwtScaleDraw * ); const QwtScaleDraw *scaleDraw() const; QwtScaleDraw *scaleDraw(); - void setPosition(double pos); + void setPosition( double pos ); double position() const; - void setBorderDistance(int numPixels); + void setBorderDistance( int numPixels ); int borderDistance() const; - void setAlignment(QwtScaleDraw::Alignment); + void setAlignment( QwtScaleDraw::Alignment ); - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &rect) const; + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; - virtual void updateScaleDiv(const QwtScaleDiv&, - const QwtScaleDiv&); + virtual void updateScaleDiv( const QwtScaleDiv &, const QwtScaleDiv & ); private: - void updateBorders(); - class PrivateData; PrivateData *d_data; }; diff --git a/libs/qwt/qwt_plot_seriesitem.cpp b/libs/qwt/qwt_plot_seriesitem.cpp new file mode 100644 index 0000000000..e5007efed2 --- /dev/null +++ b/libs/qwt/qwt_plot_seriesitem.cpp @@ -0,0 +1,112 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_seriesitem.h" + +class QwtPlotSeriesItem::PrivateData +{ +public: + PrivateData(): + orientation( Qt::Vertical ) + { + } + + Qt::Orientation orientation; +}; + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotSeriesItem::QwtPlotSeriesItem( const QwtText &title ): + QwtPlotItem( title ) +{ + d_data = new PrivateData(); + setItemInterest( QwtPlotItem::ScaleInterest, true ); +} + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotSeriesItem::QwtPlotSeriesItem( const QString &title ): + QwtPlotItem( QwtText( title ) ) +{ + d_data = new PrivateData(); +} + +//! Destructor +QwtPlotSeriesItem::~QwtPlotSeriesItem() +{ + delete d_data; +} + +/*! + Set the orientation of the item. + + The orientation() might be used in specific way by a plot item. + F.e. a QwtPlotCurve uses it to identify how to display the curve + int QwtPlotCurve::Steps or QwtPlotCurve::Sticks style. + + \sa orientation() +*/ +void QwtPlotSeriesItem::setOrientation( Qt::Orientation orientation ) +{ + if ( d_data->orientation != orientation ) + { + d_data->orientation = orientation; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Orientation of the plot item + \sa setOrientation() +*/ +Qt::Orientation QwtPlotSeriesItem::orientation() const +{ + return d_data->orientation; +} + +/*! + \brief Draw the complete series + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas +*/ +void QwtPlotSeriesItem::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const +{ + drawSeries( painter, xMap, yMap, canvasRect, 0, -1 ); +} + +QRectF QwtPlotSeriesItem::boundingRect() const +{ + return dataRect(); +} + +void QwtPlotSeriesItem::updateScaleDiv( + const QwtScaleDiv &xScaleDiv, const QwtScaleDiv &yScaleDiv ) +{ + const QRectF rect = QRectF( + xScaleDiv.lowerBound(), yScaleDiv.lowerBound(), + xScaleDiv.range(), yScaleDiv.range() ); + + setRectOfInterest( rect ); +} + +void QwtPlotSeriesItem::dataChanged() +{ + itemChanged(); +} diff --git a/libs/qwt/qwt_plot_seriesitem.h b/libs/qwt/qwt_plot_seriesitem.h new file mode 100644 index 0000000000..f58334ac0a --- /dev/null +++ b/libs/qwt/qwt_plot_seriesitem.h @@ -0,0 +1,66 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_SERIES_ITEM_H +#define QWT_PLOT_SERIES_ITEM_H + +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include "qwt_scale_div.h" +#include "qwt_series_data.h" +#include "qwt_series_store.h" + +/*! + \brief Base class for plot items representing a series of samples +*/ +class QWT_EXPORT QwtPlotSeriesItem: public QwtPlotItem, + public virtual QwtAbstractSeriesStore +{ +public: + explicit QwtPlotSeriesItem( const QString &title = QString::null ); + explicit QwtPlotSeriesItem( const QwtText &title ); + + virtual ~QwtPlotSeriesItem(); + + void setOrientation( Qt::Orientation ); + Qt::Orientation orientation() const; + + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF & ) const; + + /*! + Draw a subset of the samples + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted. If to < 0 the + curve will be painted to its last point. + */ + virtual void drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const = 0; + + virtual QRectF boundingRect() const; + + virtual void updateScaleDiv( + const QwtScaleDiv &, const QwtScaleDiv & ); + +protected: + virtual void dataChanged(); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_shapeitem.cpp b/libs/qwt/qwt_plot_shapeitem.cpp new file mode 100644 index 0000000000..d2ece19e44 --- /dev/null +++ b/libs/qwt/qwt_plot_shapeitem.cpp @@ -0,0 +1,491 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_shapeitem.h" +#include "qwt_scale_map.h" +#include "qwt_painter.h" +#include "qwt_curve_fitter.h" +#include "qwt_clipper.h" + +static QPainterPath qwtTransformPath( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QPainterPath &path, bool doAlign ) +{ + QPainterPath shape; + shape.setFillRule( path.fillRule() ); + + for ( int i = 0; i < path.elementCount(); i++ ) + { + const QPainterPath::Element &element = path.elementAt( i ); + + double x = xMap.transform( element.x ); + double y = yMap.transform( element.y ); + + switch( element.type ) + { + case QPainterPath::MoveToElement: + { + if ( doAlign ) + { + x = qRound( x ); + y = qRound( y ); + } + + shape.moveTo( x, y ); + break; + } + case QPainterPath::LineToElement: + { + if ( doAlign ) + { + x = qRound( x ); + y = qRound( y ); + } + + shape.lineTo( x, y ); + break; + } + case QPainterPath::CurveToElement: + { + const QPainterPath::Element& element1 = path.elementAt( ++i ); + const double x1 = xMap.transform( element1.x ); + const double y1 = yMap.transform( element1.y ); + + const QPainterPath::Element& element2 = path.elementAt( ++i ); + const double x2 = xMap.transform( element2.x ); + const double y2 = yMap.transform( element2.y ); + + shape.cubicTo( x, y, x1, y1, x2, y2 ); + break; + } + case QPainterPath::CurveToDataElement: + { + break; + } + } + } + + return shape; +} + + +class QwtPlotShapeItem::PrivateData +{ +public: + PrivateData(): + legendMode( QwtPlotShapeItem::LegendColor ), + renderTolerance( 0.0 ) + { + } + + QwtPlotShapeItem::PaintAttributes paintAttributes; + QwtPlotShapeItem::LegendMode legendMode; + + double renderTolerance; + QRectF boundingRect; + + QPen pen; + QBrush brush; + QPainterPath shape; +}; + +/*! + \brief Constructor + + Sets the following item attributes: + - QwtPlotItem::AutoScale: true + - QwtPlotItem::Legend: false + + \param title Title +*/ +QwtPlotShapeItem::QwtPlotShapeItem( const QString& title ): + QwtPlotItem( QwtText( title ) ) +{ + init(); +} + +/*! + \brief Constructor + + Sets the following item attributes: + - QwtPlotItem::AutoScale: true + - QwtPlotItem::Legend: false + + \param title Title +*/ +QwtPlotShapeItem::QwtPlotShapeItem( const QwtText& title ): + QwtPlotItem( title ) +{ + init(); +} + +//! Destructor +QwtPlotShapeItem::~QwtPlotShapeItem() +{ + delete d_data; +} + +void QwtPlotShapeItem::init() +{ + d_data = new PrivateData(); + d_data->boundingRect = QwtPlotItem::boundingRect(); + + setItemAttribute( QwtPlotItem::AutoScale, true ); + setItemAttribute( QwtPlotItem::Legend, false ); + + setZ( 8.0 ); +} + +//! \return QwtPlotItem::Rtti_PlotShape +int QwtPlotShapeItem::rtti() const +{ + return QwtPlotItem::Rtti_PlotShape; +} + +/*! + Specify an attribute how to draw the shape + + \param attribute Paint attribute + \param on On/Off + \sa testPaintAttribute() +*/ +void QwtPlotShapeItem::setPaintAttribute( PaintAttribute attribute, bool on ) +{ + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; +} + +/*! + \return True, when attribute is enabled + \sa setPaintAttribute() +*/ +bool QwtPlotShapeItem::testPaintAttribute( PaintAttribute attribute ) const +{ + return ( d_data->paintAttributes & attribute ); +} + +/*! + Set the mode how to represent the item on the legend + + \param mode Mode + \sa legendMode() + */ +void QwtPlotShapeItem::setLegendMode( LegendMode mode ) +{ + if ( mode != d_data->legendMode ) + { + d_data->legendMode = mode; + legendChanged(); + } +} + +/*! + \return Mode how to represent the item on the legend + \sa legendMode() + */ +QwtPlotShapeItem::LegendMode QwtPlotShapeItem::legendMode() const +{ + return d_data->legendMode; +} + +//! Bounding rectangle of the shape +QRectF QwtPlotShapeItem::boundingRect() const +{ + return d_data->boundingRect; +} + +/*! + \brief Set a path built from a rectangle + + \param rect Rectangle + \sa setShape(), setPolygon(), shape() + */ +void QwtPlotShapeItem::setRect( const QRectF &rect ) +{ + QPainterPath path; + path.addRect( rect ); + + setShape( path ); +} + +/*! + \brief Set a path built from a polygon + + \param polygon Polygon + \sa setShape(), setRect(), shape() + */ +void QwtPlotShapeItem::setPolygon( const QPolygonF &polygon ) +{ + QPainterPath shape; + shape.addPolygon( polygon ); + + setShape( shape ); +} + +/*! + \brief Set the shape to be displayed + + \param shape Shape + \sa setShape(), shape() + */ +void QwtPlotShapeItem::setShape( const QPainterPath &shape ) +{ + if ( shape != d_data->shape ) + { + d_data->shape = shape; + if ( shape.isEmpty() ) + { + d_data->boundingRect = QwtPlotItem::boundingRect(); + } + else + { + d_data->boundingRect = shape.boundingRect(); + } + + itemChanged(); + } +} + +/*! + \return Shape to be displayed + \sa setShape() + */ +QPainterPath QwtPlotShapeItem::shape() const +{ + return d_data->shape; +} + +/*! + Build and assign a pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotShapeItem::setPen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setPen( QPen( color, width, style ) ); +} + +/*! + \brief Assign a pen + + The pen is used to draw the outline of the shape + + \param pen Pen + \sa pen(), brush() +*/ +void QwtPlotShapeItem::setPen( const QPen &pen ) +{ + if ( pen != d_data->pen ) + { + d_data->pen = pen; + itemChanged(); + } +} + +/*! + \return Pen used to draw the outline of the shape + \sa setPen(), brush() +*/ +QPen QwtPlotShapeItem::pen() const +{ + return d_data->pen; +} + +/*! + Assign a brush. + + The brush is used to fill the path + + \param brush Brush + \sa brush(), pen() +*/ +void QwtPlotShapeItem::setBrush( const QBrush &brush ) +{ + if ( brush != d_data->brush ) + { + d_data->brush = brush; + itemChanged(); + } +} + +/*! + \return Brush used to fill the shape + \sa setBrush(), pen() +*/ +QBrush QwtPlotShapeItem::brush() const +{ + return d_data->brush; +} + +/*! + \brief Set the tolerance for the weeding optimization + + After translating the shape into target device coordinate + ( usually widget geometries ) the painter path can be simplified + by a point weeding algorithm ( Douglas-Peucker ). + + For shapes built from curves and ellipses weeding might + have the opposite effect because they have to be expanded + to polygons. + + \param tolerance Accepted error when reducing the number of points + A value <= 0.0 disables weeding. + + \sa renderTolerance(), QwtWeedingCurveFitter + */ +void QwtPlotShapeItem::setRenderTolerance( double tolerance ) +{ + tolerance = qMax( tolerance, 0.0 ); + + if ( tolerance != d_data->renderTolerance ) + { + d_data->renderTolerance = tolerance; + itemChanged(); + } +} + +/*! + \return Tolerance for the weeding optimization + \sa setRenderTolerance() + */ +double QwtPlotShapeItem::renderTolerance() const +{ + return d_data->renderTolerance; +} + +/*! + Draw the shape item + + \param painter Painter + \param xMap X-Scale Map + \param yMap Y-Scale Map + \param canvasRect Contents rect of the plot canvas +*/ +void QwtPlotShapeItem::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const +{ + if ( d_data->shape.isEmpty() ) + return; + + if ( d_data->pen.style() == Qt::NoPen + && d_data->brush.style() == Qt::NoBrush ) + { + return; + } + + const QRectF cRect = QwtScaleMap::invTransform( + xMap, yMap, canvasRect.toRect() ); + + if ( d_data->boundingRect.intersects( cRect ) ) + { + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + QPainterPath path = qwtTransformPath( xMap, yMap, + d_data->shape, doAlign ); + + if ( testPaintAttribute( QwtPlotShapeItem::ClipPolygons ) ) + { + qreal pw = qMax( qreal( 1.0 ), painter->pen().widthF()); + QRectF clipRect = canvasRect.adjusted( -pw, -pw, pw, pw ); + + QPainterPath clippedPath; + clippedPath.setFillRule( path.fillRule() ); + + const QList<QPolygonF> polygons = path.toSubpathPolygons(); + for ( int i = 0; i < polygons.size(); i++ ) + { + const QPolygonF p = QwtClipper::clipPolygonF( + clipRect, polygons[i], true ); + + clippedPath.addPolygon( p ); + + } + + path = clippedPath; + } + + if ( d_data->renderTolerance > 0.0 ) + { + QwtWeedingCurveFitter fitter( d_data->renderTolerance ); + + QPainterPath fittedPath; + fittedPath.setFillRule( path.fillRule() ); + + const QList<QPolygonF> polygons = path.toSubpathPolygons(); + for ( int i = 0; i < polygons.size(); i++ ) + fittedPath.addPolygon( fitter.fitCurve( polygons[ i ] ) ); + + path = fittedPath; + } + + painter->setPen( d_data->pen ); + painter->setBrush( d_data->brush ); + + painter->drawPath( path ); + } +} + +/*! + \return A rectangle filled with the color of the brush ( or the pen ) + + \param index Index of the legend entry + ( usually there is only one ) + \param size Icon size + + \sa setLegendIconSize(), legendData() +*/ +QwtGraphic QwtPlotShapeItem::legendIcon( int index, + const QSizeF &size ) const +{ + Q_UNUSED( index ); + + QwtGraphic icon; + icon.setDefaultSize( size ); + + if ( size.isEmpty() ) + return icon; + + if ( d_data->legendMode == QwtPlotShapeItem::LegendShape ) + { + const QRectF &br = d_data->boundingRect; + + QPainter painter( &icon ); + painter.setRenderHint( QPainter::Antialiasing, + testRenderHint( QwtPlotItem::RenderAntialiased ) ); + + painter.translate( -br.topLeft() ); + + painter.setPen( d_data->pen ); + painter.setBrush( d_data->brush ); + painter.drawPath( d_data->shape ); + } + else + { + QColor iconColor; + if ( d_data->brush.style() != Qt::NoBrush ) + iconColor = d_data->brush.color(); + else + iconColor = d_data->pen.color(); + + icon = defaultIcon( iconColor, size ); + } + + return icon; +} + diff --git a/libs/qwt/qwt_plot_shapeitem.h b/libs/qwt/qwt_plot_shapeitem.h new file mode 100644 index 0000000000..76f78a126c --- /dev/null +++ b/libs/qwt/qwt_plot_shapeitem.h @@ -0,0 +1,111 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_SHAPE_ITEM_H +#define QWT_PLOT_SHAPE_ITEM_H + +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include <qpainterpath.h> + +/*! + \brief A plot item, which displays any graphical shape, + that can be defined by a QPainterPath + + A QPainterPath is a shape composed from intersecting and uniting + regions, rectangles, ellipses or irregular areas defined by lines, and curves. + QwtPlotShapeItem displays a shape with a pen and brush. + + QwtPlotShapeItem offers a couple of optimizations like clipping or weeding. + These algorithms need to convert the painter path into polygons that might be + less performant for paths built from curves and ellipses. + + \sa QwtPlotZone +*/ +class QWT_EXPORT QwtPlotShapeItem: public QwtPlotItem +{ +public: + /*! + Attributes to modify the drawing algorithm. + The default disables all attributes + + \sa setPaintAttribute(), testPaintAttribute() + */ + enum PaintAttribute + { + /*! + Clip polygons before painting them. In situations, where points + are far outside the visible area (f.e when zooming deep) this + might be a substantial improvement for the painting performance + + But polygon clipping will convert the painter path into + polygons what might introduce a negative impact on the + performance of paths composed from curves or ellipses. + */ + ClipPolygons = 0x01, + }; + + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + + //! Mode how to display the item on the legend + enum LegendMode + { + //! Display a scaled down version of the shape + LegendShape, + + //! Display a filled rectangle + LegendColor + }; + + explicit QwtPlotShapeItem( const QString &title = QString::null ); + explicit QwtPlotShapeItem( const QwtText &title ); + + virtual ~QwtPlotShapeItem(); + + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + void setLegendMode( LegendMode ); + LegendMode legendMode() const; + + void setRect( const QRectF & ); + void setPolygon( const QPolygonF & ); + + void setShape( const QPainterPath & ); + QPainterPath shape() const; + + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); + QPen pen() const; + + void setBrush( const QBrush & ); + QBrush brush() const; + + void setRenderTolerance( double ); + double renderTolerance() const; + + virtual QRectF boundingRect() const; + + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; + + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; + + virtual int rtti() const; + +private: + void init(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_spectrocurve.cpp b/libs/qwt/qwt_plot_spectrocurve.cpp new file mode 100644 index 0000000000..5a2a023dd7 --- /dev/null +++ b/libs/qwt/qwt_plot_spectrocurve.cpp @@ -0,0 +1,321 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_spectrocurve.h" +#include "qwt_color_map.h" +#include "qwt_scale_map.h" +#include "qwt_painter.h" +#include <qpainter.h> + +class QwtPlotSpectroCurve::PrivateData +{ +public: + PrivateData(): + colorRange( 0.0, 1000.0 ), + penWidth(0.0), + paintAttributes( QwtPlotSpectroCurve::ClipPoints ) + { + colorMap = new QwtLinearColorMap(); + } + + ~PrivateData() + { + delete colorMap; + } + + QwtColorMap *colorMap; + QwtInterval colorRange; + QVector<QRgb> colorTable; + double penWidth; + QwtPlotSpectroCurve::PaintAttributes paintAttributes; +}; + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotSpectroCurve::QwtPlotSpectroCurve( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotSpectroCurve::QwtPlotSpectroCurve( const QString &title ): + QwtPlotSeriesItem( QwtText( title ) ) +{ + init(); +} + +//! Destructor +QwtPlotSpectroCurve::~QwtPlotSpectroCurve() +{ + delete d_data; +} + +/*! + \brief Initialize data members +*/ +void QwtPlotSpectroCurve::init() +{ + setItemAttribute( QwtPlotItem::Legend ); + setItemAttribute( QwtPlotItem::AutoScale ); + + d_data = new PrivateData; + setData( new QwtPoint3DSeriesData() ); + + setZ( 20.0 ); +} + +//! \return QwtPlotItem::Rtti_PlotSpectroCurve +int QwtPlotSpectroCurve::rtti() const +{ + return QwtPlotItem::Rtti_PlotSpectroCurve; +} + +/*! + Specify an attribute how to draw the curve + + \param attribute Paint attribute + \param on On/Off + /sa PaintAttribute, testPaintAttribute() +*/ +void QwtPlotSpectroCurve::setPaintAttribute( PaintAttribute attribute, bool on ) +{ + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; +} + +/*! + \return True, when attribute is enabled + \sa PaintAttribute, setPaintAttribute() +*/ +bool QwtPlotSpectroCurve::testPaintAttribute( PaintAttribute attribute ) const +{ + return ( d_data->paintAttributes & attribute ); +} + +/*! + Initialize data with an array of samples. + \param samples Vector of points +*/ +void QwtPlotSpectroCurve::setSamples( const QVector<QwtPoint3D> &samples ) +{ + setData( new QwtPoint3DSeriesData( samples ) ); +} + +/*! + Assign a series of samples + + setSamples() is just a wrapper for setData() without any additional + value - beside that it is easier to find for the developer. + + \param data Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. +*/ +void QwtPlotSpectroCurve::setSamples( + QwtSeriesData<QwtPoint3D> *data ) +{ + setData( data ); +} + +/*! + Change the color map + + Often it is useful to display the mapping between intensities and + colors as an additional plot axis, showing a color bar. + + \param colorMap Color Map + + \sa colorMap(), setColorRange(), QwtColorMap::color(), + QwtScaleWidget::setColorBarEnabled(), QwtScaleWidget::setColorMap() +*/ +void QwtPlotSpectroCurve::setColorMap( QwtColorMap *colorMap ) +{ + if ( colorMap != d_data->colorMap ) + { + delete d_data->colorMap; + d_data->colorMap = colorMap; + } + + legendChanged(); + itemChanged(); +} + +/*! + \return Color Map used for mapping the intensity values to colors + \sa setColorMap(), setColorRange(), QwtColorMap::color() +*/ +const QwtColorMap *QwtPlotSpectroCurve::colorMap() const +{ + return d_data->colorMap; +} + +/*! + Set the value interval, that corresponds to the color map + + \param interval interval.minValue() corresponds to 0.0, + interval.maxValue() to 1.0 on the color map. + + \sa colorRange(), setColorMap(), QwtColorMap::color() +*/ +void QwtPlotSpectroCurve::setColorRange( const QwtInterval &interval ) +{ + if ( interval != d_data->colorRange ) + { + d_data->colorRange = interval; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Value interval, that corresponds to the color map + \sa setColorRange(), setColorMap(), QwtColorMap::color() +*/ +QwtInterval &QwtPlotSpectroCurve::colorRange() const +{ + return d_data->colorRange; +} + +/*! + Assign a pen width + + \param penWidth New pen width + \sa penWidth() +*/ +void QwtPlotSpectroCurve::setPenWidth(double penWidth) +{ + if ( penWidth < 0.0 ) + penWidth = 0.0; + + if ( d_data->penWidth != penWidth ) + { + d_data->penWidth = penWidth; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Pen width used to draw a dot + \sa setPenWidth() +*/ +double QwtPlotSpectroCurve::penWidth() const +{ + return d_data->penWidth; +} + +/*! + Draw a subset of the points + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawDots() +*/ +void QwtPlotSpectroCurve::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( !painter || dataSize() <= 0 ) + return; + + if ( to < 0 ) + to = dataSize() - 1; + + if ( from < 0 ) + from = 0; + + if ( from > to ) + return; + + drawDots( painter, xMap, yMap, canvasRect, from, to ); +} + +/*! + Draw a subset of the points + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawSeries() +*/ +void QwtPlotSpectroCurve::drawDots( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( !d_data->colorRange.isValid() ) + return; + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + const QwtColorMap::Format format = d_data->colorMap->format(); + if ( format == QwtColorMap::Indexed ) + d_data->colorTable = d_data->colorMap->colorTable( d_data->colorRange ); + + const QwtSeriesData<QwtPoint3D> *series = data(); + + for ( int i = from; i <= to; i++ ) + { + const QwtPoint3D sample = series->sample( i ); + + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); + } + + if ( d_data->paintAttributes & QwtPlotSpectroCurve::ClipPoints ) + { + if ( !canvasRect.contains( xi, yi ) ) + continue; + } + + if ( format == QwtColorMap::RGB ) + { + const QRgb rgb = d_data->colorMap->rgb( + d_data->colorRange, sample.z() ); + + painter->setPen( QPen( QColor::fromRgba( rgb ), d_data->penWidth ) ); + } + else + { + const unsigned char index = d_data->colorMap->colorIndex( + d_data->colorRange, sample.z() ); + + painter->setPen( QPen( QColor::fromRgba( d_data->colorTable[index] ), + d_data->penWidth ) ); + } + + QwtPainter::drawPoint( painter, QPointF( xi, yi ) ); + } + + d_data->colorTable.clear(); +} diff --git a/libs/qwt/qwt_plot_spectrocurve.h b/libs/qwt/qwt_plot_spectrocurve.h new file mode 100644 index 0000000000..1972c3e6ec --- /dev/null +++ b/libs/qwt/qwt_plot_spectrocurve.h @@ -0,0 +1,79 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_CURVE_3D_H +#define QWT_PLOT_CURVE_3D_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_series_data.h" + +class QwtSymbol; +class QwtColorMap; + +/*! + \brief Curve that displays 3D points as dots, where the z coordinate is + mapped to a color. +*/ +class QWT_EXPORT QwtPlotSpectroCurve: + public QwtPlotSeriesItem, QwtSeriesStore<QwtPoint3D> +{ +public: + //! Paint attributes + enum PaintAttribute + { + //! Clip points outside the canvas rectangle + ClipPoints = 1 + }; + + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + + explicit QwtPlotSpectroCurve( const QString &title = QString::null ); + explicit QwtPlotSpectroCurve( const QwtText &title ); + + virtual ~QwtPlotSpectroCurve(); + + virtual int rtti() const; + + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + void setSamples( const QVector<QwtPoint3D> & ); + void setSamples( QwtSeriesData<QwtPoint3D> * ); + + + void setColorMap( QwtColorMap * ); + const QwtColorMap *colorMap() const; + + void setColorRange( const QwtInterval & ); + QwtInterval & colorRange() const; + + virtual void drawSeries( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + void setPenWidth(double width); + double penWidth() const; + +protected: + virtual void drawDots( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + +private: + void init(); + + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotSpectroCurve::PaintAttributes ) + +#endif diff --git a/libs/qwt/qwt_plot_spectrogram.cpp b/libs/qwt/qwt_plot_spectrogram.cpp index 75622ab7ee..0c59013a32 100644 --- a/libs/qwt/qwt_plot_spectrogram.cpp +++ b/libs/qwt/qwt_plot_spectrogram.cpp @@ -7,108 +7,49 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qimage.h> -#include <qpen.h> -#include <qpainter.h> +#include "qwt_plot_spectrogram.h" #include "qwt_painter.h" -#include "qwt_double_interval.h" +#include "qwt_interval.h" #include "qwt_scale_map.h" #include "qwt_color_map.h" -#include "qwt_plot_spectrogram.h" - -#if QT_VERSION < 0x040000 -typedef QValueVector<QRgb> QwtColorTable; -#else -typedef QVector<QRgb> QwtColorTable; -#endif - -class QwtPlotSpectrogramImage: public QImage -{ - // This class hides some Qt3/Qt4 API differences -public: - QwtPlotSpectrogramImage(const QSize &size, QwtColorMap::Format format): -#if QT_VERSION < 0x040000 - QImage(size, format == QwtColorMap::RGB ? 32 : 8) -#else - QImage(size, format == QwtColorMap::RGB - ? QImage::Format_ARGB32 : QImage::Format_Indexed8 ) -#endif - { - } - - QwtPlotSpectrogramImage(const QImage &other): - QImage(other) { - } - - void initColorTable(const QImage& other) { -#if QT_VERSION < 0x040000 - const unsigned int numColors = other.numColors(); - - setNumColors(numColors); - for ( unsigned int i = 0; i < numColors; i++ ) - setColor(i, other.color(i)); -#else - setColorTable(other.colorTable()); -#endif - } - -#if QT_VERSION < 0x040000 - - void setColorTable(const QwtColorTable &colorTable) { - setNumColors(colorTable.size()); - for ( unsigned int i = 0; i < colorTable.size(); i++ ) - setColor(i, colorTable[i]); - } - - QwtColorTable colorTable() const { - QwtColorTable table(numColors()); - for ( int i = 0; i < numColors(); i++ ) - table[i] = color(i); - - return table; - } +#include <qimage.h> +#include <qpen.h> +#include <qpainter.h> +#include <qmath.h> +#include <qalgorithms.h> +#if QT_VERSION >= 0x040400 +#include <qthread.h> +#include <qfuture.h> +#include <qtconcurrentrun.h> #endif -}; class QwtPlotSpectrogram::PrivateData { public: - class DummyData: public QwtRasterData + PrivateData(): + data( NULL ) { - public: - virtual QwtRasterData *copy() const { - return new DummyData(); - } - - virtual double value(double, double) const { - return 0.0; - } - - virtual QwtDoubleInterval range() const { - return QwtDoubleInterval(0.0, 1.0); - } - }; - - PrivateData() { - data = new DummyData(); colorMap = new QwtLinearColorMap(); displayMode = ImageMode; - conrecAttributes = QwtRasterData::IgnoreAllVerticesOnLevel; - conrecAttributes |= QwtRasterData::IgnoreOutOfRange; + conrecFlags = QwtRasterData::IgnoreAllVerticesOnLevel; +#if 0 + conrecFlags |= QwtRasterData::IgnoreOutOfRange; +#endif } - ~PrivateData() { + ~PrivateData() + { delete data; delete colorMap; } QwtRasterData *data; QwtColorMap *colorMap; - int displayMode; + DisplayModes displayMode; - QwtValueList contourLevels; + QList<double> contourLevels; QPen defaultContourPen; - int conrecAttributes; + QwtRasterData::ConrecFlags conrecFlags; }; /*! @@ -122,15 +63,15 @@ public: \sa QwtPlotItem::setItemAttribute(), QwtPlotItem::setZ() */ -QwtPlotSpectrogram::QwtPlotSpectrogram(const QString &title): - QwtPlotRasterItem(title) +QwtPlotSpectrogram::QwtPlotSpectrogram( const QString &title ): + QwtPlotRasterItem( title ) { d_data = new PrivateData(); - setItemAttribute(QwtPlotItem::AutoScale, true); - setItemAttribute(QwtPlotItem::Legend, false); + setItemAttribute( QwtPlotItem::AutoScale, true ); + setItemAttribute( QwtPlotItem::Legend, false ); - setZ(8.0); + setZ( 8.0 ); } //! Destructor @@ -155,15 +96,17 @@ int QwtPlotSpectrogram::rtti() const \sa DisplayMode, displayMode() */ -void QwtPlotSpectrogram::setDisplayMode(DisplayMode mode, bool on) +void QwtPlotSpectrogram::setDisplayMode( DisplayMode mode, bool on ) { - if ( on != bool(mode & d_data->displayMode) ) { + if ( on != bool( mode & d_data->displayMode ) ) + { if ( on ) d_data->displayMode |= mode; else d_data->displayMode &= ~mode; } + legendChanged(); itemChanged(); } @@ -173,9 +116,9 @@ void QwtPlotSpectrogram::setDisplayMode(DisplayMode mode, bool on) \param mode Display mode \return true if mode is enabled */ -bool QwtPlotSpectrogram::testDisplayMode(DisplayMode mode) const +bool QwtPlotSpectrogram::testDisplayMode( DisplayMode mode ) const { - return (d_data->displayMode & mode); + return ( d_data->displayMode & mode ); } /*! @@ -189,12 +132,17 @@ bool QwtPlotSpectrogram::testDisplayMode(DisplayMode mode) const \sa colorMap(), QwtScaleWidget::setColorBarEnabled(), QwtScaleWidget::setColorMap() */ -void QwtPlotSpectrogram::setColorMap(const QwtColorMap &colorMap) +void QwtPlotSpectrogram::setColorMap( QwtColorMap *colorMap ) { - delete d_data->colorMap; - d_data->colorMap = colorMap.copy(); + if ( d_data->colorMap != colorMap ) + { + delete d_data->colorMap; + d_data->colorMap = colorMap; + } invalidateCache(); + + legendChanged(); itemChanged(); } @@ -202,9 +150,28 @@ void QwtPlotSpectrogram::setColorMap(const QwtColorMap &colorMap) \return Color Map used for mapping the intensity values to colors \sa setColorMap() */ -const QwtColorMap &QwtPlotSpectrogram::colorMap() const +const QwtColorMap *QwtPlotSpectrogram::colorMap() const { - return *d_data->colorMap; + return d_data->colorMap; +} + +/*! + Build and assign the default pen for the contour lines + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotSpectrogram::setDefaultContourPen( + const QColor &color, qreal width, Qt::PenStyle style ) +{ + setDefaultContourPen( QPen( color, width, style ) ); } /*! @@ -215,19 +182,22 @@ const QwtColorMap &QwtPlotSpectrogram::colorMap() const Otherwise (pen.style() == Qt::NoPen) the pen is calculated for each contour level using contourPen(). - \sa defaultContourPen, contourPen + \sa defaultContourPen(), contourPen() */ -void QwtPlotSpectrogram::setDefaultContourPen(const QPen &pen) +void QwtPlotSpectrogram::setDefaultContourPen( const QPen &pen ) { - if ( pen != d_data->defaultContourPen ) { + if ( pen != d_data->defaultContourPen ) + { d_data->defaultContourPen = pen; + + legendChanged(); itemChanged(); } } /*! \return Default contour pen - \sa setDefaultContourPen + \sa setDefaultContourPen() */ QPen QwtPlotSpectrogram::defaultContourPen() const { @@ -243,35 +213,39 @@ QPen QwtPlotSpectrogram::defaultContourPen() const \return Pen for the contour line \note contourPen is only used if defaultContourPen().style() == Qt::NoPen - \sa setDefaultContourPen, setColorMap, setContourLevels + \sa setDefaultContourPen(), setColorMap(), setContourLevels() */ -QPen QwtPlotSpectrogram::contourPen(double level) const +QPen QwtPlotSpectrogram::contourPen( double level ) const { - const QwtDoubleInterval intensityRange = d_data->data->range(); - const QColor c(d_data->colorMap->rgb(intensityRange, level)); + if ( d_data->data == NULL || d_data->colorMap == NULL ) + return QPen(); + + const QwtInterval intensityRange = d_data->data->interval(Qt::ZAxis); + const QColor c( d_data->colorMap->rgb( intensityRange, level ) ); - return QPen(c); + return QPen( c ); } /*! Modify an attribute of the CONREC algorithm, used to calculate the contour lines. - \param attribute CONREC attribute + \param flag CONREC flag \param on On/Off - \sa testConrecAttribute, renderContourLines, QwtRasterData::contourLines + \sa testConrecFlag(), renderContourLines(), + QwtRasterData::contourLines() */ -void QwtPlotSpectrogram::setConrecAttribute( - QwtRasterData::ConrecAttribute attribute, bool on) +void QwtPlotSpectrogram::setConrecFlag( + QwtRasterData::ConrecFlag flag, bool on ) { - if ( bool(d_data->conrecAttributes & attribute) == on ) + if ( bool( d_data->conrecFlags & flag ) == on ) return; if ( on ) - d_data->conrecAttributes |= attribute; + d_data->conrecFlags |= flag; else - d_data->conrecAttributes &= ~attribute; + d_data->conrecFlags &= ~flag; itemChanged(); } @@ -280,44 +254,47 @@ void QwtPlotSpectrogram::setConrecAttribute( Test an attribute of the CONREC algorithm, used to calculate the contour lines. - \param attribute CONREC attribute + \param flag CONREC flag \return true, is enabled - \sa setConrecAttribute, renderContourLines, QwtRasterData::contourLines + The default setting enables QwtRasterData::IgnoreAllVerticesOnLevel + + \sa setConrecClag(), renderContourLines(), + QwtRasterData::contourLines() */ -bool QwtPlotSpectrogram::testConrecAttribute( - QwtRasterData::ConrecAttribute attribute) const +bool QwtPlotSpectrogram::testConrecFlag( + QwtRasterData::ConrecFlag flag ) const { - return d_data->conrecAttributes & attribute; + return d_data->conrecFlags & flag; } /*! Set the levels of the contour lines \param levels Values of the contour levels - \sa contourLevels, renderContourLines, QwtRasterData::contourLines + \sa contourLevels(), renderContourLines(), + QwtRasterData::contourLines() \note contourLevels returns the same levels but sorted. */ -void QwtPlotSpectrogram::setContourLevels(const QwtValueList &levels) +void QwtPlotSpectrogram::setContourLevels( const QList<double> &levels ) { d_data->contourLevels = levels; -#if QT_VERSION >= 0x040000 - qSort(d_data->contourLevels); -#else - qHeapSort(d_data->contourLevels); -#endif + qSort( d_data->contourLevels ); + + legendChanged(); itemChanged(); } /*! - \brief Return the levels of the contour lines. + \return Levels of the contour lines. The levels are sorted in increasing order. - \sa contourLevels, renderContourLines, QwtRasterData::contourLines + \sa contourLevels(), renderContourLines(), + QwtRasterData::contourLines() */ -QwtValueList QwtPlotSpectrogram::contourLevels() const +QList<double> QwtPlotSpectrogram::contourLevels() const { return d_data->contourLevels; } @@ -328,192 +305,243 @@ QwtValueList QwtPlotSpectrogram::contourLevels() const \param data Spectrogram Data \sa data() */ -void QwtPlotSpectrogram::setData(const QwtRasterData &data) +void QwtPlotSpectrogram::setData( QwtRasterData *data ) { - delete d_data->data; - d_data->data = data.copy(); + if ( data != d_data->data ) + { + delete d_data->data; + d_data->data = data; - invalidateCache(); - itemChanged(); + invalidateCache(); + itemChanged(); + } +} + +/*! + \return Spectrogram data + \sa setData() +*/ +const QwtRasterData *QwtPlotSpectrogram::data() const +{ + return d_data->data; } /*! \return Spectrogram data \sa setData() */ -const QwtRasterData &QwtPlotSpectrogram::data() const +QwtRasterData *QwtPlotSpectrogram::data() { - return *d_data->data; + return d_data->data; } /*! - \return Bounding rect of the data - \sa QwtRasterData::boundingRect + \return Bounding interval for an axis + + The default implementation returns the interval of the + associated raster data object. + + \param axis X, Y, or Z axis + \sa QwtRasterData::interval() */ -QwtDoubleRect QwtPlotSpectrogram::boundingRect() const +QwtInterval QwtPlotSpectrogram::interval(Qt::Axis axis) const { - return d_data->data->boundingRect(); + if ( d_data->data == NULL ) + return QwtInterval(); + + return d_data->data->interval( axis ); } /*! - \brief Returns the recommended raster for a given rect. + \brief Pixel hint + + The geometry of a pixel is used to calculated the resolution and + alignment of the rendered image. - F.e the raster hint is used to limit the resolution of - the image that is rendered. + The default implementation returns data()->pixelHint( rect ); - \param rect Rect for the raster hint - \return data().rasterHint(rect) + \param area In most implementations the resolution of the data doesn't + depend on the requested area. + + \return Bounding rectangle of a pixel + + \sa QwtPlotRasterItem::pixelHint(), QwtRasterData::pixelHint(), + render(), renderImage() */ -QSize QwtPlotSpectrogram::rasterHint(const QwtDoubleRect &rect) const +QRectF QwtPlotSpectrogram::pixelHint( const QRectF &area ) const { - return d_data->data->rasterHint(rect); + if ( d_data->data == NULL ) + return QRectF(); + + return d_data->data->pixelHint( area ); } /*! - \brief Render an image from the data and color map. + \brief Render an image from data and color map. - The area is translated into a rect of the paint device. - For each pixel of this rect the intensity is mapped - into a color. + For each pixel of area the value is mapped into a color. \param xMap X-Scale Map \param yMap Y-Scale Map - \param area Area that should be rendered in scale coordinates. + \param area Requested area for the image in scale coordinates + \param imageSize Size of the requested image \return A QImage::Format_Indexed8 or QImage::Format_ARGB32 depending on the color map. - \sa QwtRasterData::intensity(), QwtColorMap::rgb(), + \sa QwtRasterData::value(), QwtColorMap::rgb(), QwtColorMap::colorIndex() */ QImage QwtPlotSpectrogram::renderImage( const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QwtDoubleRect &area) const + const QRectF &area, const QSize &imageSize ) const { - if ( area.isEmpty() ) + if ( imageSize.isEmpty() || d_data->data == NULL + || d_data->colorMap == NULL ) + { return QImage(); - - QRect rect = transform(xMap, yMap, area); - - QwtScaleMap xxMap = xMap; - QwtScaleMap yyMap = yMap; - - const QSize res = d_data->data->rasterHint(area); - if ( res.isValid() ) { - /* - It is useless to render an image with a higher resolution - than the data offers. Of course someone will have to - scale this image later into the size of the given rect, but f.e. - in case of postscript this will done on the printer. - */ - rect.setSize(rect.size().boundedTo(res)); - - int px1 = rect.x(); - int px2 = rect.x() + rect.width(); - if ( xMap.p1() > xMap.p2() ) - qSwap(px1, px2); - - double sx1 = area.x(); - double sx2 = area.x() + area.width(); - if ( xMap.s1() > xMap.s2() ) - qSwap(sx1, sx2); - - int py1 = rect.y(); - int py2 = rect.y() + rect.height(); - if ( yMap.p1() > yMap.p2() ) - qSwap(py1, py2); - - double sy1 = area.y(); - double sy2 = area.y() + area.height(); - if ( yMap.s1() > yMap.s2() ) - qSwap(sy1, sy2); - - xxMap.setPaintInterval(px1, px2); - xxMap.setScaleInterval(sx1, sx2); - yyMap.setPaintInterval(py1, py2); - yyMap.setScaleInterval(sy1, sy2); } - QwtPlotSpectrogramImage image(rect.size(), d_data->colorMap->format()); - - const QwtDoubleInterval intensityRange = d_data->data->range(); + const QwtInterval intensityRange = d_data->data->interval( Qt::ZAxis ); if ( !intensityRange.isValid() ) - return image; + return QImage(); - d_data->data->initRaster(area, rect.size()); + QImage::Format format = ( d_data->colorMap->format() == QwtColorMap::RGB ) + ? QImage::Format_ARGB32 : QImage::Format_Indexed8; - if ( d_data->colorMap->format() == QwtColorMap::RGB ) { - for ( int y = rect.top(); y <= rect.bottom(); y++ ) { - const double ty = yyMap.invTransform(y); + QImage image( imageSize, format ); - QRgb *line = (QRgb *)image.scanLine(y - rect.top()); - for ( int x = rect.left(); x <= rect.right(); x++ ) { - const double tx = xxMap.invTransform(x); + if ( d_data->colorMap->format() == QwtColorMap::Indexed ) + image.setColorTable( d_data->colorMap->colorTable( intensityRange ) ); - *line++ = d_data->colorMap->rgb(intensityRange, - d_data->data->value(tx, ty)); - } - } - } else if ( d_data->colorMap->format() == QwtColorMap::Indexed ) { - image.setColorTable(d_data->colorMap->colorTable(intensityRange)); + d_data->data->initRaster( area, image.size() ); - for ( int y = rect.top(); y <= rect.bottom(); y++ ) { - const double ty = yyMap.invTransform(y); +#if QT_VERSION >= 0x040400 && !defined(QT_NO_QFUTURE) + uint numThreads = renderThreadCount(); - unsigned char *line = image.scanLine(y - rect.top()); - for ( int x = rect.left(); x <= rect.right(); x++ ) { - const double tx = xxMap.invTransform(x); + if ( numThreads <= 0 ) + numThreads = QThread::idealThreadCount(); - *line++ = d_data->colorMap->colorIndex(intensityRange, - d_data->data->value(tx, ty)); - } + if ( numThreads <= 0 ) + numThreads = 1; + + const int numRows = imageSize.height() / numThreads; + + QList< QFuture<void> > futures; + for ( uint i = 0; i < numThreads; i++ ) + { + QRect tile( 0, i * numRows, image.width(), numRows ); + if ( i == numThreads - 1 ) + { + tile.setHeight( image.height() - i * numRows ); + renderTile( xMap, yMap, tile, &image ); + } + else + { + futures += QtConcurrent::run( + this, &QwtPlotSpectrogram::renderTile, + xMap, yMap, tile, &image ); } } + for ( int i = 0; i < futures.size(); i++ ) + futures[i].waitForFinished(); + +#else // QT_VERSION < 0x040400 + const QRect tile( 0, 0, image.width(), image.height() ); + renderTile( xMap, yMap, tile, &image ); +#endif d_data->data->discardRaster(); - // Mirror the image in case of inverted maps + return image; +} - const bool hInvert = xxMap.p1() > xxMap.p2(); - const bool vInvert = yyMap.p1() < yyMap.p2(); - if ( hInvert || vInvert ) { -#ifdef __GNUC__ -#endif -#if QT_VERSION < 0x040000 - image = image.mirror(hInvert, vInvert); -#else - image = image.mirrored(hInvert, vInvert); -#endif +/*! + \brief Render a tile of an image. + + Rendering in tiles can be used to composite an image in parallel + threads. + + \param xMap X-Scale Map + \param yMap Y-Scale Map + \param tile Geometry of the tile in image coordinates + \param image Image to be rendered +*/ +void QwtPlotSpectrogram::renderTile( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRect &tile, QImage *image ) const +{ + const QwtInterval range = d_data->data->interval( Qt::ZAxis ); + if ( !range.isValid() ) + return; + + if ( d_data->colorMap->format() == QwtColorMap::RGB ) + { + for ( int y = tile.top(); y <= tile.bottom(); y++ ) + { + const double ty = yMap.invTransform( y ); + + QRgb *line = reinterpret_cast<QRgb *>( image->scanLine( y ) ); + line += tile.left(); + + for ( int x = tile.left(); x <= tile.right(); x++ ) + { + const double tx = xMap.invTransform( x ); + + *line++ = d_data->colorMap->rgb( range, + d_data->data->value( tx, ty ) ); + } + } } + else if ( d_data->colorMap->format() == QwtColorMap::Indexed ) + { + for ( int y = tile.top(); y <= tile.bottom(); y++ ) + { + const double ty = yMap.invTransform( y ); - return image; + unsigned char *line = image->scanLine( y ); + line += tile.left(); + + for ( int x = tile.left(); x <= tile.right(); x++ ) + { + const double tx = xMap.invTransform( x ); + + *line++ = d_data->colorMap->colorIndex( range, + d_data->data->value( tx, ty ) ); + } + } + } } /*! \brief Return the raster to be used by the CONREC contour algorithm. - A larger size will improve the precisision of the CONREC algorithm, + A larger size will improve the precision of the CONREC algorithm, but will slow down the time that is needed to calculate the lines. The default implementation returns rect.size() / 2 bounded to - data().rasterHint(). + the resolution depending on pixelSize(). - \param area Rect, where to calculate the contour lines - \param rect Rect in pixel coordinates, where to paint the contour lines + \param area Rectangle, where to calculate the contour lines + \param rect Rectangle in pixel coordinates, where to paint the contour lines \return Raster to be used by the CONREC contour algorithm. \note The size will be bounded to rect.size(). - \sa drawContourLines, QwtRasterData::contourLines + \sa drawContourLines(), QwtRasterData::contourLines() */ -QSize QwtPlotSpectrogram::contourRasterSize(const QwtDoubleRect &area, - const QRect &rect) const +QSize QwtPlotSpectrogram::contourRasterSize( + const QRectF &area, const QRect &rect ) const { QSize raster = rect.size() / 2; - const QSize rasterHint = d_data->data->rasterHint(area); - if ( rasterHint.isValid() ) - raster = raster.boundedTo(rasterHint); + const QRectF pixelRect = pixelHint( area ); + if ( !pixelRect.isEmpty() ) + { + const QSize res( qCeil( rect.width() / pixelRect.width() ), + qCeil( rect.height() / pixelRect.height() ) ); + raster = raster.boundedTo( res ); + } return raster; } @@ -523,24 +551,20 @@ QSize QwtPlotSpectrogram::contourRasterSize(const QwtDoubleRect &area, \param rect Rectangle, where to calculate the contour lines \param raster Raster, used by the CONREC algorithm + \return Calculated contour lines - \sa contourLevels, setConrecAttribute, QwtRasterData::contourLines + \sa contourLevels(), setConrecFlag(), + QwtRasterData::contourLines() */ QwtRasterData::ContourLines QwtPlotSpectrogram::renderContourLines( - const QwtDoubleRect &rect, const QSize &raster) const + const QRectF &rect, const QSize &raster ) const { - return d_data->data->contourLines(rect, raster, - d_data->contourLevels, d_data->conrecAttributes ); -} + if ( d_data->data == NULL ) + return QwtRasterData::ContourLines(); -// These pragmas are local modifications to this third party library to silence warnings -#ifdef Q_OS_LINUX -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-but-set-variable" -#elif defined(Q_OS_MAC) -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-variable" -#endif + return d_data->data->contourLines( rect, raster, + d_data->contourLevels, d_data->conrecFlags ); +} /*! Paint the contour lines @@ -550,91 +574,87 @@ QwtRasterData::ContourLines QwtPlotSpectrogram::renderContourLines( \param yMap Maps y-values into pixel coordinates. \param contourLines Contour lines - \sa renderContourLines, defaultContourPen, contourPen + \sa renderContourLines(), defaultContourPen(), contourPen() */ -void QwtPlotSpectrogram::drawContourLines(QPainter *painter, +void QwtPlotSpectrogram::drawContourLines( QPainter *painter, const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QwtRasterData::ContourLines &contourLines) const + const QwtRasterData::ContourLines &contourLines ) const { - const QwtDoubleInterval intensityRange = d_data->data->range(); + if ( d_data->data == NULL ) + return; - const int numLevels = (int)d_data->contourLevels.size(); - for (int l = 0; l < numLevels; l++) { + const int numLevels = d_data->contourLevels.size(); + for ( int l = 0; l < numLevels; l++ ) + { const double level = d_data->contourLevels[l]; QPen pen = defaultContourPen(); if ( pen.style() == Qt::NoPen ) - pen = contourPen(level); + pen = contourPen( level ); if ( pen.style() == Qt::NoPen ) continue; - painter->setPen(pen); + painter->setPen( pen ); -#if QT_VERSION >= 0x040000 const QPolygonF &lines = contourLines[level]; -#else - const QwtArray<QwtDoublePoint> &lines = contourLines[level]; -#endif - for ( int i = 0; i < (int)lines.size(); i += 2 ) { - const QPoint p1( xMap.transform(lines[i].x()), - yMap.transform(lines[i].y()) ); - const QPoint p2( xMap.transform(lines[i+1].x()), - yMap.transform(lines[i+1].y()) ); - - QwtPainter::drawLine(painter, p1, p2); + for ( int i = 0; i < lines.size(); i += 2 ) + { + const QPointF p1( xMap.transform( lines[i].x() ), + yMap.transform( lines[i].y() ) ); + const QPointF p2( xMap.transform( lines[i+1].x() ), + yMap.transform( lines[i+1].y() ) ); + + QwtPainter::drawLine( painter, p1, p2 ); } } } -#ifndef Q_OS_WIN -#pragma GCC diagnostic pop -#endif - /*! \brief Draw the spectrogram \param painter Painter \param xMap Maps x-values into pixel coordinates. \param yMap Maps y-values into pixel coordinates. - \param canvasRect Contents rect of the canvas in painter coordinates + \param canvasRect Contents rectangle of the canvas in painter coordinates - \sa setDisplayMode, renderImage, - QwtPlotRasterItem::draw, drawContourLines + \sa setDisplayMode(), renderImage(), + QwtPlotRasterItem::draw(), drawContourLines() */ - -void QwtPlotSpectrogram::draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &canvasRect) const +void QwtPlotSpectrogram::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const { if ( d_data->displayMode & ImageMode ) - QwtPlotRasterItem::draw(painter, xMap, yMap, canvasRect); + QwtPlotRasterItem::draw( painter, xMap, yMap, canvasRect ); - if ( d_data->displayMode & ContourMode ) { - // Add some pixels at the borders, so that + if ( d_data->displayMode & ContourMode ) + { + // Add some pixels at the borders const int margin = 2; - QRect rasterRect(canvasRect.x() - margin, canvasRect.y() - margin, - canvasRect.width() + 2 * margin, canvasRect.height() + 2 * margin); + QRectF rasterRect( canvasRect.x() - margin, canvasRect.y() - margin, + canvasRect.width() + 2 * margin, canvasRect.height() + 2 * margin ); - QwtDoubleRect area = invTransform(xMap, yMap, rasterRect); + QRectF area = QwtScaleMap::invTransform( xMap, yMap, rasterRect ); - const QwtDoubleRect br = boundingRect(); - if ( br.isValid() ) { + const QRectF br = boundingRect(); + if ( br.isValid() ) + { area &= br; if ( area.isEmpty() ) return; - rasterRect = transform(xMap, yMap, area); + rasterRect = QwtScaleMap::transform( xMap, yMap, area ); } - QSize raster = contourRasterSize(area, rasterRect); - raster = raster.boundedTo(rasterRect.size()); - if ( raster.isValid() ) { + QSize raster = contourRasterSize( area, rasterRect.toRect() ); + raster = raster.boundedTo( rasterRect.toRect().size() ); + if ( raster.isValid() ) + { const QwtRasterData::ContourLines lines = - renderContourLines(area, raster); + renderContourLines( area, raster ); - drawContourLines(painter, xMap, yMap, lines); + drawContourLines( painter, xMap, yMap, lines ); } } } - diff --git a/libs/qwt/qwt_plot_spectrogram.h b/libs/qwt/qwt_plot_spectrogram.h index 057c3a1a43..1aa6989a6a 100644 --- a/libs/qwt/qwt_plot_spectrogram.h +++ b/libs/qwt/qwt_plot_spectrogram.h @@ -10,26 +10,29 @@ #ifndef QWT_PLOT_SPECTROGRAM_H #define QWT_PLOT_SPECTROGRAM_H -#include <qglobal.h> - -#include "qwt_valuelist.h" +#include "qwt_global.h" #include "qwt_raster_data.h" #include "qwt_plot_rasteritem.h" +#include <qlist.h> class QwtColorMap; /*! \brief A plot item, which displays a spectrogram - A spectrogram displays threedimenional data, where the 3rd dimension + A spectrogram displays 3-dimensional data, where the 3rd dimension ( the intensity ) is displayed using colors. The colors are calculated from the values using a color map. + On multi-core systems the performance of the image composition + can often be improved by dividing the area into tiles - each of them + rendered in a different thread ( see QwtPlotItem::setRenderThreadCount() ). + In ContourMode contour lines are painted for the contour levels. \image html spectrogram3.png - \sa QwtRasterData, QwtColorMap + \sa QwtRasterData, QwtColorMap, QwtPlotItem::setRenderThreadCount() */ class QWT_EXPORT QwtPlotSpectrogram: public QwtPlotRasterItem @@ -37,72 +40,79 @@ class QWT_EXPORT QwtPlotSpectrogram: public QwtPlotRasterItem public: /*! The display mode controls how the raster data will be represented. - - ImageMode\n - The values are mapped to colors using a color map. - - ContourMode\n - The data is displayed using contour lines - - When both modes are enabled the contour lines are painted on - top of the spectrogram. The default setting enables ImageMode. - \sa setDisplayMode(), testDisplayMode() */ - enum DisplayMode { - ImageMode = 1, - ContourMode = 2 + enum DisplayMode + { + //! The values are mapped to colors using a color map. + ImageMode = 0x01, + + //! The data is displayed using contour lines + ContourMode = 0x02 }; - explicit QwtPlotSpectrogram(const QString &title = QString::null); + //! Display modes + typedef QFlags<DisplayMode> DisplayModes; + + explicit QwtPlotSpectrogram( const QString &title = QString::null ); virtual ~QwtPlotSpectrogram(); - void setDisplayMode(DisplayMode, bool on = true); - bool testDisplayMode(DisplayMode) const; + void setDisplayMode( DisplayMode, bool on = true ); + bool testDisplayMode( DisplayMode ) const; - void setData(const QwtRasterData &data); - const QwtRasterData &data() const; + void setData( QwtRasterData *data ); + const QwtRasterData *data() const; + QwtRasterData *data(); - void setColorMap(const QwtColorMap &); - const QwtColorMap &colorMap() const; + void setColorMap( QwtColorMap * ); + const QwtColorMap *colorMap() const; - virtual QwtDoubleRect boundingRect() const; - virtual QSize rasterHint(const QwtDoubleRect &) const; + virtual QwtInterval interval(Qt::Axis) const; + virtual QRectF pixelHint( const QRectF & ) const; - void setDefaultContourPen(const QPen &); + void setDefaultContourPen( const QColor &, + qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setDefaultContourPen( const QPen & ); QPen defaultContourPen() const; - virtual QPen contourPen(double level) const; + virtual QPen contourPen( double level ) const; - void setConrecAttribute(QwtRasterData::ConrecAttribute, bool on); - bool testConrecAttribute(QwtRasterData::ConrecAttribute) const; + void setConrecFlag( QwtRasterData::ConrecFlag, bool on ); + bool testConrecFlag( QwtRasterData::ConrecFlag ) const; - void setContourLevels(const QwtValueList &); - QwtValueList contourLevels() const; + void setContourLevels( const QList<double> & ); + QList<double> contourLevels() const; virtual int rtti() const; - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &rect) const; + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; protected: virtual QImage renderImage( const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QwtDoubleRect &rect) const; + const QRectF &area, const QSize &imageSize ) const; virtual QSize contourRasterSize( - const QwtDoubleRect &, const QRect &) const; + const QRectF &, const QRect & ) const; virtual QwtRasterData::ContourLines renderContourLines( - const QwtDoubleRect &rect, const QSize &raster) const; + const QRectF &rect, const QSize &raster ) const; - virtual void drawContourLines(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QwtRasterData::ContourLines& lines) const; + virtual void drawContourLines( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtRasterData::ContourLines& lines ) const; + + void renderTile( const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRect &imageRect, QImage *image ) const; private: class PrivateData; PrivateData *d_data; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotSpectrogram::DisplayModes ) + #endif diff --git a/libs/qwt/qwt_plot_svgitem.cpp b/libs/qwt/qwt_plot_svgitem.cpp index 94858dca4d..dd318da588 100644 --- a/libs/qwt/qwt_plot_svgitem.cpp +++ b/libs/qwt/qwt_plot_svgitem.cpp @@ -7,35 +7,21 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qglobal.h> - +#include "qwt_plot_svgitem.h" +#include "qwt_scale_map.h" +#include "qwt_painter.h" #include <qpainter.h> -#if QT_VERSION >= 0x040100 #include <qsvgrenderer.h> -#else -#include <qbuffer.h> -#include <qpicture.h> -#endif -#if QT_VERSION < 0x040000 -#include <qpaintdevicemetrics.h> -#endif -#include "qwt_scale_map.h" -#include "qwt_legend.h" -#include "qwt_legend_item.h" -#include "qwt_plot_svgitem.h" class QwtPlotSvgItem::PrivateData { public: - PrivateData() { + PrivateData() + { } - QwtDoubleRect boundingRect; -#if QT_VERSION >= 0x040100 + QRectF boundingRect; QSvgRenderer renderer; -#else - QPicture picture; -#endif }; /*! @@ -47,8 +33,8 @@ public: \param title Title */ -QwtPlotSvgItem::QwtPlotSvgItem(const QString& title): - QwtPlotItem(QwtText(title)) +QwtPlotSvgItem::QwtPlotSvgItem( const QString& title ): + QwtPlotItem( QwtText( title ) ) { init(); } @@ -62,8 +48,8 @@ QwtPlotSvgItem::QwtPlotSvgItem(const QString& title): \param title Title */ -QwtPlotSvgItem::QwtPlotSvgItem(const QwtText& title): - QwtPlotItem(title) +QwtPlotSvgItem::QwtPlotSvgItem( const QwtText& title ): + QwtPlotItem( title ) { init(); } @@ -77,11 +63,12 @@ QwtPlotSvgItem::~QwtPlotSvgItem() void QwtPlotSvgItem::init() { d_data = new PrivateData(); + d_data->boundingRect = QwtPlotItem::boundingRect(); - setItemAttribute(QwtPlotItem::AutoScale, true); - setItemAttribute(QwtPlotItem::Legend, false); + setItemAttribute( QwtPlotItem::AutoScale, true ); + setItemAttribute( QwtPlotItem::Legend, false ); - setZ(8.0); + setZ( 8.0 ); } //! \return QwtPlotItem::Rtti_PlotSVG @@ -98,16 +85,15 @@ int QwtPlotSvgItem::rtti() const \return true, if the SVG file could be loaded */ -bool QwtPlotSvgItem::loadFile(const QwtDoubleRect &rect, - const QString &fileName) +bool QwtPlotSvgItem::loadFile( const QRectF &rect, + const QString &fileName ) { d_data->boundingRect = rect; -#if QT_VERSION >= 0x040100 - const bool ok = d_data->renderer.load(fileName); -#else - const bool ok = d_data->picture.load(fileName, "svg"); -#endif + const bool ok = d_data->renderer.load( fileName ); + + legendChanged(); itemChanged(); + return ok; } @@ -119,32 +105,24 @@ bool QwtPlotSvgItem::loadFile(const QwtDoubleRect &rect, \return true, if the SVG data could be loaded */ -bool QwtPlotSvgItem::loadData(const QwtDoubleRect &rect, - const QByteArray &data) +bool QwtPlotSvgItem::loadData( const QRectF &rect, + const QByteArray &data ) { d_data->boundingRect = rect; -#if QT_VERSION >= 0x040100 - const bool ok = d_data->renderer.load(data); -#else -#if QT_VERSION >= 0x040000 - QBuffer buffer(&(QByteArray&)data); -#else - QBuffer buffer(data); -#endif - const bool ok = d_data->picture.load(&buffer, "svg"); -#endif + const bool ok = d_data->renderer.load( data ); + + legendChanged(); itemChanged(); + return ok; } -//! Bounding rect of the item -QwtDoubleRect QwtPlotSvgItem::boundingRect() const +//! Bounding rectangle of the item +QRectF QwtPlotSvgItem::boundingRect() const { return d_data->boundingRect; } -#if QT_VERSION >= 0x040100 - //! \return Renderer used to render the SVG data const QSvgRenderer &QwtPlotSvgItem::renderer() const { @@ -156,7 +134,6 @@ QSvgRenderer &QwtPlotSvgItem::renderer() { return d_data->renderer; } -#endif /*! Draw the SVG item @@ -166,19 +143,21 @@ QSvgRenderer &QwtPlotSvgItem::renderer() \param yMap Y-Scale Map \param canvasRect Contents rect of the plot canvas */ -void QwtPlotSvgItem::draw(QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &canvasRect) const +void QwtPlotSvgItem::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const { - const QwtDoubleRect cRect = invTransform(xMap, yMap, canvasRect); - const QwtDoubleRect bRect = boundingRect(); - if ( bRect.isValid() && cRect.isValid() ) { - QwtDoubleRect rect = bRect; - if ( bRect.contains(cRect) ) + const QRectF cRect = QwtScaleMap::invTransform( + xMap, yMap, canvasRect.toRect() ); + const QRectF bRect = boundingRect(); + if ( bRect.isValid() && cRect.isValid() ) + { + QRectF rect = bRect; + if ( bRect.contains( cRect ) ) rect = cRect; - const QRect r = transform(xMap, yMap, rect); - render(painter, viewBox(rect), r); + const QRectF r = QwtScaleMap::transform( xMap, yMap, rect ); + render( painter, viewBox( rect ), r ); } } @@ -186,99 +165,55 @@ void QwtPlotSvgItem::draw(QPainter *painter, Render the SVG data \param painter Painter - \param viewBox View Box, see QSvgRenderer::viewBox - \param rect Traget rectangle on the paint device + \param viewBox View Box, see QSvgRenderer::viewBox() + \param rect Target rectangle on the paint device */ -void QwtPlotSvgItem::render(QPainter *painter, - const QwtDoubleRect &viewBox, const QRect &rect) const +void QwtPlotSvgItem::render( QPainter *painter, + const QRectF &viewBox, const QRectF &rect ) const { if ( !viewBox.isValid() ) return; -#if QT_VERSION >= 0x040200 - d_data->renderer.setViewBox(viewBox); - d_data->renderer.render(painter, rect); - return; -#else - -#if QT_VERSION >= 0x040100 - const QSize paintSize(painter->window().width(), - painter->window().height()); - if ( !paintSize.isValid() ) - return; - - const double xRatio = paintSize.width() / viewBox.width(); - const double yRatio = paintSize.height() / viewBox.height(); - - const double dx = rect.left() / xRatio + 1.0; - const double dy = rect.top() / yRatio + 1.0; - - const double mx = double(rect.width()) / paintSize.width(); - const double my = double(rect.height()) / paintSize.height(); - - painter->save(); - - painter->translate(dx, dy); - painter->scale(mx, my); + QRectF r = rect; - d_data->renderer.setViewBox(viewBox.toRect()); - d_data->renderer.render(painter); - - painter->restore(); -#else - const double mx = rect.width() / viewBox.width(); - const double my = rect.height() / viewBox.height(); - const double dx = rect.x() - mx * viewBox.x(); - const double dy = rect.y() - my * viewBox.y(); - - painter->save(); - - painter->translate(dx, dy); - painter->scale(mx, my); - - d_data->picture.play(painter); + if ( QwtPainter::roundingAlignment( painter ) ) + { + r.setLeft ( qRound( r.left() ) ); + r.setRight ( qRound( r.right() ) ); + r.setTop ( qRound( r.top() ) ); + r.setBottom ( qRound( r.bottom() ) ); + } - painter->restore(); -#endif // < 0x040100 -#endif // < 0x040200 + d_data->renderer.setViewBox( viewBox ); + d_data->renderer.render( painter, r ); } /*! - Calculate the viewBox from an rect and boundingRect(). + Calculate the view box from rect and boundingRect(). \param rect Rectangle in scale coordinates - \return viewBox View Box, see QSvgRenderer::viewBox + \return View box, see QSvgRenderer::viewBox() */ -QwtDoubleRect QwtPlotSvgItem::viewBox(const QwtDoubleRect &rect) const +QRectF QwtPlotSvgItem::viewBox( const QRectF &rect ) const { -#if QT_VERSION >= 0x040100 const QSize sz = d_data->renderer.defaultSize(); -#else -#if QT_VERSION > 0x040000 - const QSize sz(d_data->picture.width(), - d_data->picture.height()); -#else - QPaintDeviceMetrics metrics(&d_data->picture); - const QSize sz(metrics.width(), metrics.height()); -#endif -#endif - const QwtDoubleRect br = boundingRect(); + const QRectF br = boundingRect(); if ( !rect.isValid() || !br.isValid() || sz.isNull() ) - return QwtDoubleRect(); + return QRectF(); QwtScaleMap xMap; - xMap.setScaleInterval(br.left(), br.right()); - xMap.setPaintInterval(0, sz.width()); + xMap.setScaleInterval( br.left(), br.right() ); + xMap.setPaintInterval( 0, sz.width() ); QwtScaleMap yMap; - yMap.setScaleInterval(br.top(), br.bottom()); - yMap.setPaintInterval(sz.height(), 0); + yMap.setScaleInterval( br.top(), br.bottom() ); + yMap.setPaintInterval( sz.height(), 0 ); - const double x1 = xMap.xTransform(rect.left()); - const double x2 = xMap.xTransform(rect.right()); - const double y1 = yMap.xTransform(rect.bottom()); - const double y2 = yMap.xTransform(rect.top()); + const double x1 = xMap.transform( rect.left() ); + const double x2 = xMap.transform( rect.right() ); + const double y1 = yMap.transform( rect.bottom() ); + const double y2 = yMap.transform( rect.top() ); - return QwtDoubleRect(x1, y1, x2 - x1, y2 - y1); + return QRectF( x1, y1, x2 - x1, y2 - y1 ); } diff --git a/libs/qwt/qwt_plot_svgitem.h b/libs/qwt/qwt_plot_svgitem.h index 264c5de609..1d98dee849 100644 --- a/libs/qwt/qwt_plot_svgitem.h +++ b/libs/qwt/qwt_plot_svgitem.h @@ -10,16 +10,12 @@ #ifndef QWT_PLOT_SVGITEM_H #define QWT_PLOT_SVGITEM_H -#include <qglobal.h> - -#include <qstring.h> -#include "qwt_double_rect.h" +#include "qwt_global.h" #include "qwt_plot_item.h" +#include <qstring.h> -#if QT_VERSION >= 0x040100 class QSvgRenderer; class QByteArray; -#endif /*! \brief A plot item, which displays @@ -31,30 +27,29 @@ class QByteArray; class QWT_EXPORT QwtPlotSvgItem: public QwtPlotItem { public: - explicit QwtPlotSvgItem(const QString& title = QString::null ); - explicit QwtPlotSvgItem(const QwtText& title ); + explicit QwtPlotSvgItem( const QString& title = QString::null ); + explicit QwtPlotSvgItem( const QwtText& title ); virtual ~QwtPlotSvgItem(); - bool loadFile(const QwtDoubleRect&, const QString &fileName); - bool loadData(const QwtDoubleRect&, const QByteArray &); + bool loadFile( const QRectF&, const QString &fileName ); + bool loadData( const QRectF&, const QByteArray & ); - virtual QwtDoubleRect boundingRect() const; + virtual QRectF boundingRect() const; - virtual void draw(QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRect &rect) const; + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; virtual int rtti() const; protected: -#if QT_VERSION >= 0x040100 const QSvgRenderer &renderer() const; QSvgRenderer &renderer(); -#endif - void render(QPainter *painter, - const QwtDoubleRect &viewBox, const QRect &rect) const; - QwtDoubleRect viewBox(const QwtDoubleRect &area) const; + void render( QPainter *painter, + const QRectF &viewBox, const QRectF &rect ) const; + + QRectF viewBox( const QRectF &area ) const; private: void init(); diff --git a/libs/qwt/qwt_plot_textlabel.cpp b/libs/qwt/qwt_plot_textlabel.cpp new file mode 100644 index 0000000000..a9e19644c7 --- /dev/null +++ b/libs/qwt/qwt_plot_textlabel.cpp @@ -0,0 +1,261 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_textlabel.h" +#include "qwt_painter.h" +#include "qwt_scale_map.h" +#include <qpainter.h> +#include <qpixmap.h> +#include <qmath.h> + +static QRect qwtItemRect( int renderFlags, + const QRectF &rect, const QSizeF &itemSize ) +{ + int x; + if ( renderFlags & Qt::AlignLeft ) + { + x = rect.left(); + } + else if ( renderFlags & Qt::AlignRight ) + { + x = rect.right() - itemSize.width(); + } + else + { + x = rect.center().x() - 0.5 * itemSize.width(); + } + + int y; + if ( renderFlags & Qt::AlignTop ) + { + y = rect.top(); + } + else if ( renderFlags & Qt::AlignBottom ) + { + y = rect.bottom() - itemSize.height(); + } + else + { + y = rect.center().y() - 0.5 * itemSize.height(); + } + + return QRect( x, y, itemSize.width(), itemSize.height() ); +} + +class QwtPlotTextLabel::PrivateData +{ +public: + PrivateData(): + margin( 5 ) + { + } + + QwtText text; + int margin; + + QPixmap pixmap; +}; + +/*! + \brief Constructor + + Initializes an text label with an empty text + + Sets the following item attributes: + + - QwtPlotItem::AutoScale: true + - QwtPlotItem::Legend: false + + The z value is initialized by 150 + + \sa QwtPlotItem::setItemAttribute(), QwtPlotItem::setZ() +*/ + +QwtPlotTextLabel::QwtPlotTextLabel(): + QwtPlotItem( QwtText( "Label" ) ) +{ + d_data = new PrivateData; + + setItemAttribute( QwtPlotItem::AutoScale, false ); + setItemAttribute( QwtPlotItem::Legend, false ); + + setZ( 150 ); +} + +//! Destructor +QwtPlotTextLabel::~QwtPlotTextLabel() +{ + delete d_data; +} + +//! \return QwtPlotItem::Rtti_PlotTextLabel +int QwtPlotTextLabel::rtti() const +{ + return QwtPlotItem::Rtti_PlotTextLabel; +} + +/*! + Set the text + + The label will be aligned to the plot canvas according to + the alignment flags of text. + + \param text Text to be displayed + + \sa text(), QwtText::renderFlags() +*/ +void QwtPlotTextLabel::setText( const QwtText &text ) +{ + if ( d_data->text != text ) + { + d_data->text = text; + + invalidateCache(); + itemChanged(); + } +} + +/*! + \return Text to be displayed + \sa setText() +*/ +QwtText QwtPlotTextLabel::text() const +{ + return d_data->text; +} + +/*! + Set the margin + + The margin is the distance between the contentsRect() + of the plot canvas and the rectangle where the label can + be displayed. + + \param margin Margin + + \sa margin(), textRect() + */ +void QwtPlotTextLabel::setMargin( int margin ) +{ + margin = qMax( margin, 0 ); + if ( d_data->margin != margin ) + { + d_data->margin = margin; + itemChanged(); + } +} + +/*! + \return Margin added to the contentsMargins() of the canvas + \sa setMargin() +*/ +int QwtPlotTextLabel::margin() const +{ + return d_data->margin; +} + +/*! + Draw the text label + + \param painter Painter + \param xMap x Scale Map + \param yMap y Scale Map + \param canvasRect Contents rectangle of the canvas in painter coordinates + + \sa textRect() +*/ + +void QwtPlotTextLabel::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const +{ + Q_UNUSED( xMap ); + Q_UNUSED( yMap ); + + const int m = d_data->margin; + + const QRectF rect = textRect( canvasRect.adjusted( m, m, -m, -m ), + d_data->text.textSize( painter->font() ) ); + + bool doCache = QwtPainter::roundingAlignment( painter ); + if ( doCache ) + { + switch( painter->paintEngine()->type() ) + { + case QPaintEngine::Picture: + case QPaintEngine::User: // usually QwtGraphic + { + // don't use a cache for record/replay devices + doCache = false; + break; + } + default:; + } + } + + if ( doCache ) + { + // when the paint device is aligning it is not one + // where scalability matters ( PDF, SVG ). + // As rendering a text label is an expensive operation + // we use a cache. + + int pw = 0; + if ( d_data->text.borderPen().style() != Qt::NoPen ) + pw = qMax( d_data->text.borderPen().width(), 1 ); + + QRect pixmapRect; + pixmapRect.setLeft( qFloor( rect.left() ) - pw ); + pixmapRect.setTop( qFloor( rect.top() ) - pw ); + pixmapRect.setRight( qCeil( rect.right() ) + pw ); + pixmapRect.setBottom( qCeil( rect.bottom() ) + pw ); + + if ( d_data->pixmap.isNull() || + ( pixmapRect.size() != d_data->pixmap.size() ) ) + { + d_data->pixmap = QPixmap( pixmapRect.size() ); + d_data->pixmap.fill( Qt::transparent ); + + const QRect r( pw, pw, + pixmapRect.width() - 2 * pw, pixmapRect.height() - 2 * pw ); + + QPainter pmPainter( &d_data->pixmap ); + d_data->text.draw( &pmPainter, r ); + } + + painter->drawPixmap( pixmapRect, d_data->pixmap ); + } + else + { + d_data->text.draw( painter, rect ); + } +} + +/*! + \brief Align the text label + + \param rect Canvas rectangle with margins subtracted + \param textSize Size required to draw the text + + \return A rectangle aligned according the the alignment flags of + the text. + + \sa setMargin(), QwtText::renderFlags(), QwtText::textSize() + */ +QRectF QwtPlotTextLabel::textRect( + const QRectF &rect, const QSizeF &textSize ) const +{ + return qwtItemRect( d_data->text.renderFlags(), rect, textSize ); +} + +//! Invalidate all internal cache +void QwtPlotTextLabel::invalidateCache() +{ + d_data->pixmap = QPixmap(); +} diff --git a/libs/qwt/qwt_plot_textlabel.h b/libs/qwt/qwt_plot_textlabel.h new file mode 100644 index 0000000000..c7b849660a --- /dev/null +++ b/libs/qwt/qwt_plot_textlabel.h @@ -0,0 +1,75 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_TEXT_LABEL_H +#define QWT_PLOT_TEXT_LABEL_H 1 + +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include "qwt_text.h" + +/*! + \brief A plot item, which displays a text label + + QwtPlotTextLabel displays a text label aligned to the plot canvas. + + In opposite to QwtPlotMarker the position of the label is unrelated to + plot coordinates. + + As drawing a text is an expensive operation the label is cached + in a pixmap to speed up replots. + + \par Example + The following code shows how to add a title. + +\verbatim + QwtText title( "Plot Title" ); + title.setRenderFlags( Qt::AlignHCenter | Qt::AlignTop ); + + QFont font; + font.setBold( true ); + title.setFont( font ); + + QwtPlotTextLabel *titleItem = new QwtPlotTextLabel(); + titleItem->setText( title ); + titleItem->attach( this ); +\endverbatim + + \sa QwtPlotMarker +*/ + +class QWT_EXPORT QwtPlotTextLabel: public QwtPlotItem +{ +public: + QwtPlotTextLabel(); + virtual ~QwtPlotTextLabel(); + + virtual int rtti() const; + + void setText( const QwtText & ); + QwtText text() const; + + void setMargin( int margin ); + int margin() const; + + virtual QRectF textRect( const QRectF &, const QSizeF & ) const; + +protected: + virtual void draw( QPainter *, + const QwtScaleMap &, const QwtScaleMap &, + const QRectF &) const; + + void invalidateCache(); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_tradingcurve.cpp b/libs/qwt/qwt_plot_tradingcurve.cpp new file mode 100644 index 0000000000..04d877b1bd --- /dev/null +++ b/libs/qwt/qwt_plot_tradingcurve.cpp @@ -0,0 +1,682 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_tradingcurve.h" +#include "qwt_scale_map.h" +#include "qwt_clipper.h" +#include "qwt_painter.h" +#include <qpainter.h> + +static inline bool qwtIsSampleInside( const QwtOHLCSample &sample, + double tMin, double tMax, double vMin, double vMax ) +{ + const double t = sample.time; + const QwtInterval interval = sample.boundingInterval(); + + const bool isOffScreen = ( t < tMin ) || ( t > tMax ) + || ( interval.maxValue() < vMin ) || ( interval.minValue() > vMax ); + + return !isOffScreen; +} + +class QwtPlotTradingCurve::PrivateData +{ +public: + PrivateData(): + symbolStyle( QwtPlotTradingCurve::CandleStick ), + symbolExtent( 0.6 ), + minSymbolWidth( 2.0 ), + maxSymbolWidth( -1.0 ), + paintAttributes( QwtPlotTradingCurve::ClipSymbols ) + { + symbolBrush[0] = QBrush( Qt::white ); + symbolBrush[1] = QBrush( Qt::black ); + } + + QwtPlotTradingCurve::SymbolStyle symbolStyle; + double symbolExtent; + double minSymbolWidth; + double maxSymbolWidth; + + QPen symbolPen; + QBrush symbolBrush[2]; // Increasing/Decreasing + + QwtPlotTradingCurve::PaintAttributes paintAttributes; +}; + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotTradingCurve::QwtPlotTradingCurve( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotTradingCurve::QwtPlotTradingCurve( const QString &title ): + QwtPlotSeriesItem( QwtText( title ) ) +{ + init(); +} + +//! Destructor +QwtPlotTradingCurve::~QwtPlotTradingCurve() +{ + delete d_data; +} + +//! Initialize internal members +void QwtPlotTradingCurve::init() +{ + setItemAttribute( QwtPlotItem::Legend, true ); + setItemAttribute( QwtPlotItem::AutoScale, true ); + + d_data = new PrivateData; + setData( new QwtTradingChartData() ); + + setZ( 19.0 ); +} + +//! \return QwtPlotItem::Rtti_PlotTradingCurve +int QwtPlotTradingCurve::rtti() const +{ + return QwtPlotTradingCurve::Rtti_PlotTradingCurve; +} + +/*! + Specify an attribute how to draw the curve + + \param attribute Paint attribute + \param on On/Off + \sa testPaintAttribute() +*/ +void QwtPlotTradingCurve::setPaintAttribute( + PaintAttribute attribute, bool on ) +{ + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; +} + +/*! + \return True, when attribute is enabled + \sa PaintAttribute, setPaintAttribute() +*/ +bool QwtPlotTradingCurve::testPaintAttribute( + PaintAttribute attribute ) const +{ + return ( d_data->paintAttributes & attribute ); +} + +/*! + Initialize data with an array of samples. + \param samples Vector of samples + + \sa QwtPlotSeriesItem::setData() +*/ +void QwtPlotTradingCurve::setSamples( + const QVector<QwtOHLCSample> &samples ) +{ + setData( new QwtTradingChartData( samples ) ); +} + +/*! + Assign a series of samples + + setSamples() is just a wrapper for setData() without any additional + value - beside that it is easier to find for the developer. + + \param data Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. +*/ +void QwtPlotTradingCurve::setSamples( + QwtSeriesData<QwtOHLCSample> *data ) +{ + setData( data ); +} + +/*! + Set the symbol style + + \param style Symbol style + + \sa symbolStyle(), setSymbolExtent(), + setSymbolPen(), setSymbolBrush() +*/ +void QwtPlotTradingCurve::setSymbolStyle( SymbolStyle style ) +{ + if ( style != d_data->symbolStyle ) + { + d_data->symbolStyle = style; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Symbol style + \sa setSymbolStyle(), symbolExtent(), symbolPen(), symbolBrush() +*/ +QwtPlotTradingCurve::SymbolStyle QwtPlotTradingCurve::symbolStyle() const +{ + return d_data->symbolStyle; +} + +/*! + Build and assign the symbol pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotTradingCurve::setSymbolPen( + const QColor &color, qreal width, Qt::PenStyle style ) +{ + setSymbolPen( QPen( color, width, style ) ); +} + +/*! + \brief Set the symbol pen + + The symbol pen is used for rendering the lines of the + bar or candlestick symbols + + \sa symbolPen(), setSymbolBrush() +*/ +void QwtPlotTradingCurve::setSymbolPen( const QPen &pen ) +{ + if ( pen != d_data->symbolPen ) + { + d_data->symbolPen = pen; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Symbol pen + \sa setSymbolPen(), symbolBrush() +*/ +QPen QwtPlotTradingCurve::symbolPen() const +{ + return d_data->symbolPen; +} + +/*! + Set the symbol brush + + \param direction Direction type + \param brush Brush used to fill the body of all candlestick + symbols with the direction + + \sa symbolBrush(), setSymbolPen() +*/ +void QwtPlotTradingCurve::setSymbolBrush( + Direction direction, const QBrush &brush ) +{ + if ( direction < 0 || direction >= 2 ) + return; + + if ( brush != d_data->symbolBrush[ direction ] ) + { + d_data->symbolBrush[ direction ] = brush; + + legendChanged(); + itemChanged(); + } +} + +/*! + \param direction + \return Brush used to fill the body of all candlestick + symbols with the direction + + \sa setSymbolPen(), symbolBrush() +*/ +QBrush QwtPlotTradingCurve::symbolBrush( Direction direction ) const +{ + if ( direction < 0 || direction >= 2 ) + return QBrush(); + + return d_data->symbolBrush[ direction ]; +} + +/*! + \brief Set the extent of the symbol + + The width of the symbol is given in scale coordinates. When painting + a symbol the width is scaled into paint device coordinates + by scaledSymbolWidth(). The scaled width is bounded by + minSymbolWidth(), maxSymbolWidth() + + \param extent Symbol width in scale coordinates + + \sa symbolExtent(), scaledSymbolWidth(), + setMinSymbolWidth(), setMaxSymbolWidth() +*/ +void QwtPlotTradingCurve::setSymbolExtent( double extent ) +{ + extent = qMax( 0.0, extent ); + if ( extent != d_data->symbolExtent ) + { + d_data->symbolExtent = extent; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Extent of a symbol in scale coordinates + \sa setSymbolExtent(), scaledSymbolWidth(), + minSymbolWidth(), maxSymbolWidth() +*/ +double QwtPlotTradingCurve::symbolExtent() const +{ + return d_data->symbolExtent; +} + +/*! + Set a minimum for the symbol width + + \param width Width in paint device coordinates + \sa minSymbolWidth(), setMaxSymbolWidth(), setSymbolExtent() + */ +void QwtPlotTradingCurve::setMinSymbolWidth( double width ) +{ + width = qMax( width, 0.0 ); + if ( width != d_data->minSymbolWidth ) + { + d_data->minSymbolWidth = width; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Minmum for the symbol width + \sa setMinSymbolWidth(), maxSymbolWidth(), symbolExtent() + */ +double QwtPlotTradingCurve::minSymbolWidth() const +{ + return d_data->minSymbolWidth; +} + +/*! + Set a maximum for the symbol width + + A value <= 0.0 means an unlimited width + + \param width Width in paint device coordinates + \sa maxSymbolWidth(), setMinSymbolWidth(), setSymbolExtent() + */ +void QwtPlotTradingCurve::setMaxSymbolWidth( double width ) +{ + if ( width != d_data->maxSymbolWidth ) + { + d_data->maxSymbolWidth = width; + + legendChanged(); + itemChanged(); + } +} + +/*! + \return Maximum for the symbol width + \sa setMaxSymbolWidth(), minSymbolWidth(), symbolExtent() + */ +double QwtPlotTradingCurve::maxSymbolWidth() const +{ + return d_data->maxSymbolWidth; +} + +/*! + \return Bounding rectangle of all samples. + For an empty series the rectangle is invalid. +*/ +QRectF QwtPlotTradingCurve::boundingRect() const +{ + QRectF rect = QwtPlotSeriesItem::boundingRect(); + if ( rect.isValid() && orientation() == Qt::Vertical ) + rect.setRect( rect.y(), rect.x(), rect.height(), rect.width() ); + + return rect; +} + +/*! + Draw an interval of the curve + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted. If to < 0 the + curve will be painted to its last point. + + \sa drawSymbols() +*/ +void QwtPlotTradingCurve::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( to < 0 ) + to = dataSize() - 1; + + if ( from < 0 ) + from = 0; + + if ( from > to ) + return; + + painter->save(); + + if ( d_data->symbolStyle != QwtPlotTradingCurve::NoSymbol ) + drawSymbols( painter, xMap, yMap, canvasRect, from, to ); + + painter->restore(); +} + +/*! + Draw symbols + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rectangle of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted + + \sa drawSeries() +*/ +void QwtPlotTradingCurve::drawSymbols( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + const QRectF tr = QwtScaleMap::invTransform( xMap, yMap, canvasRect ); + + const QwtScaleMap *timeMap, *valueMap; + double tMin, tMax, vMin, vMax; + + const Qt::Orientation orient = orientation(); + if ( orient == Qt::Vertical ) + { + timeMap = &xMap; + valueMap = &yMap; + + tMin = tr.left(); + tMax = tr.right(); + vMin = tr.top(); + vMax = tr.bottom(); + } + else + { + timeMap = &yMap; + valueMap = &xMap; + + vMin = tr.left(); + vMax = tr.right(); + tMin = tr.top(); + tMax = tr.bottom(); + } + + const bool inverted = timeMap->isInverting(); + const bool doClip = d_data->paintAttributes & ClipSymbols; + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double symbolWidth = scaledSymbolWidth( xMap, yMap, canvasRect ); + if ( doAlign ) + symbolWidth = qFloor( 0.5 * symbolWidth ) * 2.0; + + QPen pen = d_data->symbolPen; + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + + for ( int i = from; i <= to; i++ ) + { + const QwtOHLCSample s = sample( i ); + + if ( !doClip || qwtIsSampleInside( s, tMin, tMax, vMin, vMax ) ) + { + QwtOHLCSample translatedSample; + + translatedSample.time = timeMap->transform( s.time ); + translatedSample.open = valueMap->transform( s.open ); + translatedSample.high = valueMap->transform( s.high ); + translatedSample.low = valueMap->transform( s.low ); + translatedSample.close = valueMap->transform( s.close ); + + const int brushIndex = ( s.open < s.close ) + ? QwtPlotTradingCurve::Increasing + : QwtPlotTradingCurve::Decreasing; + + if ( doAlign ) + { + translatedSample.time = qRound( translatedSample.time ); + translatedSample.open = qRound( translatedSample.open ); + translatedSample.high = qRound( translatedSample.high ); + translatedSample.low = qRound( translatedSample.low ); + translatedSample.close = qRound( translatedSample.close ); + } + + switch( d_data->symbolStyle ) + { + case Bar: + { + drawBar( painter, translatedSample, + orient, inverted, symbolWidth ); + break; + } + case CandleStick: + { + painter->setBrush( d_data->symbolBrush[ brushIndex ] ); + drawCandleStick( painter, translatedSample, + orient, symbolWidth ); + break; + } + default: + { + if ( d_data->symbolStyle >= UserSymbol ) + { + painter->setBrush( d_data->symbolBrush[ brushIndex ] ); + drawUserSymbol( painter, d_data->symbolStyle, + translatedSample, orient, inverted, symbolWidth ); + } + } + } + } + } +} + +/*! + \brief Draw a symbol for a symbol style >= UserSymbol + + The implementation does nothing and is intended to be overloaded + + \param painter Qt painter, initialized with pen/brush + \param symbolStyle Symbol style + \param sample Samples already translated into paint device coordinates + \param orientation Vertical or horizontal + \param inverted True, when the opposite scale + ( Qt::Vertical: x, Qt::Horizontal: y ) is increasing + in the opposite direction as QPainter coordinates. + \param symbolWidth Width of the symbol in paint device coordinates +*/ +void QwtPlotTradingCurve::drawUserSymbol( QPainter *painter, + SymbolStyle symbolStyle, const QwtOHLCSample &sample, + Qt::Orientation orientation, bool inverted, double symbolWidth ) const +{ + Q_UNUSED( painter ) + Q_UNUSED( symbolStyle ) + Q_UNUSED( orientation ) + Q_UNUSED( inverted ) + Q_UNUSED( symbolWidth ) + Q_UNUSED( sample ) +} + +/*! + \brief Draw a bar + + \param painter Qt painter, initialized with pen/brush + \param sample Sample, already translated into paint device coordinates + \param orientation Vertical or horizontal + \param inverted When inverted is false the open tick is painted + to the left/top, otherwise it is painted right/bottom. + The close tick is painted in the opposite direction + of the open tick. + painted in the opposite d + opposite direction. + \param width Width or height of the candle, depending on the orientation + + \sa Bar +*/ +void QwtPlotTradingCurve::drawBar( QPainter *painter, + const QwtOHLCSample &sample, Qt::Orientation orientation, + bool inverted, double width ) const +{ + double w2 = 0.5 * width; + if ( inverted ) + w2 *= -1; + + if ( orientation == Qt::Vertical ) + { + QwtPainter::drawLine( painter, + sample.time, sample.low, sample.time, sample.high ); + + QwtPainter::drawLine( painter, + sample.time - w2, sample.open, sample.time, sample.open ); + QwtPainter::drawLine( painter, + sample.time + w2, sample.close, sample.time, sample.close ); + } + else + { + QwtPainter::drawLine( painter, sample.low, sample.time, + sample.high, sample.time ); + QwtPainter::drawLine( painter, + sample.open, sample.time - w2, sample.open, sample.time ); + QwtPainter::drawLine( painter, + sample.close, sample.time + w2, sample.close, sample.time ); + } +} + +/*! + \brief Draw a candle stick + + \param painter Qt painter, initialized with pen/brush + \param sample Samples already translated into paint device coordinates + \param orientation Vertical or horizontal + \param width Width or height of the candle, depending on the orientation + + \sa CandleStick +*/ +void QwtPlotTradingCurve::drawCandleStick( QPainter *painter, + const QwtOHLCSample &sample, Qt::Orientation orientation, + double width ) const +{ + const double t = sample.time; + const double v1 = qMin( sample.low, sample.high ); + const double v2 = qMin( sample.open, sample.close ); + const double v3 = qMax( sample.low, sample.high ); + const double v4 = qMax( sample.open, sample.close ); + + if ( orientation == Qt::Vertical ) + { + QwtPainter::drawLine( painter, t, v1, t, v2 ); + QwtPainter::drawLine( painter, t, v3, t, v4 ); + + QRectF rect( t - 0.5 * width, sample.open, + width, sample.close - sample.open ); + + QwtPainter::drawRect( painter, rect ); + } + else + { + QwtPainter::drawLine( painter, v1, t, v2, t ); + QwtPainter::drawLine( painter, v3, t, v4, t ); + + const QRectF rect( sample.open, t - 0.5 * width, + sample.close - sample.open, width ); + + QwtPainter::drawRect( painter, rect ); + } +} + +/*! + \return A rectangle filled with the color of the symbol pen + + \param index Index of the legend entry + ( usually there is only one ) + \param size Icon size + + \sa setLegendIconSize(), legendData() +*/ +QwtGraphic QwtPlotTradingCurve::legendIcon( int index, + const QSizeF &size ) const +{ + Q_UNUSED( index ); + return defaultIcon( d_data->symbolPen.color(), size ); +} + +/*! + Calculate the symbol width in paint coordinates + + The width is calculated by scaling the symbol extent into + paint device coordinates bounded by the minimum/maximum + symbol width. + + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rectangle of the canvas + + \return Symbol width in paint coordinates + + \sa symbolExtent(), minSymbolWidth(), maxSymbolWidth() +*/ +double QwtPlotTradingCurve::scaledSymbolWidth( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const +{ + Q_UNUSED( canvasRect ); + + if ( d_data->maxSymbolWidth > 0.0 && + d_data->minSymbolWidth >= d_data->maxSymbolWidth ) + { + return d_data->minSymbolWidth; + } + + const QwtScaleMap *map = + ( orientation() == Qt::Vertical ) ? &xMap : &yMap; + + const double pos = map->transform( map->s1() + d_data->symbolExtent ); + + double width = qAbs( pos - map->p1() ); + + width = qMax( width, d_data->minSymbolWidth ); + if ( d_data->maxSymbolWidth > 0.0 ) + width = qMin( width, d_data->maxSymbolWidth ); + + return width; +} diff --git a/libs/qwt/qwt_plot_tradingcurve.h b/libs/qwt/qwt_plot_tradingcurve.h new file mode 100644 index 0000000000..8a4121f5da --- /dev/null +++ b/libs/qwt/qwt_plot_tradingcurve.h @@ -0,0 +1,174 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_TRADING_CURVE_H +#define QWT_PLOT_TRADING_CURVE_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_series_data.h" + +/*! + \brief QwtPlotTradingCurve illustrates movements in the price of a + financial instrument over time. + + QwtPlotTradingCurve supports candlestick or bar ( OHLC ) charts + that are used in the domain of technical analysis. + + While the length ( height or width depending on orientation() ) + of each symbol depends on the corresponding OHLC sample the size + of the other dimension can be controlled using: + + - setSymbolExtent() + - setSymbolMinWidth() + - setSymbolMaxWidth() + + The extent is a size in scale coordinates, so that the symbol width + is increasing when the plot is zoomed in. Minimum/Maximum width + is in widget coordinates independent from the zoom level. + When setting the minimum and maximum to the same value, the width of + the symbol is fixed. +*/ +class QWT_EXPORT QwtPlotTradingCurve: + public QwtPlotSeriesItem, QwtSeriesStore<QwtOHLCSample> +{ +public: + /*! + \brief Symbol styles. + + The default setting is QwtPlotSeriesItem::CandleStick. + \sa setSymbolStyle(), symbolStyle() + */ + enum SymbolStyle + { + //! Nothing is displayed + NoSymbol = -1, + + /*! + A line on the chart shows the price range (the highest and lowest + prices) over one unit of time, e.g. one day or one hour. + Tick marks project from each side of the line indicating the + opening and closing price. + */ + Bar, + + /*! + The range between opening/closing price are displayed as + a filled box. The fill brush depends on the direction of the + price movement. The box is connected to the highest/lowest + values by lines. + */ + CandleStick, + + /*! + SymbolTypes >= UserSymbol are displayed by drawUserSymbol(), + that needs to be overloaded and implemented in derived + curve classes. + + \sa drawUserSymbol() + */ + UserSymbol = 100 + }; + + /*! + \brief Direction of a price movement + */ + enum Direction + { + //! The closing price is higher than the opening price + Increasing, + + //! The closing price is lower than the opening price + Decreasing + }; + + /*! + Attributes to modify the drawing algorithm. + \sa setPaintAttribute(), testPaintAttribute() + */ + enum PaintAttribute + { + //! Check if a symbol is on the plot canvas before painting it. + ClipSymbols = 0x01 + }; + + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + + explicit QwtPlotTradingCurve( const QString &title = QString::null ); + explicit QwtPlotTradingCurve( const QwtText &title ); + + virtual ~QwtPlotTradingCurve(); + + virtual int rtti() const; + + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + void setSamples( const QVector<QwtOHLCSample> & ); + void setSamples( QwtSeriesData<QwtOHLCSample> * ); + + void setSymbolStyle( SymbolStyle style ); + SymbolStyle symbolStyle() const; + + void setSymbolPen( const QColor &, + qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setSymbolPen( const QPen & ); + QPen symbolPen() const; + + void setSymbolBrush( Direction, const QBrush & ); + QBrush symbolBrush( Direction ) const; + + void setSymbolExtent( double width ); + double symbolExtent() const; + + void setMinSymbolWidth( double ); + double minSymbolWidth() const; + + void setMaxSymbolWidth( double ); + double maxSymbolWidth() const; + + virtual void drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual QRectF boundingRect() const; + + virtual QwtGraphic legendIcon( int index, const QSizeF & ) const; + +protected: + + void init(); + + virtual void drawSymbols( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void drawUserSymbol( QPainter *, + SymbolStyle, const QwtOHLCSample &, + Qt::Orientation, bool inverted, double width ) const; + + void drawBar( QPainter *painter, const QwtOHLCSample &, + Qt::Orientation, bool inverted, double width ) const; + + void drawCandleStick( QPainter *, const QwtOHLCSample &, + Qt::Orientation, double width ) const; + + virtual double scaledSymbolWidth( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotTradingCurve::PaintAttributes ) + +#endif diff --git a/libs/qwt/qwt_plot_xml.cpp b/libs/qwt/qwt_plot_xml.cpp index 7dc87b179b..5332a78f4f 100644 --- a/libs/qwt/qwt_plot_xml.cpp +++ b/libs/qwt/qwt_plot_xml.cpp @@ -9,19 +9,34 @@ #include "qwt_plot.h" -void QwtPlot::applyProperties(const QString &xmlDocument) +/*! + This method is intended for manipulating the plot widget + from a specific editor in the Qwt designer plugin. + + \warning The plot editor has never been implemented. +*/ +void QwtPlot::applyProperties( const QString & /* xmlDocument */ ) { -#if 1 +#if 0 // Temporary dummy code, for designer tests - setTitle(xmlDocument); + setTitle( xmlDocument ); replot(); #endif } +/*! + This method is intended for manipulating the plot widget + from a specific editor in the Qwt designer plugin. + + \return QString::null + \warning The plot editor has never been implemented. +*/ QString QwtPlot::grabProperties() const { -#if 1 +#if 0 // Temporary dummy code, for designer tests return title().text(); +#else + return QString::null; #endif } diff --git a/libs/qwt/qwt_plot_zoneitem.cpp b/libs/qwt/qwt_plot_zoneitem.cpp new file mode 100644 index 0000000000..f4ef69659b --- /dev/null +++ b/libs/qwt/qwt_plot_zoneitem.cpp @@ -0,0 +1,315 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_zoneitem.h" +#include "qwt_painter.h" +#include "qwt_scale_map.h" +#include <qpainter.h> + +class QwtPlotZoneItem::PrivateData +{ +public: + PrivateData(): + orientation( Qt::Vertical ), + pen( Qt::NoPen ) + { + QColor c( Qt::darkGray ); + c.setAlpha( 100 ); + brush = QBrush( c ); + } + + Qt::Orientation orientation; + QPen pen; + QBrush brush; + QwtInterval interval; +}; + +/*! + \brief Constructor + + Initializes the zone with no pen and a semi transparent gray brush + + Sets the following item attributes: + + - QwtPlotItem::AutoScale: false + - QwtPlotItem::Legend: false + + The z value is initialized by 5 + + \sa QwtPlotItem::setItemAttribute(), QwtPlotItem::setZ() +*/ +QwtPlotZoneItem::QwtPlotZoneItem(): + QwtPlotItem( QwtText( "Zone" ) ) +{ + d_data = new PrivateData; + + setItemAttribute( QwtPlotItem::AutoScale, false ); + setItemAttribute( QwtPlotItem::Legend, false ); + + setZ( 5 ); +} + +//! Destructor +QwtPlotZoneItem::~QwtPlotZoneItem() +{ + delete d_data; +} + +//! \return QwtPlotItem::Rtti_PlotZone +int QwtPlotZoneItem::rtti() const +{ + return QwtPlotItem::Rtti_PlotZone; +} + +/*! + Build and assign a pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) what makes it + non cosmetic ( see QPen::isCosmetic() ). This method has been introduced + to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtPlotZoneItem::setPen( const QColor &color, qreal width, Qt::PenStyle style ) +{ + setPen( QPen( color, width, style ) ); +} + +/*! + \brief Assign a pen + + The pen is used to draw the border lines of the zone + + \param pen Pen + \sa pen(), setBrush() +*/ +void QwtPlotZoneItem::setPen( const QPen &pen ) +{ + if ( d_data->pen != pen ) + { + d_data->pen = pen; + itemChanged(); + } +} + +/*! + \return Pen used to draw the border lines + \sa setPen(), brush() +*/ +const QPen &QwtPlotZoneItem::pen() const +{ + return d_data->pen; +} + +/*! + \brief Assign a brush + + The brush is used to fill the zone + + \param brush Brush + \sa pen(), setBrush() +*/ +void QwtPlotZoneItem::setBrush( const QBrush &brush ) +{ + if ( d_data->brush != brush ) + { + d_data->brush = brush; + itemChanged(); + } +} + +/*! + \return Brush used to fill the zone + \sa setPen(), brush() +*/ +const QBrush &QwtPlotZoneItem::brush() const +{ + return d_data->brush; +} + +/*! + \brief Set the orientation of the zone + + A horizontal zone highlights an interval of the y axis, + a vertical zone of the x axis. It is unbounded in the + opposite direction. + + \sa orientation(), QwtPlotItem::setAxes() +*/ +void QwtPlotZoneItem::setOrientation( Qt::Orientation orientation ) +{ + if ( d_data->orientation != orientation ) + { + d_data->orientation = orientation; + itemChanged(); + } +} + +/*! + \return Orientation of the zone + \sa setOrientation() + */ +Qt::Orientation QwtPlotZoneItem::orientation() +{ + return d_data->orientation; +} + +/*! + Set the interval of the zone + + For a horizontal zone the interval is related to the y axis, + for a vertical zone it is related to the x axis. + + \param min Minimum of the interval + \param max Maximum of the interval + + \sa interval(), setOrientation() + */ +void QwtPlotZoneItem::setInterval( double min, double max ) +{ + setInterval( QwtInterval( min, max ) ); +} + +/*! + Set the interval of the zone + + For a horizontal zone the interval is related to the y axis, + for a vertical zone it is related to the x axis. + + \param interval Zone interval + + \sa interval(), setOrientation() + */ +void QwtPlotZoneItem::setInterval( const QwtInterval &interval ) +{ + if ( d_data->interval != interval ) + { + d_data->interval = interval; + itemChanged(); + } +} + +/*! + \return Zone interval + \sa setInterval(), orientation() + */ +QwtInterval QwtPlotZoneItem::interval() const +{ + return d_data->interval; +} + +/*! + Draw the zone + + \param painter Painter + \param xMap x Scale Map + \param yMap y Scale Map + \param canvasRect Contents rectangle of the canvas in painter coordinates +*/ + +void QwtPlotZoneItem::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const +{ + if ( !d_data->interval.isValid() ) + return; + + QPen pen = d_data->pen; + pen.setCapStyle( Qt::FlatCap ); + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + if ( d_data->orientation == Qt::Horizontal ) + { + double y1 = yMap.transform( d_data->interval.minValue() ); + double y2 = yMap.transform( d_data->interval.maxValue() ); + + if ( doAlign ) + { + y1 = qRound( y1 ); + y2 = qRound( y2 ); + } + + QRectF r( canvasRect.left(), y1, canvasRect.width(), y2 - y1 ); + r = r.normalized(); + + if ( ( d_data->brush.style() != Qt::NoBrush ) && ( y1 != y2 ) ) + { + QwtPainter::fillRect( painter, r, d_data->brush ); + } + + if ( d_data->pen.style() != Qt::NoPen ) + { + painter->setPen( d_data->pen ); + + QwtPainter::drawLine( painter, r.left(), r.top(), r.right(), r.top() ); + QwtPainter::drawLine( painter, r.left(), r.bottom(), r.right(), r.bottom() ); + } + } + else + { + double x1 = xMap.transform( d_data->interval.minValue() ); + double x2 = xMap.transform( d_data->interval.maxValue() ); + + if ( doAlign ) + { + x1 = qRound( x1 ); + x2 = qRound( x2 ); + } + + QRectF r( x1, canvasRect.top(), x2 - x1, canvasRect.height() ); + r = r.normalized(); + + if ( ( d_data->brush.style() != Qt::NoBrush ) && ( x1 != x2 ) ) + { + QwtPainter::fillRect( painter, r, d_data->brush ); + } + + if ( d_data->pen.style() != Qt::NoPen ) + { + painter->setPen( d_data->pen ); + + QwtPainter::drawLine( painter, r.left(), r.top(), r.left(), r.bottom() ); + QwtPainter::drawLine( painter, r.right(), r.top(), r.right(), r.bottom() ); + } + } +} + +/*! + The bounding rectangle is build from the interval in one direction + and something invalid for the opposite direction. + + \return An invalid rectangle with valid boundaries in one direction +*/ +QRectF QwtPlotZoneItem::boundingRect() const +{ + QRectF br = QwtPlotItem::boundingRect(); + + const QwtInterval &intv = d_data->interval; + + if ( intv.isValid() ) + { + if ( d_data->orientation == Qt::Horizontal ) + { + br.setTop( intv.minValue() ); + br.setBottom( intv.maxValue() ); + } + else + { + br.setLeft( intv.minValue() ); + br.setRight( intv.maxValue() ); + } + } + + return br; +} diff --git a/libs/qwt/qwt_plot_zoneitem.h b/libs/qwt/qwt_plot_zoneitem.h new file mode 100644 index 0000000000..f78226abe3 --- /dev/null +++ b/libs/qwt/qwt_plot_zoneitem.h @@ -0,0 +1,65 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_ZONE_ITEM_H +#define QWT_PLOT_ZONE_ITEM_H + +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include "qwt_interval.h" + +class QPen; +class QBrush; + +/*! + \brief A plot item, which displays a zone + + A horizontal zone highlights an interval of the y axis - a vertical + zone an interval of the x axis - and is unbounded in the opposite direction. + It is filled with a brush and its border lines are optionally displayed with a pen. + + \note For displaying an area that is bounded for x and y coordinates + use QwtPlotShapeItem +*/ + +class QWT_EXPORT QwtPlotZoneItem: + public QwtPlotItem +{ +public: + explicit QwtPlotZoneItem(); + virtual ~QwtPlotZoneItem(); + + virtual int rtti() const; + + void setOrientation( Qt::Orientation ); + Qt::Orientation orientation(); + + void setInterval( double min, double max ); + void setInterval( const QwtInterval & ); + QwtInterval interval() const; + + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); + const QPen &pen() const; + + void setBrush( const QBrush & ); + const QBrush &brush() const; + + virtual void draw( QPainter *, + const QwtScaleMap &, const QwtScaleMap &, + const QRectF &) const; + + virtual QRectF boundingRect() const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_plot_zoomer.cpp b/libs/qwt/qwt_plot_zoomer.cpp index ab8350f9a4..beee39f76f 100644 --- a/libs/qwt/qwt_plot_zoomer.cpp +++ b/libs/qwt/qwt_plot_zoomer.cpp @@ -7,24 +7,17 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <math.h> -#include "qwt_plot.h" -#include "qwt_plot_canvas.h" #include "qwt_plot_zoomer.h" +#include "qwt_plot.h" #include "qwt_scale_div.h" -#if QT_VERSION < 0x040000 -typedef QValueStack<QwtDoubleRect> QwtZoomStack; -#else -typedef QStack<QwtDoubleRect> QwtZoomStack; -#endif +#include "qwt_picker_machine.h" +#include <qalgorithms.h> class QwtPlotZoomer::PrivateData { public: uint zoomRectIndex; - QwtZoomStack zoomStack; + QStack<QRectF> zoomStack; int maxStackDepth; }; @@ -37,93 +30,64 @@ public: is set to QwtPlot::xBottom. If both or no y-axis are enabled, it is set to QwtPlot::yLeft. - The selectionFlags() are set to - QwtPicker::RectSelection & QwtPicker::ClickSelection, the - tracker mode to QwtPicker::ActiveOnly. + The zoomer is initialized with a QwtPickerDragRectMachine, + the tracker mode is set to QwtPicker::ActiveOnly and the rubber band + is set to QwtPicker::RectRubberBand \param canvas Plot canvas to observe, also the parent object - \param doReplot Call replot for the attached plot before initializing + \param doReplot Call QwtPlot::replot() for the attached plot before initializing the zoomer with its scales. This might be necessary, when the plot is in a state with pending scale changes. \sa QwtPlot::autoReplot(), QwtPlot::replot(), setZoomBase() */ -QwtPlotZoomer::QwtPlotZoomer(QwtPlotCanvas *canvas, bool doReplot): - QwtPlotPicker(canvas) +QwtPlotZoomer::QwtPlotZoomer( QWidget *canvas, bool doReplot ): + QwtPlotPicker( canvas ) { if ( canvas ) - init(RectSelection & ClickSelection, ActiveOnly, doReplot); + init( doReplot ); } /*! \brief Create a zoomer for a plot canvas. - The selectionFlags() are set to - QwtPicker::RectSelection & QwtPicker::ClickSelection, the - tracker mode to QwtPicker::ActiveOnly. + The zoomer is initialized with a QwtPickerDragRectMachine, + the tracker mode is set to QwtPicker::ActiveOnly and the rubber band + is set to QwtPicker;;RectRubberBand \param xAxis X axis of the zoomer \param yAxis Y axis of the zoomer \param canvas Plot canvas to observe, also the parent object - \param doReplot Call replot for the attached plot before initializing + \param doReplot Call QwtPlot::replot() for the attached plot before initializing the zoomer with its scales. This might be necessary, when the plot is in a state with pending scale changes. \sa QwtPlot::autoReplot(), QwtPlot::replot(), setZoomBase() */ -QwtPlotZoomer::QwtPlotZoomer(int xAxis, int yAxis, - QwtPlotCanvas *canvas, bool doReplot): - QwtPlotPicker(xAxis, yAxis, canvas) -{ - if ( canvas ) - init(RectSelection & ClickSelection, ActiveOnly, doReplot); -} - -/*! - Create a zoomer for a plot canvas. - - \param xAxis X axis of the zoomer - \param yAxis Y axis of the zoomer - \param selectionFlags Or'd value of QwtPicker::RectSelectionType and - QwtPicker::SelectionMode. - QwtPicker::RectSelection will be auto added. - \param trackerMode Tracker mode - \param canvas Plot canvas to observe, also the parent object - \param doReplot Call replot for the attached plot before initializing - the zoomer with its scales. This might be necessary, - when the plot is in a state with pending scale changes. - - \sa QwtPicker, QwtPicker::setSelectionFlags(), QwtPicker::setRubberBand(), - QwtPicker::setTrackerMode - - \sa QwtPlot::autoReplot(), QwtPlot::replot(), setZoomBase() -*/ - -QwtPlotZoomer::QwtPlotZoomer(int xAxis, int yAxis, int selectionFlags, - DisplayMode trackerMode, QwtPlotCanvas *canvas, bool doReplot): - QwtPlotPicker(xAxis, yAxis, canvas) +QwtPlotZoomer::QwtPlotZoomer( int xAxis, int yAxis, + QWidget *canvas, bool doReplot ): + QwtPlotPicker( xAxis, yAxis, canvas ) { if ( canvas ) - init(selectionFlags, trackerMode, doReplot); + init( doReplot ); } //! Init the zoomer, used by the constructors -void QwtPlotZoomer::init(int selectionFlags, - DisplayMode trackerMode, bool doReplot) +void QwtPlotZoomer::init( bool doReplot ) { d_data = new PrivateData; d_data->maxStackDepth = -1; - setSelectionFlags(selectionFlags); - setTrackerMode(trackerMode); - setRubberBand(RectRubberBand); + setTrackerMode( ActiveOnly ); + setRubberBand( RectRubberBand ); + setStateMachine( new QwtPickerDragRectMachine() ); if ( doReplot && plot() ) plot()->replot(); - setZoomBase(scaleRect()); + setZoomBase( scaleRect() ); } QwtPlotZoomer::~QwtPlotZoomer() @@ -142,21 +106,24 @@ QwtPlotZoomer::~QwtPlotZoomer() \note depth doesn't include the zoom base, so zoomStack().count() might be maxStackDepth() + 1. */ -void QwtPlotZoomer::setMaxStackDepth(int depth) +void QwtPlotZoomer::setMaxStackDepth( int depth ) { d_data->maxStackDepth = depth; - if ( depth >= 0 ) { + if ( depth >= 0 ) + { // unzoom if the current depth is below d_data->maxStackDepth const int zoomOut = - int(d_data->zoomStack.count()) - 1 - depth; // -1 for the zoom base - - if ( zoomOut > 0 ) { - zoom(-zoomOut); - for ( int i = int(d_data->zoomStack.count()) - 1; - i > int(d_data->zoomRectIndex); i-- ) { - (void)d_data->zoomStack.pop(); // remove trailing rects + int( d_data->zoomStack.count() ) - 1 - depth; // -1 for the zoom base + + if ( zoomOut > 0 ) + { + zoom( -zoomOut ); + for ( int i = int( d_data->zoomStack.count() ) - 1; + i > int( d_data->zoomRectIndex ); i-- ) + { + ( void )d_data->zoomStack.pop(); // remove trailing rects } } } @@ -172,12 +139,12 @@ int QwtPlotZoomer::maxStackDepth() const } /*! - Return the zoom stack. zoomStack()[0] is the zoom base, - zoomStack()[1] the first zoomed rectangle. + \return The zoom stack. zoomStack()[0] is the zoom base, + zoomStack()[1] the first zoomed rectangle. \sa setZoomStack(), zoomRectIndex() */ -const QwtZoomStack &QwtPlotZoomer::zoomStack() const +const QStack<QRectF> &QwtPlotZoomer::zoomStack() const { return d_data->zoomStack; } @@ -186,7 +153,7 @@ const QwtZoomStack &QwtPlotZoomer::zoomStack() const \return Initial rectangle of the zoomer \sa setZoomBase(), zoomRect() */ -QwtDoubleRect QwtPlotZoomer::zoomBase() const +QRectF QwtPlotZoomer::zoomBase() const { return d_data->zoomStack[0]; } @@ -194,13 +161,13 @@ QwtDoubleRect QwtPlotZoomer::zoomBase() const /*! Reinitialized the zoom stack with scaleRect() as base. - \param doReplot Call replot for the attached plot before initializing + \param doReplot Call QwtPlot::replot() for the attached plot before initializing the zoomer with its scales. This might be necessary, when the plot is in a state with pending scale changes. \sa zoomBase(), scaleRect() QwtPlot::autoReplot(), QwtPlot::replot(). */ -void QwtPlotZoomer::setZoomBase(bool doReplot) +void QwtPlotZoomer::setZoomBase( bool doReplot ) { QwtPlot *plt = plot(); if ( plt == NULL ) @@ -210,7 +177,7 @@ void QwtPlotZoomer::setZoomBase(bool doReplot) plt->replot(); d_data->zoomStack.clear(); - d_data->zoomStack.push(scaleRect()); + d_data->zoomStack.push( scaleRect() ); d_data->zoomRectIndex = 0; rescale(); @@ -220,27 +187,28 @@ void QwtPlotZoomer::setZoomBase(bool doReplot) \brief Set the initial size of the zoomer. base is united with the current scaleRect() and the zoom stack is - reinitalized with it as zoom base. plot is zoomed to scaleRect(). + reinitialized with it as zoom base. plot is zoomed to scaleRect(). \param base Zoom base \sa zoomBase(), scaleRect() */ -void QwtPlotZoomer::setZoomBase(const QwtDoubleRect &base) +void QwtPlotZoomer::setZoomBase( const QRectF &base ) { const QwtPlot *plt = plot(); if ( !plt ) return; - const QwtDoubleRect sRect = scaleRect(); - const QwtDoubleRect bRect = base | sRect; + const QRectF sRect = scaleRect(); + const QRectF bRect = base | sRect; d_data->zoomStack.clear(); - d_data->zoomStack.push(bRect); + d_data->zoomStack.push( bRect ); d_data->zoomRectIndex = 0; - if ( base != sRect ) { - d_data->zoomStack.push(sRect); + if ( base != sRect ) + { + d_data->zoomStack.push( sRect ); d_data->zoomRectIndex++; } @@ -248,11 +216,10 @@ void QwtPlotZoomer::setZoomBase(const QwtDoubleRect &base) } /*! - Rectangle at the current position on the zoom stack. - + \return Rectangle at the current position on the zoom stack. \sa zoomRectIndex(), scaleRect(). */ -QwtDoubleRect QwtPlotZoomer::zoomRect() const +QRectF QwtPlotZoomer::zoomRect() const { return d_data->zoomStack[d_data->zoomRectIndex]; } @@ -269,33 +236,35 @@ uint QwtPlotZoomer::zoomRectIndex() const \brief Zoom in Clears all rectangles above the current position of the - zoom stack and pushs the intersection of zoomRect() and - the normalized rect on it. + zoom stack and pushes the normalized rectangle on it. \note If the maximal stack depth is reached, zoom is ignored. \note The zoomed signal is emitted. */ -void QwtPlotZoomer::zoom(const QwtDoubleRect &rect) +void QwtPlotZoomer::zoom( const QRectF &rect ) { if ( d_data->maxStackDepth >= 0 && - int(d_data->zoomRectIndex) >= d_data->maxStackDepth ) { + int( d_data->zoomRectIndex ) >= d_data->maxStackDepth ) + { return; } - const QwtDoubleRect zoomRect = d_data->zoomStack[0] & rect.normalized(); - if ( zoomRect != d_data->zoomStack[d_data->zoomRectIndex] ) { - for ( uint i = int(d_data->zoomStack.count()) - 1; - i > d_data->zoomRectIndex; i-- ) { - (void)d_data->zoomStack.pop(); + const QRectF zoomRect = rect.normalized(); + if ( zoomRect != d_data->zoomStack[d_data->zoomRectIndex] ) + { + for ( uint i = int( d_data->zoomStack.count() ) - 1; + i > d_data->zoomRectIndex; i-- ) + { + ( void )d_data->zoomStack.pop(); } - d_data->zoomStack.push(zoomRect); + d_data->zoomStack.push( zoomRect ); d_data->zoomRectIndex++; rescale(); - emit zoomed(zoomRect); + Q_EMIT zoomed( zoomRect ); } } @@ -303,28 +272,29 @@ void QwtPlotZoomer::zoom(const QwtDoubleRect &rect) \brief Zoom in or out Activate a rectangle on the zoom stack with an offset relative - to the current position. Negative values of offest will zoom out, + to the current position. Negative values of offset will zoom out, positive zoom in. A value of 0 zooms out to the zoom base. \param offset Offset relative to the current position of the zoom stack. \note The zoomed signal is emitted. \sa zoomRectIndex() */ -void QwtPlotZoomer::zoom(int offset) +void QwtPlotZoomer::zoom( int offset ) { if ( offset == 0 ) d_data->zoomRectIndex = 0; - else { + else + { int newIndex = d_data->zoomRectIndex + offset; - newIndex = qwtMax(0, newIndex); - newIndex = qwtMin(int(d_data->zoomStack.count()) - 1, newIndex); + newIndex = qMax( 0, newIndex ); + newIndex = qMin( int( d_data->zoomStack.count() ) - 1, newIndex ); - d_data->zoomRectIndex = uint(newIndex); + d_data->zoomRectIndex = uint( newIndex ); } rescale(); - emit zoomed(zoomRect()); + Q_EMIT zoomed( zoomRect() ); } /*! @@ -342,34 +312,36 @@ void QwtPlotZoomer::zoom(int offset) \sa zoomStack(), zoomRectIndex() */ void QwtPlotZoomer::setZoomStack( - const QwtZoomStack &zoomStack, int zoomRectIndex) + const QStack<QRectF> &zoomStack, int zoomRectIndex ) { if ( zoomStack.isEmpty() ) return; if ( d_data->maxStackDepth >= 0 && - int(zoomStack.count()) > d_data->maxStackDepth ) { + int( zoomStack.count() ) > d_data->maxStackDepth ) + { return; } - if ( zoomRectIndex < 0 || zoomRectIndex > int(zoomStack.count()) ) + if ( zoomRectIndex < 0 || zoomRectIndex > int( zoomStack.count() ) ) zoomRectIndex = zoomStack.count() - 1; const bool doRescale = zoomStack[zoomRectIndex] != zoomRect(); d_data->zoomStack = zoomStack; - d_data->zoomRectIndex = uint(zoomRectIndex); + d_data->zoomRectIndex = uint( zoomRectIndex ); - if ( doRescale ) { + if ( doRescale ) + { rescale(); - emit zoomed(zoomRect()); + Q_EMIT zoomed( zoomRect() ); } } /*! Adjust the observed plot to zoomRect() - \note Initiates QwtPlot::replot + \note Initiates QwtPlot::replot() */ void QwtPlotZoomer::rescale() @@ -378,29 +350,27 @@ void QwtPlotZoomer::rescale() if ( !plt ) return; - const QwtDoubleRect &rect = d_data->zoomStack[d_data->zoomRectIndex]; - if ( rect != scaleRect() ) { + const QRectF &rect = d_data->zoomStack[d_data->zoomRectIndex]; + if ( rect != scaleRect() ) + { const bool doReplot = plt->autoReplot(); - plt->setAutoReplot(false); + plt->setAutoReplot( false ); double x1 = rect.left(); double x2 = rect.right(); - if ( plt->axisScaleDiv(xAxis())->lBound() > - plt->axisScaleDiv(xAxis())->hBound() ) { - qSwap(x1, x2); - } + if ( !plt->axisScaleDiv( xAxis() ).isIncreasing() ) + qSwap( x1, x2 ); - plt->setAxisScale(xAxis(), x1, x2); + plt->setAxisScale( xAxis(), x1, x2 ); double y1 = rect.top(); double y2 = rect.bottom(); - if ( plt->axisScaleDiv(yAxis())->lBound() > - plt->axisScaleDiv(yAxis())->hBound() ) { - qSwap(y1, y2); - } - plt->setAxisScale(yAxis(), y1, y2); + if ( !plt->axisScaleDiv( yAxis() ).isIncreasing() ) + qSwap( y1, y2 ); - plt->setAutoReplot(doReplot); + plt->setAxisScale( yAxis(), y1, y2 ); + + plt->setAutoReplot( doReplot ); plt->replot(); } @@ -413,11 +383,12 @@ void QwtPlotZoomer::rescale() \param yAxis Y axis */ -void QwtPlotZoomer::setAxis(int xAxis, int yAxis) +void QwtPlotZoomer::setAxis( int xAxis, int yAxis ) { - if ( xAxis != QwtPlotPicker::xAxis() || yAxis != QwtPlotPicker::yAxis() ) { - QwtPlotPicker::setAxis(xAxis, yAxis); - setZoomBase(scaleRect()); + if ( xAxis != QwtPlotPicker::xAxis() || yAxis != QwtPlotPicker::yAxis() ) + { + QwtPlotPicker::setAxis( xAxis, yAxis ); + setZoomBase( scaleRect() ); } } @@ -431,20 +402,20 @@ void QwtPlotZoomer::setAxis(int xAxis, int yAxis) \note The mouse events can be changed, using QwtEventPattern::setMousePattern: 2, 1 */ -void QwtPlotZoomer::widgetMouseReleaseEvent(QMouseEvent *me) +void QwtPlotZoomer::widgetMouseReleaseEvent( QMouseEvent *me ) { - if ( mouseMatch(MouseSelect2, me) ) - zoom(0); - else if ( mouseMatch(MouseSelect3, me) ) - zoom(-1); - else if ( mouseMatch(MouseSelect6, me) ) - zoom(+1); + if ( mouseMatch( MouseSelect2, me ) ) + zoom( 0 ); + else if ( mouseMatch( MouseSelect3, me ) ) + zoom( -1 ); + else if ( mouseMatch( MouseSelect6, me ) ) + zoom( +1 ); else - QwtPlotPicker::widgetMouseReleaseEvent(me); + QwtPlotPicker::widgetMouseReleaseEvent( me ); } /*! - Qt::Key_Plus zooms out, Qt::Key_Minus zooms in one position on the + Qt::Key_Plus zooms in, Qt::Key_Minus zooms out one position on the zoom stack, Qt::Key_Escape zooms out to the zoom base. Changes the current position on the stack, but doesn't pop @@ -454,18 +425,19 @@ void QwtPlotZoomer::widgetMouseReleaseEvent(QMouseEvent *me) QwtEventPattern::setKeyPattern: 3, 4, 5 */ -void QwtPlotZoomer::widgetKeyPressEvent(QKeyEvent *ke) +void QwtPlotZoomer::widgetKeyPressEvent( QKeyEvent *ke ) { - if ( !isActive() ) { - if ( keyMatch(KeyUndo, ke) ) - zoom(-1); - else if ( keyMatch(KeyRedo, ke) ) - zoom(+1); - else if ( keyMatch(KeyHome, ke) ) - zoom(0); + if ( !isActive() ) + { + if ( keyMatch( KeyUndo, ke ) ) + zoom( -1 ); + else if ( keyMatch( KeyRedo, ke ) ) + zoom( +1 ); + else if ( keyMatch( KeyHome, ke ) ) + zoom( 0 ); } - QwtPlotPicker::widgetKeyPressEvent(ke); + QwtPlotPicker::widgetKeyPressEvent( ke ); } /*! @@ -476,23 +448,25 @@ void QwtPlotZoomer::widgetKeyPressEvent(QKeyEvent *ke) \note The changed rectangle is limited by the zoom base */ -void QwtPlotZoomer::moveBy(double dx, double dy) +void QwtPlotZoomer::moveBy( double dx, double dy ) { - const QwtDoubleRect &rect = d_data->zoomStack[d_data->zoomRectIndex]; - move(rect.left() + dx, rect.top() + dy); + const QRectF &rect = d_data->zoomStack[d_data->zoomRectIndex]; + moveTo( QPointF( rect.left() + dx, rect.top() + dy ) ); } /*! Move the the current zoom rectangle. - \param x X value - \param y Y value + \param pos New position - \sa QwtDoubleRect::move + \sa QRectF::moveTo() \note The changed rectangle is limited by the zoom base */ -void QwtPlotZoomer::move(double x, double y) +void QwtPlotZoomer::moveTo( const QPointF &pos ) { + double x = pos.x(); + double y = pos.y(); + if ( x < zoomBase().left() ) x = zoomBase().left(); if ( x > zoomBase().right() - zoomRect().width() ) @@ -503,8 +477,9 @@ void QwtPlotZoomer::move(double x, double y) if ( y > zoomBase().bottom() - zoomRect().height() ) y = zoomBase().bottom() - zoomRect().height(); - if ( x != zoomRect().left() || y != zoomRect().top() ) { - d_data->zoomStack[d_data->zoomRectIndex].moveTo(x, y); + if ( x != zoomRect().left() || y != zoomRect().top() ) + { + d_data->zoomStack[d_data->zoomRectIndex].moveTo( x, y ); rescale(); } } @@ -512,37 +487,33 @@ void QwtPlotZoomer::move(double x, double y) /*! \brief Check and correct a selected rectangle - Reject rectangles with a hight or width < 2, otherwise + Reject rectangles with a height or width < 2, otherwise expand the selected rectangle to a minimum size of 11x11 and accept it. - \return true If rect is accepted, or has been changed - to a accepted rectangle. + \return true If the rectangle is accepted, or has been changed + to an accepted one. */ -bool QwtPlotZoomer::accept(QwtPolygon &pa) const +bool QwtPlotZoomer::accept( QPolygon &pa ) const { if ( pa.count() < 2 ) return false; - QRect rect = QRect(pa[0], pa[int(pa.count()) - 1]); -#if QT_VERSION < 0x040000 - rect = rect.normalize(); -#else + QRect rect = QRect( pa[0], pa[int( pa.count() ) - 1] ); rect = rect.normalized(); -#endif const int minSize = 2; - if (rect.width() < minSize && rect.height() < minSize ) + if ( rect.width() < minSize && rect.height() < minSize ) return false; const int minZoomSize = 11; const QPoint center = rect.center(); - rect.setSize(rect.size().expandedTo(QSize(minZoomSize, minZoomSize))); - rect.moveCenter(center); + rect.setSize( rect.size().expandedTo( QSize( minZoomSize, minZoomSize ) ) ); + rect.moveCenter( center ); - pa.resize(2); + pa.resize( 2 ); pa[0] = rect.topLeft(); pa[1] = rect.bottomRight(); @@ -554,12 +525,10 @@ bool QwtPlotZoomer::accept(QwtPolygon &pa) const \return zoomBase().width() / 10e4, zoomBase().height() / 10e4 */ -QwtDoubleSize QwtPlotZoomer::minZoomSize() const +QSizeF QwtPlotZoomer::minZoomSize() const { - return QwtDoubleSize( - d_data->zoomStack[0].width() / 10e4, - d_data->zoomStack[0].height() / 10e4 - ); + return QSizeF( d_data->zoomStack[0].width() / 10e4, + d_data->zoomStack[0].height() / 10e4 ); } /*! @@ -570,18 +539,21 @@ QwtDoubleSize QwtPlotZoomer::minZoomSize() const */ void QwtPlotZoomer::begin() { - if ( d_data->maxStackDepth >= 0 ) { - if ( d_data->zoomRectIndex >= uint(d_data->maxStackDepth) ) + if ( d_data->maxStackDepth >= 0 ) + { + if ( d_data->zoomRectIndex >= uint( d_data->maxStackDepth ) ) return; } - const QwtDoubleSize minSize = minZoomSize(); - if ( minSize.isValid() ) { - const QwtDoubleSize sz = + const QSizeF minSize = minZoomSize(); + if ( minSize.isValid() ) + { + const QSizeF sz = d_data->zoomStack[d_data->zoomRectIndex].size() * 0.9999; if ( minSize.width() >= sz.width() && - minSize.height() >= sz.height() ) { + minSize.height() >= sz.height() ) + { return; } } @@ -593,57 +565,40 @@ void QwtPlotZoomer::begin() Expand the selected rectangle to minZoomSize() and zoom in if accepted. - \sa QwtPlotZoomer::accept()a, QwtPlotZoomer::minZoomSize() + \param ok If true, complete the selection and emit selected signals + otherwise discard the selection. + + \sa accept(), minZoomSize() + \return True if the selection has been accepted, false otherwise */ -bool QwtPlotZoomer::end(bool ok) +bool QwtPlotZoomer::end( bool ok ) { - ok = QwtPlotPicker::end(ok); - if (!ok) + ok = QwtPlotPicker::end( ok ); + if ( !ok ) return false; QwtPlot *plot = QwtPlotZoomer::plot(); if ( !plot ) return false; - const QwtPolygon &pa = selection(); + const QPolygon &pa = selection(); if ( pa.count() < 2 ) return false; - QRect rect = QRect(pa[0], pa[int(pa.count() - 1)]); -#if QT_VERSION < 0x040000 - rect = rect.normalize(); -#else + QRect rect = QRect( pa[0], pa[int( pa.count() - 1 )] ); rect = rect.normalized(); -#endif + QRectF zoomRect = invTransform( rect ).normalized(); - QwtDoubleRect zoomRect = invTransform(rect).normalized(); - - const QwtDoublePoint center = zoomRect.center(); - zoomRect.setSize(zoomRect.size().expandedTo(minZoomSize())); - zoomRect.moveCenter(center); + const QSizeF minSize = minZoomSize(); + if ( minSize.isValid() ) + { + const QPointF center = zoomRect.center(); + zoomRect.setSize( zoomRect.size().expandedTo( minZoomSize() ) ); + zoomRect.moveCenter( center ); + } - zoom(zoomRect); + zoom( zoomRect ); return true; } - -/*! - Set the selection flags - - \param flags Or'd value of QwtPicker::RectSelectionType and - QwtPicker::SelectionMode. The default value is - QwtPicker::RectSelection & QwtPicker::ClickSelection. - - \sa selectionFlags(), SelectionType, RectSelectionType, SelectionMode - \note QwtPicker::RectSelection will be auto added. -*/ - -void QwtPlotZoomer::setSelectionFlags(int flags) -{ - // we accept only rects - flags &= ~(PointSelection | PolygonSelection); - flags |= RectSelection; - - QwtPlotPicker::setSelectionFlags(flags); -} diff --git a/libs/qwt/qwt_plot_zoomer.h b/libs/qwt/qwt_plot_zoomer.h index 9904c53aee..1bc05b46a8 100644 --- a/libs/qwt/qwt_plot_zoomer.h +++ b/libs/qwt/qwt_plot_zoomer.h @@ -7,101 +7,108 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_PLOT_ZOOMER_H #define QWT_PLOT_ZOOMER_H -#include <qglobal.h> -#if QT_VERSION < 0x040000 -#include <qvaluestack.h> -#else -#include <qstack.h> -#endif - -#include "qwt_double_rect.h" +#include "qwt_global.h" #include "qwt_plot_picker.h" +#include <qstack.h> /*! \brief QwtPlotZoomer provides stacked zooming for a plot widget - QwtPlotZoomer offers rubberband selections on the plot canvas, - translating the selected rectangles into plot coordinates and - adjusting the axes to them. Zooming can repeated as often as - possible, limited only by maxStackDepth() or minZoomSize(). - Each rectangle is pushed on a stack. + QwtPlotZoomer selects rectangles from user inputs ( mouse or keyboard ) + translates them into plot coordinates and adjusts the axes to them. + The selection is supported by a rubber band and optionally by displaying + the coordinates of the current mouse position. + + Zooming can be repeated as often as possible, limited only by + maxStackDepth() or minZoomSize(). Each rectangle is pushed on a stack. + + The default setting how to select rectangles is + a QwtPickerDragRectMachine with the following bindings: + + - QwtEventPattern::MouseSelect1\n + The first point of the zoom rectangle is selected by a mouse press, + the second point from the position, where the mouse is released. + + - QwtEventPattern::KeySelect1\n + The first key press selects the first, the second key press + selects the second point. + + - QwtEventPattern::KeyAbort\n + Discard the selection in the state, where the first point + is selected. + + To traverse the zoom stack the following bindings are used: + + - QwtEventPattern::MouseSelect3, QwtEventPattern::KeyUndo\n + Zoom out one position on the zoom stack + + - QwtEventPattern::MouseSelect6, QwtEventPattern::KeyRedo\n + Zoom in one position on the zoom stack + + - QwtEventPattern::MouseSelect2, QwtEventPattern::KeyHome\n + Zoom to the zoom base + + The setKeyPattern() and setMousePattern() functions can be used + to configure the zoomer actions. The following example + shows, how to configure the 'I' and 'O' keys for zooming in and out + one position on the zoom stack. The "Home" key is used to + "unzoom" the plot. - Zoom rectangles can be selected depending on selectionFlags() using the - mouse or keyboard (QwtEventPattern, QwtPickerMachine). - QwtEventPattern::MouseSelect3/QwtEventPattern::KeyUndo, - or QwtEventPattern::MouseSelect6/QwtEventPattern::KeyRedo - walk up and down the zoom stack. - QwtEventPattern::MouseSelect2 or QwtEventPattern::KeyHome unzoom to - the initial size. + \code + zoomer = new QwtPlotZoomer( plot ); + zoomer->setKeyPattern( QwtEventPattern::KeyRedo, Qt::Key_I, Qt::ShiftModifier ); + zoomer->setKeyPattern( QwtEventPattern::KeyUndo, Qt::Key_O, Qt::ShiftModifier ); + zoomer->setKeyPattern( QwtEventPattern::KeyHome, Qt::Key_Home ); + \endcode QwtPlotZoomer is tailored for plots with one x and y axis, but it is - allowed to attach a second QwtPlotZoomer for the other axes. + allowed to attach a second QwtPlotZoomer ( without rubber band and tracker ) + for the other axes. \note The realtime example includes an derived zoomer class that adds scrollbars to the plot canvas. + + \sa QwtPlotPanner, QwtPlotMagnifier */ class QWT_EXPORT QwtPlotZoomer: public QwtPlotPicker { Q_OBJECT public: - explicit QwtPlotZoomer(QwtPlotCanvas *, bool doReplot = true); - explicit QwtPlotZoomer(int xAxis, int yAxis, - QwtPlotCanvas *, bool doReplot = true); - explicit QwtPlotZoomer(int xAxis, int yAxis, int selectionFlags, - DisplayMode trackerMode, QwtPlotCanvas *, - bool doReplot = true); + explicit QwtPlotZoomer( QWidget *, bool doReplot = true ); + explicit QwtPlotZoomer( int xAxis, int yAxis, + QWidget *, bool doReplot = true ); virtual ~QwtPlotZoomer(); - virtual void setZoomBase(bool doReplot = true); - virtual void setZoomBase(const QwtDoubleRect &); + virtual void setZoomBase( bool doReplot = true ); + virtual void setZoomBase( const QRectF & ); - QwtDoubleRect zoomBase() const; - QwtDoubleRect zoomRect() const; + QRectF zoomBase() const; + QRectF zoomRect() const; - virtual void setAxis(int xAxis, int yAxis); + virtual void setAxis( int xAxis, int yAxis ); - void setMaxStackDepth(int); + void setMaxStackDepth( int ); int maxStackDepth() const; -#if QT_VERSION < 0x040000 - const QValueStack<QwtDoubleRect> &zoomStack() const; - void setZoomStack(const QValueStack<QwtDoubleRect> &, - int zoomRectIndex = -1); -#else - const QStack<QwtDoubleRect> &zoomStack() const; - void setZoomStack(const QStack<QwtDoubleRect> &, - int zoomRectIndex = -1); -#endif - uint zoomRectIndex() const; - - virtual void setSelectionFlags(int); - -public slots: - void moveBy(double x, double y); + const QStack<QRectF> &zoomStack() const; + void setZoomStack( const QStack<QRectF> &, + int zoomRectIndex = -1 ); -// These pragmas are local modifications to this third party library to silence warnings -#ifndef Q_OS_WIN -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Woverloaded-virtual" -#endif - - virtual void move(double x, double y); + uint zoomRectIndex() const; -#ifndef Q_OS_WIN -#pragma GCC diagnostic pop -#endif +public Q_SLOTS: + void moveBy( double x, double y ); + virtual void moveTo( const QPointF & ); - virtual void zoom(const QwtDoubleRect &); - virtual void zoom(int up); + virtual void zoom( const QRectF & ); + virtual void zoom( int up ); -signals: +Q_SIGNALS: /*! A signal emitting the zoomRect(), when the plot has been zoomed in or out. @@ -109,22 +116,22 @@ signals: \param rect Current zoom rectangle. */ - void zoomed(const QwtDoubleRect &rect); + void zoomed( const QRectF &rect ); protected: virtual void rescale(); - virtual QwtDoubleSize minZoomSize() const; + virtual QSizeF minZoomSize() const; - virtual void widgetMouseReleaseEvent(QMouseEvent *); - virtual void widgetKeyPressEvent(QKeyEvent *); + virtual void widgetMouseReleaseEvent( QMouseEvent * ); + virtual void widgetKeyPressEvent( QKeyEvent * ); virtual void begin(); - virtual bool end(bool ok = true); - virtual bool accept(QwtPolygon &) const; + virtual bool end( bool ok = true ); + virtual bool accept( QPolygon & ) const; private: - void init(int selectionFlags, DisplayMode trackerMode, bool doReplot); + void init( bool doReplot ); class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_point_3d.cpp b/libs/qwt/qwt_point_3d.cpp new file mode 100644 index 0000000000..27e4c1e8f4 --- /dev/null +++ b/libs/qwt/qwt_point_3d.cpp @@ -0,0 +1,22 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_point_3d.h" + +#ifndef QT_NO_DEBUG_STREAM + +QDebug operator<<( QDebug debug, const QwtPoint3D &point ) +{ + debug.nospace() << "QwtPoint3D(" << point.x() + << "," << point.y() << "," << point.z() << ")"; + return debug.space(); +} + +#endif + diff --git a/libs/qwt/qwt_point_3d.h b/libs/qwt/qwt_point_3d.h new file mode 100644 index 0000000000..5b0b40e895 --- /dev/null +++ b/libs/qwt/qwt_point_3d.h @@ -0,0 +1,189 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +/*! \file */ +#ifndef QWT_POINT_3D_H +#define QWT_POINT_3D_H 1 + +#include "qwt_global.h" +#include <qpoint.h> +#ifndef QT_NO_DEBUG_STREAM +#include <qdebug.h> +#endif + +/*! + \brief QwtPoint3D class defines a 3D point in double coordinates +*/ + +class QWT_EXPORT QwtPoint3D +{ +public: + QwtPoint3D(); + QwtPoint3D( double x, double y, double z ); + QwtPoint3D( const QwtPoint3D & ); + QwtPoint3D( const QPointF & ); + + bool isNull() const; + + double x() const; + double y() const; + double z() const; + + double &rx(); + double &ry(); + double &rz(); + + void setX( double x ); + void setY( double y ); + void setZ( double y ); + + QPointF toPoint() const; + + bool operator==( const QwtPoint3D & ) const; + bool operator!=( const QwtPoint3D & ) const; + +private: + double d_x; + double d_y; + double d_z; +}; + +Q_DECLARE_TYPEINFO(QwtPoint3D, Q_MOVABLE_TYPE); + +#ifndef QT_NO_DEBUG_STREAM +QWT_EXPORT QDebug operator<<( QDebug, const QwtPoint3D & ); +#endif + +/*! + Constructs a null point. + \sa isNull() +*/ +inline QwtPoint3D::QwtPoint3D(): + d_x( 0.0 ), + d_y( 0.0 ), + d_z( 0.0 ) +{ +} + +//! Constructs a point with coordinates specified by x, y and z. +inline QwtPoint3D::QwtPoint3D( double x, double y, double z = 0.0 ): + d_x( x ), + d_y( y ), + d_z( z ) +{ +} + +/*! + Copy constructor. + Constructs a point using the values of the point specified. +*/ +inline QwtPoint3D::QwtPoint3D( const QwtPoint3D &other ): + d_x( other.d_x ), + d_y( other.d_y ), + d_z( other.d_z ) +{ +} + +/*! + Constructs a point with x and y coordinates from a 2D point, + and a z coordinate of 0. +*/ +inline QwtPoint3D::QwtPoint3D( const QPointF &other ): + d_x( other.x() ), + d_y( other.y() ), + d_z( 0.0 ) +{ +} + +/*! + \return True if the point is null; otherwise returns false. + + A point is considered to be null if x, y and z-coordinates + are equal to zero. +*/ +inline bool QwtPoint3D::isNull() const +{ + return d_x == 0.0 && d_y == 0.0 && d_z == 0.0; +} + +//! \return The x-coordinate of the point. +inline double QwtPoint3D::x() const +{ + return d_x; +} + +//! \return The y-coordinate of the point. +inline double QwtPoint3D::y() const +{ + return d_y; +} + +//! \return The z-coordinate of the point. +inline double QwtPoint3D::z() const +{ + return d_z; +} + +//! \return A reference to the x-coordinate of the point. +inline double &QwtPoint3D::rx() +{ + return d_x; +} + +//! \return A reference to the y-coordinate of the point. +inline double &QwtPoint3D::ry() +{ + return d_y; +} + +//! \return A reference to the z-coordinate of the point. +inline double &QwtPoint3D::rz() +{ + return d_z; +} + +//! Sets the x-coordinate of the point to the value specified by x. +inline void QwtPoint3D::setX( double x ) +{ + d_x = x; +} + +//! Sets the y-coordinate of the point to the value specified by y. +inline void QwtPoint3D::setY( double y ) +{ + d_y = y; +} + +//! Sets the z-coordinate of the point to the value specified by z. +inline void QwtPoint3D::setZ( double z ) +{ + d_z = z; +} + +/*! + \return 2D point, where the z coordinate is dropped. +*/ +inline QPointF QwtPoint3D::toPoint() const +{ + return QPointF( d_x, d_y ); +} + +//! \return True, if this point and other are equal; otherwise returns false. +inline bool QwtPoint3D::operator==( const QwtPoint3D &other ) const +{ + return ( d_x == other.d_x ) && ( d_y == other.d_y ) && ( d_z == other.d_z ); +} + +//! \return True if this rect and other are different; otherwise returns false. +inline bool QwtPoint3D::operator!=( const QwtPoint3D &other ) const +{ + return !operator==( other ); +} + +#endif diff --git a/libs/qwt/qwt_point_data.cpp b/libs/qwt/qwt_point_data.cpp new file mode 100644 index 0000000000..d4eeaaabb3 --- /dev/null +++ b/libs/qwt/qwt_point_data.cpp @@ -0,0 +1,304 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_point_data.h" +#include "qwt_math.h" +#include <string.h> + +/*! + Constructor + + \param x Array of x values + \param y Array of y values + + \sa QwtPlotCurve::setData(), QwtPlotCurve::setSamples() +*/ +QwtPointArrayData::QwtPointArrayData( + const QVector<double> &x, const QVector<double> &y ): + d_x( x ), + d_y( y ) +{ +} + +/*! + Constructor + + \param x Array of x values + \param y Array of y values + \param size Size of the x and y arrays + \sa QwtPlotCurve::setData(), QwtPlotCurve::setSamples() +*/ +QwtPointArrayData::QwtPointArrayData( const double *x, + const double *y, size_t size ) +{ + d_x.resize( size ); + ::memcpy( d_x.data(), x, size * sizeof( double ) ); + + d_y.resize( size ); + ::memcpy( d_y.data(), y, size * sizeof( double ) ); +} + +/*! + \brief Calculate the bounding rectangle + + The bounding rectangle is calculated once by iterating over all + points and is stored for all following requests. + + \return Bounding rectangle +*/ +QRectF QwtPointArrayData::boundingRect() const +{ + if ( d_boundingRect.width() < 0 ) + d_boundingRect = qwtBoundingRect( *this ); + + return d_boundingRect; +} + +//! \return Size of the data set +size_t QwtPointArrayData::size() const +{ + return qMin( d_x.size(), d_y.size() ); +} + +/*! + Return the sample at position i + + \param index Index + \return Sample at position i +*/ +QPointF QwtPointArrayData::sample( size_t index ) const +{ + return QPointF( d_x[int( index )], d_y[int( index )] ); +} + +//! \return Array of the x-values +const QVector<double> &QwtPointArrayData::xData() const +{ + return d_x; +} + +//! \return Array of the y-values +const QVector<double> &QwtPointArrayData::yData() const +{ + return d_y; +} + +/*! + Constructor + + \param x Array of x values + \param y Array of y values + \param size Size of the x and y arrays + + \warning The programmer must assure that the memory blocks referenced + by the pointers remain valid during the lifetime of the + QwtPlotCPointer object. + + \sa QwtPlotCurve::setData(), QwtPlotCurve::setRawSamples() +*/ +QwtCPointerData::QwtCPointerData( + const double *x, const double *y, size_t size ): + d_x( x ), + d_y( y ), + d_size( size ) +{ +} + +/*! + \brief Calculate the bounding rectangle + + The bounding rectangle is calculated once by iterating over all + points and is stored for all following requests. + + \return Bounding rectangle +*/ +QRectF QwtCPointerData::boundingRect() const +{ + if ( d_boundingRect.width() < 0 ) + d_boundingRect = qwtBoundingRect( *this ); + + return d_boundingRect; +} + +//! \return Size of the data set +size_t QwtCPointerData::size() const +{ + return d_size; +} + +/*! + Return the sample at position i + + \param index Index + \return Sample at position i +*/ +QPointF QwtCPointerData::sample( size_t index ) const +{ + return QPointF( d_x[int( index )], d_y[int( index )] ); +} + +//! \return Array of the x-values +const double *QwtCPointerData::xData() const +{ + return d_x; +} + +//! \return Array of the y-values +const double *QwtCPointerData::yData() const +{ + return d_y; +} + +/*! + Constructor + + \param size Number of points + \param interval Bounding interval for the points + + \sa setInterval(), setSize() +*/ +QwtSyntheticPointData::QwtSyntheticPointData( + size_t size, const QwtInterval &interval ): + d_size( size ), + d_interval( interval ) +{ +} + +/*! + Change the number of points + + \param size Number of points + \sa size(), setInterval() +*/ +void QwtSyntheticPointData::setSize( size_t size ) +{ + d_size = size; +} + +/*! + \return Number of points + \sa setSize(), interval() +*/ +size_t QwtSyntheticPointData::size() const +{ + return d_size; +} + +/*! + Set the bounding interval + + \param interval Interval + \sa interval(), setSize() +*/ +void QwtSyntheticPointData::setInterval( const QwtInterval &interval ) +{ + d_interval = interval.normalized(); +} + +/*! + \return Bounding interval + \sa setInterval(), size() +*/ +QwtInterval QwtSyntheticPointData::interval() const +{ + return d_interval; +} + +/*! + Set a the "rectangle of interest" + + QwtPlotSeriesItem defines the current area of the plot canvas + as "rect of interest" ( QwtPlotSeriesItem::updateScaleDiv() ). + + If interval().isValid() == false the x values are calculated + in the interval rect.left() -> rect.right(). + + \sa rectOfInterest() +*/ +void QwtSyntheticPointData::setRectOfInterest( const QRectF &rect ) +{ + d_rectOfInterest = rect; + d_intervalOfInterest = QwtInterval( + rect.left(), rect.right() ).normalized(); +} + +/*! + \return "rectangle of interest" + \sa setRectOfInterest() +*/ +QRectF QwtSyntheticPointData::rectOfInterest() const +{ + return d_rectOfInterest; +} + +/*! + \brief Calculate the bounding rectangle + + This implementation iterates over all points, what could often + be implemented much faster using the characteristics of the series. + When there are many points it is recommended to overload and + reimplement this method using the characteristics of the series + ( if possible ). + + \return Bounding rectangle +*/ +QRectF QwtSyntheticPointData::boundingRect() const +{ + if ( d_size == 0 || + !( d_interval.isValid() || d_intervalOfInterest.isValid() ) ) + { + return QRectF( 1.0, 1.0, -2.0, -2.0 ); // something invalid + } + + return qwtBoundingRect( *this ); +} + +/*! + Calculate the point from an index + + \param index Index + \return QPointF(x(index), y(x(index))); + + \warning For invalid indices ( index < 0 || index >= size() ) + (0, 0) is returned. +*/ +QPointF QwtSyntheticPointData::sample( size_t index ) const +{ + if ( index >= d_size ) + return QPointF( 0, 0 ); + + const double xValue = x( index ); + const double yValue = y( xValue ); + + return QPointF( xValue, yValue ); +} + +/*! + Calculate a x-value from an index + + x values are calculated by dividing an interval into + equidistant steps. If !interval().isValid() the + interval is calculated from the "rectangle of interest". + + \param index Index of the requested point + \return Calculated x coordinate + + \sa interval(), rectOfInterest(), y() +*/ +double QwtSyntheticPointData::x( uint index ) const +{ + const QwtInterval &interval = d_interval.isValid() ? + d_interval : d_intervalOfInterest; + + if ( !interval.isValid() || d_size == 0 || index >= d_size ) + return 0.0; + + const double dx = interval.width() / d_size; + return interval.minValue() + index * dx; +} diff --git a/libs/qwt/qwt_point_data.h b/libs/qwt/qwt_point_data.h new file mode 100644 index 0000000000..c4c9c0c35f --- /dev/null +++ b/libs/qwt/qwt_point_data.h @@ -0,0 +1,146 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_POINT_DATA_H +#define QWT_POINT_DATA_H 1 + +#include "qwt_global.h" +#include "qwt_series_data.h" + +/*! + \brief Interface for iterating over two QVector<double> objects. +*/ +class QWT_EXPORT QwtPointArrayData: public QwtSeriesData<QPointF> +{ +public: + QwtPointArrayData( const QVector<double> &x, const QVector<double> &y ); + QwtPointArrayData( const double *x, const double *y, size_t size ); + + virtual QRectF boundingRect() const; + + virtual size_t size() const; + virtual QPointF sample( size_t i ) const; + + const QVector<double> &xData() const; + const QVector<double> &yData() const; + +private: + QVector<double> d_x; + QVector<double> d_y; +}; + +/*! + \brief Data class containing two pointers to memory blocks of doubles. + */ +class QWT_EXPORT QwtCPointerData: public QwtSeriesData<QPointF> +{ +public: + QwtCPointerData( const double *x, const double *y, size_t size ); + + virtual QRectF boundingRect() const; + virtual size_t size() const; + virtual QPointF sample( size_t i ) const; + + const double *xData() const; + const double *yData() const; + +private: + const double *d_x; + const double *d_y; + size_t d_size; +}; + +/*! + \brief Synthetic point data + + QwtSyntheticPointData provides a fixed number of points for an interval. + The points are calculated in equidistant steps in x-direction. + + If the interval is invalid, the points are calculated for + the "rectangle of interest", what normally is the displayed area on the + plot canvas. In this mode you get different levels of detail, when + zooming in/out. + + \par Example + + The following example shows how to implement a sinus curve. + + \code +#include <cmath> +#include <qwt_series_data.h> +#include <qwt_plot_curve.h> +#include <qwt_plot.h> +#include <qapplication.h> + +class SinusData: public QwtSyntheticPointData +{ +public: + SinusData(): + QwtSyntheticPointData( 100 ) + { + } + + virtual double y( double x ) const + { + return qSin( x ); + } +}; + +int main(int argc, char **argv) +{ + QApplication a( argc, argv ); + + QwtPlot plot; + plot.setAxisScale( QwtPlot::xBottom, 0.0, 10.0 ); + plot.setAxisScale( QwtPlot::yLeft, -1.0, 1.0 ); + + QwtPlotCurve *curve = new QwtPlotCurve( "y = sin(x)" ); + curve->setData( new SinusData() ); + curve->attach( &plot ); + + plot.show(); + return a.exec(); +} + \endcode +*/ +class QWT_EXPORT QwtSyntheticPointData: public QwtSeriesData<QPointF> +{ +public: + QwtSyntheticPointData( size_t size, + const QwtInterval & = QwtInterval() ); + + void setSize( size_t size ); + virtual size_t size() const; + + void setInterval( const QwtInterval& ); + QwtInterval interval() const; + + virtual QRectF boundingRect() const; + virtual QPointF sample( size_t i ) const; + + /*! + Calculate a y value for a x value + + \param x x value + \return Corresponding y value + */ + virtual double y( double x ) const = 0; + virtual double x( uint index ) const; + + virtual void setRectOfInterest( const QRectF & ); + QRectF rectOfInterest() const; + +private: + size_t d_size; + QwtInterval d_interval; + QRectF d_rectOfInterest; + QwtInterval d_intervalOfInterest; +}; + +#endif diff --git a/libs/qwt/qwt_point_mapper.cpp b/libs/qwt/qwt_point_mapper.cpp new file mode 100644 index 0000000000..eee0e29cb5 --- /dev/null +++ b/libs/qwt/qwt_point_mapper.cpp @@ -0,0 +1,721 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_point_mapper.h" +#include "qwt_scale_map.h" +#include "qwt_pixel_matrix.h" +#include <qpolygon.h> +#include <qimage.h> +#include <qpen.h> +#include <qpainter.h> + +#if QT_VERSION >= 0x040400 + +#include <qthread.h> +#include <qfuture.h> +#include <qtconcurrentrun.h> + +#if !defined(QT_NO_QFUTURE) +#define QWT_USE_THREADS 0 +#endif + +#endif + +static QRectF qwtInvalidRect( 0.0, 0.0, -1.0, -1.0 ); + +// Helper class to work around the 5 parameters +// limitation of QtConcurrent::run() +class QwtDotsCommand +{ +public: + const QwtSeriesData<QPointF> *series; + int from; + int to; + QRgb rgb; +}; + +static void qwtRenderDots( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtDotsCommand command, const QPoint &pos, QImage *image ) +{ + const QRgb rgb = command.rgb; + QRgb *bits = reinterpret_cast<QRgb *>( image->bits() ); + + const int w = image->width(); + const int h = image->height(); + + const int x0 = pos.x(); + const int y0 = pos.y(); + + for ( int i = command.from; i <= command.to; i++ ) + { + const QPointF sample = command.series->sample( i ); + + const int x = static_cast<int>( xMap.transform( sample.x() ) + 0.5 ) - x0; + const int y = static_cast<int>( yMap.transform( sample.y() ) + 0.5 ) - y0; + + if ( x >= 0 && x < w && y >= 0 && y < h ) + bits[ y * w + x ] = rgb; + } +} + +static inline int qwtRoundValue( double value ) +{ +#if 1 + return qRound( value ); +#else + // A little bit faster, but differs from qRound() + // for negative values. Should be no problem as we are + // rounding widgets coordinates, where negative values + // are clipped off anyway ( at least when there is no + // painter transformation ) + + return static_cast<int>( value + 0.5 ); +#endif +} + +// some functors, so that the compile can inline +struct QwtRoundI +{ + inline int operator()( double value ) + { + return qwtRoundValue( value ); + } +}; + +struct QwtRoundF +{ + inline double operator()( double value ) + { + return static_cast<double>( qwtRoundValue( value ) ); + } +}; + +struct QwtNoRoundF +{ + inline double operator()( double value ) + { + return value; + } +}; + +// mapping points without any filtering - beside checking +// the bounding rectangle + +template<class Polygon, class Point, class Round> +static inline Polygon qwtToPoints( + const QRectF &boundingRect, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, + int from, int to, Round round ) +{ + Polygon polyline( to - from + 1 ); + Point *points = polyline.data(); + + int numPoints = 0; + + if ( boundingRect.isValid() ) + { + // iterating over all values + // filtering out all points outside of + // the bounding rectangle + + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = series->sample( i ); + + const double x = xMap.transform( sample.x() ); + const double y = yMap.transform( sample.y() ); + + if ( boundingRect.contains( x, y ) ) + { + points[ numPoints ].rx() = round( x ); + points[ numPoints ].ry() = round( y ); + + numPoints++; + } + } + + polyline.resize( numPoints ); + } + else + { + // simply iterating over all values + // without any filtering + + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = series->sample( i ); + + const double x = xMap.transform( sample.x() ); + const double y = yMap.transform( sample.y() ); + + points[ numPoints ].rx() = round( x ); + points[ numPoints ].ry() = round( y ); + + numPoints++; + } + } + + return polyline; +} + +static inline QPolygon qwtToPointsI( + const QRectF &boundingRect, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, + int from, int to ) +{ + return qwtToPoints<QPolygon, QPoint>( + boundingRect, xMap, yMap, series, from, to, QwtRoundI() ); +} + +template<class Round> +static inline QPolygonF qwtToPointsF( + const QRectF &boundingRect, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, + int from, int to, Round round ) +{ + return qwtToPoints<QPolygonF, QPointF>( + boundingRect, xMap, yMap, series, from, to, round ); +} + +// Mapping points with filtering out consecutive +// points mapped to the same position + +template<class Polygon, class Point, class Round> +static inline Polygon qwtToPolylineFiltered( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, + int from, int to, Round round ) +{ + // in curves with many points consecutive points + // are often mapped to the same position. As this might + // result in empty lines ( or symbols hidden by others ) + // we try to filter them out + + Polygon polyline( to - from + 1 ); + Point *points = polyline.data(); + + const QPointF sample0 = series->sample( from ); + + points[0].rx() = round( xMap.transform( sample0.x() ) ); + points[0].ry() = round( yMap.transform( sample0.y() ) ); + + int pos = 0; + for ( int i = from + 1; i <= to; i++ ) + { + const QPointF sample = series->sample( i ); + + const Point p( round( xMap.transform( sample.x() ) ), + round( yMap.transform( sample.y() ) ) ); + + if ( points[pos] != p ) + points[++pos] = p; + } + + polyline.resize( pos + 1 ); + return polyline; +} + +static inline QPolygon qwtToPolylineFilteredI( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, + int from, int to ) +{ + return qwtToPolylineFiltered<QPolygon, QPoint>( + xMap, yMap, series, from, to, QwtRoundI() ); +} + +template<class Round> +static inline QPolygonF qwtToPolylineFilteredF( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, + int from, int to, Round round ) +{ + return qwtToPolylineFiltered<QPolygonF, QPointF>( + xMap, yMap, series, from, to, round ); +} + +template<class Polygon, class Point> +static inline Polygon qwtToPointsFiltered( + const QRectF &boundingRect, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) +{ + // F.e. in scatter plots ( no connecting lines ) we + // can sort out all duplicates ( not only consecutive points ) + + Polygon polygon( to - from + 1 ); + Point *points = polygon.data(); + + QwtPixelMatrix pixelMatrix( boundingRect.toAlignedRect() ); + + int numPoints = 0; + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = series->sample( i ); + + const int x = qwtRoundValue( xMap.transform( sample.x() ) ); + const int y = qwtRoundValue( yMap.transform( sample.y() ) ); + + if ( pixelMatrix.testAndSetPixel( x, y, true ) == false ) + { + points[ numPoints ].rx() = x; + points[ numPoints ].ry() = y; + + numPoints++; + } + } + + polygon.resize( numPoints ); + return polygon; +} + +static inline QPolygon qwtToPointsFilteredI( + const QRectF &boundingRect, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) +{ + return qwtToPointsFiltered<QPolygon, QPoint>( + boundingRect, xMap, yMap, series, from, to ); +} + +static inline QPolygonF qwtToPointsFilteredF( + const QRectF &boundingRect, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) +{ + return qwtToPointsFiltered<QPolygonF, QPointF>( + boundingRect, xMap, yMap, series, from, to ); +} + +class QwtPointMapper::PrivateData +{ +public: + PrivateData(): + boundingRect( qwtInvalidRect ) + { + } + + QRectF boundingRect; + QwtPointMapper::TransformationFlags flags; +}; + +//! Constructor +QwtPointMapper::QwtPointMapper() +{ + d_data = new PrivateData(); +} + +//! Destructor +QwtPointMapper::~QwtPointMapper() +{ + delete d_data; +} + +/*! + Set the flags affecting the transformation process + + \param flags Flags + \sa flags(), setFlag() + */ +void QwtPointMapper::setFlags( TransformationFlags flags ) +{ + d_data->flags = flags; +} + +/*! + \return Flags affecting the transformation process + \sa setFlags(), setFlag() + */ +QwtPointMapper::TransformationFlags QwtPointMapper::flags() const +{ + return d_data->flags; +} + +/*! + Modify a flag affecting the transformation process + + \param flag Flag type + \param on Value + + \sa flag(), setFlags() + */ +void QwtPointMapper::setFlag( TransformationFlag flag, bool on ) +{ + if ( on ) + d_data->flags |= flag; + else + d_data->flags &= ~flag; +} + +/*! + \return True, when the flag is set + \param flag Flag type + \sa setFlag(), setFlags() + */ +bool QwtPointMapper::testFlag( TransformationFlag flag ) const +{ + return d_data->flags & flag; +} + +/*! + Set a bounding rectangle for the point mapping algorithm + + A valid bounding rectangle can be used for optimizations + + \param rect Bounding rectangle + \sa boundingRect() + */ +void QwtPointMapper::setBoundingRect( const QRectF &rect ) +{ + d_data->boundingRect = rect; +} + +/*! + \return Bounding rectangle + \sa setBoundingRect() + */ +QRectF QwtPointMapper::boundingRect() const +{ + return d_data->boundingRect; +} + +/*! + \brief Translate a series of points into a QPolygonF + + When the WeedOutPoints flag is enabled consecutive points, + that are mapped to the same position will be one point. + + When RoundPoints is set all points are rounded to integers + but returned as PolygonF - what only makes sense + when the further processing of the values need a QPolygonF. + + \param xMap x map + \param yMap y map + \param series Series of points to be mapped + \param from Index of the first point to be painted + \param to Index of the last point to be painted + + \return Translated polygon +*/ +QPolygonF QwtPointMapper::toPolygonF( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const +{ + QPolygonF polyline; + + if ( d_data->flags & WeedOutPoints ) + { + if ( d_data->flags & RoundPoints ) + { + polyline = qwtToPolylineFilteredF( + xMap, yMap, series, from, to, QwtRoundF() ); + } + else + { + polyline = qwtToPolylineFilteredF( + xMap, yMap, series, from, to, QwtNoRoundF() ); + } + } + else + { + if ( d_data->flags & RoundPoints ) + { + polyline = qwtToPointsF( qwtInvalidRect, + xMap, yMap, series, from, to, QwtRoundF() ); + } + else + { + polyline = qwtToPointsF( qwtInvalidRect, + xMap, yMap, series, from, to, QwtNoRoundF() ); + } + } + + return polyline; +} + +/*! + \brief Translate a series of points into a QPolygon + + When the WeedOutPoints flag is enabled consecutive points, + that are mapped to the same position will be one point. + + \param xMap x map + \param yMap y map + \param series Series of points to be mapped + \param from Index of the first point to be painted + \param to Index of the last point to be painted + + \return Translated polygon +*/ +QPolygon QwtPointMapper::toPolygon( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const +{ + QPolygon polyline; + + if ( d_data->flags & WeedOutPoints ) + { + polyline = qwtToPolylineFilteredI( + xMap, yMap, series, from, to ); + } + else + { + polyline = qwtToPointsI( + qwtInvalidRect, xMap, yMap, series, from, to ); + } + + return polyline; +} + +/*! + \brief Translate a series into a QPolygonF + + - WeedOutPoints & RoundPoints & boundingRect().isValid() + All points that are mapped to the same position + will be one point. Points outside of the bounding + rectangle are ignored. + + - WeedOutPoints & RoundPoints & !boundingRect().isValid() + All consecutive points that are mapped to the same position + will one point + + - WeedOutPoints & !RoundPoints + All consecutive points that are mapped to the same position + will one point + + - !WeedOutPoints & boundingRect().isValid() + Points outside of the bounding rectangle are ignored. + + When RoundPoints is set all points are rounded to integers + but returned as PolygonF - what only makes sense + when the further processing of the values need a QPolygonF. + + \param xMap x map + \param yMap y map + \param series Series of points to be mapped + \param from Index of the first point to be painted + \param to Index of the last point to be painted + + \return Translated polygon +*/ +QPolygonF QwtPointMapper::toPointsF( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const +{ + QPolygonF points; + + if ( d_data->flags & WeedOutPoints ) + { + if ( d_data->flags & RoundPoints ) + { + if ( d_data->boundingRect.isValid() ) + { + points = qwtToPointsFilteredF( d_data->boundingRect, + xMap, yMap, series, from, to ); + } + else + { + // without a bounding rectangle all we can + // do is to filter out duplicates of + // consecutive points + + points = qwtToPolylineFilteredF( + xMap, yMap, series, from, to, QwtRoundF() ); + } + } + else + { + // when rounding is not allowed we can't use + // qwtToPointsFilteredF + + points = qwtToPolylineFilteredF( + xMap, yMap, series, from, to, QwtNoRoundF() ); + } + } + else + { + if ( d_data->flags & RoundPoints ) + { + points = qwtToPointsF( d_data->boundingRect, + xMap, yMap, series, from, to, QwtRoundF() ); + } + else + { + points = qwtToPointsF( d_data->boundingRect, + xMap, yMap, series, from, to, QwtNoRoundF() ); + } + } + + return points; +} + +/*! + \brief Translate a series of points into a QPolygon + + - WeedOutPoints & boundingRect().isValid() + All points that are mapped to the same position + will be one point. Points outside of the bounding + rectangle are ignored. + + - WeedOutPoints & !boundingRect().isValid() + All consecutive points that are mapped to the same position + will one point + + - !WeedOutPoints & boundingRect().isValid() + Points outside of the bounding rectangle are ignored. + + \param xMap x map + \param yMap y map + \param series Series of points to be mapped + \param from Index of the first point to be painted + \param to Index of the last point to be painted + + \return Translated polygon +*/ +QPolygon QwtPointMapper::toPoints( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const +{ + QPolygon points; + + if ( d_data->flags & WeedOutPoints ) + { + if ( d_data->boundingRect.isValid() ) + { + points = qwtToPointsFilteredI( d_data->boundingRect, + xMap, yMap, series, from, to ); + } + else + { + // when we don't have the bounding rectangle all + // we can do is to filter out consecutive duplicates + + points = qwtToPolylineFilteredI( + xMap, yMap, series, from, to ); + } + } + else + { + points = qwtToPointsI( + d_data->boundingRect, xMap, yMap, series, from, to ); + } + + return points; +} + + +/*! + \brief Translate a series into a QImage + + \param xMap x map + \param yMap y map + \param series Series of points to be mapped + \param from Index of the first point to be painted + \param to Index of the last point to be painted + \param pen Pen used for drawing a point + of the image, where a point is mapped to + \param antialiased True, when the dots should be displayed + antialiased + \param numThreads Number of threads to be used for rendering. + If numThreads is set to 0, the system specific + ideal thread count is used. + + \return Image displaying the series +*/ +QImage QwtPointMapper::toImage( + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to, + const QPen &pen, bool antialiased, uint numThreads ) const +{ + Q_UNUSED( antialiased ) + +#if QWT_USE_THREADS + if ( numThreads == 0 ) + numThreads = QThread::idealThreadCount(); + + if ( numThreads <= 0 ) + numThreads = 1; +#else + Q_UNUSED( numThreads ) +#endif + + // a very special optimization for scatter plots + // where every sample is mapped to one pixel only. + + const QRect rect = d_data->boundingRect.toAlignedRect(); + + QImage image( rect.size(), QImage::Format_ARGB32 ); + image.fill( Qt::transparent ); + + if ( pen.width() <= 1 && pen.color().alpha() == 255 ) + { + QwtDotsCommand command; + command.series = series; + command.rgb = pen.color().rgba(); + +#if QWT_USE_THREADS + const int numPoints = ( to - from + 1 ) / numThreads; + + QList< QFuture<void> > futures; + for ( uint i = 0; i < numThreads; i++ ) + { + const QPoint pos = rect.topLeft(); + + const int index0 = from + i * numPoints; + if ( i == numThreads - 1 ) + { + command.from = index0; + command.to = to; + + qwtRenderDots( xMap, yMap, command, pos, &image ); + } + else + { + command.from = index0; + command.to = index0 + numPoints - 1; + + futures += QtConcurrent::run( &qwtRenderDots, + xMap, yMap, command, pos, &image ); + } + } + for ( int i = 0; i < futures.size(); i++ ) + futures[i].waitForFinished(); +#else + command.from = from; + command.to = to; + + qwtRenderDots( xMap, yMap, command, rect.topLeft(), &image ); +#endif + } + else + { + // fallback implementation: to be replaced later by + // setting the pixels of the image like above, TODO ... + + QPainter painter( &image ); + painter.setPen( pen ); + painter.setRenderHint( QPainter::Antialiasing, antialiased ); + + const int chunkSize = 1000; + for ( int i = from; i <= to; i += chunkSize ) + { + const int indexTo = qMin( i + chunkSize - 1, to ); + const QPolygon points = toPoints( + xMap, yMap, series, i, indexTo ); + + painter.drawPoints( points ); + } + } + + return image; +} diff --git a/libs/qwt/qwt_point_mapper.h b/libs/qwt/qwt_point_mapper.h new file mode 100644 index 0000000000..918fc8a659 --- /dev/null +++ b/libs/qwt/qwt_point_mapper.h @@ -0,0 +1,89 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2003 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_POINT_MAPPER_H +#define QWT_POINT_MAPPER_H + +#include "qwt_global.h" +#include "qwt_series_data.h" +#include <qimage.h> + +class QwtScaleMap; +class QPolygonF; +class QPolygon; + +/*! + \brief A helper class for translating a series of points + + QwtPointMapper is a collection of methods and optimizations + for translating a series of points into paint device coordinates. + It is used by QwtPlotCurve but might also be useful for + similar plot items displaying a QwtSeriesData<QPointF>. + */ +class QWT_EXPORT QwtPointMapper +{ +public: + /*! + \brief Flags affecting the transformation process + \sa setFlag(), setFlags() + */ + enum TransformationFlag + { + //! Round points to integer values + RoundPoints = 0x01, + + /*! + Try to remove points, that are translated to the + same position. + */ + WeedOutPoints = 0x02 + }; + + /*! + \brief Flags affecting the transformation process + \sa setFlag(), setFlags() + */ + typedef QFlags<TransformationFlag> TransformationFlags; + + QwtPointMapper(); + ~QwtPointMapper(); + + void setFlags( TransformationFlags ); + TransformationFlags flags() const; + + void setFlag( TransformationFlag, bool on = true ); + bool testFlag( TransformationFlag ) const; + + void setBoundingRect( const QRectF & ); + QRectF boundingRect() const; + + QPolygonF toPolygonF( const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const; + + QPolygon toPolygon( const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const; + + QPolygon toPoints( const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const; + + QPolygonF toPointsF( const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to ) const; + + QImage toImage( const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QwtSeriesData<QPointF> *series, int from, int to, + const QPen &, bool antialiased, uint numThreads ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPointMapper::TransformationFlags ) + +#endif diff --git a/libs/qwt/qwt_point_polar.cpp b/libs/qwt/qwt_point_polar.cpp new file mode 100644 index 0000000000..644bcf118c --- /dev/null +++ b/libs/qwt/qwt_point_polar.cpp @@ -0,0 +1,121 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * QwtPolar Widget Library + * Copyright (C) 2008 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_point_polar.h" +#include "qwt_math.h" + +#if QT_VERSION < 0x040601 +#define qAtan2(y, x) ::atan2(y, x) +#endif + +/*! + Convert and assign values from a point in Cartesian coordinates + + \param p Point in Cartesian coordinates + \sa setPoint(), toPoint() +*/ +QwtPointPolar::QwtPointPolar( const QPointF &p ) +{ + d_radius = qSqrt( qwtSqr( p.x() ) + qwtSqr( p.y() ) ); + d_azimuth = qAtan2( p.y(), p.x() ); +} + +/*! + Convert and assign values from a point in Cartesian coordinates + \param p Point in Cartesian coordinates +*/ +void QwtPointPolar::setPoint( const QPointF &p ) +{ + d_radius = qSqrt( qwtSqr( p.x() ) + qwtSqr( p.y() ) ); + d_azimuth = qAtan2( p.y(), p.x() ); +} + +/*! + Convert and return values in Cartesian coordinates + + \return Converted point in Cartesian coordinates + + \note Invalid or null points will be returned as QPointF(0.0, 0.0) + \sa isValid(), isNull() +*/ +QPointF QwtPointPolar::toPoint() const +{ + if ( d_radius <= 0.0 ) + return QPointF( 0.0, 0.0 ); + + const double x = d_radius * qCos( d_azimuth ); + const double y = d_radius * qSin( d_azimuth ); + + return QPointF( x, y ); +} + +/*! + \brief Compare 2 points + + Two points are equal to each other if radius and + azimuth-coordinates are the same. Points are not equal, when + the azimuth differs, but other.azimuth() == azimuth() % (2 * PI). + + \return True if the point is equal to other; otherwise return false. + + \sa normalized() +*/ +bool QwtPointPolar::operator==( const QwtPointPolar &other ) const +{ + return d_radius == other.d_radius && d_azimuth == other.d_azimuth; +} + +/*! + Compare 2 points + + Two points are equal to each other if radius and + azimuth-coordinates are the same. Points are not equal, when + the azimuth differs, but other.azimuth() == azimuth() % (2 * PI). + + \return True if the point is not equal to other; otherwise return false. + \sa normalized() +*/ +bool QwtPointPolar::operator!=( const QwtPointPolar &other ) const +{ + return d_radius != other.d_radius || d_azimuth != other.d_azimuth; +} + +/*! + Normalize radius and azimuth + + When the radius is < 0.0 it is set to 0.0. The azimuth is + a value >= 0.0 and < 2 * M_PI. + + \return Normalized point +*/ +QwtPointPolar QwtPointPolar::normalized() const +{ + const double radius = qMax( d_radius, 0.0 ); + + double azimuth = d_azimuth; + if ( azimuth < -2.0 * M_PI || azimuth >= 2 * M_PI ) + azimuth = ::fmod( d_azimuth, 2 * M_PI ); + + if ( azimuth < 0.0 ) + azimuth += 2 * M_PI; + + return QwtPointPolar( azimuth, radius ); +} + +#ifndef QT_NO_DEBUG_STREAM + +QDebug operator<<( QDebug debug, const QwtPointPolar &point ) +{ + debug.nospace() << "QwtPointPolar(" + << point.azimuth() << "," << point.radius() << ")"; + + return debug.space(); +} + +#endif + diff --git a/libs/qwt/qwt_point_polar.h b/libs/qwt/qwt_point_polar.h new file mode 100644 index 0000000000..2b0a162c5a --- /dev/null +++ b/libs/qwt/qwt_point_polar.h @@ -0,0 +1,201 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +/*! \file */ +#ifndef _QWT_POINT_POLAR_H_ +#define _QWT_POINT_POLAR_H_ 1 + +#include "qwt_global.h" +#include "qwt_math.h" +#include <qpoint.h> +#ifndef QT_NO_DEBUG_STREAM +#include <qdebug.h> +#endif + +/*! + \brief A point in polar coordinates + + In polar coordinates a point is determined by an angle and a distance. + See http://en.wikipedia.org/wiki/Polar_coordinate_system +*/ + +class QWT_EXPORT QwtPointPolar +{ +public: + QwtPointPolar(); + QwtPointPolar( double azimuth, double radius ); + QwtPointPolar( const QwtPointPolar & ); + QwtPointPolar( const QPointF & ); + + void setPoint( const QPointF & ); + QPointF toPoint() const; + + bool isValid() const; + bool isNull() const; + + double radius() const; + double azimuth() const; + + double &rRadius(); + double &rAzimuth(); + + void setRadius( double ); + void setAzimuth( double ); + + bool operator==( const QwtPointPolar & ) const; + bool operator!=( const QwtPointPolar & ) const; + + QwtPointPolar normalized() const; + +private: + double d_azimuth; + double d_radius; +}; + +/*! + Constructs a null point, with a radius and azimuth set to 0.0. + \sa QPointF::isNull() +*/ +inline QwtPointPolar::QwtPointPolar(): + d_azimuth( 0.0 ), + d_radius( 0.0 ) +{ +} + +/*! + Constructs a point with coordinates specified by radius and azimuth. + + \param azimuth Azimuth + \param radius Radius +*/ +inline QwtPointPolar::QwtPointPolar( double azimuth, double radius ): + d_azimuth( azimuth ), + d_radius( radius ) +{ +} + +/*! + Constructs a point using the values of the point specified. + \param other Other point +*/ +inline QwtPointPolar::QwtPointPolar( const QwtPointPolar &other ): + d_azimuth( other.d_azimuth ), + d_radius( other.d_radius ) +{ +} + +//! Returns true if radius() >= 0.0 +inline bool QwtPointPolar::isValid() const +{ + return d_radius >= 0.0; +} + +//! Returns true if radius() >= 0.0 +inline bool QwtPointPolar::isNull() const +{ + return d_radius == 0.0; +} + +//! Returns the radius. +inline double QwtPointPolar::radius() const +{ + return d_radius; +} + +//! Returns the azimuth. +inline double QwtPointPolar::azimuth() const +{ + return d_azimuth; +} + +//! Returns the radius. +inline double &QwtPointPolar::rRadius() +{ + return d_radius; +} + +//! Returns the azimuth. +inline double &QwtPointPolar::rAzimuth() +{ + return d_azimuth; +} + +//! Sets the radius to radius. +inline void QwtPointPolar::setRadius( double radius ) +{ + d_radius = radius; +} + +//! Sets the atimuth to atimuth. +inline void QwtPointPolar::setAzimuth( double azimuth ) +{ + d_azimuth = azimuth; +} + +#ifndef QT_NO_DEBUG_STREAM +QWT_EXPORT QDebug operator<<( QDebug, const QwtPointPolar & ); +#endif + +inline QPoint qwtPolar2Pos( const QPoint &pole, + double radius, double angle ) +{ + const double x = pole.x() + radius * qCos( angle ); + const double y = pole.y() - radius * qSin( angle ); + + return QPoint( qRound( x ), qRound( y ) ); +} + +inline QPoint qwtDegree2Pos( const QPoint &pole, + double radius, double angle ) +{ + return qwtPolar2Pos( pole, radius, angle / 180.0 * M_PI ); +} + +inline QPointF qwtPolar2Pos( const QPointF &pole, + double radius, double angle ) +{ + const double x = pole.x() + radius * qCos( angle ); + const double y = pole.y() - radius * qSin( angle ); + + return QPointF( x, y); +} + +inline QPointF qwtDegree2Pos( const QPointF &pole, + double radius, double angle ) +{ + return qwtPolar2Pos( pole, radius, angle / 180.0 * M_PI ); +} + +inline QPointF qwtFastPolar2Pos( const QPointF &pole, + double radius, double angle ) +{ +#if QT_VERSION < 0x040601 + const double x = pole.x() + radius * ::cos( angle ); + const double y = pole.y() - radius * ::sin( angle ); +#else + const double x = pole.x() + radius * qFastCos( angle ); + const double y = pole.y() - radius * qFastSin( angle ); +#endif + + return QPointF( x, y); +} + +inline QPointF qwtFastDegree2Pos( const QPointF &pole, + double radius, double angle ) +{ + return qwtFastPolar2Pos( pole, radius, angle / 180.0 * M_PI ); +} + +inline QwtPointPolar qwtFastPos2Polar( const QPointF &pos ) +{ + return QwtPointPolar( qwtFastAtan2( pos.y(), pos.x() ), + qSqrt( qwtSqr( pos.x() ) + qwtSqr( pos.y() ) ) ); +} + +#endif diff --git a/libs/qwt/qwt_raster_data.cpp b/libs/qwt/qwt_raster_data.cpp index a7fbf7953d..9ea11cb7b3 100644 --- a/libs/qwt/qwt_raster_data.cpp +++ b/libs/qwt/qwt_raster_data.cpp @@ -8,77 +8,40 @@ *****************************************************************************/ #include "qwt_raster_data.h" - -class QwtRasterData::Contour3DPoint -{ -public: - inline void setPos(double x, double y) { - d_x = x; - d_y = y; - } - - inline QwtDoublePoint pos() const { - return QwtDoublePoint(d_x, d_y); - } - - inline void setX(double x) { - d_x = x; - } - inline void setY(double y) { - d_y = y; - } - inline void setZ(double z) { - d_z = z; - } - - inline double x() const { - return d_x; - } - inline double y() const { - return d_y; - } - inline double z() const { - return d_z; - } - -private: - double d_x; - double d_y; - double d_z; -}; +#include "qwt_point_3d.h" +#include <qnumeric.h> class QwtRasterData::ContourPlane { public: - inline ContourPlane(double z): - d_z(z) { + inline ContourPlane( double z ): + d_z( z ) + { } - inline bool intersect(const Contour3DPoint vertex[3], - QwtDoublePoint line[2], bool ignoreOnPlane) const; + inline bool intersect( const QwtPoint3D vertex[3], + QPointF line[2], bool ignoreOnPlane ) const; - inline double z() const { - return d_z; - } + inline double z() const { return d_z; } private: - inline int compare(double z) const; - inline QwtDoublePoint intersection( - const Contour3DPoint& p1, const Contour3DPoint &p2) const; + inline int compare( double z ) const; + inline QPointF intersection( + const QwtPoint3D& p1, const QwtPoint3D &p2 ) const; double d_z; }; inline bool QwtRasterData::ContourPlane::intersect( - const Contour3DPoint vertex[3], QwtDoublePoint line[2], - bool ignoreOnPlane) const + const QwtPoint3D vertex[3], QPointF line[2], + bool ignoreOnPlane ) const { bool found = true; // Are the vertices below (-1), on (0) or above (1) the plan ? - const int eq1 = compare(vertex[0].z()); - const int eq2 = compare(vertex[1].z()); - const int eq3 = compare(vertex[2].z()); + const int eq1 = compare( vertex[0].z() ); + const int eq2 = compare( vertex[1].z() ); + const int eq3 = compare( vertex[2].z() ); /* (a) All the vertices lie below the contour level. @@ -93,7 +56,8 @@ inline bool QwtRasterData::ContourPlane::intersect( (j) All the vertices lie above the contour level. */ - static const int tab[3][3][3] = { + static const int tab[3][3][3] = + { // jump table to avoid nested case statements { { 0, 0, 8 }, { 0, 2, 5 }, { 7, 6, 9 } }, { { 0, 3, 4 }, { 1, 10, 1 }, { 4, 3, 0 } }, @@ -101,134 +65,138 @@ inline bool QwtRasterData::ContourPlane::intersect( }; const int edgeType = tab[eq1+1][eq2+1][eq3+1]; - switch (edgeType) { - case 1: - // d(0,0,-1), h(0,0,1) - line[0] = vertex[0].pos(); - line[1] = vertex[1].pos(); - break; - case 2: - // d(-1,0,0), h(1,0,0) - line[0] = vertex[1].pos(); - line[1] = vertex[2].pos(); - break; - case 3: - // d(0,-1,0), h(0,1,0) - line[0] = vertex[2].pos(); - line[1] = vertex[0].pos(); - break; - case 4: - // e(0,-1,1), e(0,1,-1) - line[0] = vertex[0].pos(); - line[1] = intersection(vertex[1], vertex[2]); - break; - case 5: - // e(-1,0,1), e(1,0,-1) - line[0] = vertex[1].pos(); - line[1] = intersection(vertex[2], vertex[0]); - break; - case 6: - // e(-1,1,0), e(1,0,-1) - line[0] = vertex[1].pos(); - line[1] = intersection(vertex[0], vertex[1]); - break; - case 7: - // c(-1,1,-1), f(1,1,-1) - line[0] = intersection(vertex[0], vertex[1]); - line[1] = intersection(vertex[1], vertex[2]); - break; - case 8: - // c(-1,-1,1), f(1,1,-1) - line[0] = intersection(vertex[1], vertex[2]); - line[1] = intersection(vertex[2], vertex[0]); - break; - case 9: - // f(-1,1,1), c(1,-1,-1) - line[0] = intersection(vertex[2], vertex[0]); - line[1] = intersection(vertex[0], vertex[1]); - break; - case 10: - // g(0,0,0) - // The CONREC algorithm has no satisfying solution for - // what to do, when all vertices are on the plane. - - if ( ignoreOnPlane ) + switch ( edgeType ) + { + case 1: + // d(0,0,-1), h(0,0,1) + line[0] = vertex[0].toPoint(); + line[1] = vertex[1].toPoint(); + break; + case 2: + // d(-1,0,0), h(1,0,0) + line[0] = vertex[1].toPoint(); + line[1] = vertex[2].toPoint(); + break; + case 3: + // d(0,-1,0), h(0,1,0) + line[0] = vertex[2].toPoint(); + line[1] = vertex[0].toPoint(); + break; + case 4: + // e(0,-1,1), e(0,1,-1) + line[0] = vertex[0].toPoint(); + line[1] = intersection( vertex[1], vertex[2] ); + break; + case 5: + // e(-1,0,1), e(1,0,-1) + line[0] = vertex[1].toPoint(); + line[1] = intersection( vertex[2], vertex[0] ); + break; + case 6: + // e(-1,1,0), e(1,0,-1) + line[0] = vertex[2].toPoint(); + line[1] = intersection( vertex[0], vertex[1] ); + break; + case 7: + // c(-1,1,-1), f(1,1,-1) + line[0] = intersection( vertex[0], vertex[1] ); + line[1] = intersection( vertex[1], vertex[2] ); + break; + case 8: + // c(-1,-1,1), f(1,1,-1) + line[0] = intersection( vertex[1], vertex[2] ); + line[1] = intersection( vertex[2], vertex[0] ); + break; + case 9: + // f(-1,1,1), c(1,-1,-1) + line[0] = intersection( vertex[2], vertex[0] ); + line[1] = intersection( vertex[0], vertex[1] ); + break; + case 10: + // g(0,0,0) + // The CONREC algorithm has no satisfying solution for + // what to do, when all vertices are on the plane. + + if ( ignoreOnPlane ) + found = false; + else + { + line[0] = vertex[2].toPoint(); + line[1] = vertex[0].toPoint(); + } + break; + default: found = false; - else { - line[0] = vertex[2].pos(); - line[1] = vertex[0].pos(); - } - break; - default: - found = false; } return found; } -inline int QwtRasterData::ContourPlane::compare(double z) const +inline int QwtRasterData::ContourPlane::compare( double z ) const { - if (z > d_z) + if ( z > d_z ) return 1; - if (z < d_z) + if ( z < d_z ) return -1; return 0; } -inline QwtDoublePoint QwtRasterData::ContourPlane::intersection( - const Contour3DPoint& p1, const Contour3DPoint &p2) const +inline QPointF QwtRasterData::ContourPlane::intersection( + const QwtPoint3D& p1, const QwtPoint3D &p2 ) const { const double h1 = p1.z() - d_z; const double h2 = p2.z() - d_z; - const double x = (h2 * p1.x() - h1 * p2.x()) / (h2 - h1); - const double y = (h2 * p1.y() - h1 * p2.y()) / (h2 - h1); + const double x = ( h2 * p1.x() - h1 * p2.x() ) / ( h2 - h1 ); + const double y = ( h2 * p1.y() - h1 * p2.y() ) / ( h2 - h1 ); - return QwtDoublePoint(x, y); + return QPointF( x, y ); } +//! Constructor QwtRasterData::QwtRasterData() { } -QwtRasterData::QwtRasterData(const QwtDoubleRect &boundingRect): - d_boundingRect(boundingRect) -{ -} - +//! Destructor QwtRasterData::~QwtRasterData() { } -void QwtRasterData::setBoundingRect(const QwtDoubleRect &boundingRect) -{ - d_boundingRect = boundingRect; -} +/*! + Set the bounding interval for the x, y or z coordinates. -QwtDoubleRect QwtRasterData::boundingRect() const + \param axis Axis + \param interval Bounding interval + + \sa interval() +*/ +void QwtRasterData::setInterval( Qt::Axis axis, const QwtInterval &interval ) { - return d_boundingRect; + d_intervals[axis] = interval; } /*! \brief Initialize a raster - Before the composition of an image QwtPlotSpectrogram calls initRaster, + Before the composition of an image QwtPlotSpectrogram calls initRaster(), announcing the area and its resolution that will be requested. The default implementation does nothing, but for data sets that - are stored in files, it might be good idea to reimplement initRaster, + are stored in files, it might be good idea to reimplement initRaster(), where the data is resampled and loaded into memory. - \param rect Area of the raster + \param area Area of the raster \param raster Number of horizontal and vertical pixels \sa initRaster(), value() */ -void QwtRasterData::initRaster(const QwtDoubleRect &, const QSize&) +void QwtRasterData::initRaster( const QRectF &area, const QSize &raster ) { + Q_UNUSED( area ); + Q_UNUSED( raster ); } /*! @@ -246,43 +214,53 @@ void QwtRasterData::discardRaster() } /*! - \brief Find the raster of the data for an area + \brief Pixel hint - The resolution is the number of horizontal and vertical pixels - that the data can return for an area. An invalid resolution - indicates that the data can return values for any detail level. + pixelHint() returns the geometry of a pixel, that can be used + to calculate the resolution and alignment of the plot item, that is + representing the data. + + Width and height of the hint need to be the horizontal + and vertical distances between 2 neighbored points. + The center of the hint has to be the position of any point + ( it doesn't matter which one ). - The resolution will limit the size of the image that is rendered - from the data. F.e. this might be important when printing a spectrogram - to a A0 printer with 600 dpi. + An empty hint indicates, that there are values for any detail level. - The default implementation returns an invalid resolution (size) + Limiting the resolution of the image might significantly improve + the performance and heavily reduce the amount of memory when rendering + a QImage from the raster data. - \param rect In most implementations the resolution of the data doesn't - depend on the requested rectangle. + The default implementation returns an empty rectangle recommending + to render in target device ( f.e. screen ) resolution. - \return Resolution, as number of horizontal and vertical pixels + \param area In most implementations the resolution of the data doesn't + depend on the requested area. + + \return Bounding rectangle of a pixel */ -QSize QwtRasterData::rasterHint(const QwtDoubleRect &) const +QRectF QwtRasterData::pixelHint( const QRectF &area ) const { - return QSize(); // use screen resolution + Q_UNUSED( area ); + return QRectF(); } /*! Calculate contour lines + \param rect Bounding rectangle for the contour lines + \param raster Number of data pixels of the raster data + \param levels List of limits, where to insert contour lines + \param flags Flags to customize the contouring algorithm + + \return Calculated contour lines + An adaption of CONREC, a simple contouring algorithm. http://local.wasp.uwa.edu.au/~pbourke/papers/conrec/ */ -#if QT_VERSION >= 0x040000 QwtRasterData::ContourLines QwtRasterData::contourLines( - const QwtDoubleRect &rect, const QSize &raster, - const QList<double> &levels, int flags) const -#else -QwtRasterData::ContourLines QwtRasterData::contourLines( - const QwtDoubleRect &rect, const QSize &raster, - const QValueList<double> &levels, int flags) const -#endif + const QRectF &rect, const QSize &raster, + const QList<double> &levels, ConrecFlags flags ) const { ContourLines contourLines; @@ -295,15 +273,18 @@ QwtRasterData::ContourLines QwtRasterData::contourLines( const bool ignoreOnPlane = flags & QwtRasterData::IgnoreAllVerticesOnLevel; - const QwtDoubleInterval range = this->range(); + const QwtInterval range = interval( Qt::ZAxis ); bool ignoreOutOfRange = false; if ( range.isValid() ) ignoreOutOfRange = flags & IgnoreOutOfRange; - ((QwtRasterData*)this)->initRaster(rect, raster); + QwtRasterData *that = const_cast<QwtRasterData *>( this ); + that->initRaster( rect, raster ); - for ( int y = 0; y < raster.height() - 1; y++ ) { - enum Position { + for ( int y = 0; y < raster.height() - 1; y++ ) + { + enum Position + { Center, TopLeft, @@ -314,41 +295,48 @@ QwtRasterData::ContourLines QwtRasterData::contourLines( NumPositions }; - Contour3DPoint xy[NumPositions]; + QwtPoint3D xy[NumPositions]; - for ( int x = 0; x < raster.width() - 1; x++ ) { - const QwtDoublePoint pos(rect.x() + x * dx, rect.y() + y * dy); + for ( int x = 0; x < raster.width() - 1; x++ ) + { + const QPointF pos( rect.x() + x * dx, rect.y() + y * dy ); - if ( x == 0 ) { - xy[TopRight].setPos(pos.x(), pos.y()); + if ( x == 0 ) + { + xy[TopRight].setX( pos.x() ); + xy[TopRight].setY( pos.y() ); xy[TopRight].setZ( - value( xy[TopRight].x(), xy[TopRight].y()) + value( xy[TopRight].x(), xy[TopRight].y() ) ); - xy[BottomRight].setPos(pos.x(), pos.y() + dy); + xy[BottomRight].setX( pos.x() ); + xy[BottomRight].setY( pos.y() + dy ); xy[BottomRight].setZ( - value(xy[BottomRight].x(), xy[BottomRight].y()) + value( xy[BottomRight].x(), xy[BottomRight].y() ) ); } xy[TopLeft] = xy[TopRight]; xy[BottomLeft] = xy[BottomRight]; - xy[TopRight].setPos(pos.x() + dx, pos.y()); - xy[BottomRight].setPos(pos.x() + dx, pos.y() + dy); + xy[TopRight].setX( pos.x() + dx ); + xy[TopRight].setY( pos.y() ); + xy[BottomRight].setX( pos.x() + dx ); + xy[BottomRight].setY( pos.y() + dy ); xy[TopRight].setZ( - value(xy[TopRight].x(), xy[TopRight].y()) + value( xy[TopRight].x(), xy[TopRight].y() ) ); xy[BottomRight].setZ( - value(xy[BottomRight].x(), xy[BottomRight].y()) + value( xy[BottomRight].x(), xy[BottomRight].y() ) ); double zMin = xy[TopLeft].z(); double zMax = zMin; double zSum = zMin; - for ( int i = TopRight; i <= BottomLeft; i++ ) { + for ( int i = TopRight; i <= BottomLeft; i++ ) + { const double z = xy[i].z(); zSum += z; @@ -358,58 +346,59 @@ QwtRasterData::ContourLines QwtRasterData::contourLines( zMax = z; } - if ( ignoreOutOfRange ) { - if ( !range.contains(zMin) || !range.contains(zMax) ) + if ( qIsNaN( zSum ) ) + { + // one of the points is NaN + continue; + } + + if ( ignoreOutOfRange ) + { + if ( !range.contains( zMin ) || !range.contains( zMax ) ) continue; } if ( zMax < levels[0] || - zMin > levels[levels.size() - 1] ) { + zMin > levels[levels.size() - 1] ) + { continue; } - xy[Center].setPos(pos.x() + 0.5 * dx, pos.y() + 0.5 * dy); - xy[Center].setZ(0.25 * zSum); - const int numLevels = (int)levels.size(); - for (int l = 0; l < numLevels; l++) { + xy[Center].setX( pos.x() + 0.5 * dx ); + xy[Center].setY( pos.y() + 0.5 * dy ); + xy[Center].setZ( 0.25 * zSum ); + + const int numLevels = levels.size(); + for ( int l = 0; l < numLevels; l++ ) + { const double level = levels[l]; if ( level < zMin || level > zMax ) continue; -#if QT_VERSION >= 0x040000 QPolygonF &lines = contourLines[level]; -#else - QwtArray<QwtDoublePoint> &lines = contourLines[level]; -#endif - const ContourPlane plane(level); + const ContourPlane plane( level ); - QwtDoublePoint line[2]; - Contour3DPoint vertex[3]; + QPointF line[2]; + QwtPoint3D vertex[3]; - for (int m = TopLeft; m < NumPositions; m++) { + for ( int m = TopLeft; m < NumPositions; m++ ) + { vertex[0] = xy[m]; vertex[1] = xy[0]; vertex[2] = xy[m != BottomLeft ? m + 1 : TopLeft]; const bool intersects = - plane.intersect(vertex, line, ignoreOnPlane); - if ( intersects ) { -#if QT_VERSION >= 0x040000 + plane.intersect( vertex, line, ignoreOnPlane ); + if ( intersects ) + { lines += line[0]; lines += line[1]; -#else - const int index = lines.size(); - lines.resize(lines.size() + 2, QGArray::SpeedOptim); - - lines[index] = line[0]; - lines[index+1] = line[1]; -#endif } } } } } - ((QwtRasterData*)this)->discardRaster(); + that->discardRaster(); return contourLines; } diff --git a/libs/qwt/qwt_raster_data.h b/libs/qwt/qwt_raster_data.h index 45a5316f5b..f69fa46ab1 100644 --- a/libs/qwt/qwt_raster_data.h +++ b/libs/qwt/qwt_raster_data.h @@ -7,99 +7,89 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_RASTER_DATA_H #define QWT_RASTER_DATA_H 1 -#include <qmap.h> #include "qwt_global.h" -#include "qwt_double_rect.h" -#include "qwt_double_interval.h" - -#if QT_VERSION >= 0x040000 +#include "qwt_interval.h" +#include <qmap.h> #include <qlist.h> -#include <QPolygonF> - -#if defined(QWT_TEMPLATEDLL) -// MOC_SKIP_BEGIN -template class QWT_EXPORT QMap<double, QPolygonF>; -// MOC_SKIP_END -#endif - -#else -#include <qvaluelist.h> -#include "qwt_array.h" -#include "qwt_double_rect.h" -#if defined(QWT_TEMPLATEDLL) -// MOC_SKIP_BEGIN -#ifndef QWTARRAY_TEMPLATE_QWTDOUBLEPOINT // by mjo3 -#define QWTARRAY_TEMPLATE_QWTDOUBLEPOINT -template class QWT_EXPORT QwtArray<QwtDoublePoint>; -#endif //end of QWTARRAY_TEMPLATE_QWTDOUBLEPOINT -#ifndef QMAP_TEMPLATE_DOUBLE_QWTDOUBLEPOINT // by mjo3 -#define QMAP_TEMPLATE_DOUBLE_QWTDOUBLEPOINT -template class QWT_EXPORT QMap<double, QwtArray<QwtDoublePoint> >; -#endif //end of QMAP_TEMPLATE_QWTDOUBLEPOINT -// MOC_SKIP_END -#endif -#endif +#include <qpolygon.h> class QwtScaleMap; /*! \brief QwtRasterData defines an interface to any type of raster data. + + QwtRasterData is an abstract interface, that is used by + QwtPlotRasterItem to find the values at the pixels of its raster. + + Often a raster item is used to display values from a matrix. Then the + derived raster data class needs to implement some sort of resampling, + that maps the raster of the matrix into the requested raster of + the raster item ( depending on resolution and scales of the canvas ). */ class QWT_EXPORT QwtRasterData { public: -#if QT_VERSION >= 0x040000 + //! Contour lines typedef QMap<double, QPolygonF> ContourLines; -#else - typedef QMap<double, QwtArray<QwtDoublePoint> > ContourLines; -#endif - enum ConrecAttribute { - IgnoreAllVerticesOnLevel = 1, - IgnoreOutOfRange = 2 + //! Flags to modify the contour algorithm + enum ConrecFlag + { + //! Ignore all vertices on the same level + IgnoreAllVerticesOnLevel = 0x01, + + //! Ignore all values, that are out of range + IgnoreOutOfRange = 0x02 }; + //! Flags to modify the contour algorithm + typedef QFlags<ConrecFlag> ConrecFlags; + QwtRasterData(); - QwtRasterData(const QwtDoubleRect &); virtual ~QwtRasterData(); - //! Clone the data - virtual QwtRasterData *copy() const = 0; - - virtual void setBoundingRect(const QwtDoubleRect &); - QwtDoubleRect boundingRect() const; + virtual void setInterval( Qt::Axis, const QwtInterval & ); + const QwtInterval &interval(Qt::Axis) const; - virtual QSize rasterHint(const QwtDoubleRect &) const; + virtual QRectF pixelHint( const QRectF & ) const; - virtual void initRaster(const QwtDoubleRect &, const QSize& raster); + virtual void initRaster( const QRectF &, const QSize& raster ); virtual void discardRaster(); - //! \return the value at a raster position - virtual double value(double x, double y) const = 0; + /*! + \return the value at a raster position + \param x X value in plot coordinates + \param y Y value in plot coordinates + */ + virtual double value( double x, double y ) const = 0; - //! \return the range of the values - virtual QwtDoubleInterval range() const = 0; - -#if QT_VERSION >= 0x040000 - virtual ContourLines contourLines(const QwtDoubleRect &rect, - const QSize &raster, const QList<double> &levels, - int flags) const; -#else - virtual ContourLines contourLines(const QwtDoubleRect &rect, - const QSize &raster, const QValueList<double> &levels, - int flags) const; -#endif + virtual ContourLines contourLines( const QRectF &rect, + const QSize &raster, const QList<double> &levels, + ConrecFlags ) const; class Contour3DPoint; class ContourPlane; private: - QwtDoubleRect d_boundingRect; + // Disabled copy constructor and operator= + QwtRasterData( const QwtRasterData & ); + QwtRasterData &operator=( const QwtRasterData & ); + + QwtInterval d_intervals[3]; }; +/*! + \return Bounding interval for a axis + \sa setInterval +*/ +inline const QwtInterval &QwtRasterData::interval( Qt::Axis axis) const +{ + return d_intervals[axis]; +} + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtRasterData::ConrecFlags ) + #endif diff --git a/libs/qwt/qwt_round_scale_draw.cpp b/libs/qwt/qwt_round_scale_draw.cpp index dba8f3b740..17a116f529 100644 --- a/libs/qwt/qwt_round_scale_draw.cpp +++ b/libs/qwt/qwt_round_scale_draw.cpp @@ -7,32 +7,32 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <math.h> -#include <qpen.h> -#include <qpainter.h> -#include <qfontmetrics.h> +#include "qwt_round_scale_draw.h" #include "qwt_painter.h" #include "qwt_scale_div.h" #include "qwt_scale_map.h" -#include "qwt_round_scale_draw.h" +#include "qwt_math.h" +#include <qpen.h> +#include <qpainter.h> +#include <qfontmetrics.h> +#include <qmath.h> class QwtRoundScaleDraw::PrivateData { public: PrivateData(): - center(50, 50), - radius(50), - startAngle(-135 * 16), - endAngle(135 * 16) { + center( 50.0, 50.0 ), + radius( 50.0 ), + startAngle( -135.0 ), + endAngle( 135.0 ) + { } - QPoint center; - int radius; + QPointF center; + double radius; - int startAngle; - int endAngle; + double startAngle; + double endAngle; }; /*! @@ -46,41 +46,25 @@ QwtRoundScaleDraw::QwtRoundScaleDraw() { d_data = new QwtRoundScaleDraw::PrivateData; - setRadius(50); - scaleMap().setPaintInterval(d_data->startAngle, d_data->endAngle); + setRadius( 50 ); + scaleMap().setPaintInterval( d_data->startAngle, d_data->endAngle ); } -//! Copy constructor -QwtRoundScaleDraw::QwtRoundScaleDraw(const QwtRoundScaleDraw &other): - QwtAbstractScaleDraw(other) -{ - d_data = new QwtRoundScaleDraw::PrivateData(*other.d_data); -} - - //! Destructor QwtRoundScaleDraw::~QwtRoundScaleDraw() { delete d_data; } -//! Assignment operator -QwtRoundScaleDraw &QwtRoundScaleDraw::operator=(const QwtRoundScaleDraw &other) -{ - *(QwtAbstractScaleDraw*)this = (const QwtAbstractScaleDraw &)other; - *d_data = *other.d_data; - return *this; -} - /*! Change of radius the scale Radius is the radius of the backbone without ticks and labels. \param radius New Radius - \sa moveCenter + \sa moveCenter() */ -void QwtRoundScaleDraw::setRadius(int radius) +void QwtRoundScaleDraw::setRadius( double radius ) { d_data->radius = radius; } @@ -90,9 +74,10 @@ void QwtRoundScaleDraw::setRadius(int radius) Radius is the radius of the backbone without ticks and labels. + \return Radius of the scale \sa setRadius(), extent() */ -int QwtRoundScaleDraw::radius() const +double QwtRoundScaleDraw::radius() const { return d_data->radius; } @@ -101,15 +86,15 @@ int QwtRoundScaleDraw::radius() const Move the center of the scale draw, leaving the radius unchanged \param center New center - \sa setRadius + \sa setRadius() */ -void QwtRoundScaleDraw::moveCenter(const QPoint ¢er) +void QwtRoundScaleDraw::moveCenter( const QPointF ¢er ) { d_data->center = center; } //! Get the center of the scale -QPoint QwtRoundScaleDraw::center() const +QPointF QwtRoundScaleDraw::center() const { return d_data->center; } @@ -126,25 +111,28 @@ QPoint QwtRoundScaleDraw::center() const \warning <ul> <li>The angle range is limited to [-360, 360] degrees. Angles exceeding this range will be clipped. - <li>For angles more than 359 degrees above or below min(angle1, angle2), + <li>For angles more or equal than 360 degrees above or below min(angle1, angle2), scale marks will not be drawn. - <li>If you need a counterclockwise scale, use QwtScaleDiv::setRange + <li>If you need a counterclockwise scale, use QwtScaleDiv::setInterval() </ul> */ -void QwtRoundScaleDraw::setAngleRange(double angle1, double angle2) +void QwtRoundScaleDraw::setAngleRange( double angle1, double angle2 ) { - angle1 = qwtLim(angle1, -360.0, 360.0); - angle2 = qwtLim(angle2, -360.0, 360.0); +#if 0 + angle1 = qBound( -360.0, angle1, 360.0 ); + angle2 = qBound( -360.0, angle2, 360.0 ); +#endif - d_data->startAngle = qRound(angle1 * 16.0); - d_data->endAngle = qRound(angle2 * 16.0); + d_data->startAngle = angle1; + d_data->endAngle = angle2; - if (d_data->startAngle == d_data->endAngle) { + if ( d_data->startAngle == d_data->endAngle ) + { d_data->startAngle -= 1; d_data->endAngle += 1; } - scaleMap().setPaintInterval(d_data->startAngle, d_data->endAngle); + scaleMap().setPaintInterval( d_data->startAngle, d_data->endAngle ); } /*! @@ -155,38 +143,40 @@ void QwtRoundScaleDraw::setAngleRange(double angle1, double angle2) \sa drawTick(), drawBackbone() */ -void QwtRoundScaleDraw::drawLabel(QPainter *painter, double value) const +void QwtRoundScaleDraw::drawLabel( QPainter *painter, double value ) const { - const QwtText label = tickLabel(painter->font(), value); + const QwtText label = tickLabel( painter->font(), value ); if ( label.isEmpty() ) return; - const int tval = map().transform(value); - if ((tval > d_data->startAngle + 359 * 16) - || (tval < d_data->startAngle - 359 * 16)) { + const double tval = scaleMap().transform( value ); + if ( ( tval >= d_data->startAngle + 360.0 ) + || ( tval <= d_data->startAngle - 360.0 ) ) + { return; } double radius = d_data->radius; - if ( hasComponent(QwtAbstractScaleDraw::Ticks) || - hasComponent(QwtAbstractScaleDraw::Backbone) ) { + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) || + hasComponent( QwtAbstractScaleDraw::Backbone ) ) + { radius += spacing(); } - if ( hasComponent(QwtAbstractScaleDraw::Ticks) ) - radius += majTickLength(); + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) + radius += tickLength( QwtScaleDiv::MajorTick ); - const QSize sz = label.textSize(painter->font()); - const double arc = tval / 16.0 / 360.0 * 2 * M_PI; + const QSizeF sz = label.textSize( painter->font() ); + const double arc = qwtRadians( tval ); - const int x = d_data->center.x() + - qRound((radius + sz.width() / 2.0) * sin(arc)); - const int y = d_data->center.y() - - qRound( (radius + sz.height() / 2.0) * cos(arc)); + const double x = d_data->center.x() + + ( radius + sz.width() / 2.0 ) * qSin( arc ); + const double y = d_data->center.y() - + ( radius + sz.height() / 2.0 ) * qCos( arc ); - const QRect r(x - sz.width() / 2, y - sz.height() / 2, - sz.width(), sz.height() ); - label.draw(painter, r); + const QRectF r( x - sz.width() / 2, y - sz.height() / 2, + sz.width(), sz.height() ); + label.draw( painter, r ); } /*! @@ -198,30 +188,31 @@ void QwtRoundScaleDraw::drawLabel(QPainter *painter, double value) const \sa drawBackbone(), drawLabel() */ -void QwtRoundScaleDraw::drawTick(QPainter *painter, double value, int len) const +void QwtRoundScaleDraw::drawTick( QPainter *painter, double value, double len ) const { if ( len <= 0 ) return; - const int tval = map().transform(value); + const double tval = scaleMap().transform( value ); - const int cx = d_data->center.x(); - const int cy = d_data->center.y(); - const int radius = d_data->radius; + const double cx = d_data->center.x(); + const double cy = d_data->center.y(); + const double radius = d_data->radius; - if ((tval <= d_data->startAngle + 359 * 16) - || (tval >= d_data->startAngle - 359 * 16)) { - const double arc = double(tval) / 16.0 * M_PI / 180.0; + if ( ( tval < d_data->startAngle + 360.0 ) + || ( tval > d_data->startAngle - 360.0 ) ) + { + const double arc = qwtRadians( tval ); - const double sinArc = sin(arc); - const double cosArc = cos(arc); + const double sinArc = qSin( arc ); + const double cosArc = qCos( arc ); - const int x1 = qRound( cx + radius * sinArc ); - const int x2 = qRound( cx + (radius + len) * sinArc ); - const int y1 = qRound( cy - radius * cosArc ); - const int y2 = qRound( cy - (radius + len) * cosArc ); + const double x1 = cx + radius * sinArc; + const double x2 = cx + ( radius + len ) * sinArc; + const double y1 = cy - radius * cosArc; + const double y2 = cy - ( radius + len ) * cosArc; - QwtPainter::drawLine(painter, x1, y1, x2, y2); + QwtPainter::drawLine( painter, x1, y1, x2, y2 ); } } @@ -231,84 +222,93 @@ void QwtRoundScaleDraw::drawTick(QPainter *painter, double value, int len) const \sa drawTick(), drawLabel() */ -void QwtRoundScaleDraw::drawBackbone(QPainter *painter) const +void QwtRoundScaleDraw::drawBackbone( QPainter *painter ) const { - const int a1 = qRound(qwtMin(map().p1(), map().p2()) - 90 * 16); - const int a2 = qRound(qwtMax(map().p1(), map().p2()) - 90 * 16); + const double deg1 = scaleMap().p1(); + const double deg2 = scaleMap().p2(); + + const int a1 = qRound( qMin( deg1, deg2 ) - 90 ); + const int a2 = qRound( qMax( deg1, deg2 ) - 90 ); - const int radius = d_data->radius; - const int x = d_data->center.x() - radius; - const int y = d_data->center.y() - radius; + const double radius = d_data->radius; + const double x = d_data->center.x() - radius; + const double y = d_data->center.y() - radius; - painter->drawArc(x, y, 2 * radius, 2 * radius, - -a2, a2 - a1 + 1); // counterclockwise + painter->drawArc( QRectF( x, y, 2 * radius, 2 * radius ), + -a2 * 16, ( a2 - a1 + 1 ) * 16 ); // counterclockwise } /*! Calculate the extent of the scale - The extent is the distcance between the baseline to the outermost + The extent is the distance between the baseline to the outermost pixel of the scale draw. radius() + extent() is an upper limit for the radius of the bounding circle. - \param pen Pen that is used for painting backbone and ticks \param font Font used for painting the labels + \return Calculated extent \sa setMinimumExtent(), minimumExtent() - \warning The implemented algo is not too smart and + \warning The implemented algorithm is not too smart and calculates only an upper limit, that might be a few pixels too large */ -int QwtRoundScaleDraw::extent(const QPen &pen, const QFont &font) const +double QwtRoundScaleDraw::extent( const QFont &font ) const { - int d = 0; + double d = 0.0; - if ( hasComponent(QwtAbstractScaleDraw::Labels) ) { + if ( hasComponent( QwtAbstractScaleDraw::Labels ) ) + { const QwtScaleDiv &sd = scaleDiv(); - const QwtValueList &ticks = sd.ticks(QwtScaleDiv::MajorTick); - for (uint i = 0; i < (uint)ticks.count(); i++) { + const QList<double> &ticks = sd.ticks( QwtScaleDiv::MajorTick ); + for ( int i = 0; i < ticks.count(); i++ ) + { const double value = ticks[i]; - if ( !sd.contains(value) ) + if ( !sd.contains( value ) ) continue; - const QwtText label = tickLabel(font, value); + const QwtText label = tickLabel( font, value ); if ( label.isEmpty() ) continue; - const int tval = map().transform(value); - if ((tval < d_data->startAngle + 360 * 16) - && (tval > d_data->startAngle - 360 * 16)) { - const double arc = tval / 16.0 / 360.0 * 2 * M_PI; + const double tval = scaleMap().transform( value ); + if ( ( tval < d_data->startAngle + 360 ) + && ( tval > d_data->startAngle - 360 ) ) + { + const double arc = qwtRadians( tval ); - const QSize sz = label.textSize(font); - const double off = qwtMax(sz.width(), sz.height()); + const QSizeF sz = label.textSize( font ); + const double off = qMax( sz.width(), sz.height() ); - double x = off * sin(arc); - double y = off * cos(arc); + double x = off * qSin( arc ); + double y = off * qCos( arc ); - const int dist = (int)ceil(sqrt(x * x + y * y) + 1 ); + const double dist = qSqrt( x * x + y * y ); if ( dist > d ) d = dist; } } } - if ( hasComponent(QwtAbstractScaleDraw::Ticks) ) { - d += majTickLength(); + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) + { + d += maxTickLength(); } - if ( hasComponent(QwtAbstractScaleDraw::Backbone) ) { - const int pw = qwtMax( 1, pen.width() ); // penwidth can be zero + if ( hasComponent( QwtAbstractScaleDraw::Backbone ) ) + { + const double pw = qMax( 1, penWidth() ); // pen width can be zero d += pw; } - if ( hasComponent(QwtAbstractScaleDraw::Labels) && - ( hasComponent(QwtAbstractScaleDraw::Ticks) || - hasComponent(QwtAbstractScaleDraw::Backbone) ) ) { + if ( hasComponent( QwtAbstractScaleDraw::Labels ) && + ( hasComponent( QwtAbstractScaleDraw::Ticks ) || + hasComponent( QwtAbstractScaleDraw::Backbone ) ) ) + { d += spacing(); } - d = qwtMax(d, minimumExtent()); + d = qMax( d, minimumExtent() ); return d; } diff --git a/libs/qwt/qwt_round_scale_draw.h b/libs/qwt/qwt_round_scale_draw.h index 61c52f4c77..54971bbb06 100644 --- a/libs/qwt/qwt_round_scale_draw.h +++ b/libs/qwt/qwt_round_scale_draw.h @@ -10,19 +10,17 @@ #ifndef QWT_ROUND_SCALE_DRAW_H #define QWT_ROUND_SCALE_DRAW_H -#include <qpoint.h> #include "qwt_global.h" #include "qwt_abstract_scale_draw.h" - -class QPen; +#include <qpoint.h> /*! \brief A class for drawing round scales QwtRoundScaleDraw can be used to draw round scales. - The circle segment can be adjusted by QwtRoundScaleDraw::setAngleRange(). + The circle segment can be adjusted by setAngleRange(). The geometry of the scale can be specified with - QwtRoundScaleDraw::moveCenter() and QwtRoundScaleDraw::setRadius(). + moveCenter() and setRadius(). After a scale division has been specified as a QwtScaleDiv object using QwtAbstractScaleDraw::setScaleDiv(const QwtScaleDiv &s), @@ -33,36 +31,36 @@ class QWT_EXPORT QwtRoundScaleDraw: public QwtAbstractScaleDraw { public: QwtRoundScaleDraw(); - QwtRoundScaleDraw(const QwtRoundScaleDraw &); - virtual ~QwtRoundScaleDraw(); - QwtRoundScaleDraw &operator=(const QwtRoundScaleDraw &other); - - void setRadius(int radius); - int radius() const; + void setRadius( double radius ); + double radius() const; - void moveCenter(int x, int y); - void moveCenter(const QPoint &); - QPoint center() const; + void moveCenter( double x, double y ); + void moveCenter( const QPointF & ); + QPointF center() const; - void setAngleRange(double angle1, double angle2); + void setAngleRange( double angle1, double angle2 ); - virtual int extent(const QPen &, const QFont &) const; + virtual double extent( const QFont & ) const; protected: - virtual void drawTick(QPainter *p, double val, int len) const; - virtual void drawBackbone(QPainter *p) const; - virtual void drawLabel(QPainter *p, double val) const; + virtual void drawTick( QPainter *, double val, double len ) const; + virtual void drawBackbone( QPainter * ) const; + virtual void drawLabel( QPainter *, double val ) const; private: + QwtRoundScaleDraw( const QwtRoundScaleDraw & ); + QwtRoundScaleDraw &operator=( const QwtRoundScaleDraw &other ); + class PrivateData; PrivateData *d_data; }; -inline void QwtRoundScaleDraw::moveCenter(int x, int y) +//! Move the center of the scale draw, leaving the radius unchanged +inline void QwtRoundScaleDraw::moveCenter( double x, double y ) { - moveCenter(QPoint(x, y)); + moveCenter( QPointF( x, y ) ); } #endif diff --git a/libs/qwt/qwt_samples.h b/libs/qwt/qwt_samples.h new file mode 100644 index 0000000000..6f9be3d77a --- /dev/null +++ b/libs/qwt/qwt_samples.h @@ -0,0 +1,239 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_SAMPLES_H +#define QWT_SAMPLES_H 1 + +#include "qwt_global.h" +#include "qwt_interval.h" +#include <qvector.h> +#include <qrect.h> + +//! \brief A sample of the types (x1-x2, y) or (x, y1-y2) +class QWT_EXPORT QwtIntervalSample +{ +public: + QwtIntervalSample(); + QwtIntervalSample( double, const QwtInterval & ); + QwtIntervalSample( double value, double min, double max ); + + bool operator==( const QwtIntervalSample & ) const; + bool operator!=( const QwtIntervalSample & ) const; + + //! Value + double value; + + //! Interval + QwtInterval interval; +}; + +/*! + Constructor + The value is set to 0.0, the interval is invalid +*/ +inline QwtIntervalSample::QwtIntervalSample(): + value( 0.0 ) +{ +} + +//! Constructor +inline QwtIntervalSample::QwtIntervalSample( + double v, const QwtInterval &intv ): + value( v ), + interval( intv ) +{ +} + +//! Constructor +inline QwtIntervalSample::QwtIntervalSample( + double v, double min, double max ): + value( v ), + interval( min, max ) +{ +} + +//! Compare operator +inline bool QwtIntervalSample::operator==( + const QwtIntervalSample &other ) const +{ + return value == other.value && interval == other.interval; +} + +//! Compare operator +inline bool QwtIntervalSample::operator!=( + const QwtIntervalSample &other ) const +{ + return !( *this == other ); +} + +//! \brief A sample of the types (x1...xn, y) or (x, y1..yn) +class QWT_EXPORT QwtSetSample +{ +public: + QwtSetSample(); + QwtSetSample( double, const QVector<double> & = QVector<double>() ); + + bool operator==( const QwtSetSample &other ) const; + bool operator!=( const QwtSetSample &other ) const; + + double added() const; + + //! value + double value; + + //! Vector of values associated to value + QVector<double> set; +}; + +/*! + Constructor + The value is set to 0.0 +*/ +inline QwtSetSample::QwtSetSample(): + value( 0.0 ) +{ +} + +/*! + Constructor + + \param v Value + \param s Set of values +*/ +inline QwtSetSample::QwtSetSample( double v, const QVector< double > &s ): + value( v ), + set( s ) +{ +} + +//! Compare operator +inline bool QwtSetSample::operator==( const QwtSetSample &other ) const +{ + return value == other.value && set == other.set; +} + +//! Compare operator +inline bool QwtSetSample::operator!=( const QwtSetSample &other ) const +{ + return !( *this == other ); +} + +//! \return All values of the set added +inline double QwtSetSample::added() const +{ + double y = 0.0; + for ( int i = 0; i < set.size(); i++ ) + y += set[i]; + + return y; +} + +/*! + \brief Open-High-Low-Close sample used in financial charts + + In financial charts the movement of a price in a time interval is often + represented by the opening/closing prices and the lowest/highest prices + in this interval. + + \sa QwtTradingChartData +*/ +class QWT_EXPORT QwtOHLCSample +{ +public: + QwtOHLCSample( double time = 0.0, + double open = 0.0, double high = 0.0, + double low = 0.0, double close = 0.0 ); + + QwtInterval boundingInterval() const; + + bool isValid() const; + + /*! + Time of the sample, usually a number representing + a specific interval - like a day. + */ + double time; + + //! Opening price + double open; + + //! Highest price + double high; + + //! Lowest price + double low; + + //! Closing price + double close; +}; + + +/*! + Constructor + + \param t Time value + \param o Open value + \param h High value + \param l Low value + \param c Close value +*/ +inline QwtOHLCSample::QwtOHLCSample( double t, + double o, double h, double l, double c ): + time( t ), + open( o ), + high( h ), + low( l ), + close( c ) +{ +} + +/*! + \brief Check if a sample is valid + + A sample is valid, when all of the following checks are true: + + - low <= high + - low <= open <= high + - low <= close <= high + + \return True, when the sample is valid + */ +inline bool QwtOHLCSample::isValid() const +{ + return ( low <= high ) + && ( open >= low ) + && ( open <= high ) + && ( close >= low ) + && ( close <= high ); +} + +/*! + \brief Calculate the bounding interval of the OHLC values + + For valid samples the limits of this interval are always low/high. + + \return Bounding interval + \sa isValid() + */ +inline QwtInterval QwtOHLCSample::boundingInterval() const +{ + double minY = open; + minY = qMin( minY, high ); + minY = qMin( minY, low ); + minY = qMin( minY, close ); + + double maxY = open; + maxY = qMax( maxY, high ); + maxY = qMax( maxY, low ); + maxY = qMax( maxY, close ); + + return QwtInterval( minY, maxY ); +} + +#endif diff --git a/libs/qwt/qwt_sampling_thread.cpp b/libs/qwt/qwt_sampling_thread.cpp new file mode 100644 index 0000000000..4cffb3dee3 --- /dev/null +++ b/libs/qwt/qwt_sampling_thread.cpp @@ -0,0 +1,106 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_sampling_thread.h" +#include "qwt_system_clock.h" + +class QwtSamplingThread::PrivateData +{ +public: + QwtSystemClock clock; + + double interval; + bool isStopped; +}; + + +//! Constructor +QwtSamplingThread::QwtSamplingThread( QObject *parent ): + QThread( parent ) +{ + d_data = new PrivateData; + d_data->interval = 1000; // 1 second + d_data->isStopped = true; +} + +//! Destructor +QwtSamplingThread::~QwtSamplingThread() +{ + delete d_data; +} + +/*! + Change the interval (in ms), when sample() is called. + The default interval is 1000.0 ( = 1s ) + + \param interval Interval + \sa interval() +*/ +void QwtSamplingThread::setInterval( double interval ) +{ + if ( interval < 0.0 ) + interval = 0.0; + + d_data->interval = interval; +} + +/*! + \return Interval (in ms), between 2 calls of sample() + \sa setInterval() +*/ +double QwtSamplingThread::interval() const +{ + return d_data->interval; +} + +/*! + \return Time (in ms) since the thread was started + \sa QThread::start(), run() +*/ +double QwtSamplingThread::elapsed() const +{ + if ( d_data->isStopped ) + return 0.0; + + return d_data->clock.elapsed(); +} + +/*! + Terminate the collecting thread + \sa QThread::start(), run() +*/ +void QwtSamplingThread::stop() +{ + d_data->isStopped = true; +} + +/*! + Loop collecting samples started from QThread::start() + \sa stop() +*/ +void QwtSamplingThread::run() +{ + d_data->clock.start(); + d_data->isStopped = false; + + while ( !d_data->isStopped ) + { + const double elapsed = d_data->clock.elapsed(); + sample( elapsed / 1000.0 ); + + if ( d_data->interval > 0.0 ) + { + const double msecs = + d_data->interval - ( d_data->clock.elapsed() - elapsed ); + + if ( msecs > 0.0 ) + usleep( qRound( 1000.0 * msecs ) ); + } + } +} diff --git a/libs/qwt/qwt_sampling_thread.h b/libs/qwt/qwt_sampling_thread.h new file mode 100644 index 0000000000..9b1a9084c7 --- /dev/null +++ b/libs/qwt/qwt_sampling_thread.h @@ -0,0 +1,50 @@ +#ifndef _QWT_SAMPLING_THREAD_H_ +#define _QWT_SAMPLING_THREAD_H_ + +#include "qwt_global.h" +#include <qthread.h> + +/*! + \brief A thread collecting samples at regular intervals. + + Continuous signals are converted into a discrete signal by + collecting samples at regular intervals. A discrete signal + can be displayed by a QwtPlotSeriesItem on a QwtPlot widget. + + QwtSamplingThread starts a thread calling periodically sample(), + to collect and store ( or emit ) a single sample. + + \sa QwtPlotCurve, QwtPlotSeriesItem +*/ +class QWT_EXPORT QwtSamplingThread: public QThread +{ + Q_OBJECT + +public: + virtual ~QwtSamplingThread(); + + double interval() const; + double elapsed() const; + +public Q_SLOTS: + void setInterval( double interval ); + void stop(); + +protected: + explicit QwtSamplingThread( QObject *parent = NULL ); + + virtual void run(); + + /*! + Collect a sample + + \param elapsed Time since the thread was started in milliseconds + */ + virtual void sample( double elapsed ) = 0; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_scale_div.cpp b/libs/qwt/qwt_scale_div.cpp index 836d7d6924..2fd3d3f42f 100644 --- a/libs/qwt/qwt_scale_div.cpp +++ b/libs/qwt/qwt_scale_div.cpp @@ -9,73 +9,173 @@ #include "qwt_scale_div.h" #include "qwt_math.h" -#include "qwt_double_interval.h" +#include <qalgorithms.h> -//! Construct an invalid QwtScaleDiv instance. -QwtScaleDiv::QwtScaleDiv(): - d_lBound(0.0), - d_hBound(0.0), - d_isValid(false) +/*! + Construct a division without ticks + + \param lowerBound First boundary + \param upperBound Second boundary + + \note lowerBound might be greater than upperBound for inverted scales + */ +QwtScaleDiv::QwtScaleDiv( double lowerBound, double upperBound ): + d_lowerBound( lowerBound ), + d_upperBound( upperBound ) { } /*! - Construct QwtScaleDiv instance. + Construct a scale division \param interval Interval \param ticks List of major, medium and minor ticks */ -QwtScaleDiv::QwtScaleDiv( - const QwtDoubleInterval &interval, - QwtValueList ticks[NTickTypes]): - d_lBound(interval.minValue()), - d_hBound(interval.maxValue()), - d_isValid(true) +QwtScaleDiv::QwtScaleDiv( const QwtInterval &interval, + QList<double> ticks[NTickTypes] ): + d_lowerBound( interval.minValue() ), + d_upperBound( interval.maxValue() ) { for ( int i = 0; i < NTickTypes; i++ ) d_ticks[i] = ticks[i]; } /*! - Construct QwtScaleDiv instance. + Construct a scale division - \param lBound First interval limit - \param hBound Second interval limit + \param lowerBound First boundary + \param upperBound Second boundary \param ticks List of major, medium and minor ticks + + \note lowerBound might be greater than upperBound for inverted scales */ -QwtScaleDiv::QwtScaleDiv( - double lBound, double hBound, - QwtValueList ticks[NTickTypes]): - d_lBound(lBound), - d_hBound(hBound), - d_isValid(true) +QwtScaleDiv::QwtScaleDiv( double lowerBound, double upperBound, + QList<double> ticks[NTickTypes] ): + d_lowerBound( lowerBound ), + d_upperBound( upperBound ) { for ( int i = 0; i < NTickTypes; i++ ) d_ticks[i] = ticks[i]; } +/*! + Construct a scale division + + \param lowerBound First boundary + \param upperBound Second boundary + \param minorTicks List of minor ticks + \param mediumTicks List medium ticks + \param majorTicks List of major ticks + + \note lowerBound might be greater than upperBound for inverted scales +*/ +QwtScaleDiv::QwtScaleDiv( double lowerBound, double upperBound, + const QList<double> &minorTicks, + const QList<double> &mediumTicks, + const QList<double> &majorTicks ): + d_lowerBound( lowerBound ), + d_upperBound( upperBound ) +{ + d_ticks[ MinorTick ] = minorTicks; + d_ticks[ MediumTick ] = mediumTicks; + d_ticks[ MajorTick ] = majorTicks; +} + +/*! + Change the interval + + \param lowerBound First boundary + \param upperBound Second boundary + + \note lowerBound might be greater than upperBound for inverted scales +*/ +void QwtScaleDiv::setInterval( double lowerBound, double upperBound ) +{ + d_lowerBound = lowerBound; + d_upperBound = upperBound; +} + /*! Change the interval - \interval Interval + + \param interval Interval +*/ +void QwtScaleDiv::setInterval( const QwtInterval &interval ) +{ + d_lowerBound = interval.minValue(); + d_upperBound = interval.maxValue(); +} + +/*! + \return lowerBound -> upperBound +*/ +QwtInterval QwtScaleDiv::interval() const +{ + return QwtInterval( d_lowerBound, d_upperBound ); +} + +/*! + Set the first boundary + + \param lowerBound First boundary + \sa lowerBiound(), setUpperBound() + */ +void QwtScaleDiv::setLowerBound( double lowerBound ) +{ + d_lowerBound = lowerBound; +} + +/*! + \return First boundary + \sa upperBound() +*/ +double QwtScaleDiv::lowerBound() const +{ + return d_lowerBound; +} + +/*! + Set the second boundary + + \param upperBound Second boundary + \sa upperBound(), setLowerBound() + */ +void QwtScaleDiv::setUpperBound( double upperBound ) +{ + d_upperBound = upperBound; +} + +/*! + \return upper bound + \sa lowerBound() +*/ +double QwtScaleDiv::upperBound() const +{ + return d_upperBound; +} + +/*! + \return upperBound() - lowerBound() */ -void QwtScaleDiv::setInterval(const QwtDoubleInterval &interval) +double QwtScaleDiv::range() const { - setInterval(interval.minValue(), interval.maxValue()); + return d_upperBound - d_lowerBound; } /*! \brief Equality operator \return true if this instance is equal to other */ -int QwtScaleDiv::operator==(const QwtScaleDiv &other) const +bool QwtScaleDiv::operator==( const QwtScaleDiv &other ) const { - if ( d_lBound != other.d_lBound || - d_hBound != other.d_hBound || - d_isValid != other.d_isValid ) { + if ( d_lowerBound != other.d_lowerBound || + d_upperBound != other.d_upperBound ) + { return false; } - for ( int i = 0; i < NTickTypes; i++ ) { + for ( int i = 0; i < NTickTypes; i++ ) + { if ( d_ticks[i] != other.d_ticks[i] ) return false; } @@ -85,67 +185,119 @@ int QwtScaleDiv::operator==(const QwtScaleDiv &other) const /*! \brief Inequality - \return true if this instance is not equal to s + \return true if this instance is not equal to other */ -int QwtScaleDiv::operator!=(const QwtScaleDiv &s) const +bool QwtScaleDiv::operator!=( const QwtScaleDiv &other ) const { - return (!(*this == s)); + return ( !( *this == other ) ); } -//! Invalidate the scale division -void QwtScaleDiv::invalidate() +//! Check if the scale division is empty( lowerBound() == upperBound() ) +bool QwtScaleDiv::isEmpty() const { - d_isValid = false; - - // detach arrays - for ( int i = 0; i < NTickTypes; i++ ) - d_ticks[i].clear(); - - d_lBound = d_hBound = 0; + return ( d_lowerBound == d_upperBound ); } -//! Check if the scale division is valid -bool QwtScaleDiv::isValid() const +//! Check if the scale division is increasing( lowerBound() <= upperBound() ) +bool QwtScaleDiv::isIncreasing() const { - return d_isValid; + return d_lowerBound <= d_upperBound; } -bool QwtScaleDiv::contains(double v) const -{ - if ( !d_isValid ) - return false; +/*! + Return if a value is between lowerBound() and upperBound() - const double min = qwtMin(d_lBound, d_hBound); - const double max = qwtMax(d_lBound, d_hBound); + \param value Value + \return true/false +*/ +bool QwtScaleDiv::contains( double value ) const +{ + const double min = qMin( d_lowerBound, d_upperBound ); + const double max = qMax( d_lowerBound, d_upperBound ); - return v >= min && v <= max; + return value >= min && value <= max; } -//! Invert the scale divison +/*! + Invert the scale division + \sa inverted() + */ void QwtScaleDiv::invert() { - qSwap(d_lBound, d_hBound); + qSwap( d_lowerBound, d_upperBound ); - for ( int i = 0; i < NTickTypes; i++ ) { - QwtValueList& ticks = d_ticks[i]; + for ( int i = 0; i < NTickTypes; i++ ) + { + QList<double>& ticks = d_ticks[i]; const int size = ticks.count(); const int size2 = size / 2; - for (int i=0; i < size2; i++) - qSwap(ticks[i], ticks[size - 1 - i]); + for ( int j = 0; j < size2; j++ ) + qSwap( ticks[j], ticks[size - 1 - j] ); } } +/*! + \return A scale division with inverted boundaries and ticks + \sa invert() + */ +QwtScaleDiv QwtScaleDiv::inverted() const +{ + QwtScaleDiv other = *this; + other.invert(); + + return other; +} + +/*! + Return a scale division with an interval [lowerBound, upperBound] + where all ticks outside this interval are removed + + \param lowerBound Lower bound + \param upperBound Upper bound + + \return Scale division with all ticks inside of the given interval + + \note lowerBound might be greater than upperBound for inverted scales +*/ +QwtScaleDiv QwtScaleDiv::bounded( + double lowerBound, double upperBound ) const +{ + const double min = qMin( lowerBound, upperBound ); + const double max = qMax( lowerBound, upperBound ); + + QwtScaleDiv sd; + sd.setInterval( lowerBound, upperBound ); + + for ( int tickType = 0; tickType < QwtScaleDiv::NTickTypes; tickType++ ) + { + const QList<double> &ticks = d_ticks[ tickType ]; + + QList<double> boundedTicks; + for ( int i = 0; i < ticks.size(); i++ ) + { + const double tick = ticks[i]; + if ( tick >= min && tick <= max ) + boundedTicks += tick; + } + + sd.setTicks( tickType, boundedTicks ); + } + + return sd; + +} + /*! Assign ticks \param type MinorTick, MediumTick or MajorTick \param ticks Values of the tick positions */ -void QwtScaleDiv::setTicks(int type, const QwtValueList &ticks) +void QwtScaleDiv::setTicks( int type, const QList<double> &ticks ) { - if ( type >= 0 || type < NTickTypes ) + if ( type >= 0 && type < NTickTypes ) d_ticks[type] = ticks; } @@ -153,12 +305,27 @@ void QwtScaleDiv::setTicks(int type, const QwtValueList &ticks) Return a list of ticks \param type MinorTick, MediumTick or MajorTick + \return Tick list */ -const QwtValueList &QwtScaleDiv::ticks(int type) const +QList<double> QwtScaleDiv::ticks( int type ) const { - if ( type >= 0 || type < NTickTypes ) + if ( type >= 0 && type < NTickTypes ) return d_ticks[type]; - static QwtValueList noTicks; - return noTicks; + return QList<double>(); +} + +#ifndef QT_NO_DEBUG_STREAM + +QDebug operator<<( QDebug debug, const QwtScaleDiv &scaleDiv ) +{ + debug << scaleDiv.lowerBound() << "<->" << scaleDiv.upperBound(); + debug << "Major: " << scaleDiv.ticks( QwtScaleDiv::MajorTick ); + debug << "Medium: " << scaleDiv.ticks( QwtScaleDiv::MediumTick ); + debug << "Minor: " << scaleDiv.ticks( QwtScaleDiv::MinorTick ); + + return debug; } + +#endif + diff --git a/libs/qwt/qwt_scale_div.h b/libs/qwt/qwt_scale_div.h index dfb9213146..7259e228d4 100644 --- a/libs/qwt/qwt_scale_div.h +++ b/libs/qwt/qwt_scale_div.h @@ -11,112 +11,100 @@ #define QWT_SCALE_DIV_H #include "qwt_global.h" -#include "qwt_valuelist.h" -#include "qwt_double_interval.h" +#include "qwt_interval.h" +#include <qlist.h> -class QwtDoubleInterval; +#ifndef QT_NO_DEBUG_STREAM +#include <qdebug.h> +#endif /*! \brief A class representing a scale division - A scale division consists of its limits and 3 list - of tick values qualified as major, medium and minor ticks. + A Qwt scale is defined by its boundaries and 3 list + for the positions of the major, medium and minor ticks. + + The upperLimit() might be smaller than the lowerLimit() + to indicate inverted scales. - In most cases scale divisions are calculated by a QwtScaleEngine. + Scale divisions can be calculated from a QwtScaleEngine. - \sa QwtScaleEngine::subDivideInto, QwtScaleEngine::subDivide + \sa QwtScaleEngine::divideScale(), QwtPlot::setAxisScaleDiv(), + QwtAbstractSlider::setScaleDiv() */ class QWT_EXPORT QwtScaleDiv { public: - enum TickType { + //! Scale tick types + enum TickType + { + //! No ticks NoTick = -1, + //! Minor ticks MinorTick, + + //! Medium ticks MediumTick, + + //! Major ticks MajorTick, + //! Number of valid tick types NTickTypes }; - explicit QwtScaleDiv(); - explicit QwtScaleDiv(const QwtDoubleInterval &, - QwtValueList[NTickTypes]); - explicit QwtScaleDiv(double lBound, double rBound, - QwtValueList[NTickTypes]); + explicit QwtScaleDiv( double lowerBound = 0.0, + double upperBound = 0.0 ); - int operator==(const QwtScaleDiv &s) const; - int operator!=(const QwtScaleDiv &s) const; + explicit QwtScaleDiv( const QwtInterval &, QList<double>[NTickTypes] ); - void setInterval(double lBound, double rBound); - void setInterval(const QwtDoubleInterval &); - QwtDoubleInterval interval() const; + explicit QwtScaleDiv( double lowerBound, double upperBound, + QList<double>[NTickTypes] ); - inline double lBound() const; - inline double hBound() const; - inline double range() const; + explicit QwtScaleDiv( double lowerBound, double upperBound, + const QList<double> &minorTicks, const QList<double> &mediumTicks, + const QList<double> &majorTicks ); - bool contains(double v) const; + bool operator==( const QwtScaleDiv & ) const; + bool operator!=( const QwtScaleDiv & ) const; - void setTicks(int type, const QwtValueList &); - const QwtValueList &ticks(int type) const; + void setInterval( double lowerBound, double upperBound ); + void setInterval( const QwtInterval & ); + QwtInterval interval() const; - void invalidate(); - bool isValid() const; + void setLowerBound( double ); + double lowerBound() const; - void invert(); + void setUpperBound( double ); + double upperBound() const; -private: - double d_lBound; - double d_hBound; - QwtValueList d_ticks[NTickTypes]; + double range() const; - bool d_isValid; -}; + bool contains( double value ) const; -/*! - Change the interval - \lBound left bound - \rBound right bound -*/ -inline void QwtScaleDiv::setInterval(double lBound, double hBound) -{ - d_lBound = lBound; - d_hBound = hBound; -} + void setTicks( int tickType, const QList<double> & ); + QList<double> ticks( int tickType ) const; -/*! - \return lBound -> hBound -*/ -inline QwtDoubleInterval QwtScaleDiv::interval() const -{ - return QwtDoubleInterval(d_lBound, d_hBound); -} + bool isEmpty() const; + bool isIncreasing() const; -/*! - \return left bound - \sa QwtScaleDiv::hBound -*/ -inline double QwtScaleDiv::lBound() const -{ - return d_lBound; -} + void invert(); + QwtScaleDiv inverted() const; -/*! - \return right bound - \sa QwtScaleDiv::lBound -*/ -inline double QwtScaleDiv::hBound() const -{ - return d_hBound; -} + QwtScaleDiv bounded( double lowerBound, double upperBound ) const; + +private: + double d_lowerBound; + double d_upperBound; + QList<double> d_ticks[NTickTypes]; +}; + +Q_DECLARE_TYPEINFO( QwtScaleDiv, Q_MOVABLE_TYPE ); + +#ifndef QT_NO_DEBUG_STREAM +QWT_EXPORT QDebug operator<<( QDebug, const QwtScaleDiv & ); +#endif -/*! - \return hBound() - lBound() -*/ -inline double QwtScaleDiv::range() const -{ - return d_hBound - d_lBound; -} #endif diff --git a/libs/qwt/qwt_scale_draw.cpp b/libs/qwt/qwt_scale_draw.cpp index 36e7a89ed4..6778ebe930 100644 --- a/libs/qwt/qwt_scale_draw.cpp +++ b/libs/qwt/qwt_scale_draw.cpp @@ -7,45 +7,37 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <qpen.h> -#include <qpainter.h> -#include "qwt_math.h" -#include "qwt_painter.h" -#include "qwt_polygon.h" +#include "qwt_scale_draw.h" #include "qwt_scale_div.h" #include "qwt_scale_map.h" -#include "qwt_scale_draw.h" +#include "qwt_math.h" +#include "qwt_painter.h" +#include <qpen.h> +#include <qpainter.h> +#include <qmath.h> -#if QT_VERSION < 0x040000 -#include <qwmatrix.h> -#define QwtMatrix QWMatrix -#else -#include <qmatrix.h> -#define QwtMatrix QMatrix +#if QT_VERSION < 0x040601 +#define qFastSin(x) qSin(x) +#define qFastCos(x) qCos(x) #endif class QwtScaleDraw::PrivateData { public: PrivateData(): - len(0), - alignment(QwtScaleDraw::BottomScale), - labelAlignment(0), - labelRotation(0.0) { + len( 0 ), + alignment( QwtScaleDraw::BottomScale ), + labelAlignment( 0 ), + labelRotation( 0.0 ) + { } - QPoint pos; - int len; + QPointF pos; + double len; Alignment alignment; -#if QT_VERSION < 0x040000 - int labelAlignment; -#else Qt::Alignment labelAlignment; -#endif double labelRotation; }; @@ -59,14 +51,7 @@ public: QwtScaleDraw::QwtScaleDraw() { d_data = new QwtScaleDraw::PrivateData; - setLength(100); -} - -//! Copy constructor -QwtScaleDraw::QwtScaleDraw(const QwtScaleDraw &other): - QwtAbstractScaleDraw(other) -{ - d_data = new QwtScaleDraw::PrivateData(*other.d_data); + setLength( 100 ); } //! Destructor @@ -75,17 +60,10 @@ QwtScaleDraw::~QwtScaleDraw() delete d_data; } -//! Assignment operator -QwtScaleDraw &QwtScaleDraw::operator=(const QwtScaleDraw &other) -{ - *(QwtAbstractScaleDraw*)this = (const QwtAbstractScaleDraw &)other; - *d_data = *other.d_data; - return *this; -} - /*! Return alignment of the scale \sa setAlignment() + \return Alignment of the scale */ QwtScaleDraw::Alignment QwtScaleDraw::alignment() const { @@ -95,10 +73,12 @@ QwtScaleDraw::Alignment QwtScaleDraw::alignment() const /*! Set the alignment of the scale + \param align Alignment of the scale + The default alignment is QwtScaleDraw::BottomScale \sa alignment() */ -void QwtScaleDraw::setAlignment(Alignment align) +void QwtScaleDraw::setAlignment( Alignment align ) { d_data->alignment = align; } @@ -109,18 +89,21 @@ void QwtScaleDraw::setAlignment(Alignment align) TopScale, BottomScale are horizontal (Qt::Horizontal) scales, LeftScale, RightScale are vertical (Qt::Vertical) scales. + \return Orientation of the scale + \sa alignment() */ Qt::Orientation QwtScaleDraw::orientation() const { - switch(d_data->alignment) { - case TopScale: - case BottomScale: - return Qt::Horizontal; - case LeftScale: - case RightScale: - default: - return Qt::Vertical; + switch ( d_data->alignment ) + { + case TopScale: + case BottomScale: + return Qt::Horizontal; + case LeftScale: + case RightScale: + default: + return Qt::Vertical; } } @@ -134,47 +117,69 @@ Qt::Orientation QwtScaleDraw::orientation() const \param start Start border distance \param end End border distance */ -void QwtScaleDraw::getBorderDistHint(const QFont &font, - int &start, int &end ) const +void QwtScaleDraw::getBorderDistHint( + const QFont &font, int &start, int &end ) const { start = 0; end = 0; - if ( !hasComponent(QwtAbstractScaleDraw::Labels) ) + if ( !hasComponent( QwtAbstractScaleDraw::Labels ) ) return; - const QwtValueList &ticks = scaleDiv().ticks(QwtScaleDiv::MajorTick); + const QList<double> &ticks = scaleDiv().ticks( QwtScaleDiv::MajorTick ); if ( ticks.count() == 0 ) return; - QRect lr = labelRect(font, ticks[0]); - - // find the distance between tick and border - int off = qwtAbs(map().transform(ticks[0]) - qRound(map().p1())); + // Find the ticks, that are mapped to the borders. + // minTick is the tick, that is mapped to the top/left-most position + // in widget coordinates. + + double minTick = ticks[0]; + double minPos = scaleMap().transform( minTick ); + double maxTick = minTick; + double maxPos = minPos; + + for ( int i = 1; i < ticks.count(); i++ ) + { + const double tickPos = scaleMap().transform( ticks[i] ); + if ( tickPos < minPos ) + { + minTick = ticks[i]; + minPos = tickPos; + } + if ( tickPos > scaleMap().transform( maxTick ) ) + { + maxTick = ticks[i]; + maxPos = tickPos; + } + } + double e = 0.0; + double s = 0.0; if ( orientation() == Qt::Vertical ) - end = lr.bottom() + 1 - off; - else - start = -lr.left() - off; - - const int lastTick = ticks.count() - 1; - lr = labelRect(font, ticks[lastTick]); + { + s = -labelRect( font, minTick ).top(); + s -= qAbs( minPos - qRound( scaleMap().p2() ) ); - // find the distance between tick and border - off = qwtAbs(map().transform(ticks[lastTick]) - qRound(map().p2())); - - if ( orientation() == Qt::Vertical ) - start = -lr.top() - off; + e = labelRect( font, maxTick ).bottom(); + e -= qAbs( maxPos - scaleMap().p1() ); + } else - end = lr.right() + 1 - off; + { + s = -labelRect( font, minTick ).left(); + s -= qAbs( minPos - scaleMap().p1() ); - // if the distance between tick and border is larger - // than half of the label width/height, we set to 0 + e = labelRect( font, maxTick ).right(); + e -= qAbs( maxPos - scaleMap().p2() ); + } - if ( start < 0 ) - start = 0; - if ( end < 0 ) - end = 0; + if ( s < 0.0 ) + s = 0.0; + if ( e < 0.0 ) + e = 0.0; + + start = qCeil( s ); + end = qCeil( e ); } /*! @@ -187,35 +192,39 @@ void QwtScaleDraw::getBorderDistHint(const QFont &font, \sa getBorderDistHint() */ -int QwtScaleDraw::minLabelDist(const QFont &font) const +int QwtScaleDraw::minLabelDist( const QFont &font ) const { - if ( !hasComponent(QwtAbstractScaleDraw::Labels) ) + if ( !hasComponent( QwtAbstractScaleDraw::Labels ) ) return 0; - const QwtValueList &ticks = scaleDiv().ticks(QwtScaleDiv::MajorTick); - if (ticks.count() == 0) + const QList<double> &ticks = scaleDiv().ticks( QwtScaleDiv::MajorTick ); + if ( ticks.isEmpty() ) return 0; - const QFontMetrics fm(font); + const QFontMetrics fm( font ); - const bool vertical = (orientation() == Qt::Vertical); + const bool vertical = ( orientation() == Qt::Vertical ); - QRect bRect1; - QRect bRect2 = labelRect(font, ticks[0]); - if ( vertical ) { - bRect2.setRect(-bRect2.bottom(), 0, bRect2.height(), bRect2.width()); + QRectF bRect1; + QRectF bRect2 = labelRect( font, ticks[0] ); + if ( vertical ) + { + bRect2.setRect( -bRect2.bottom(), 0.0, bRect2.height(), bRect2.width() ); } - int maxDist = 0; - for (uint i = 1; i < (uint)ticks.count(); i++ ) { + double maxDist = 0.0; + + for ( int i = 1; i < ticks.count(); i++ ) + { bRect1 = bRect2; - bRect2 = labelRect(font, ticks[i]); - if ( vertical ) { - bRect2.setRect(-bRect2.bottom(), 0, - bRect2.height(), bRect2.width()); + bRect2 = labelRect( font, ticks[i] ); + if ( vertical ) + { + bRect2.setRect( -bRect2.bottom(), 0.0, + bRect2.height(), bRect2.width() ); } - int dist = fm.leading(); // space between the labels + double dist = fm.leading(); // space between the labels if ( bRect1.right() > 0 ) dist += bRect1.right(); if ( bRect2.left() < 0 ) @@ -225,26 +234,24 @@ int QwtScaleDraw::minLabelDist(const QFont &font) const maxDist = dist; } - double angle = labelRotation() / 180.0 * M_PI; + double angle = qwtRadians( labelRotation() ); if ( vertical ) angle += M_PI / 2; - if ( sin(angle) == 0.0 ) - return maxDist; + const double sinA = qFastSin( angle ); // qreal -> double + if ( qFuzzyCompare( sinA + 1.0, 1.0 ) ) + return qCeil( maxDist ); const int fmHeight = fm.ascent() - 2; // The distance we need until there is // the height of the label font. This height is needed - // for the neighbour labal. + // for the neighbored label. - int labelDist = (int)(fmHeight / sin(angle) * cos(angle)); + double labelDist = fmHeight / qFastSin( angle ) * qFastCos( angle ); if ( labelDist < 0 ) labelDist = -labelDist; - // The cast above floored labelDist. We want to ceil. - labelDist++; - // For text orientations close to the scale orientation if ( labelDist > maxDist ) @@ -256,7 +263,7 @@ int QwtScaleDraw::minLabelDist(const QFont &font) const if ( labelDist < fmHeight ) labelDist = fmHeight; - return labelDist; + return qCeil( labelDist ); } /*! @@ -267,116 +274,127 @@ int QwtScaleDraw::minLabelDist(const QFont &font) const the major tick length, the spacing and the maximum width/height of the labels. - \param pen Pen that is used for painting backbone and ticks \param font Font used for painting the labels + \return Extent \sa minLength() */ -int QwtScaleDraw::extent(const QPen &pen, const QFont &font) const +double QwtScaleDraw::extent( const QFont &font ) const { - int d = 0; + double d = 0; - if ( hasComponent(QwtAbstractScaleDraw::Labels) ) { + if ( hasComponent( QwtAbstractScaleDraw::Labels ) ) + { if ( orientation() == Qt::Vertical ) - d = maxLabelWidth(font); + d = maxLabelWidth( font ); else - d = maxLabelHeight(font); + d = maxLabelHeight( font ); if ( d > 0 ) d += spacing(); } - if ( hasComponent(QwtAbstractScaleDraw::Ticks) ) { - d += majTickLength(); + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) + { + d += maxTickLength(); } - if ( hasComponent(QwtAbstractScaleDraw::Backbone) ) { - const int pw = qwtMax( 1, pen.width() ); // penwidth can be zero + if ( hasComponent( QwtAbstractScaleDraw::Backbone ) ) + { + const double pw = qMax( 1, penWidth() ); // pen width can be zero d += pw; } - d = qwtMax(d, minimumExtent()); + d = qMax( d, minimumExtent() ); return d; } /*! Calculate the minimum length that is needed to draw the scale - \param pen Pen that is used for painting backbone and ticks \param font Font used for painting the labels + \return Minimum length that is needed to draw the scale \sa extent() */ -int QwtScaleDraw::minLength(const QPen &pen, const QFont &font) const +int QwtScaleDraw::minLength( const QFont &font ) const { int startDist, endDist; - getBorderDistHint(font, startDist, endDist); + getBorderDistHint( font, startDist, endDist ); const QwtScaleDiv &sd = scaleDiv(); const uint minorCount = - sd.ticks(QwtScaleDiv::MinorTick).count() + - sd.ticks(QwtScaleDiv::MediumTick).count(); + sd.ticks( QwtScaleDiv::MinorTick ).count() + + sd.ticks( QwtScaleDiv::MediumTick ).count(); const uint majorCount = - sd.ticks(QwtScaleDiv::MajorTick).count(); + sd.ticks( QwtScaleDiv::MajorTick ).count(); int lengthForLabels = 0; - if ( hasComponent(QwtAbstractScaleDraw::Labels) ) { - if ( majorCount >= 2 ) - lengthForLabels = minLabelDist(font) * (majorCount - 1); - } + if ( hasComponent( QwtAbstractScaleDraw::Labels ) ) + lengthForLabels = minLabelDist( font ) * majorCount; int lengthForTicks = 0; - if ( hasComponent(QwtAbstractScaleDraw::Ticks) ) { - const int pw = qwtMax( 1, pen.width() ); // penwidth can be zero - lengthForTicks = 2 * (majorCount + minorCount) * pw; + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) + { + const double pw = qMax( 1, penWidth() ); // penwidth can be zero + lengthForTicks = qCeil( ( majorCount + minorCount ) * ( pw + 1.0 ) ); } - return startDist + endDist + qwtMax(lengthForLabels, lengthForTicks); + return startDist + endDist + qMax( lengthForLabels, lengthForTicks ); } /*! Find the position, where to paint a label - The position has a distance of majTickLength() + spacing() + 1 - from the backbone. The direction depends on the alignment() + The position has a distance that depends on the length of the ticks + in direction of the alignment(). \param value Value + \return Position, where to paint a label */ -QPoint QwtScaleDraw::labelPosition( double value) const +QPointF QwtScaleDraw::labelPosition( double value ) const { - const int tval = map().transform(value); - int dist = spacing() + 1; - if ( hasComponent(QwtAbstractScaleDraw::Ticks) ) - dist += majTickLength(); - - int px = 0; - int py = 0; - - switch(alignment()) { - case RightScale: { - px = d_data->pos.x() + dist; - py = tval; - break; - } - case LeftScale: { - px = d_data->pos.x() - dist; - py = tval; - break; - } - case BottomScale: { - px = tval; - py = d_data->pos.y() + dist; - break; - } - case TopScale: { - px = tval; - py = d_data->pos.y() - dist; - break; - } + const double tval = scaleMap().transform( value ); + double dist = spacing(); + if ( hasComponent( QwtAbstractScaleDraw::Backbone ) ) + dist += qMax( 1, penWidth() ); + + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) + dist += tickLength( QwtScaleDiv::MajorTick ); + + double px = 0; + double py = 0; + + switch ( alignment() ) + { + case RightScale: + { + px = d_data->pos.x() + dist; + py = tval; + break; + } + case LeftScale: + { + px = d_data->pos.x() - dist; + py = tval; + break; + } + case BottomScale: + { + px = tval; + py = d_data->pos.y() + dist; + break; + } + case TopScale: + { + px = tval; + py = d_data->pos.y() - dist; + break; + } } - return QPoint(px, py); + return QPointF( px, py ); } /*! @@ -384,94 +402,86 @@ QPoint QwtScaleDraw::labelPosition( double value) const \param painter Painter \param value Value of the tick - \param len Lenght of the tick + \param len Length of the tick \sa drawBackbone(), drawLabel() */ -void QwtScaleDraw::drawTick(QPainter *painter, double value, int len) const +void QwtScaleDraw::drawTick( QPainter *painter, double value, double len ) const { if ( len <= 0 ) return; - int pw2 = qwtMin((int)painter->pen().width(), len) / 2; - - QwtScaleMap scaleMap = map(); - const QwtMetricsMap metricsMap = QwtPainter::metricsMap(); - QPoint pos = d_data->pos; - - if ( !metricsMap.isIdentity() ) { - /* - The perfect position of the ticks is important. - To avoid rounding errors we have to use - device coordinates. - */ - QwtPainter::resetMetricsMap(); - - pos = metricsMap.layoutToDevice(pos); - - if ( orientation() == Qt::Vertical ) { - scaleMap.setPaintInterval( - metricsMap.layoutToDeviceY((int)scaleMap.p1()), - metricsMap.layoutToDeviceY((int)scaleMap.p2()) - ); - len = metricsMap.layoutToDeviceX(len); - } else { - scaleMap.setPaintInterval( - metricsMap.layoutToDeviceX((int)scaleMap.p1()), - metricsMap.layoutToDeviceX((int)scaleMap.p2()) - ); - len = metricsMap.layoutToDeviceY(len); - } - } + const bool roundingAlignment = QwtPainter::roundingAlignment( painter ); - const int tval = scaleMap.transform(value); + QPointF pos = d_data->pos; - switch(alignment()) { - case LeftScale: { -#if QT_VERSION < 0x040000 - QwtPainter::drawLine(painter, pos.x() + pw2, tval, - pos.x() - len - 2 * pw2, tval); -#else - QwtPainter::drawLine(painter, pos.x() - pw2, tval, - pos.x() - len, tval); -#endif - break; - } + double tval = scaleMap().transform( value ); + if ( roundingAlignment ) + tval = qRound( tval ); - case RightScale: { -#if QT_VERSION < 0x040000 - QwtPainter::drawLine(painter, pos.x(), tval, - pos.x() + len + pw2, tval); -#else - QwtPainter::drawLine(painter, pos.x() + pw2, tval, - pos.x() + len, tval); -#endif - break; - } + const int pw = penWidth(); + int a = 0; + if ( pw > 1 && roundingAlignment ) + a = 1; - case BottomScale: { -#if QT_VERSION < 0x040000 - QwtPainter::drawLine(painter, tval, pos.y(), - tval, pos.y() + len + 2 * pw2); -#else - QwtPainter::drawLine(painter, tval, pos.y() + pw2, - tval, pos.y() + len); -#endif - break; - } + switch ( alignment() ) + { + case LeftScale: + { + double x1 = pos.x() + a; + double x2 = pos.x() + a - pw - len; + if ( roundingAlignment ) + { + x1 = qRound( x1 ); + x2 = qRound( x2 ); + } - case TopScale: { -#if QT_VERSION < 0x040000 - QwtPainter::drawLine(painter, tval, pos.y() + pw2, - tval, pos.y() - len - 2 * pw2); -#else - QwtPainter::drawLine(painter, tval, pos.y() - pw2, - tval, pos.y() - len); -#endif - break; - } + QwtPainter::drawLine( painter, x1, tval, x2, tval ); + break; + } + + case RightScale: + { + double x1 = pos.x(); + double x2 = pos.x() + pw + len; + if ( roundingAlignment ) + { + x1 = qRound( x1 ); + x2 = qRound( x2 ); + } + + QwtPainter::drawLine( painter, x1, tval, x2, tval ); + break; + } + + case BottomScale: + { + double y1 = pos.y(); + double y2 = pos.y() + pw + len; + if ( roundingAlignment ) + { + y1 = qRound( y1 ); + y2 = qRound( y2 ); + } + + QwtPainter::drawLine( painter, tval, y1, tval, y2 ); + break; + } + + case TopScale: + { + double y1 = pos.y() + a; + double y2 = pos.y() - pw - len + a; + if ( roundingAlignment ) + { + y1 = qRound( y1 ); + y2 = qRound( y2 ); + } + + QwtPainter::drawLine( painter, tval, y1, tval, y2 ); + break; + } } - QwtPainter::setMetricsMap(metricsMap); // restore metrics map } /*! @@ -480,30 +490,69 @@ void QwtScaleDraw::drawTick(QPainter *painter, double value, int len) const \sa drawTick(), drawLabel() */ -void QwtScaleDraw::drawBackbone(QPainter *painter) const +void QwtScaleDraw::drawBackbone( QPainter *painter ) const { - const int bw2 = painter->pen().width() / 2; - - const QPoint &pos = d_data->pos; - const int len = d_data->len - 1; - - switch(alignment()) { - case LeftScale: - QwtPainter::drawLine(painter, pos.x() - bw2, - pos.y(), pos.x() - bw2, pos.y() + len ); - break; - case RightScale: - QwtPainter::drawLine(painter, pos.x() + bw2, - pos.y(), pos.x() + bw2, pos.y() + len); - break; - case TopScale: - QwtPainter::drawLine(painter, pos.x(), pos.y() - bw2, - pos.x() + len, pos.y() - bw2); - break; - case BottomScale: - QwtPainter::drawLine(painter, pos.x(), pos.y() + bw2, - pos.x() + len, pos.y() + bw2); - break; + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + const QPointF &pos = d_data->pos; + const double len = d_data->len; + const int pw = qMax( penWidth(), 1 ); + + // pos indicates a border not the center of the backbone line + // so we need to shift its position depending on the pen width + // and the alignment of the scale + + double off; + if ( doAlign ) + { + if ( alignment() == LeftScale || alignment() == TopScale ) + off = ( pw - 1 ) / 2; + else + off = pw / 2; + } + else + { + off = 0.5 * penWidth(); + } + + switch ( alignment() ) + { + case LeftScale: + { + double x = pos.x() - off; + if ( doAlign ) + x = qRound( x ); + + QwtPainter::drawLine( painter, x, pos.y(), x, pos.y() + len ); + break; + } + case RightScale: + { + double x = pos.x() + off; + if ( doAlign ) + x = qRound( x ); + + QwtPainter::drawLine( painter, x, pos.y(), x, pos.y() + len ); + break; + } + case TopScale: + { + double y = pos.y() - off; + if ( doAlign ) + y = qRound( y ); + + QwtPainter::drawLine( painter, pos.x(), y, pos.x() + len, y ); + break; + } + case BottomScale: + { + double y = pos.y() + off; + if ( doAlign ) + y = qRound( y ); + + QwtPainter::drawLine( painter, pos.x(), y, pos.x() + len, y ); + break; + } } } @@ -538,7 +587,7 @@ void QwtScaleDraw::drawBackbone(QPainter *painter) const \sa pos(), setLength() */ -void QwtScaleDraw::move(const QPoint &pos) +void QwtScaleDraw::move( const QPointF &pos ) { d_data->pos = pos; updateMap(); @@ -548,7 +597,7 @@ void QwtScaleDraw::move(const QPoint &pos) \return Origin of the scale \sa move(), length() */ -QPoint QwtScaleDraw::pos() const +QPointF QwtScaleDraw::pos() const { return d_data->pos; } @@ -559,14 +608,22 @@ QPoint QwtScaleDraw::pos() const The length doesn't include the space needed for overlapping labels. + \param length Length of the backbone + \sa move(), minLabelDist() */ -void QwtScaleDraw::setLength(int length) +void QwtScaleDraw::setLength( double length ) { +#if 1 if ( length >= 0 && length < 10 ) length = 10; + + // why should we accept negative lengths ??? if ( length < 0 && length > -10 ) length = -10; +#else + length = qMax( length, 10 ); +#endif d_data->len = length; updateMap(); @@ -576,7 +633,7 @@ void QwtScaleDraw::setLength(int length) \return the length of the backbone \sa setLength(), pos() */ -int QwtScaleDraw::length() const +double QwtScaleDraw::length() const { return d_data->len; } @@ -589,163 +646,144 @@ int QwtScaleDraw::length() const \sa drawTick(), drawBackbone(), boundingLabelRect() */ -void QwtScaleDraw::drawLabel(QPainter *painter, double value) const +void QwtScaleDraw::drawLabel( QPainter *painter, double value ) const { - QwtText lbl = tickLabel(painter->font(), value); + QwtText lbl = tickLabel( painter->font(), value ); if ( lbl.isEmpty() ) return; - const QPoint pos = labelPosition(value); + QPointF pos = labelPosition( value ); - QSize labelSize = lbl.textSize(painter->font()); - if ( labelSize.height() % 2 ) - labelSize.setHeight(labelSize.height() + 1); + QSizeF labelSize = lbl.textSize( painter->font() ); - const QwtMatrix m = labelMatrix( pos, labelSize); + const QTransform transform = labelTransformation( pos, labelSize ); painter->save(); -#if QT_VERSION < 0x040000 - painter->setWorldMatrix(m, true); -#else - painter->setMatrix(m, true); -#endif + painter->setWorldTransform( transform, true ); + + lbl.draw ( painter, QRect( QPoint( 0, 0 ), labelSize.toSize() ) ); - lbl.draw (painter, QRect(QPoint(0, 0), labelSize) ); painter->restore(); } /*! - Find the bounding rect for the label. The coordinates of - the rect are absolute coordinates ( calculated from pos() ). + \brief Find the bounding rectangle for the label. + + The coordinates of the rectangle are absolute ( calculated from pos() ). in direction of the tick. \param font Font used for painting \param value Value + \return Bounding rectangle \sa labelRect() */ -QRect QwtScaleDraw::boundingLabelRect(const QFont &font, double value) const +QRect QwtScaleDraw::boundingLabelRect( const QFont &font, double value ) const { - QwtText lbl = tickLabel(font, value); + QwtText lbl = tickLabel( font, value ); if ( lbl.isEmpty() ) return QRect(); - const QPoint pos = labelPosition(value); - QSize labelSize = lbl.textSize(font); - if ( labelSize.height() % 2 ) - labelSize.setHeight(labelSize.height() + 1); + const QPointF pos = labelPosition( value ); + QSizeF labelSize = lbl.textSize( font ); - const QwtMatrix m = labelMatrix( pos, labelSize); - return m.mapRect(QRect(QPoint(0, 0), labelSize)); + const QTransform transform = labelTransformation( pos, labelSize ); + return transform.mapRect( QRect( QPoint( 0, 0 ), labelSize.toSize() ) ); } /*! - Calculate the matrix that is needed to paint a label + Calculate the transformation that is needed to paint a label depending on its alignment and rotation. \param pos Position where to paint the label \param size Size of the label + \return Transformation matrix \sa setLabelAlignment(), setLabelRotation() */ -QwtMatrix QwtScaleDraw::labelMatrix( - const QPoint &pos, const QSize &size) const +QTransform QwtScaleDraw::labelTransformation( + const QPointF &pos, const QSizeF &size ) const { - QwtMatrix m; - m.translate(pos.x(), pos.y()); - m.rotate(labelRotation()); + QTransform transform; + transform.translate( pos.x(), pos.y() ); + transform.rotate( labelRotation() ); int flags = labelAlignment(); - if ( flags == 0 ) { - switch(alignment()) { - case RightScale: { - if ( flags == 0 ) - flags = Qt::AlignRight | Qt::AlignVCenter; - break; - } - case LeftScale: { - if ( flags == 0 ) - flags = Qt::AlignLeft | Qt::AlignVCenter; - break; - } - case BottomScale: { - if ( flags == 0 ) - flags = Qt::AlignHCenter | Qt::AlignBottom; - break; - } - case TopScale: { - if ( flags == 0 ) - flags = Qt::AlignHCenter | Qt::AlignTop; - break; - } + if ( flags == 0 ) + { + switch ( alignment() ) + { + case RightScale: + { + if ( flags == 0 ) + flags = Qt::AlignRight | Qt::AlignVCenter; + break; + } + case LeftScale: + { + if ( flags == 0 ) + flags = Qt::AlignLeft | Qt::AlignVCenter; + break; + } + case BottomScale: + { + if ( flags == 0 ) + flags = Qt::AlignHCenter | Qt::AlignBottom; + break; + } + case TopScale: + { + if ( flags == 0 ) + flags = Qt::AlignHCenter | Qt::AlignTop; + break; + } } } - const int w = size.width(); - const int h = size.height(); - - int x, y; + double x, y; if ( flags & Qt::AlignLeft ) - x = -w; + x = -size.width(); else if ( flags & Qt::AlignRight ) - x = -(w % 2); + x = 0.0; else // Qt::AlignHCenter - x = -(w / 2); + x = -( 0.5 * size.width() ); if ( flags & Qt::AlignTop ) - y = -h ; + y = -size.height(); else if ( flags & Qt::AlignBottom ) - y = -(h % 2); + y = 0; else // Qt::AlignVCenter - y = -(h/2); + y = -( 0.5 * size.height() ); - m.translate(x, y); + transform.translate( x, y ); - return m; + return transform; } /*! - Find the bounding rect for the label. The coordinates of - the rect are relative to spacing + ticklength from the backbone + Find the bounding rectangle for the label. The coordinates of + the rectangle are relative to spacing + tick length from the backbone in direction of the tick. \param font Font used for painting \param value Value + + \return Bounding rectangle that is needed to draw a label */ -QRect QwtScaleDraw::labelRect(const QFont &font, double value) const +QRectF QwtScaleDraw::labelRect( const QFont &font, double value ) const { - QwtText lbl = tickLabel(font, value); + QwtText lbl = tickLabel( font, value ); if ( lbl.isEmpty() ) - return QRect(0, 0, 0, 0); + return QRectF( 0.0, 0.0, 0.0, 0.0 ); - const QPoint pos = labelPosition(value); - - QSize labelSize = lbl.textSize(font); - if ( labelSize.height() % 2 ) { - labelSize.setHeight(labelSize.height() + 1); - } + const QPointF pos = labelPosition( value ); - const QwtMatrix m = labelMatrix(pos, labelSize); + const QSizeF labelSize = lbl.textSize( font ); + const QTransform transform = labelTransformation( pos, labelSize ); -#if 0 - QRect br = QwtMetricsMap::translate(m, QRect(QPoint(0, 0), labelSize)); -#else - QwtPolygon pol(4); - pol.setPoint(0, 0, 0); - pol.setPoint(1, 0, labelSize.height() - 1 ); - pol.setPoint(2, labelSize.width() - 1, 0); - pol.setPoint(3, labelSize.width() - 1, labelSize.height() - 1 ); - - pol = QwtMetricsMap::translate(m, pol); - QRect br = pol.boundingRect(); -#endif - -#if QT_VERSION < 0x040000 - br.moveBy(-pos.x(), -pos.y()); -#else - br.translate(-pos.x(), -pos.y()); -#endif + QRectF br = transform.mapRect( QRectF( QPointF( 0, 0 ), labelSize ) ); + br.translate( -pos.x(), -pos.y() ); return br; } @@ -755,10 +793,12 @@ QRect QwtScaleDraw::labelRect(const QFont &font, double value) const \param font Label font \param value Value + + \return Size that is needed to draw a label */ -QSize QwtScaleDraw::labelSize(const QFont &font, double value) const +QSizeF QwtScaleDraw::labelSize( const QFont &font, double value ) const { - return labelRect(font, value).size(); + return labelRect( font, value ).size(); } /*! @@ -774,7 +814,7 @@ QSize QwtScaleDraw::labelSize(const QFont &font, double value) const \sa setLabelAlignment(), labelRotation(), labelAlignment(). */ -void QwtScaleDraw::setLabelRotation(double rotation) +void QwtScaleDraw::setLabelRotation( double rotation ) { d_data->labelRotation = rotation; } @@ -791,7 +831,7 @@ double QwtScaleDraw::labelRotation() const /*! \brief Change the label flags - Labels are aligned to the point ticklength + spacing away from the backbone. + Labels are aligned to the point tick length + spacing away from the backbone. The alignment is relative to the orientation of the label text. In case of an flags of 0 the label will be aligned @@ -804,20 +844,16 @@ double QwtScaleDraw::labelRotation() const Changing the alignment is often necessary for rotated labels. - \param alignment Or'd Qt::AlignmentFlags <see qnamespace.h> + \param alignment Or'd Qt::AlignmentFlags see <qnamespace.h> \sa setLabelRotation(), labelRotation(), labelAlignment() \warning The various alignments might be confusing. The alignment of the label is not the alignment of the scale and is not the alignment of the flags - (QwtText::flags()) returned from QwtAbstractScaleDraw::label(). + ( QwtText::flags() ) returned from QwtAbstractScaleDraw::label(). */ -#if QT_VERSION < 0x040000 -void QwtScaleDraw::setLabelAlignment(int alignment) -#else -void QwtScaleDraw::setLabelAlignment(Qt::Alignment alignment) -#endif +void QwtScaleDraw::setLabelAlignment( Qt::Alignment alignment ) { d_data->labelAlignment = alignment; } @@ -826,11 +862,7 @@ void QwtScaleDraw::setLabelAlignment(Qt::Alignment alignment) \return the label flags \sa setLabelAlignment(), labelRotation() */ -#if QT_VERSION < 0x040000 -int QwtScaleDraw::labelAlignment() const -#else Qt::Alignment QwtScaleDraw::labelAlignment() const -#endif { return d_data->labelAlignment; } @@ -839,49 +871,56 @@ Qt::Alignment QwtScaleDraw::labelAlignment() const \param font Font \return the maximum width of a label */ -int QwtScaleDraw::maxLabelWidth(const QFont &font) const +int QwtScaleDraw::maxLabelWidth( const QFont &font ) const { - int maxWidth = 0; + double maxWidth = 0.0; - const QwtValueList &ticks = scaleDiv().ticks(QwtScaleDiv::MajorTick); - for (uint i = 0; i < (uint)ticks.count(); i++) { + const QList<double> &ticks = scaleDiv().ticks( QwtScaleDiv::MajorTick ); + for ( int i = 0; i < ticks.count(); i++ ) + { const double v = ticks[i]; - if ( scaleDiv().contains(v) ) { - const int w = labelSize(font, ticks[i]).width(); + if ( scaleDiv().contains( v ) ) + { + const double w = labelSize( font, ticks[i] ).width(); if ( w > maxWidth ) maxWidth = w; } } - return maxWidth; + return qCeil( maxWidth ); } /*! \param font Font \return the maximum height of a label */ -int QwtScaleDraw::maxLabelHeight(const QFont &font) const +int QwtScaleDraw::maxLabelHeight( const QFont &font ) const { - int maxHeight = 0; + double maxHeight = 0.0; - const QwtValueList &ticks = scaleDiv().ticks(QwtScaleDiv::MajorTick); - for (uint i = 0; i < (uint)ticks.count(); i++) { + const QList<double> &ticks = scaleDiv().ticks( QwtScaleDiv::MajorTick ); + for ( int i = 0; i < ticks.count(); i++ ) + { const double v = ticks[i]; - if ( scaleDiv().contains(v) ) { - const int h = labelSize(font, ticks[i]).height(); + if ( scaleDiv().contains( v ) ) + { + const double h = labelSize( font, ticks[i] ).height(); if ( h > maxHeight ) maxHeight = h; } } - return maxHeight; + return qCeil( maxHeight ); } void QwtScaleDraw::updateMap() { + const QPointF pos = d_data->pos; + double len = d_data->len; + QwtScaleMap &sm = scaleMap(); if ( orientation() == Qt::Vertical ) - sm.setPaintInterval(d_data->pos.y() + d_data->len, d_data->pos.y()); + sm.setPaintInterval( pos.y() + len, pos.y() ); else - sm.setPaintInterval(d_data->pos.x(), d_data->pos.x() + d_data->len); + sm.setPaintInterval( pos.x(), pos.x() + len ); } diff --git a/libs/qwt/qwt_scale_draw.h b/libs/qwt/qwt_scale_draw.h index e29dc0a45d..005e834da7 100644 --- a/libs/qwt/qwt_scale_draw.h +++ b/libs/qwt/qwt_scale_draw.h @@ -10,9 +10,11 @@ #ifndef QWT_SCALE_DRAW_H #define QWT_SCALE_DRAW_H -#include <qpoint.h> #include "qwt_global.h" #include "qwt_abstract_scale_draw.h" +#include <qpoint.h> +#include <qrect.h> +#include <qtransform.h> /*! \brief A class for drawing scales @@ -26,7 +28,6 @@ using QwtAbstractScaleDraw::setScaleDiv(const QwtScaleDiv &s), the scale can be drawn with the QwtAbstractScaleDraw::draw() member. */ - class QWT_EXPORT QwtScaleDraw: public QwtAbstractScaleDraw { public: @@ -34,76 +35,86 @@ public: Alignment of the scale draw \sa setAlignment(), alignment() */ - enum Alignment { BottomScale, TopScale, LeftScale, RightScale }; + enum Alignment + { + //! The scale is below + BottomScale, - QwtScaleDraw(); - QwtScaleDraw(const QwtScaleDraw &); + //! The scale is above + TopScale, - virtual ~QwtScaleDraw(); + //! The scale is left + LeftScale, + + //! The scale is right + RightScale + }; - QwtScaleDraw &operator=(const QwtScaleDraw &other); + QwtScaleDraw(); + virtual ~QwtScaleDraw(); - void getBorderDistHint(const QFont &, int &start, int &end) const; - int minLabelDist(const QFont &) const; + void getBorderDistHint( const QFont &, int &start, int &end ) const; + int minLabelDist( const QFont & ) const; - int minLength(const QPen &, const QFont &) const; - virtual int extent(const QPen &, const QFont &) const; + int minLength( const QFont & ) const; + virtual double extent( const QFont & ) const; - void move(int x, int y); - void move(const QPoint &); - void setLength(int length); + void move( double x, double y ); + void move( const QPointF & ); + void setLength( double length ); Alignment alignment() const; - void setAlignment(Alignment); + void setAlignment( Alignment ); Qt::Orientation orientation() const; - QPoint pos() const; - int length() const; + QPointF pos() const; + double length() const; -#if QT_VERSION < 0x040000 - void setLabelAlignment(int); - int labelAlignment() const; -#else - void setLabelAlignment(Qt::Alignment); + void setLabelAlignment( Qt::Alignment ); Qt::Alignment labelAlignment() const; -#endif - void setLabelRotation(double rotation); + void setLabelRotation( double rotation ); double labelRotation() const; - int maxLabelHeight(const QFont &) const; - int maxLabelWidth(const QFont &) const; + int maxLabelHeight( const QFont & ) const; + int maxLabelWidth( const QFont & ) const; - QPoint labelPosition(double val) const; + QPointF labelPosition( double val ) const; - QRect labelRect(const QFont &, double val) const; - QSize labelSize(const QFont &, double val) const; + QRectF labelRect( const QFont &, double val ) const; + QSizeF labelSize( const QFont &, double val ) const; - QRect boundingLabelRect(const QFont &, double val) const; + QRect boundingLabelRect( const QFont &, double val ) const; protected: + QTransform labelTransformation( const QPointF &, const QSizeF & ) const; -#if QT_VERSION < 0x040000 - QWMatrix labelMatrix(const QPoint &, const QSize &) const; -#else - QMatrix labelMatrix(const QPoint &, const QSize &) const; -#endif - - virtual void drawTick(QPainter *p, double val, int len) const; - virtual void drawBackbone(QPainter *p) const; - virtual void drawLabel(QPainter *p, double val) const; + virtual void drawTick( QPainter *, double val, double len ) const; + virtual void drawBackbone( QPainter * ) const; + virtual void drawLabel( QPainter *, double val ) const; private: + QwtScaleDraw( const QwtScaleDraw & ); + QwtScaleDraw &operator=( const QwtScaleDraw &other ); + void updateMap(); class PrivateData; PrivateData *d_data; }; -inline void QwtScaleDraw::move(int x, int y) +/*! + Move the position of the scale + + \param x X coordinate + \param y Y coordinate + + \sa move(const QPointF &) +*/ +inline void QwtScaleDraw::move( double x, double y ) { - move(QPoint(x, y)); + move( QPointF( x, y ) ); } #endif diff --git a/libs/qwt/qwt_scale_engine.cpp b/libs/qwt/qwt_scale_engine.cpp index 63b520399b..686c9d6603 100644 --- a/libs/qwt/qwt_scale_engine.cpp +++ b/libs/qwt/qwt_scale_engine.cpp @@ -7,72 +7,135 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_scale_engine.h" #include "qwt_math.h" #include "qwt_scale_map.h" -#include "qwt_scale_engine.h" +#include <qalgorithms.h> +#include <qmath.h> +#include <float.h> -static const double _eps = 1.0e-6; +#if QT_VERSION < 0x040601 +#define qFabs(x) ::fabs(x) +#define qExp(x) ::exp(x) +#endif -/*! - \brief Compare 2 values, relative to an interval +static inline double qwtLog( double base, double value ) +{ + return log( value ) / log( base ); +} + +static inline QwtInterval qwtLogInterval( double base, const QwtInterval &interval ) +{ + return QwtInterval( qwtLog( base, interval.minValue() ), + qwtLog( base, interval.maxValue() ) ); +} + +static inline QwtInterval qwtPowInterval( double base, const QwtInterval &interval ) +{ + return QwtInterval( qPow( base, interval.minValue() ), + qPow( base, interval.maxValue() ) ); +} - Values are "equal", when : - \f$\cdot value2 - value1 <= abs(intervalSize * 10e^{-6})\f$ - \param value1 First value to compare - \param value2 Second value to compare - \param intervalSize interval size +#if 1 - \return 0: if equal, -1: if value2 > value1, 1: if value1 > value2 -*/ -int QwtScaleArithmetic::compareEps(double value1, double value2, - double intervalSize) +// this version often doesn't find the best ticks: f.e for 15: 5, 10 +static double qwtStepSize( double intervalSize, int maxSteps, uint base ) { - const double eps = qwtAbs(_eps * intervalSize); + const double minStep = + QwtScaleArithmetic::divideInterval( intervalSize, maxSteps, base ); + + if ( minStep != 0.0 ) + { + // # ticks per interval + const int numTicks = qCeil( qAbs( intervalSize / minStep ) ) - 1; + + // Do the minor steps fit into the interval? + if ( qwtFuzzyCompare( ( numTicks + 1 ) * qAbs( minStep ), + qAbs( intervalSize ), intervalSize ) > 0 ) + { + // The minor steps doesn't fit into the interval + return 0.5 * intervalSize; + } + } + + return minStep; +} - if ( value2 - value1 > eps ) - return -1; +#else - if ( value1 - value2 > eps ) - return 1; +static double qwtStepSize( double intervalSize, int maxSteps, uint base ) +{ + if ( maxSteps <= 0 ) + return 0.0; + + if ( maxSteps > 2 ) + { + for ( int numSteps = maxSteps; numSteps > 1; numSteps-- ) + { + const double stepSize = intervalSize / numSteps; + + const double p = ::floor( ::log( stepSize ) / ::log( base ) ); + const double fraction = qPow( base, p ); + + for ( uint n = base; n > 1; n /= 2 ) + { + if ( qFuzzyCompare( stepSize, n * fraction ) ) + return stepSize; + + if ( n == 3 && ( base % 2 ) == 0 ) + { + if ( qFuzzyCompare( stepSize, 2 * fraction ) ) + return stepSize; + } + } + } + } - return 0; + return intervalSize * 0.5; } +#endif + +static const double _eps = 1.0e-6; + /*! Ceil a value, relative to an interval - \param value Value to ceil + \param value Value to be ceiled \param intervalSize Interval size - \sa floorEps + \return Rounded value + + \sa floorEps() */ -double QwtScaleArithmetic::ceilEps(double value, - double intervalSize) +double QwtScaleArithmetic::ceilEps( double value, + double intervalSize ) { const double eps = _eps * intervalSize; - value = (value - eps) / intervalSize; - return ceil(value) * intervalSize; + value = ( value - eps ) / intervalSize; + return ::ceil( value ) * intervalSize; } /*! Floor a value, relative to an interval - \param value Value to floor + \param value Value to be floored \param intervalSize Interval size - \sa floorEps + \return Rounded value + \sa floorEps() */ -double QwtScaleArithmetic::floorEps(double value, double intervalSize) +double QwtScaleArithmetic::floorEps( double value, double intervalSize ) { const double eps = _eps * intervalSize; - value = (value + eps) / intervalSize; - return floor(value) * intervalSize; + value = ( value + eps ) / intervalSize; + return ::floor( value ) * intervalSize; } -/* +/*! \brief Divide an interval into steps \f$stepSize = (intervalSize - intervalSize * 10e^{-6}) / numSteps\f$ @@ -81,144 +144,179 @@ double QwtScaleArithmetic::floorEps(double value, double intervalSize) \param numSteps Number of steps \return Step size */ -double QwtScaleArithmetic::divideEps(double intervalSize, double numSteps) +double QwtScaleArithmetic::divideEps( double intervalSize, double numSteps ) { if ( numSteps == 0.0 || intervalSize == 0.0 ) return 0.0; - return (intervalSize - (_eps * intervalSize)) / numSteps; + return ( intervalSize - ( _eps * intervalSize ) ) / numSteps; } /*! - Find the smallest value out of {1,2,5}*10^n with an integer number n - which is greater than or equal to x + Calculate a step size for a given interval - \param x Input value -*/ -double QwtScaleArithmetic::ceil125(double x) + \param intervalSize Interval size + \param numSteps Number of steps + \param base Base for the division ( usually 10 ) + + \return Calculated step size + */ +double QwtScaleArithmetic::divideInterval( + double intervalSize, int numSteps, uint base ) { - if (x == 0.0) + if ( numSteps <= 0 ) return 0.0; - const double sign = (x > 0) ? 1.0 : -1.0; - const double lx = log10(fabs(x)); - const double p10 = floor(lx); - - double fr = pow(10.0, lx - p10); - if (fr <=1.0) - fr = 1.0; - else if (fr <= 2.0) - fr = 2.0; - else if (fr <= 5.0) - fr = 5.0; - else - fr = 10.0; + const double v = QwtScaleArithmetic::divideEps( intervalSize, numSteps ); + if ( v == 0.0 ) + return 0.0; - return sign * fr * pow(10.0, p10); -} + const double lx = qwtLog( base, qFabs( v ) ); + const double p = ::floor( lx ); -/*! - \brief Find the largest value out of {1,2,5}*10^n with an integer number n - which is smaller than or equal to x + const double fraction = qPow( base, lx - p ); - \param x Input value -*/ -double QwtScaleArithmetic::floor125(double x) -{ - if (x == 0.0) - return 0.0; + uint n = base; + while ( ( n > 1 ) && ( fraction <= n / 2 ) ) + n /= 2; - double sign = (x > 0) ? 1.0 : -1.0; - const double lx = log10(fabs(x)); - const double p10 = floor(lx); - - double fr = pow(10.0, lx - p10); - if (fr >= 10.0) - fr = 10.0; - else if (fr >= 5.0) - fr = 5.0; - else if (fr >= 2.0) - fr = 2.0; - else - fr = 1.0; + double stepSize = n * qPow( base, p ); + if ( v < 0 ) + stepSize = -stepSize; - return sign * fr * pow(10.0, p10); + return stepSize; } class QwtScaleEngine::PrivateData { public: PrivateData(): - attributes(QwtScaleEngine::NoAttribute), - loMargin(0.0), - hiMargin(0.0), - referenceValue(0.0) { + attributes( QwtScaleEngine::NoAttribute ), + lowerMargin( 0.0 ), + upperMargin( 0.0 ), + referenceValue( 0.0 ), + base( 10 ), + transform( NULL ) + { + } + + ~PrivateData() + { + delete transform; } - int attributes; // scale attributes + QwtScaleEngine::Attributes attributes; - double loMargin; // margins - double hiMargin; + double lowerMargin; + double upperMargin; - double referenceValue; // reference value + double referenceValue; + uint base; + + QwtTransform* transform; }; -//! Ctor -QwtScaleEngine::QwtScaleEngine() +/*! + Constructor + + \param base Base of the scale engine + \sa setBase() + */ +QwtScaleEngine::QwtScaleEngine( uint base ) { d_data = new PrivateData; + setBase( base ); } -//! Dtor +//! Destructor QwtScaleEngine::~QwtScaleEngine () { delete d_data; } +/*! + Assign a transformation + + \param transform Transformation + + The transformation object is used as factory for clones + that are returned by transformation() + + The scale engine takes ownership of the transformation. + + \sa QwtTransform::copy(), transformation() + + */ +void QwtScaleEngine::setTransformation( QwtTransform *transform ) +{ + if ( transform != d_data->transform ) + { + delete d_data->transform; + d_data->transform = transform; + } +} + +/*! + Create and return a clone of the transformation + of the engine. When the engine has no special transformation + NULL is returned, indicating no transformation. + + \return A clone of the transfomation + \sa setTransformation() + */ +QwtTransform *QwtScaleEngine::transformation() const +{ + QwtTransform *transform = NULL; + if ( d_data->transform ) + transform = d_data->transform->copy(); + + return transform; +} + /*! \return the margin at the lower end of the scale The default margin is 0. - \sa QwtScaleEngine::setMargins() + \sa setMargins() */ -double QwtScaleEngine::loMargin() const +double QwtScaleEngine::lowerMargin() const { - return d_data->loMargin; + return d_data->lowerMargin; } /*! \return the margin at the upper end of the scale The default margin is 0. - \sa QwtScaleEngine::setMargins() + \sa setMargins() */ -double QwtScaleEngine::hiMargin() const +double QwtScaleEngine::upperMargin() const { - return d_data->hiMargin; + return d_data->upperMargin; } /*! \brief Specify margins at the scale's endpoints - \param mlo minimum distance between the scale's lower boundary and the + \param lower minimum distance between the scale's lower boundary and the smallest enclosed value - \param mhi minimum distance between the scale's upper boundary and the + \param upper minimum distance between the scale's upper boundary and the greatest enclosed value Margins can be used to leave a minimum amount of space between the enclosed intervals and the boundaries of the scale. \warning - \li QwtLog10ScaleEngine measures the margins in decades. + \li QwtLogScaleEngine measures the margins in decades. - \sa QwtScaleEngine::hiMargin, QwtScaleEngine::loMargin + \sa upperMargin(), lowerMargin() */ -void QwtScaleEngine::setMargins(double mlo, double mhi) +void QwtScaleEngine::setMargins( double lower, double upper ) { - d_data->loMargin = qwtMax(mlo,0.0); - d_data->hiMargin = qwtMax(mhi,0.0); + d_data->lowerMargin = qMax( lower, 0.0 ); + d_data->upperMargin = qMax( upper, 0.0 ); } /*! @@ -230,13 +328,10 @@ void QwtScaleEngine::setMargins(double mlo, double mhi) \return Step size */ double QwtScaleEngine::divideInterval( - double intervalSize, int numSteps) const + double intervalSize, int numSteps ) const { - if ( numSteps <= 0 ) - return 0.0; - - double v = QwtScaleArithmetic::divideEps(intervalSize, numSteps); - return QwtScaleArithmetic::ceil125(v); + return QwtScaleArithmetic::divideInterval( + intervalSize, numSteps, d_data->base ); } /*! @@ -245,23 +340,19 @@ double QwtScaleEngine::divideInterval( \param interval Interval \param value Value - \sa QwtScaleArithmetic::compareEps + \return True, when the value is inside the interval */ bool QwtScaleEngine::contains( - const QwtDoubleInterval &interval, double value) const + const QwtInterval &interval, double value ) const { - if (!interval.isValid() ) + if ( !interval.isValid() ) return false; - if ( QwtScaleArithmetic::compareEps(value, - interval.minValue(), interval.width()) < 0 ) { + if ( qwtFuzzyCompare( value, interval.minValue(), interval.width() ) < 0 ) return false; - } - if ( QwtScaleArithmetic::compareEps(value, - interval.maxValue(), interval.width()) > 0 ) { + if ( qwtFuzzyCompare( value, interval.maxValue(), interval.width() ) > 0 ) return false; - } return true; } @@ -274,37 +365,48 @@ bool QwtScaleEngine::contains( \return Stripped tick list */ -QwtValueList QwtScaleEngine::strip( - const QwtValueList& ticks, - const QwtDoubleInterval &interval) const +QList<double> QwtScaleEngine::strip( const QList<double>& ticks, + const QwtInterval &interval ) const { if ( !interval.isValid() || ticks.count() == 0 ) - return QwtValueList(); + return QList<double>(); - if ( contains(interval, ticks.first()) - && contains(interval, ticks.last()) ) { + if ( contains( interval, ticks.first() ) + && contains( interval, ticks.last() ) ) + { return ticks; } - QwtValueList strippedTicks; - for ( int i = 0; i < (int)ticks.count(); i++ ) { - if ( contains(interval, ticks[i]) ) + QList<double> strippedTicks; + for ( int i = 0; i < ticks.count(); i++ ) + { + if ( contains( interval, ticks[i] ) ) strippedTicks += ticks[i]; } return strippedTicks; } /*! - \brief Build an interval for a value + \brief Build an interval around a value In case of v == 0.0 the interval is [-0.5, 0.5], otherwide it is [0.5 * v, 1.5 * v] + + \param value Initial value + \return Calculated interval */ -QwtDoubleInterval QwtScaleEngine::buildInterval(double v) const +QwtInterval QwtScaleEngine::buildInterval( double value ) const { - const double delta = (v == 0.0) ? 0.5 : qwtAbs(0.5 * v); - return QwtDoubleInterval(v - delta, v + delta); + const double delta = ( value == 0.0 ) ? 0.5 : qAbs( 0.5 * value ); + + if ( DBL_MAX - delta < value ) + return QwtInterval( DBL_MAX - delta, DBL_MAX ); + + if ( -DBL_MAX + delta > value ) + return QwtInterval( -DBL_MAX, -DBL_MAX + delta ); + + return QwtInterval( value - delta, value + delta ); } /*! @@ -313,58 +415,43 @@ QwtDoubleInterval QwtScaleEngine::buildInterval(double v) const \param attribute Attribute to change \param on On/Off - The behaviour of the scale engine can be changed - with the following attributes: - <dl> - <dt>QwtScaleEngine::IncludeReference - <dd>Build a scale which includes the reference value. - <dt>QwtScaleEngine::Symmetric - <dd>Build a scale which is symmetric to the reference value. - <dt>QwtScaleEngine::Floating - <dd>The endpoints of the scale are supposed to be equal the outmost included - values plus the specified margins (see setMargins()). If this attribute is - *not* set, the endpoints of the scale will be integer multiples of the step - size. - <dt>QwtScaleEngine::Inverted - <dd>Turn the scale upside down. - </dl> - - \sa QwtScaleEngine::testAttribute() + \sa Attribute, testAttribute() */ -void QwtScaleEngine::setAttribute(Attribute attribute, bool on) +void QwtScaleEngine::setAttribute( Attribute attribute, bool on ) { - if (on) + if ( on ) d_data->attributes |= attribute; else - d_data->attributes &= (~attribute); + d_data->attributes &= ~attribute; } /*! - Check if a attribute is set. + \return True, if attribute is enabled. \param attribute Attribute to be tested - \sa QwtScaleEngine::setAttribute() for a description of the possible options. + \sa Attribute, setAttribute() */ -bool QwtScaleEngine::testAttribute(Attribute attribute) const +bool QwtScaleEngine::testAttribute( Attribute attribute ) const { - return bool(d_data->attributes & attribute); + return ( d_data->attributes & attribute ); } /*! Change the scale attribute \param attributes Set scale attributes - \sa QwtScaleEngine::attributes() + \sa Attribute, attributes() */ -void QwtScaleEngine::setAttributes(int attributes) +void QwtScaleEngine::setAttributes( Attributes attributes ) { d_data->attributes = attributes; } /*! - Return the scale attributes + \return Scale attributes + \sa Attribute, setAttributes(), testAttribute() */ -int QwtScaleEngine::attributes() const +QwtScaleEngine::Attributes QwtScaleEngine::attributes() const { return d_data->attributes; } @@ -373,17 +460,19 @@ int QwtScaleEngine::attributes() const \brief Specify a reference point \param r new reference value - The reference point is needed if options IncludeRef or + The reference point is needed if options IncludeReference or Symmetric are active. Its default value is 0.0. + + \sa Attribute */ -void QwtScaleEngine::setReference(double r) +void QwtScaleEngine::setReference( double r ) { d_data->referenceValue = r; } /*! - \return the reference value - \sa QwtScaleEngine::setReference(), QwtScaleEngine::setAttribute() + \return the reference value + \sa setReference(), setAttribute() */ double QwtScaleEngine::reference() const { @@ -391,89 +480,128 @@ double QwtScaleEngine::reference() const } /*! - Return a transformation, for linear scales -*/ -QwtScaleTransformation *QwtLinearScaleEngine::transformation() const + Set the base of the scale engine + + While a base of 10 is what 99.9% of all applications need + certain scales might need a different base: f.e 2 + + The default setting is 10 + + \param base Base of the engine + + \sa base() + */ +void QwtScaleEngine::setBase( uint base ) +{ + d_data->base = qMax( base, 2U ); +} + +/*! + \return base Base of the scale engine + \sa setBase() + */ +uint QwtScaleEngine::base() const { - return new QwtScaleTransformation(QwtScaleTransformation::Linear); + return d_data->base; } /*! - Align and divide an interval + Constructor - \param maxNumSteps Max. number of steps - \param x1 First limit of the interval (In/Out) - \param x2 Second limit of the interval (In/Out) - \param stepSize Step size (Out) + \param base Base of the scale engine + \sa setBase() + */ +QwtLinearScaleEngine::QwtLinearScaleEngine( uint base ): + QwtScaleEngine( base ) +{ +} + +//! Destructor +QwtLinearScaleEngine::~QwtLinearScaleEngine() +{ +} + +/*! + Align and divide an interval - \sa QwtLinearScaleEngine::setAttribute + \param maxNumSteps Max. number of steps + \param x1 First limit of the interval (In/Out) + \param x2 Second limit of the interval (In/Out) + \param stepSize Step size (Out) + + \sa setAttribute() */ -void QwtLinearScaleEngine::autoScale(int maxNumSteps, - double &x1, double &x2, double &stepSize) const +void QwtLinearScaleEngine::autoScale( int maxNumSteps, + double &x1, double &x2, double &stepSize ) const { - QwtDoubleInterval interval(x1, x2); + QwtInterval interval( x1, x2 ); interval = interval.normalized(); - interval.setMinValue(interval.minValue() - loMargin()); - interval.setMaxValue(interval.maxValue() + hiMargin()); + interval.setMinValue( interval.minValue() - lowerMargin() ); + interval.setMaxValue( interval.maxValue() + upperMargin() ); - if (testAttribute(QwtScaleEngine::Symmetric)) - interval = interval.symmetrize(reference()); + if ( testAttribute( QwtScaleEngine::Symmetric ) ) + interval = interval.symmetrize( reference() ); - if (testAttribute(QwtScaleEngine::IncludeReference)) - interval = interval.extend(reference()); + if ( testAttribute( QwtScaleEngine::IncludeReference ) ) + interval = interval.extend( reference() ); - if (interval.width() == 0.0) - interval = buildInterval(interval.minValue()); + if ( interval.width() == 0.0 ) + interval = buildInterval( interval.minValue() ); - stepSize = divideInterval(interval.width(), qwtMax(maxNumSteps, 1)); + stepSize = QwtScaleArithmetic::divideInterval( + interval.width(), qMax( maxNumSteps, 1 ), base() ); - if ( !testAttribute(QwtScaleEngine::Floating) ) - interval = align(interval, stepSize); + if ( !testAttribute( QwtScaleEngine::Floating ) ) + interval = align( interval, stepSize ); x1 = interval.minValue(); x2 = interval.maxValue(); - if (testAttribute(QwtScaleEngine::Inverted)) { - qSwap(x1, x2); + if ( testAttribute( QwtScaleEngine::Inverted ) ) + { + qSwap( x1, x2 ); stepSize = -stepSize; } } /*! - \brief Calculate a scale division + \brief Calculate a scale division for an interval \param x1 First interval limit \param x2 Second interval limit - \param maxMajSteps Maximum for the number of major steps - \param maxMinSteps Maximum number of minor steps - \param stepSize Step size. If stepSize == 0, the scaleEngine + \param maxMajorSteps Maximum for the number of major steps + \param maxMinorSteps Maximum number of minor steps + \param stepSize Step size. If stepSize == 0, the engine calculates one. - \sa QwtScaleEngine::stepSize, QwtScaleEngine::subDivide + \return Calculated scale division */ -QwtScaleDiv QwtLinearScaleEngine::divideScale(double x1, double x2, - int maxMajSteps, int maxMinSteps, double stepSize) const +QwtScaleDiv QwtLinearScaleEngine::divideScale( double x1, double x2, + int maxMajorSteps, int maxMinorSteps, double stepSize ) const { - QwtDoubleInterval interval = QwtDoubleInterval(x1, x2).normalized(); - if (interval.width() <= 0 ) + QwtInterval interval = QwtInterval( x1, x2 ).normalized(); + if ( interval.width() <= 0 ) return QwtScaleDiv(); - stepSize = qwtAbs(stepSize); - if ( stepSize == 0.0 ) { - if ( maxMajSteps < 1 ) - maxMajSteps = 1; + stepSize = qAbs( stepSize ); + if ( stepSize == 0.0 ) + { + if ( maxMajorSteps < 1 ) + maxMajorSteps = 1; - stepSize = divideInterval(interval.width(), maxMajSteps); + stepSize = QwtScaleArithmetic::divideInterval( + interval.width(), maxMajorSteps, base() ); } QwtScaleDiv scaleDiv; - if ( stepSize != 0.0 ) { - QwtValueList ticks[QwtScaleDiv::NTickTypes]; - buildTicks(interval, stepSize, maxMinSteps, ticks); + if ( stepSize != 0.0 ) + { + QList<double> ticks[QwtScaleDiv::NTickTypes]; + buildTicks( interval, stepSize, maxMinorSteps, ticks ); - scaleDiv = QwtScaleDiv(interval, ticks); + scaleDiv = QwtScaleDiv( interval, ticks ); } if ( x1 > x2 ) @@ -482,72 +610,93 @@ QwtScaleDiv QwtLinearScaleEngine::divideScale(double x1, double x2, return scaleDiv; } +/*! + \brief Calculate ticks for an interval + + \param interval Interval + \param stepSize Step size + \param maxMinorSteps Maximum number of minor steps + \param ticks Arrays to be filled with the calculated ticks + + \sa buildMajorTicks(), buildMinorTicks +*/ void QwtLinearScaleEngine::buildTicks( - const QwtDoubleInterval& interval, double stepSize, int maxMinSteps, - QwtValueList ticks[QwtScaleDiv::NTickTypes]) const + const QwtInterval& interval, double stepSize, int maxMinorSteps, + QList<double> ticks[QwtScaleDiv::NTickTypes] ) const { - const QwtDoubleInterval boundingInterval = - align(interval, stepSize); + const QwtInterval boundingInterval = align( interval, stepSize ); ticks[QwtScaleDiv::MajorTick] = - buildMajorTicks(boundingInterval, stepSize); + buildMajorTicks( boundingInterval, stepSize ); - if ( maxMinSteps > 0 ) { - buildMinorTicks(ticks[QwtScaleDiv::MajorTick], maxMinSteps, stepSize, - ticks[QwtScaleDiv::MinorTick], ticks[QwtScaleDiv::MediumTick]); + if ( maxMinorSteps > 0 ) + { + buildMinorTicks( ticks[QwtScaleDiv::MajorTick], maxMinorSteps, stepSize, + ticks[QwtScaleDiv::MinorTick], ticks[QwtScaleDiv::MediumTick] ); } - for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) { - ticks[i] = strip(ticks[i], interval); + for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) + { + ticks[i] = strip( ticks[i], interval ); // ticks very close to 0.0 are // explicitely set to 0.0 - for ( int j = 0; j < (int)ticks[i].count(); j++ ) { - if ( QwtScaleArithmetic::compareEps(ticks[i][j], 0.0, stepSize) == 0 ) + for ( int j = 0; j < ticks[i].count(); j++ ) + { + if ( qwtFuzzyCompare( ticks[i][j], 0.0, stepSize ) == 0 ) ticks[i][j] = 0.0; } } } -QwtValueList QwtLinearScaleEngine::buildMajorTicks( - const QwtDoubleInterval &interval, double stepSize) const +/*! + \brief Calculate major ticks for an interval + + \param interval Interval + \param stepSize Step size + + \return Calculated ticks +*/ +QList<double> QwtLinearScaleEngine::buildMajorTicks( + const QwtInterval &interval, double stepSize ) const { - int numTicks = qRound(interval.width() / stepSize) + 1; -#if 1 + int numTicks = qRound( interval.width() / stepSize ) + 1; if ( numTicks > 10000 ) numTicks = 10000; -#endif - QwtValueList ticks; + QList<double> ticks; ticks += interval.minValue(); - for (int i = 1; i < numTicks - 1; i++) + for ( int i = 1; i < numTicks - 1; i++ ) ticks += interval.minValue() + i * stepSize; ticks += interval.maxValue(); return ticks; } +/*! + \brief Calculate minor/medium ticks for major ticks + + \param majorTicks Major ticks + \param maxMinorSteps Maximum number of minor steps + \param stepSize Step size + \param minorTicks Array to be filled with the calculated minor ticks + \param mediumTicks Array to be filled with the calculated medium ticks + +*/ void QwtLinearScaleEngine::buildMinorTicks( - const QwtValueList& majorTicks, - int maxMinSteps, double stepSize, - QwtValueList &minorTicks, - QwtValueList &mediumTicks) const + const QList<double>& majorTicks, + int maxMinorSteps, double stepSize, + QList<double> &minorTicks, + QList<double> &mediumTicks ) const { - double minStep = divideInterval(stepSize, maxMinSteps); - if (minStep == 0.0) + double minStep = qwtStepSize( stepSize, maxMinorSteps, base() ); + if ( minStep == 0.0 ) return; // # ticks per interval - int numTicks = (int)::ceil(qwtAbs(stepSize / minStep)) - 1; - - // Do the minor steps fit into the interval? - if ( QwtScaleArithmetic::compareEps((numTicks + 1) * qwtAbs(minStep), - qwtAbs(stepSize), stepSize) > 0) { - numTicks = 1; - minStep = stepSize * 0.5; - } + const int numTicks = qCeil( qAbs( stepSize / minStep ) ) - 1; int medIndex = -1; if ( numTicks % 2 ) @@ -555,13 +704,15 @@ void QwtLinearScaleEngine::buildMinorTicks( // calculate minor ticks - for (int i = 0; i < (int)majorTicks.count(); i++) { + for ( int i = 0; i < majorTicks.count(); i++ ) + { double val = majorTicks[i]; - for (int k = 0; k < numTicks; k++) { + for ( int k = 0; k < numTicks; k++ ) + { val += minStep; double alignedValue = val; - if (QwtScaleArithmetic::compareEps(val, 0.0, stepSize) == 0) + if ( qwtFuzzyCompare( val, 0.0, stepSize ) == 0 ) alignedValue = 0.0; if ( k == medIndex ) @@ -583,23 +734,44 @@ void QwtLinearScaleEngine::buildMinorTicks( \return Aligned interval */ -QwtDoubleInterval QwtLinearScaleEngine::align( - const QwtDoubleInterval &interval, double stepSize) const +QwtInterval QwtLinearScaleEngine::align( + const QwtInterval &interval, double stepSize ) const { - const double x1 = - QwtScaleArithmetic::floorEps(interval.minValue(), stepSize); - const double x2 = - QwtScaleArithmetic::ceilEps(interval.maxValue(), stepSize); + double x1 = interval.minValue(); + double x2 = interval.maxValue(); + + if ( -DBL_MAX + stepSize <= x1 ) + { + const double x = QwtScaleArithmetic::floorEps( x1, stepSize ); + if ( qwtFuzzyCompare( x1, x, stepSize ) != 0 ) + x1 = x; + } - return QwtDoubleInterval(x1, x2); + if ( DBL_MAX - stepSize >= x2 ) + { + const double x = QwtScaleArithmetic::ceilEps( x2, stepSize ); + if ( qwtFuzzyCompare( x2, x, stepSize ) != 0 ) + x2 = x; + } + + return QwtInterval( x1, x2 ); } /*! - Return a transformation, for logarithmic (base 10) scales -*/ -QwtScaleTransformation *QwtLog10ScaleEngine::transformation() const + Constructor + + \param base Base of the scale engine + \sa setBase() + */ +QwtLogScaleEngine::QwtLogScaleEngine( uint base ): + QwtScaleEngine( base ) +{ + setTransformation( new QwtLogTransform() ); +} + +//! Destructor +QwtLogScaleEngine::~QwtLogScaleEngine() { - return new QwtScaleTransformation(QwtScaleTransformation::Log10); } /*! @@ -610,100 +782,145 @@ QwtScaleTransformation *QwtLog10ScaleEngine::transformation() const \param x2 Second limit of the interval (In/Out) \param stepSize Step size (Out) - \sa QwtScaleEngine::setAttribute + \sa QwtScaleEngine::setAttribute() */ -void QwtLog10ScaleEngine::autoScale(int maxNumSteps, - double &x1, double &x2, double &stepSize) const +void QwtLogScaleEngine::autoScale( int maxNumSteps, + double &x1, double &x2, double &stepSize ) const { if ( x1 > x2 ) - qSwap(x1, x2); + qSwap( x1, x2 ); - QwtDoubleInterval interval(x1 / pow(10.0, loMargin()), - x2 * pow(10.0, hiMargin()) ); + const double logBase = base(); - double logRef = 1.0; - if (reference() > LOG_MIN / 2) - logRef = qwtMin(reference(), LOG_MAX / 2); + QwtInterval interval( x1 / qPow( logBase, lowerMargin() ), + x2 * qPow( logBase, upperMargin() ) ); + + if ( interval.maxValue() / interval.minValue() < logBase ) + { + // scale width is less than one step -> try to build a linear scale + + QwtLinearScaleEngine linearScaler; + linearScaler.setAttributes( attributes() ); + linearScaler.setReference( reference() ); + linearScaler.setMargins( lowerMargin(), upperMargin() ); + + linearScaler.autoScale( maxNumSteps, x1, x2, stepSize ); + + QwtInterval linearInterval = QwtInterval( x1, x2 ).normalized(); + linearInterval = linearInterval.limited( LOG_MIN, LOG_MAX ); - if (testAttribute(QwtScaleEngine::Symmetric)) { - const double delta = qwtMax(interval.maxValue() / logRef, - logRef / interval.minValue()); - interval.setInterval(logRef / delta, logRef * delta); + if ( linearInterval.maxValue() / linearInterval.minValue() < logBase ) + { + // the aligned scale is still less than one step + if ( stepSize < 0.0 ) + stepSize = -qwtLog( logBase, qAbs( stepSize ) ); + else + stepSize = qwtLog( logBase, stepSize ); + + return; + } + } + + double logRef = 1.0; + if ( reference() > LOG_MIN / 2 ) + logRef = qMin( reference(), LOG_MAX / 2 ); + + if ( testAttribute( QwtScaleEngine::Symmetric ) ) + { + const double delta = qMax( interval.maxValue() / logRef, + logRef / interval.minValue() ); + interval.setInterval( logRef / delta, logRef * delta ); } - if (testAttribute(QwtScaleEngine::IncludeReference)) - interval = interval.extend(logRef); + if ( testAttribute( QwtScaleEngine::IncludeReference ) ) + interval = interval.extend( logRef ); - interval = interval.limited(LOG_MIN, LOG_MAX); + interval = interval.limited( LOG_MIN, LOG_MAX ); - if (interval.width() == 0.0) - interval = buildInterval(interval.minValue()); + if ( interval.width() == 0.0 ) + interval = buildInterval( interval.minValue() ); - stepSize = divideInterval(log10(interval).width(), qwtMax(maxNumSteps, 1)); + stepSize = divideInterval( qwtLogInterval( logBase, interval ).width(), + qMax( maxNumSteps, 1 ) ); if ( stepSize < 1.0 ) stepSize = 1.0; - if (!testAttribute(QwtScaleEngine::Floating)) - interval = align(interval, stepSize); + if ( !testAttribute( QwtScaleEngine::Floating ) ) + interval = align( interval, stepSize ); x1 = interval.minValue(); x2 = interval.maxValue(); - if (testAttribute(QwtScaleEngine::Inverted)) { - qSwap(x1, x2); + if ( testAttribute( QwtScaleEngine::Inverted ) ) + { + qSwap( x1, x2 ); stepSize = -stepSize; } } /*! - \brief Calculate a scale division + \brief Calculate a scale division for an interval \param x1 First interval limit \param x2 Second interval limit - \param maxMajSteps Maximum for the number of major steps - \param maxMinSteps Maximum number of minor steps - \param stepSize Step size. If stepSize == 0, the scaleEngine + \param maxMajorSteps Maximum for the number of major steps + \param maxMinorSteps Maximum number of minor steps + \param stepSize Step size. If stepSize == 0, the engine calculates one. - \sa QwtScaleEngine::stepSize, QwtLog10ScaleEngine::subDivide + \return Calculated scale division */ -QwtScaleDiv QwtLog10ScaleEngine::divideScale(double x1, double x2, - int maxMajSteps, int maxMinSteps, double stepSize) const +QwtScaleDiv QwtLogScaleEngine::divideScale( double x1, double x2, + int maxMajorSteps, int maxMinorSteps, double stepSize ) const { - QwtDoubleInterval interval = QwtDoubleInterval(x1, x2).normalized(); - interval = interval.limited(LOG_MIN, LOG_MAX); + QwtInterval interval = QwtInterval( x1, x2 ).normalized(); + interval = interval.limited( LOG_MIN, LOG_MAX ); - if (interval.width() <= 0 ) + if ( interval.width() <= 0 ) return QwtScaleDiv(); - if (interval.maxValue() / interval.minValue() < 10.0) { + const double logBase = base(); + + if ( interval.maxValue() / interval.minValue() < logBase ) + { // scale width is less than one decade -> build linear scale QwtLinearScaleEngine linearScaler; - linearScaler.setAttributes(attributes()); - linearScaler.setReference(reference()); - linearScaler.setMargins(loMargin(), hiMargin()); + linearScaler.setAttributes( attributes() ); + linearScaler.setReference( reference() ); + linearScaler.setMargins( lowerMargin(), upperMargin() ); + + if ( stepSize != 0.0 ) + { + if ( stepSize < 0.0 ) + stepSize = -qPow( logBase, -stepSize ); + else + stepSize = qPow( logBase, stepSize ); + } - return linearScaler.divideScale(x1, x2, - maxMajSteps, maxMinSteps, stepSize); + return linearScaler.divideScale( x1, x2, + maxMajorSteps, maxMinorSteps, stepSize ); } - stepSize = qwtAbs(stepSize); - if ( stepSize == 0.0 ) { - if ( maxMajSteps < 1 ) - maxMajSteps = 1; + stepSize = qAbs( stepSize ); + if ( stepSize == 0.0 ) + { + if ( maxMajorSteps < 1 ) + maxMajorSteps = 1; - stepSize = divideInterval(log10(interval).width(), maxMajSteps); + stepSize = divideInterval( + qwtLogInterval( logBase, interval ).width(), maxMajorSteps ); if ( stepSize < 1.0 ) stepSize = 1.0; // major step must be >= 1 decade } QwtScaleDiv scaleDiv; - if ( stepSize != 0.0 ) { - QwtValueList ticks[QwtScaleDiv::NTickTypes]; - buildTicks(interval, stepSize, maxMinSteps, ticks); + if ( stepSize != 0.0 ) + { + QList<double> ticks[QwtScaleDiv::NTickTypes]; + buildTicks( interval, stepSize, maxMinorSteps, ticks ); - scaleDiv = QwtScaleDiv(interval, ticks); + scaleDiv = QwtScaleDiv( interval, ticks ); } if ( x1 > x2 ) @@ -712,120 +929,164 @@ QwtScaleDiv QwtLog10ScaleEngine::divideScale(double x1, double x2, return scaleDiv; } -void QwtLog10ScaleEngine::buildTicks( - const QwtDoubleInterval& interval, double stepSize, int maxMinSteps, - QwtValueList ticks[QwtScaleDiv::NTickTypes]) const +/*! + \brief Calculate ticks for an interval + + \param interval Interval + \param maxMinorSteps Maximum number of minor steps + \param stepSize Step size + \param ticks Arrays to be filled with the calculated ticks + + \sa buildMajorTicks(), buildMinorTicks +*/ +void QwtLogScaleEngine::buildTicks( + const QwtInterval& interval, double stepSize, int maxMinorSteps, + QList<double> ticks[QwtScaleDiv::NTickTypes] ) const { - const QwtDoubleInterval boundingInterval = - align(interval, stepSize); + const QwtInterval boundingInterval = align( interval, stepSize ); ticks[QwtScaleDiv::MajorTick] = - buildMajorTicks(boundingInterval, stepSize); + buildMajorTicks( boundingInterval, stepSize ); - if ( maxMinSteps > 0 ) { - ticks[QwtScaleDiv::MinorTick] = buildMinorTicks( - ticks[QwtScaleDiv::MajorTick], maxMinSteps, stepSize); + if ( maxMinorSteps > 0 ) + { + buildMinorTicks( ticks[QwtScaleDiv::MajorTick], maxMinorSteps, stepSize, + ticks[QwtScaleDiv::MinorTick], ticks[QwtScaleDiv::MediumTick] ); } for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) - ticks[i] = strip(ticks[i], interval); + ticks[i] = strip( ticks[i], interval ); } -QwtValueList QwtLog10ScaleEngine::buildMajorTicks( - const QwtDoubleInterval &interval, double stepSize) const +/*! + \brief Calculate major ticks for an interval + + \param interval Interval + \param stepSize Step size + + \return Calculated ticks +*/ +QList<double> QwtLogScaleEngine::buildMajorTicks( + const QwtInterval &interval, double stepSize ) const { - double width = log10(interval).width(); + double width = qwtLogInterval( base(), interval ).width(); - int numTicks = qRound(width / stepSize) + 1; + int numTicks = qRound( width / stepSize ) + 1; if ( numTicks > 10000 ) numTicks = 10000; - const double lxmin = log(interval.minValue()); - const double lxmax = log(interval.maxValue()); - const double lstep = (lxmax - lxmin) / double(numTicks - 1); + const double lxmin = ::log( interval.minValue() ); + const double lxmax = ::log( interval.maxValue() ); + const double lstep = ( lxmax - lxmin ) / double( numTicks - 1 ); - QwtValueList ticks; + QList<double> ticks; ticks += interval.minValue(); - for (int i = 1; i < numTicks; i++) - ticks += exp(lxmin + double(i) * lstep); + for ( int i = 1; i < numTicks - 1; i++ ) + ticks += qExp( lxmin + double( i ) * lstep ); ticks += interval.maxValue(); return ticks; } -QwtValueList QwtLog10ScaleEngine::buildMinorTicks( - const QwtValueList &majorTicks, - int maxMinSteps, double stepSize) const -{ - if (stepSize < 1.1) { // major step width is one decade - if ( maxMinSteps < 1 ) - return QwtValueList(); - - int k0, kstep, kmax; - - if (maxMinSteps >= 8) { - k0 = 2; - kmax = 9; - kstep = 1; - } else if (maxMinSteps >= 4) { - k0 = 2; - kmax = 8; - kstep = 2; - } else if (maxMinSteps >= 2) { - k0 = 2; - kmax = 5; - kstep = 3; - } else { - k0 = 5; - kmax = 5; - kstep = 1; - } +/*! + \brief Calculate minor/medium ticks for major ticks - QwtValueList minorTicks; + \param majorTicks Major ticks + \param maxMinorSteps Maximum number of minor steps + \param stepSize Step size + \param minorTicks Array to be filled with the calculated minor ticks + \param mediumTicks Array to be filled with the calculated medium ticks +*/ +void QwtLogScaleEngine::buildMinorTicks( + const QList<double> &majorTicks, + int maxMinorSteps, double stepSize, + QList<double> &minorTicks, + QList<double> &mediumTicks ) const +{ + const double logBase = base(); - for (int i = 0; i < (int)majorTicks.count(); i++) { + if ( stepSize < 1.1 ) // major step width is one base + { + double minStep = divideInterval( stepSize, maxMinorSteps + 1 ); + if ( minStep == 0.0 ) + return; + + const int numSteps = qRound( stepSize / minStep ); + + int mediumTickIndex = -1; + if ( ( numSteps > 2 ) && ( numSteps % 2 == 0 ) ) + mediumTickIndex = numSteps / 2; + + for ( int i = 0; i < majorTicks.count() - 1; i++ ) + { const double v = majorTicks[i]; - for (int k = k0; k<= kmax; k+=kstep) - minorTicks += v * double(k); + const double s = logBase / numSteps; + + if ( s >= 1.0 ) + { + for ( int j = 2; j < numSteps; j++ ) + { + minorTicks += v * j * s; + } + } + else + { + for ( int j = 1; j < numSteps; j++ ) + { + const double tick = v + j * v * ( logBase - 1 ) / numSteps; + if ( j == mediumTickIndex ) + mediumTicks += tick; + else + minorTicks += tick; + } + } } - - return minorTicks; - } else { // major step > one decade - double minStep = divideInterval(stepSize, maxMinSteps); + } + else + { + double minStep = divideInterval( stepSize, maxMinorSteps ); if ( minStep == 0.0 ) - return QwtValueList(); + return; if ( minStep < 1.0 ) minStep = 1.0; // # subticks per interval - int nMin = qRound(stepSize / minStep) - 1; + int numTicks = qRound( stepSize / minStep ) - 1; // Do the minor steps fit into the interval? - - if ( QwtScaleArithmetic::compareEps((nMin + 1) * minStep, - qwtAbs(stepSize), stepSize) > 0) { - nMin = 0; + if ( qwtFuzzyCompare( ( numTicks + 1 ) * minStep, + stepSize, stepSize ) > 0 ) + { + numTicks = 0; } - if (nMin < 1) - return QwtValueList(); // no subticks + if ( numTicks < 1 ) + return; + + int mediumTickIndex = -1; + if ( ( numTicks > 2 ) && ( numTicks % 2 ) ) + mediumTickIndex = numTicks / 2; + + // substep factor = base^substeps + const qreal minFactor = qMax( qPow( logBase, minStep ), qreal( logBase ) ); - // substep factor = 10^substeps - const double minFactor = qwtMax(pow(10.0, minStep), 10.0); + for ( int i = 0; i < majorTicks.count(); i++ ) + { + double tick = majorTicks[i]; + for ( int j = 0; j < numTicks; j++ ) + { + tick *= minFactor; - QwtValueList minorTicks; - for (int i = 0; i < (int)majorTicks.count(); i++) { - double val = majorTicks[i]; - for (int k=0; k< nMin; k++) { - val *= minFactor; - minorTicks += val; + if ( j == mediumTickIndex ) + mediumTicks += tick; + else + minorTicks += tick; } } - return minorTicks; } } @@ -840,34 +1101,18 @@ QwtValueList QwtLog10ScaleEngine::buildMinorTicks( \return Aligned interval */ -QwtDoubleInterval QwtLog10ScaleEngine::align( - const QwtDoubleInterval &interval, double stepSize) const +QwtInterval QwtLogScaleEngine::align( + const QwtInterval &interval, double stepSize ) const { - const QwtDoubleInterval intv = log10(interval); + const QwtInterval intv = qwtLogInterval( base(), interval ); - const double x1 = QwtScaleArithmetic::floorEps(intv.minValue(), stepSize); - const double x2 = QwtScaleArithmetic::ceilEps(intv.maxValue(), stepSize); + double x1 = QwtScaleArithmetic::floorEps( intv.minValue(), stepSize ); + if ( qwtFuzzyCompare( interval.minValue(), x1, stepSize ) == 0 ) + x1 = interval.minValue(); - return pow10(QwtDoubleInterval(x1, x2)); -} - -/*! - Return the interval [log10(interval.minValue(), log10(interval.maxValue] -*/ - -QwtDoubleInterval QwtLog10ScaleEngine::log10( - const QwtDoubleInterval &interval) const -{ - return QwtDoubleInterval(::log10(interval.minValue()), - ::log10(interval.maxValue())); -} + double x2 = QwtScaleArithmetic::ceilEps( intv.maxValue(), stepSize ); + if ( qwtFuzzyCompare( interval.maxValue(), x2, stepSize ) == 0 ) + x2 = interval.maxValue(); -/*! - Return the interval [pow10(interval.minValue(), pow10(interval.maxValue] -*/ -QwtDoubleInterval QwtLog10ScaleEngine::pow10( - const QwtDoubleInterval &interval) const -{ - return QwtDoubleInterval(pow(10.0, interval.minValue()), - pow(10.0, interval.maxValue())); + return qwtPowInterval( base(), QwtInterval( x1, x2 ) ); } diff --git a/libs/qwt/qwt_scale_engine.h b/libs/qwt/qwt_scale_engine.h index b98d5b5d6f..30e75fd152 100644 --- a/libs/qwt/qwt_scale_engine.h +++ b/libs/qwt/qwt_scale_engine.h @@ -12,9 +12,9 @@ #include "qwt_global.h" #include "qwt_scale_div.h" -#include "qwt_double_interval.h" +#include "qwt_interval.h" -class QwtScaleTransformation; +class QwtTransform; /*! \brief Arithmetic including a tolerance @@ -22,58 +22,80 @@ class QwtScaleTransformation; class QWT_EXPORT QwtScaleArithmetic { public: - static int compareEps( - double value1, double value2, double intervalSize); + static double ceilEps( double value, double intervalSize ); + static double floorEps( double value, double intervalSize ); - static double ceilEps(double value, double intervalSize); - static double floorEps(double value, double intervalSize); + static double divideEps( double interval, double steps ); - static double divideEps(double interval, double steps); - - static double ceil125(double x); - static double floor125(double x); + static double divideInterval( double interval, + int numSteps, uint base ); }; /*! \brief Base class for scale engines. - A scale engine trys to find "reasonable" ranges and step sizes + A scale engine tries to find "reasonable" ranges and step sizes for scales. The layout of the scale can be varied with setAttribute(). - Qwt offers implementations for logarithmic (log10) - and linear scales. Contributions for other types of scale engines - (date/time, log2 ... ) are welcome. + Qwt offers implementations for logarithmic and linear scales. */ class QWT_EXPORT QwtScaleEngine { public: - //! see QwtScaleEngine::setAttribute, testAttribute - enum Attribute { - NoAttribute = 0, - IncludeReference = 1, - Symmetric = 2, - Floating = 4, - Inverted = 8 + /*! + Layout attributes + \sa setAttribute(), testAttribute(), reference(), + lowerMargin(), upperMargin() + */ + + enum Attribute + { + //! No attributes + NoAttribute = 0x00, + + //! Build a scale which includes the reference() value. + IncludeReference = 0x01, + + //! Build a scale which is symmetric to the reference() value. + Symmetric = 0x02, + + /*! + The endpoints of the scale are supposed to be equal the + outmost included values plus the specified margins + (see setMargins()). + If this attribute is *not* set, the endpoints of the scale will + be integer multiples of the step size. + */ + Floating = 0x04, + + //! Turn the scale upside down. + Inverted = 0x08 }; - explicit QwtScaleEngine(); + //! Layout attributes + typedef QFlags<Attribute> Attributes; + + explicit QwtScaleEngine( uint base = 10 ); virtual ~QwtScaleEngine(); - void setAttribute(Attribute, bool on = true); - bool testAttribute(Attribute) const; + void setBase( uint base ); + uint base() const; + + void setAttribute( Attribute, bool on = true ); + bool testAttribute( Attribute ) const; - void setAttributes(int); - int attributes() const; + void setAttributes( Attributes ); + Attributes attributes() const; - void setReference(double reference); + void setReference( double reference ); double reference() const; - void setMargins(double m1, double m2); - double loMargin() const; - double hiMargin() const; + void setMargins( double lower, double upper ); + double lowerMargin() const; + double upperMargin() const; /*! Align and divide an interval @@ -83,32 +105,35 @@ public: \param x2 Second limit of the interval (In/Out) \param stepSize Step size (Return value) */ - virtual void autoScale(int maxNumSteps, - double &x1, double &x2, double &stepSize) const = 0; + virtual void autoScale( int maxNumSteps, + double &x1, double &x2, double &stepSize ) const = 0; /*! \brief Calculate a scale division \param x1 First interval limit \param x2 Second interval limit - \param maxMajSteps Maximum for the number of major steps - \param maxMinSteps Maximum number of minor steps + \param maxMajorSteps Maximum for the number of major steps + \param maxMinorSteps Maximum number of minor steps \param stepSize Step size. If stepSize == 0.0, the scaleEngine calculates one. + + \return Calculated scale division */ - virtual QwtScaleDiv divideScale(double x1, double x2, - int maxMajSteps, int maxMinSteps, - double stepSize = 0.0) const = 0; + virtual QwtScaleDiv divideScale( double x1, double x2, + int maxMajorSteps, int maxMinorSteps, + double stepSize = 0.0 ) const = 0; - //! \return a transformation - virtual QwtScaleTransformation *transformation() const = 0; + void setTransformation( QwtTransform * ); + QwtTransform *transformation() const; protected: - bool contains(const QwtDoubleInterval &, double val) const; - QwtValueList strip(const QwtValueList&, const QwtDoubleInterval &) const; - double divideInterval(double interval, int numSteps) const; + bool contains( const QwtInterval &, double val ) const; + QList<double> strip( const QList<double>&, const QwtInterval & ) const; + + double divideInterval( double interval, int numSteps ) const; - QwtDoubleInterval buildInterval(double v) const; + QwtInterval buildInterval( double v ) const; private: class PrivateData; @@ -125,35 +150,34 @@ private: class QWT_EXPORT QwtLinearScaleEngine: public QwtScaleEngine { public: - virtual void autoScale(int maxSteps, - double &x1, double &x2, double &stepSize) const; + QwtLinearScaleEngine( uint base = 10 ); + virtual ~QwtLinearScaleEngine(); - virtual QwtScaleDiv divideScale(double x1, double x2, - int numMajorSteps, int numMinorSteps, - double stepSize = 0.0) const; + virtual void autoScale( int maxSteps, + double &x1, double &x2, double &stepSize ) const; + + virtual QwtScaleDiv divideScale( double x1, double x2, + int numMajorSteps, int numMinorSteps, + double stepSize = 0.0 ) const; - virtual QwtScaleTransformation *transformation() const; protected: - QwtDoubleInterval align(const QwtDoubleInterval&, - double stepSize) const; + QwtInterval align( const QwtInterval&, double stepSize ) const; -private: void buildTicks( - const QwtDoubleInterval &, double stepSize, int maxMinSteps, - QwtValueList ticks[QwtScaleDiv::NTickTypes]) const; + const QwtInterval &, double stepSize, int maxMinSteps, + QList<double> ticks[QwtScaleDiv::NTickTypes] ) const; - void buildMinorTicks( - const QwtValueList& majorTicks, - int maxMinMark, double step, - QwtValueList &, QwtValueList &) const; + QList<double> buildMajorTicks( + const QwtInterval &interval, double stepSize ) const; - QwtValueList buildMajorTicks( - const QwtDoubleInterval &interval, double stepSize) const; + void buildMinorTicks( const QList<double>& majorTicks, + int maxMinorSteps, double stepSize, + QList<double> &minorTicks, QList<double> &mediumTicks ) const; }; /*! - \brief A scale engine for logarithmic (base 10) scales + \brief A scale engine for logarithmic scales The step size is measured in *decades* and the major step size will be adjusted to fit the pattern @@ -163,36 +187,34 @@ private: \warning the step size as well as the margins are measured in *decades*. */ -class QWT_EXPORT QwtLog10ScaleEngine: public QwtScaleEngine +class QWT_EXPORT QwtLogScaleEngine: public QwtScaleEngine { public: - virtual void autoScale(int maxSteps, - double &x1, double &x2, double &stepSize) const; + QwtLogScaleEngine( uint base = 10 ); + virtual ~QwtLogScaleEngine(); - virtual QwtScaleDiv divideScale(double x1, double x2, - int numMajorSteps, int numMinorSteps, - double stepSize = 0.0) const; + virtual void autoScale( int maxSteps, + double &x1, double &x2, double &stepSize ) const; - virtual QwtScaleTransformation *transformation() const; + virtual QwtScaleDiv divideScale( double x1, double x2, + int numMajorSteps, int numMinorSteps, + double stepSize = 0.0 ) const; protected: - QwtDoubleInterval log10(const QwtDoubleInterval&) const; - QwtDoubleInterval pow10(const QwtDoubleInterval&) const; - -private: - QwtDoubleInterval align(const QwtDoubleInterval&, - double stepSize) const; + QwtInterval align( const QwtInterval&, double stepSize ) const; void buildTicks( - const QwtDoubleInterval &, double stepSize, int maxMinSteps, - QwtValueList ticks[QwtScaleDiv::NTickTypes]) const; + const QwtInterval &, double stepSize, int maxMinSteps, + QList<double> ticks[QwtScaleDiv::NTickTypes] ) const; - QwtValueList buildMinorTicks( - const QwtValueList& majorTicks, - int maxMinMark, double step) const; + QList<double> buildMajorTicks( + const QwtInterval &interval, double stepSize ) const; - QwtValueList buildMajorTicks( - const QwtDoubleInterval &interval, double stepSize) const; + void buildMinorTicks( const QList<double>& majorTicks, + int maxMinorSteps, double stepSize, + QList<double> &minorTicks, QList<double> &mediumTicks ) const; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtScaleEngine::Attributes ) + #endif diff --git a/libs/qwt/qwt_scale_map.cpp b/libs/qwt/qwt_scale_map.cpp index ed32b70a62..c3fbad696f 100644 --- a/libs/qwt/qwt_scale_map.cpp +++ b/libs/qwt/qwt_scale_map.cpp @@ -8,73 +8,9 @@ *****************************************************************************/ #include "qwt_scale_map.h" - -QT_STATIC_CONST_IMPL double QwtScaleMap::LogMin = 1.0e-150; -QT_STATIC_CONST_IMPL double QwtScaleMap::LogMax = 1.0e150; - -//! Constructor for a linear transformation -QwtScaleTransformation::QwtScaleTransformation(Type type): - d_type(type) -{ -} - -QwtScaleTransformation::~QwtScaleTransformation() -{ -} - -QwtScaleTransformation *QwtScaleTransformation::copy() const -{ - return new QwtScaleTransformation(d_type); -} - -/*! - \brief Transform a value between 2 linear intervals - - \param x value related to the interval [x1, x2] - \param x1 first border of source interval - \param x2 first border of source interval - \param y1 first border of target interval - \param y2 first border of target interval - \return - <dl> - <dt>linear mapping:<dd>y1 + (y2 - y1) / (x2 - x1) * (x - x1)</dd> - </dl> - <dl> - <dt>log10 mapping: <dd>p1 + (p2 - p1) / log(s2 / s1) * log(x / s1)</dd> - </dl> -*/ - -double QwtScaleTransformation::xForm( - double s, double s1, double s2, double p1, double p2) const -{ - if ( d_type == Log10 ) - return p1 + (p2 - p1) / log(s2 / s1) * log(s / s1); - else - return p1 + (p2 - p1) / (s2 - s1) * (s - s1); -} - -/*! - \brief Transform a value from a linear to a logarithmic interval - - \param x value related to the linear interval [p1, p2] - \param p1 first border of linear interval - \param p2 first border of linear interval - \param s1 first border of logarithmic interval - \param s2 first border of logarithmic interval - \return - <dl> - <dt>exp((x - p1) / (p2 - p1) * log(s2 / s1)) * s1; - </dl> -*/ - -double QwtScaleTransformation::invXForm(double p, double p1, double p2, - double s1, double s2) const -{ - if ( d_type == Log10 ) - return exp((p - p1) / (p2 - p1) * log(s2 / s1)) * s1; - else - return s1 + (s2 - s1) / (p2 - p1) * (p - p1); -} +#include "qwt_math.h" +#include <qrect.h> +#include <qdebug.h> /*! \brief Constructor @@ -82,24 +18,28 @@ double QwtScaleTransformation::invXForm(double p, double p1, double p2, The scale and paint device intervals are both set to [0,1]. */ QwtScaleMap::QwtScaleMap(): - d_s1(0.0), - d_s2(1.0), - d_p1(0.0), - d_p2(1.0), - d_cnv(1.0) + d_s1( 0.0 ), + d_s2( 1.0 ), + d_p1( 0.0 ), + d_p2( 1.0 ), + d_cnv( 1.0 ), + d_ts1( 0.0 ), + d_transform( NULL ) { - d_transformation = new QwtScaleTransformation( - QwtScaleTransformation::Linear); } -QwtScaleMap::QwtScaleMap(const QwtScaleMap& other): - d_s1(other.d_s1), - d_s2(other.d_s2), - d_p1(other.d_p1), - d_p2(other.d_p2), - d_cnv(other.d_cnv) +//! Copy constructor +QwtScaleMap::QwtScaleMap( const QwtScaleMap& other ): + d_s1( other.d_s1 ), + d_s2( other.d_s2 ), + d_p1( other.d_p1 ), + d_p2( other.d_p2 ), + d_cnv( other.d_cnv ), + d_ts1( other.d_ts1 ), + d_transform( NULL ) { - d_transformation = other.d_transformation->copy(); + if ( other.d_transform ) + d_transform = other.d_transform->copy(); } /*! @@ -107,19 +47,24 @@ QwtScaleMap::QwtScaleMap(const QwtScaleMap& other): */ QwtScaleMap::~QwtScaleMap() { - delete d_transformation; + delete d_transform; } -QwtScaleMap &QwtScaleMap::operator=(const QwtScaleMap &other) +//! Assignment operator +QwtScaleMap &QwtScaleMap::operator=( const QwtScaleMap & other ) { d_s1 = other.d_s1; d_s2 = other.d_s2; d_p1 = other.d_p1; d_p2 = other.d_p2; d_cnv = other.d_cnv; + d_ts1 = other.d_ts1; - delete d_transformation; - d_transformation = other.d_transformation->copy(); + delete d_transform; + d_transform = NULL; + + if ( other.d_transform ) + d_transform = other.d_transform->copy(); return *this; } @@ -127,48 +72,42 @@ QwtScaleMap &QwtScaleMap::operator=(const QwtScaleMap &other) /*! Initialize the map with a transformation */ -void QwtScaleMap::setTransformation( - QwtScaleTransformation *transformation) +void QwtScaleMap::setTransformation( QwtTransform *transform ) { - if ( transformation == NULL ) - return; + if ( transform != d_transform ) + { + delete d_transform; + d_transform = transform; + } - delete d_transformation; - d_transformation = transformation; - setScaleInterval(d_s1, d_s2); + setScaleInterval( d_s1, d_s2 ); } //! Get the transformation -const QwtScaleTransformation *QwtScaleMap::transformation() const +const QwtTransform *QwtScaleMap::transformation() const { - return d_transformation; + return d_transform; } /*! \brief Specify the borders of the scale interval \param s1 first border \param s2 second border - \warning logarithmic scales might be aligned to [LogMin, LogMax] + \warning scales might be aligned to + transformation depending boundaries */ -void QwtScaleMap::setScaleInterval(double s1, double s2) +void QwtScaleMap::setScaleInterval( double s1, double s2 ) { - if (d_transformation->type() == QwtScaleTransformation::Log10 ) { - if (s1 < LogMin) - s1 = LogMin; - else if (s1 > LogMax) - s1 = LogMax; - - if (s2 < LogMin) - s2 = LogMin; - else if (s2 > LogMax) - s2 = LogMax; - } - d_s1 = s1; d_s2 = s2; - if ( d_transformation->type() != QwtScaleTransformation::Other ) - newFactor(); + if ( d_transform ) + { + d_s1 = d_transform->bounded( d_s1 ); + d_s2 = d_transform->bounded( d_s2 ); + } + + updateFactor(); } /*! @@ -176,48 +115,134 @@ void QwtScaleMap::setScaleInterval(double s1, double s2) \param p1 first border \param p2 second border */ -void QwtScaleMap::setPaintInterval(int p1, int p2) +void QwtScaleMap::setPaintInterval( double p1, double p2 ) { d_p1 = p1; d_p2 = p2; - if ( d_transformation->type() != QwtScaleTransformation::Other ) - newFactor(); + updateFactor(); +} + +void QwtScaleMap::updateFactor() +{ + d_ts1 = d_s1; + double ts2 = d_s2; + + if ( d_transform ) + { + d_ts1 = d_transform->transform( d_ts1 ); + ts2 = d_transform->transform( ts2 ); + } + + d_cnv = 1.0; + if ( d_ts1 != ts2 ) + d_cnv = ( d_p2 - d_p1 ) / ( ts2 - d_ts1 ); } /*! - \brief Specify the borders of the paint device interval - \param p1 first border - \param p2 second border + Transform a rectangle from scale to paint coordinates + + \param xMap X map + \param yMap Y map + \param rect Rectangle in scale coordinates + \return Rectangle in paint coordinates + + \sa invTransform() */ -void QwtScaleMap::setPaintXInterval(double p1, double p2) +QRectF QwtScaleMap::transform( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QRectF &rect ) { - d_p1 = p1; - d_p2 = p2; + double x1 = xMap.transform( rect.left() ); + double x2 = xMap.transform( rect.right() ); + double y1 = yMap.transform( rect.top() ); + double y2 = yMap.transform( rect.bottom() ); + + if ( x2 < x1 ) + qSwap( x1, x2 ); + if ( y2 < y1 ) + qSwap( y1, y2 ); + + if ( qwtFuzzyCompare( x1, 0.0, x2 - x1 ) == 0 ) + x1 = 0.0; + if ( qwtFuzzyCompare( x2, 0.0, x2 - x1 ) == 0 ) + x2 = 0.0; + if ( qwtFuzzyCompare( y1, 0.0, y2 - y1 ) == 0 ) + y1 = 0.0; + if ( qwtFuzzyCompare( y2, 0.0, y2 - y1 ) == 0 ) + y2 = 0.0; + + return QRectF( x1, y1, x2 - x1 + 1, y2 - y1 + 1 ); +} + +/*! + Transform a rectangle from paint to scale coordinates - if ( d_transformation->type() != QwtScaleTransformation::Other ) - newFactor(); + \param xMap X map + \param yMap Y map + \param pos Position in paint coordinates + \return Position in scale coordinates + \sa transform() +*/ +QPointF QwtScaleMap::invTransform( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QPointF &pos ) +{ + return QPointF( + xMap.invTransform( pos.x() ), + yMap.invTransform( pos.y() ) + ); } /*! - \brief Re-calculate the conversion factor. + Transform a point from scale to paint coordinates + + \param xMap X map + \param yMap Y map + \param pos Position in scale coordinates + \return Position in paint coordinates + + \sa invTransform() */ -void QwtScaleMap::newFactor() +QPointF QwtScaleMap::transform( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QPointF &pos ) { - d_cnv = 0.0; -#if 1 - if (d_s2 == d_s1) - return; -#endif + return QPointF( + xMap.transform( pos.x() ), + yMap.transform( pos.y() ) + ); +} - switch( d_transformation->type() ) { - case QwtScaleTransformation::Linear: - d_cnv = (d_p2 - d_p1) / (d_s2 - d_s1); - break; - case QwtScaleTransformation::Log10: - d_cnv = (d_p2 - d_p1) / log(d_s2 / d_s1); - break; - default: - ; - } +/*! + Transform a rectangle from paint to scale coordinates + + \param xMap X map + \param yMap Y map + \param rect Rectangle in paint coordinates + \return Rectangle in scale coordinates + \sa transform() +*/ +QRectF QwtScaleMap::invTransform( const QwtScaleMap &xMap, + const QwtScaleMap &yMap, const QRectF &rect ) +{ + const double x1 = xMap.invTransform( rect.left() ); + const double x2 = xMap.invTransform( rect.right() - 1 ); + const double y1 = yMap.invTransform( rect.top() ); + const double y2 = yMap.invTransform( rect.bottom() - 1 ); + + const QRectF r( x1, y1, x2 - x1, y2 - y1 ); + return r.normalized(); } + +#ifndef QT_NO_DEBUG_STREAM + +QDebug operator<<( QDebug debug, const QwtScaleMap &map ) +{ + debug.nospace() << "QwtScaleMap(" + << map.transformation() + << ", s:" << map.s1() << "->" << map.s2() + << ", p:" << map.p1() << "->" << map.p2() + << ")"; + + return debug.space(); +} + +#endif diff --git a/libs/qwt/qwt_scale_map.h b/libs/qwt/qwt_scale_map.h index ed674bdd07..c07f1ce7db 100644 --- a/libs/qwt/qwt_scale_map.h +++ b/libs/qwt/qwt_scale_map.h @@ -11,91 +11,72 @@ #define QWT_SCALE_MAP_H #include "qwt_global.h" -#include "qwt_math.h" +#include "qwt_transform.h" +#include <qrect.h> -/*! - \brief Operations for linear or logarithmic (base 10) transformations -*/ -class QWT_EXPORT QwtScaleTransformation -{ -public: - enum Type { - Linear, - Log10, - - Other - }; - - QwtScaleTransformation(Type type); - virtual ~QwtScaleTransformation(); - - virtual double xForm(double x, double s1, double s2, - double p1, double p2) const; - virtual double invXForm(double x, double s1, double s2, - double p1, double p2) const; - - inline Type type() const { - return d_type; - } - - virtual QwtScaleTransformation *copy() const; - -private: - QwtScaleTransformation(); - QwtScaleTransformation &operator=( const QwtScaleTransformation); +#ifndef QT_NO_DEBUG_STREAM +#include <qdebug.h> +#endif - const Type d_type; -}; +class QRectF; /*! \brief A scale map - QwtScaleMap offers transformations from a scale - into a paint interval and vice versa. + QwtScaleMap offers transformations from the coordinate system + of a scale into the linear coordinate system of a paint device + and vice versa. */ class QWT_EXPORT QwtScaleMap { public: QwtScaleMap(); - QwtScaleMap(const QwtScaleMap&); + QwtScaleMap( const QwtScaleMap& ); ~QwtScaleMap(); - QwtScaleMap &operator=(const QwtScaleMap &); + QwtScaleMap &operator=( const QwtScaleMap & ); + + void setTransformation( QwtTransform * ); + const QwtTransform *transformation() const; - void setTransformation(QwtScaleTransformation * ); - const QwtScaleTransformation *transformation() const; + void setPaintInterval( double p1, double p2 ); + void setScaleInterval( double s1, double s2 ); - void setPaintInterval(int p1, int p2); - void setPaintXInterval(double p1, double p2); - void setScaleInterval(double s1, double s2); + double transform( double s ) const; + double invTransform( double p ) const; - int transform(double x) const; - double invTransform(double i) const; + double p1() const; + double p2() const; - double xTransform(double x) const; + double s1() const; + double s2() const; - inline double p1() const; - inline double p2() const; + double pDist() const; + double sDist() const; - inline double s1() const; - inline double s2() const; + static QRectF transform( const QwtScaleMap &, + const QwtScaleMap &, const QRectF & ); + static QRectF invTransform( const QwtScaleMap &, + const QwtScaleMap &, const QRectF & ); - inline double pDist() const; - inline double sDist() const; + static QPointF transform( const QwtScaleMap &, + const QwtScaleMap &, const QPointF & ); + static QPointF invTransform( const QwtScaleMap &, + const QwtScaleMap &, const QPointF & ); - QT_STATIC_CONST double LogMin; - QT_STATIC_CONST double LogMax; + bool isInverting() const; private: - void newFactor(); + void updateFactor(); double d_s1, d_s2; // scale interval boundaries double d_p1, d_p2; // paint device interval boundaries double d_cnv; // conversion factor + double d_ts1; - QwtScaleTransformation *d_transformation; + QwtTransform *d_transform; }; /*! @@ -130,52 +111,65 @@ inline double QwtScaleMap::p2() const return d_p2; } +/*! + \return qwtAbs(p2() - p1()) +*/ inline double QwtScaleMap::pDist() const { - return qwtAbs(d_p2 - d_p1); + return qAbs( d_p2 - d_p1 ); } +/*! + \return qwtAbs(s2() - s1()) +*/ inline double QwtScaleMap::sDist() const { - return qwtAbs(d_s2 - d_s1); + return qAbs( d_s2 - d_s1 ); } /*! Transform a point related to the scale interval into an point related to the interval of the paint device -*/ -inline double QwtScaleMap::xTransform(double s) const -{ - // try to inline code from QwtScaleTransformation - if ( d_transformation->type() == QwtScaleTransformation::Linear ) - return d_p1 + (s - d_s1) * d_cnv; + \param s Value relative to the coordinates of the scale + \return Transformed value - if ( d_transformation->type() == QwtScaleTransformation::Log10 ) - return d_p1 + log(s / d_s1) * d_cnv; + \sa invTransform() +*/ +inline double QwtScaleMap::transform( double s ) const +{ + if ( d_transform ) + s = d_transform->transform( s ); - return d_transformation->xForm(s, d_s1, d_s2, d_p1, d_p2 ); + return d_p1 + ( s - d_ts1 ) * d_cnv; } /*! - \brief Transform an paint device value into a value in the - interval of the scale. + Transform an paint device value into a value in the + interval of the scale. + + \param p Value relative to the coordinates of the paint device + \return Transformed value + + \sa transform() */ -inline double QwtScaleMap::invTransform(double p) const +inline double QwtScaleMap::invTransform( double p ) const { - return d_transformation->invXForm(p, d_p1, d_p2, d_s1, d_s2 ); -} + double s = d_ts1 + ( p - d_p1 ) / d_cnv; + if ( d_transform ) + s = d_transform->invTransform( s ); -/*! - Transform a point related to the scale interval into an point - related to the interval of the paint device and round it to - an integer. (In Qt <= 3.x paint devices are integer based. ) + return s; +} - \sa QwtScaleMap::xTransform -*/ -inline int QwtScaleMap::transform(double s) const +//! \return True, when ( p1() < p2() ) != ( s1() < s2() ) +inline bool QwtScaleMap::isInverting() const { - return qRound(xTransform(s)); + return ( ( d_p1 < d_p2 ) != ( d_s1 < d_s2 ) ); } +#ifndef QT_NO_DEBUG_STREAM +QWT_EXPORT QDebug operator<<( QDebug, const QwtScaleMap & ); +#endif + #endif diff --git a/libs/qwt/qwt_scale_widget.cpp b/libs/qwt/qwt_scale_widget.cpp index f1705ec413..d34ada52a3 100644 --- a/libs/qwt/qwt_scale_widget.cpp +++ b/libs/qwt/qwt_scale_widget.cpp @@ -7,28 +7,31 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <qpainter.h> -#include <qevent.h> +#include "qwt_scale_widget.h" #include "qwt_painter.h" #include "qwt_color_map.h" -#include "qwt_scale_widget.h" #include "qwt_scale_map.h" #include "qwt_math.h" -#include "qwt_paint_buffer.h" #include "qwt_scale_div.h" #include "qwt_text.h" +#include "qwt_scale_engine.h" +#include <qpainter.h> +#include <qevent.h> +#include <qmath.h> +#include <qstyle.h> +#include <qstyleoption.h> class QwtScaleWidget::PrivateData { public: PrivateData(): - scaleDraw(NULL) { + scaleDraw( NULL ) + { colorBar.colorMap = NULL; } - ~PrivateData() { + ~PrivateData() + { delete scaleDraw; delete colorBar.colorMap; } @@ -39,16 +42,18 @@ public: int minBorderDist[2]; int scaleLength; int margin; - int penWidth; int titleOffset; int spacing; QwtText title; - struct t_colorBar { + QwtScaleWidget::LayoutFlags layoutFlags; + + struct t_colorBar + { bool isEnabled; int width; - QwtDoubleInterval interval; + QwtInterval interval; QwtColorMap *colorMap; } colorBar; }; @@ -57,24 +62,11 @@ public: \brief Create a scale with the position QwtScaleWidget::Left \param parent Parent widget */ -QwtScaleWidget::QwtScaleWidget(QWidget *parent): - QWidget(parent) -{ - initScale(QwtScaleDraw::LeftScale); -} - -#if QT_VERSION < 0x040000 -/*! - \brief Create a scale with the position QwtScaleWidget::Left - \param parent Parent widget - \param name Object name -*/ -QwtScaleWidget::QwtScaleWidget(QWidget *parent, const char *name): - QWidget(parent, name) +QwtScaleWidget::QwtScaleWidget( QWidget *parent ): + QWidget( parent ) { - initScale(QwtScaleDraw::LeftScale); + initScale( QwtScaleDraw::LeftScale ); } -#endif /*! \brief Constructor @@ -82,10 +74,10 @@ QwtScaleWidget::QwtScaleWidget(QWidget *parent, const char *name): \param parent Parent widget */ QwtScaleWidget::QwtScaleWidget( - QwtScaleDraw::Alignment align, QWidget *parent): - QWidget(parent) + QwtScaleDraw::Alignment align, QWidget *parent ): + QWidget( parent ) { - initScale(align); + initScale( align ); } //! Destructor @@ -95,78 +87,111 @@ QwtScaleWidget::~QwtScaleWidget() } //! Initialize the scale -void QwtScaleWidget::initScale(QwtScaleDraw::Alignment align) +void QwtScaleWidget::initScale( QwtScaleDraw::Alignment align ) { d_data = new PrivateData; -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#endif + d_data->layoutFlags = 0; + if ( align == QwtScaleDraw::RightScale ) + d_data->layoutFlags |= TitleInverted; d_data->borderDist[0] = 0; d_data->borderDist[1] = 0; d_data->minBorderDist[0] = 0; d_data->minBorderDist[1] = 0; d_data->margin = 4; - d_data->penWidth = 0; d_data->titleOffset = 0; d_data->spacing = 2; d_data->scaleDraw = new QwtScaleDraw; - d_data->scaleDraw->setAlignment(align); - d_data->scaleDraw->setLength(10); + d_data->scaleDraw->setAlignment( align ); + d_data->scaleDraw->setLength( 10 ); + + d_data->scaleDraw->setScaleDiv( + QwtLinearScaleEngine().divideScale( 0.0, 100.0, 10, 5 ) ); d_data->colorBar.colorMap = new QwtLinearColorMap(); d_data->colorBar.isEnabled = false; d_data->colorBar.width = 10; const int flags = Qt::AlignHCenter -#if QT_VERSION < 0x040000 - | Qt::WordBreak | Qt::ExpandTabs; -#else - | Qt::TextExpandTabs | Qt::TextWordWrap; -#endif - d_data->title.setRenderFlags(flags); - d_data->title.setFont(font()); - - QSizePolicy policy(QSizePolicy::MinimumExpanding, - QSizePolicy::Fixed); + | Qt::TextExpandTabs | Qt::TextWordWrap; + d_data->title.setRenderFlags( flags ); + d_data->title.setFont( font() ); + + QSizePolicy policy( QSizePolicy::MinimumExpanding, + QSizePolicy::Fixed ); if ( d_data->scaleDraw->orientation() == Qt::Vertical ) policy.transpose(); - setSizePolicy(policy); + setSizePolicy( policy ); + + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); +} + +/*! + Toggle an layout flag + + \param flag Layout flag + \param on true/false + + \sa testLayoutFlag(), LayoutFlag +*/ +void QwtScaleWidget::setLayoutFlag( LayoutFlag flag, bool on ) +{ + if ( ( ( d_data->layoutFlags & flag ) != 0 ) != on ) + { + if ( on ) + d_data->layoutFlags |= flag; + else + d_data->layoutFlags &= ~flag; + } +} -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif +/*! + Test a layout flag + \param flag Layout flag + \return true/false + \sa setLayoutFlag(), LayoutFlag +*/ +bool QwtScaleWidget::testLayoutFlag( LayoutFlag flag ) const +{ + return ( d_data->layoutFlags & flag ); } -void QwtScaleWidget::setTitle(const QString &title) +/*! + Give title new text contents + + \param title New title + \sa title(), setTitle(const QwtText &); +*/ +void QwtScaleWidget::setTitle( const QString &title ) { - if ( d_data->title.text() != title ) { - d_data->title.setText(title); + if ( d_data->title.text() != title ) + { + d_data->title.setText( title ); layoutScale(); } } /*! - \brief Give title new text contents + Give title new text contents + \param title New title - \sa QwtScaleWidget::title + \sa title() \warning The title flags are interpreted in direction of the label, AlignTop, AlignBottom can't be set as the title will always be aligned to the scale. */ -void QwtScaleWidget::setTitle(const QwtText &title) +void QwtScaleWidget::setTitle( const QwtText &title ) { QwtText t = title; - const int flags = title.renderFlags() & ~(Qt::AlignTop | Qt::AlignBottom); - t.setRenderFlags(flags); + const int flags = title.renderFlags() & ~( Qt::AlignTop | Qt::AlignBottom ); + t.setRenderFlags( flags ); - if (t != d_data->title) { + if ( t != d_data->title ) + { d_data->title = t; layoutScale(); } @@ -176,42 +201,36 @@ void QwtScaleWidget::setTitle(const QwtText &title) Change the alignment \param alignment New alignment - \sa QwtScaleWidget::alignment + \sa alignment() */ -void QwtScaleWidget::setAlignment(QwtScaleDraw::Alignment alignment) +void QwtScaleWidget::setAlignment( QwtScaleDraw::Alignment alignment ) { -#if QT_VERSION >= 0x040000 - if ( !testAttribute(Qt::WA_WState_OwnSizePolicy) ) -#else - if ( !testWState( WState_OwnSizePolicy ) ) -#endif + if ( d_data->scaleDraw ) + d_data->scaleDraw->setAlignment( alignment ); + + if ( !testAttribute( Qt::WA_WState_OwnSizePolicy ) ) { - QSizePolicy policy(QSizePolicy::MinimumExpanding, - QSizePolicy::Fixed); + QSizePolicy policy( QSizePolicy::MinimumExpanding, + QSizePolicy::Fixed ); if ( d_data->scaleDraw->orientation() == Qt::Vertical ) policy.transpose(); - setSizePolicy(policy); -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif + setSizePolicy( policy ); + + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); } - if (d_data->scaleDraw) - d_data->scaleDraw->setAlignment(alignment); layoutScale(); } /*! \return position - \sa QwtScaleWidget::setPosition + \sa setPosition() */ QwtScaleDraw::Alignment QwtScaleWidget::alignment() const { - if (!scaleDraw()) + if ( !scaleDraw() ) return QwtScaleDraw::LeftScale; return scaleDraw()->alignment(); @@ -223,11 +242,12 @@ QwtScaleDraw::Alignment QwtScaleWidget::alignment() const than minimum border distance. \param dist1 Left or top Distance \param dist2 Right or bottom distance - \sa QwtScaleWidget::borderDist + \sa borderDist() */ -void QwtScaleWidget::setBorderDist(int dist1, int dist2) +void QwtScaleWidget::setBorderDist( int dist1, int dist2 ) { - if ( dist1 != d_data->borderDist[0] || dist2 != d_data->borderDist[1] ) { + if ( dist1 != d_data->borderDist[0] || dist2 != d_data->borderDist[1] ) + { d_data->borderDist[0] = dist1; d_data->borderDist[1] = dist2; layoutScale(); @@ -237,12 +257,13 @@ void QwtScaleWidget::setBorderDist(int dist1, int dist2) /*! \brief Specify the margin to the colorBar/base line. \param margin Margin - \sa QwtScaleWidget::margin + \sa margin() */ -void QwtScaleWidget::setMargin(int margin) +void QwtScaleWidget::setMargin( int margin ) { - margin = qwtMax( 0, margin ); - if ( margin != d_data->margin ) { + margin = qMax( 0, margin ); + if ( margin != d_data->margin ) + { d_data->margin = margin; layoutScale(); } @@ -251,81 +272,80 @@ void QwtScaleWidget::setMargin(int margin) /*! \brief Specify the distance between color bar, scale and title \param spacing Spacing - \sa QwtScaleWidget::spacing + \sa spacing() */ -void QwtScaleWidget::setSpacing(int spacing) +void QwtScaleWidget::setSpacing( int spacing ) { - spacing = qwtMax( 0, spacing ); - if ( spacing != d_data->spacing ) { + spacing = qMax( 0, spacing ); + if ( spacing != d_data->spacing ) + { d_data->spacing = spacing; layoutScale(); } } -/*! - \brief Specify the width of the scale pen - \param width Pen width - \sa QwtScaleWidget::penWidth -*/ -void QwtScaleWidget::setPenWidth(int width) -{ - if ( width < 0 ) - width = 0; - - if ( width != d_data->penWidth ) { - d_data->penWidth = width; - layoutScale(); - } -} - /*! \brief Change the alignment for the labels. - \sa QwtScaleDraw::setLabelAlignment(), QwtScaleWidget::setLabelRotation() + \sa QwtScaleDraw::setLabelAlignment(), setLabelRotation() */ -#if QT_VERSION < 0x040000 -void QwtScaleWidget::setLabelAlignment(int alignment) -#else -void QwtScaleWidget::setLabelAlignment(Qt::Alignment alignment) -#endif +void QwtScaleWidget::setLabelAlignment( Qt::Alignment alignment ) { - d_data->scaleDraw->setLabelAlignment(alignment); + d_data->scaleDraw->setLabelAlignment( alignment ); layoutScale(); } /*! \brief Change the rotation for the labels. See QwtScaleDraw::setLabelRotation(). - \sa QwtScaleDraw::setLabelRotation(), QwtScaleWidget::setLabelFlags() + + \param rotation Rotation + \sa QwtScaleDraw::setLabelRotation(), setLabelFlags() */ -void QwtScaleWidget::setLabelRotation(double rotation) +void QwtScaleWidget::setLabelRotation( double rotation ) { - d_data->scaleDraw->setLabelRotation(rotation); + d_data->scaleDraw->setLabelRotation( rotation ); layoutScale(); } /*! - \brief Set a scale draw - sd has to be created with new and will be deleted in - QwtScaleWidget::~QwtScale or the next call of QwtScaleWidget::setScaleDraw. + Set a scale draw + + scaleDraw has to be created with new and will be deleted in + ~QwtScaleWidget() or the next call of setScaleDraw(). + scaleDraw will be initialized with the attributes of + the previous scaleDraw object. + + \param scaleDraw ScaleDraw object + \sa scaleDraw() */ -void QwtScaleWidget::setScaleDraw(QwtScaleDraw *sd) +void QwtScaleWidget::setScaleDraw( QwtScaleDraw *scaleDraw ) { - if ( sd == NULL || sd == d_data->scaleDraw ) + if ( ( scaleDraw == NULL ) || ( scaleDraw == d_data->scaleDraw ) ) return; - if ( d_data->scaleDraw ) - sd->setAlignment(d_data->scaleDraw->alignment()); + const QwtScaleDraw* sd = d_data->scaleDraw; + if ( sd ) + { + scaleDraw->setAlignment( sd->alignment() ); + scaleDraw->setScaleDiv( sd->scaleDiv() ); + + QwtTransform *transform = NULL; + if ( sd->scaleMap().transformation() ) + transform = sd->scaleMap().transformation()->copy(); + + scaleDraw->setTransformation( transform ); + } delete d_data->scaleDraw; - d_data->scaleDraw = sd; + d_data->scaleDraw = scaleDraw; layoutScale(); } /*! - scaleDraw of this scale - \sa QwtScaleDraw::setScaleDraw + \return scaleDraw of this scale + \sa setScaleDraw(), QwtScaleDraw::setScaleDraw() */ const QwtScaleDraw *QwtScaleWidget::scaleDraw() const { @@ -333,8 +353,8 @@ const QwtScaleDraw *QwtScaleWidget::scaleDraw() const } /*! - scaleDraw of this scale - \sa QwtScaleDraw::setScaleDraw + \return scaleDraw of this scale + \sa QwtScaleDraw::setScaleDraw() */ QwtScaleDraw *QwtScaleWidget::scaleDraw() { @@ -343,7 +363,7 @@ QwtScaleDraw *QwtScaleWidget::scaleDraw() /*! \return title - \sa QwtScaleWidget::setTitle + \sa setTitle() */ QwtText QwtScaleWidget::title() const { @@ -352,7 +372,7 @@ QwtText QwtScaleWidget::title() const /*! \return start border distance - \sa QwtScaleWidget::setBorderDist + \sa setBorderDist() */ int QwtScaleWidget::startBorderDist() const { @@ -361,7 +381,7 @@ int QwtScaleWidget::startBorderDist() const /*! \return end border distance - \sa QwtScaleWidget::setBorderDist + \sa setBorderDist() */ int QwtScaleWidget::endBorderDist() const { @@ -370,7 +390,7 @@ int QwtScaleWidget::endBorderDist() const /*! \return margin - \sa QwtScaleWidget::setMargin + \sa setMargin() */ int QwtScaleWidget::margin() const { @@ -379,7 +399,7 @@ int QwtScaleWidget::margin() const /*! \return distance between scale and title - \sa QwtScaleWidget::setMargin + \sa setMargin() */ int QwtScaleWidget::spacing() const { @@ -387,147 +407,128 @@ int QwtScaleWidget::spacing() const } /*! - \return Scale pen width - \sa QwtScaleWidget::setPenWidth + \brief paintEvent */ -int QwtScaleWidget::penWidth() const +void QwtScaleWidget::paintEvent( QPaintEvent *event ) { - return d_data->penWidth; + QPainter painter( this ); + painter.setClipRegion( event->region() ); + + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); + + draw( &painter ); } + /*! - \brief paintEvent + \brief draw the scale */ -void QwtScaleWidget::paintEvent(QPaintEvent *e) -{ - const QRect &ur = e->rect(); - if ( ur.isValid() ) { -#if QT_VERSION < 0x040000 - QwtPaintBuffer paintBuffer(this, ur); - draw(paintBuffer.painter()); -#else - QPainter painter(this); - draw(&painter); -#endif +void QwtScaleWidget::draw( QPainter *painter ) const +{ + d_data->scaleDraw->draw( painter, palette() ); + + if ( d_data->colorBar.isEnabled && d_data->colorBar.width > 0 && + d_data->colorBar.interval.isValid() ) + { + drawColorBar( painter, colorBarRect( contentsRect() ) ); + } + + QRect r = contentsRect(); + if ( d_data->scaleDraw->orientation() == Qt::Horizontal ) + { + r.setLeft( r.left() + d_data->borderDist[0] ); + r.setWidth( r.width() - d_data->borderDist[1] ); } + else + { + r.setTop( r.top() + d_data->borderDist[0] ); + r.setHeight( r.height() - d_data->borderDist[1] ); + } + + if ( !d_data->title.isEmpty() ) + drawTitle( painter, d_data->scaleDraw->alignment(), r ); } /*! - \brief draw the scale + Calculate the the rectangle for the color bar + + \param rect Bounding rectangle for all components of the scale + \return Rectangle for the color bar */ -void QwtScaleWidget::draw(QPainter *painter) const +QRectF QwtScaleWidget::colorBarRect( const QRectF& rect ) const { - painter->save(); - - QPen scalePen = painter->pen(); - scalePen.setWidth(d_data->penWidth); - painter->setPen(scalePen); - -#if QT_VERSION < 0x040000 - d_data->scaleDraw->draw(painter, colorGroup()); -#else - d_data->scaleDraw->draw(painter, palette()); -#endif - painter->restore(); + QRectF cr = rect; - if ( d_data->colorBar.isEnabled && d_data->colorBar.width > 0 && - d_data->colorBar.interval.isValid() ) { - drawColorBar(painter, colorBarRect(rect())); + if ( d_data->scaleDraw->orientation() == Qt::Horizontal ) + { + cr.setLeft( cr.left() + d_data->borderDist[0] ); + cr.setWidth( cr.width() - d_data->borderDist[1] + 1 ); } - - QRect r = rect(); - if ( d_data->scaleDraw->orientation() == Qt::Horizontal ) { - r.setLeft(r.left() + d_data->borderDist[0]); - r.setWidth(r.width() - d_data->borderDist[1]); - } else { - r.setTop(r.top() + d_data->borderDist[0]); - r.setHeight(r.height() - d_data->borderDist[1]); + else + { + cr.setTop( cr.top() + d_data->borderDist[0] ); + cr.setHeight( cr.height() - d_data->borderDist[1] + 1 ); } - if ( !d_data->title.isEmpty() ) { - QRect tr = r; - switch(d_data->scaleDraw->alignment()) { + switch ( d_data->scaleDraw->alignment() ) + { case QwtScaleDraw::LeftScale: - tr.setRight( r.right() - d_data->titleOffset ); + { + cr.setLeft( cr.right() - d_data->margin + - d_data->colorBar.width ); + cr.setWidth( d_data->colorBar.width ); break; + } case QwtScaleDraw::RightScale: - tr.setLeft( r.left() + d_data->titleOffset ); + { + cr.setLeft( cr.left() + d_data->margin ); + cr.setWidth( d_data->colorBar.width ); break; + } case QwtScaleDraw::BottomScale: - tr.setTop( r.top() + d_data->titleOffset ); + { + cr.setTop( cr.top() + d_data->margin ); + cr.setHeight( d_data->colorBar.width ); break; + } case QwtScaleDraw::TopScale: - default: - tr.setBottom( r.bottom() - d_data->titleOffset ); + { + cr.setTop( cr.bottom() - d_data->margin + - d_data->colorBar.width ); + cr.setHeight( d_data->colorBar.width ); break; } - - drawTitle(painter, d_data->scaleDraw->alignment(), tr); - } -} - -QRect QwtScaleWidget::colorBarRect(const QRect& rect) const -{ - QRect cr = rect; - - if ( d_data->scaleDraw->orientation() == Qt::Horizontal ) { - cr.setLeft(cr.left() + d_data->borderDist[0]); - cr.setWidth(cr.width() - d_data->borderDist[1] + 1); - } else { - cr.setTop(cr.top() + d_data->borderDist[0]); - cr.setHeight(cr.height() - d_data->borderDist[1] + 1); - } - - switch(d_data->scaleDraw->alignment()) { - case QwtScaleDraw::LeftScale: { - cr.setLeft( cr.right() - d_data->spacing - - d_data->colorBar.width + 1 ); - cr.setWidth(d_data->colorBar.width); - break; - } - - case QwtScaleDraw::RightScale: { - cr.setLeft( cr.left() + d_data->spacing ); - cr.setWidth(d_data->colorBar.width); - break; - } - - case QwtScaleDraw::BottomScale: { - cr.setTop( cr.top() + d_data->spacing ); - cr.setHeight(d_data->colorBar.width); - break; - } - - case QwtScaleDraw::TopScale: { - cr.setTop( cr.bottom() - d_data->spacing - - d_data->colorBar.width + 1 ); - cr.setHeight(d_data->colorBar.width); - break; - } } return cr; } /*! - \brief resizeEvent + Event handler for resize events + \param event Resize event */ -void QwtScaleWidget::resizeEvent(QResizeEvent *) +void QwtScaleWidget::resizeEvent( QResizeEvent *event ) { - layoutScale(false); + Q_UNUSED( event ); + layoutScale( false ); } -//! Recalculate the scale's geometry and layout based on -// the current rect and fonts. -// \param update_geometry notify the layout system and call update -// to redraw the scale +/*! + Recalculate the scale's geometry and layout based on + the current geometry and fonts. + + \param update_geometry Notify the layout system and call update + to redraw the scale +*/ void QwtScaleWidget::layoutScale( bool update_geometry ) { int bd0, bd1; - getBorderDistHint(bd0, bd1); + getBorderDistHint( bd0, bd1 ); if ( d_data->borderDist[0] > bd0 ) bd0 = d_data->borderDist[0]; if ( d_data->borderDist[1] > bd1 ) @@ -537,106 +538,133 @@ void QwtScaleWidget::layoutScale( bool update_geometry ) if ( d_data->colorBar.isEnabled && d_data->colorBar.interval.isValid() ) colorBarWidth = d_data->colorBar.width + d_data->spacing; - const QRect r = rect(); - int x, y, length; + const QRectF r = contentsRect(); + double x, y, length; - if ( d_data->scaleDraw->orientation() == Qt::Vertical ) { + if ( d_data->scaleDraw->orientation() == Qt::Vertical ) + { y = r.top() + bd0; - length = r.height() - (bd0 + bd1); + length = r.height() - ( bd0 + bd1 ); if ( d_data->scaleDraw->alignment() == QwtScaleDraw::LeftScale ) - x = r.right() - d_data->margin - colorBarWidth; + x = r.right() - 1.0 - d_data->margin - colorBarWidth; else x = r.left() + d_data->margin + colorBarWidth; - } else { + } + else + { x = r.left() + bd0; - length = r.width() - (bd0 + bd1); + length = r.width() - ( bd0 + bd1 ); if ( d_data->scaleDraw->alignment() == QwtScaleDraw::BottomScale ) y = r.top() + d_data->margin + colorBarWidth; else - y = r.bottom() - d_data->margin - colorBarWidth; + y = r.bottom() - 1.0 - d_data->margin - colorBarWidth; } - d_data->scaleDraw->move(x, y); - d_data->scaleDraw->setLength(length); + d_data->scaleDraw->move( x, y ); + d_data->scaleDraw->setLength( length ); - d_data->titleOffset = d_data->margin + d_data->spacing + - colorBarWidth + - d_data->scaleDraw->extent(QPen(Qt::black, d_data->penWidth), font()); + const int extent = qCeil( d_data->scaleDraw->extent( font() ) ); - if ( update_geometry ) { + d_data->titleOffset = + d_data->margin + d_data->spacing + colorBarWidth + extent; + + if ( update_geometry ) + { updateGeometry(); update(); } } -void QwtScaleWidget::drawColorBar(QPainter *painter, const QRect& rect) const +/*! + Draw the color bar of the scale widget + + \param painter Painter + \param rect Bounding rectangle for the color bar + + \sa setColorBarEnabled() +*/ +void QwtScaleWidget::drawColorBar( QPainter *painter, const QRectF& rect ) const { if ( !d_data->colorBar.interval.isValid() ) return; const QwtScaleDraw* sd = d_data->scaleDraw; - QwtPainter::drawColorBar(painter, *d_data->colorBar.colorMap, - d_data->colorBar.interval.normalized(), sd->map(), - sd->orientation(), rect); + QwtPainter::drawColorBar( painter, *d_data->colorBar.colorMap, + d_data->colorBar.interval.normalized(), sd->scaleMap(), + sd->orientation(), rect ); } /*! Rotate and paint a title according to its position into a given rectangle. + \param painter Painter \param align Alignment \param rect Bounding rectangle */ -void QwtScaleWidget::drawTitle(QPainter *painter, - QwtScaleDraw::Alignment align, const QRect &rect) const +void QwtScaleWidget::drawTitle( QPainter *painter, + QwtScaleDraw::Alignment align, const QRectF &rect ) const { - QRect r; + QRectF r = rect; double angle; int flags = d_data->title.renderFlags() & - ~(Qt::AlignTop | Qt::AlignBottom | Qt::AlignVCenter); - - switch(align) { - case QwtScaleDraw::LeftScale: - flags |= Qt::AlignTop; - angle = -90.0; - r.setRect(rect.left(), rect.bottom(), rect.height(), rect.width()); - break; - case QwtScaleDraw::RightScale: - flags |= Qt::AlignTop; - angle = 90.0; - r.setRect(rect.right(), rect.top(), rect.height(), rect.width()); - break; - case QwtScaleDraw::TopScale: - flags |= Qt::AlignTop; - angle = 0.0; - r = rect; - break; - case QwtScaleDraw::BottomScale: - default: - flags |= Qt::AlignBottom; - angle = 0.0; - r = rect; - break; + ~( Qt::AlignTop | Qt::AlignBottom | Qt::AlignVCenter ); + + switch ( align ) + { + case QwtScaleDraw::LeftScale: + angle = -90.0; + flags |= Qt::AlignTop; + r.setRect( r.left(), r.bottom(), + r.height(), r.width() - d_data->titleOffset ); + break; + + case QwtScaleDraw::RightScale: + angle = -90.0; + flags |= Qt::AlignTop; + r.setRect( r.left() + d_data->titleOffset, r.bottom(), + r.height(), r.width() - d_data->titleOffset ); + break; + + case QwtScaleDraw::BottomScale: + angle = 0.0; + flags |= Qt::AlignBottom; + r.setTop( r.top() + d_data->titleOffset ); + break; + + case QwtScaleDraw::TopScale: + default: + angle = 0.0; + flags |= Qt::AlignTop; + r.setBottom( r.bottom() - d_data->titleOffset ); + break; + } + + if ( d_data->layoutFlags & TitleInverted ) + { + if ( align == QwtScaleDraw::LeftScale + || align == QwtScaleDraw::RightScale ) + { + angle = -angle; + r.setRect( r.x() + r.height(), r.y() - r.width(), + r.width(), r.height() ); + } } painter->save(); - painter->setFont(font()); -#if QT_VERSION < 0x040000 - painter->setPen(colorGroup().color(QColorGroup::Text)); -#else - painter->setPen(palette().color(QPalette::Text)); -#endif + painter->setFont( font() ); + painter->setPen( palette().color( QPalette::Text ) ); - painter->translate(r.x(), r.y()); - if (angle != 0.0) - painter->rotate(angle); + painter->translate( r.x(), r.y() ); + if ( angle != 0.0 ) + painter->rotate( angle ); QwtText title = d_data->title; - title.setRenderFlags(flags); - title.draw(painter, QRect(0, 0, r.width(), r.height())); + title.setRenderFlags( flags ); + title.draw( painter, QRectF( 0.0, 0.0, r.width(), r.height() ) ); painter->restore(); } @@ -673,24 +701,26 @@ QSize QwtScaleWidget::minimumSizeHint() const // Note, the borderDistHint is already included in minHeight/minWidth int length = 0; int mbd1, mbd2; - getBorderDistHint(mbd1, mbd2); - length += qwtMax( 0, d_data->borderDist[0] - mbd1 ); - length += qwtMax( 0, d_data->borderDist[1] - mbd2 ); - length += d_data->scaleDraw->minLength( - QPen(Qt::black, d_data->penWidth), font()); - - int dim = dimForLength(length, font()); - if ( length < dim ) { + getBorderDistHint( mbd1, mbd2 ); + length += qMax( 0, d_data->borderDist[0] - mbd1 ); + length += qMax( 0, d_data->borderDist[1] - mbd2 ); + length += d_data->scaleDraw->minLength( font() ); + + int dim = dimForLength( length, font() ); + if ( length < dim ) + { // compensate for long titles length = dim; - dim = dimForLength(length, font()); + dim = dimForLength( length, font() ); } - QSize size(length + 2, dim); + QSize size( length + 2, dim ); if ( o == Qt::Vertical ) size.transpose(); - return size; + int left, right, top, bottom; + getContentsMargins( &left, &top, &right, &bottom ); + return size + QSize( left + right, top + bottom ); } /*! @@ -699,9 +729,9 @@ QSize QwtScaleWidget::minimumSizeHint() const \return height Height */ -int QwtScaleWidget::titleHeightForWidth(int width) const +int QwtScaleWidget::titleHeightForWidth( int width ) const { - return d_data->title.heightForWidth(width, font()); + return qCeil( d_data->title.heightForWidth( width, font() ) ); } /*! @@ -713,14 +743,14 @@ int QwtScaleWidget::titleHeightForWidth(int width) const \return height for horizontal, width for vertical scales */ -int QwtScaleWidget::dimForLength(int length, const QFont &scaleFont) const +int QwtScaleWidget::dimForLength( int length, const QFont &scaleFont ) const { - int dim = d_data->margin; - dim += d_data->scaleDraw->extent( - QPen(Qt::black, d_data->penWidth), scaleFont); + const int extent = qCeil( d_data->scaleDraw->extent( scaleFont ) ); + + int dim = d_data->margin + extent + 1; if ( !d_data->title.isEmpty() ) - dim += titleHeightForWidth(length) + d_data->spacing; + dim += titleHeightForWidth( length ) + d_data->spacing; if ( d_data->colorBar.isEnabled && d_data->colorBar.interval.isValid() ) dim += d_data->colorBar.width + d_data->spacing; @@ -737,13 +767,18 @@ int QwtScaleWidget::dimForLength(int length, const QFont &scaleFont) const The maximum of this distance an the minimum border distance is returned. + \param start Return parameter for the border width at + the beginning of the scale + \param end Return parameter for the border width at the + end of the scale + \warning <ul> <li>The minimum border distance depends on the font.</ul> \sa setMinBorderDist(), getMinBorderDist(), setBorderDist() */ -void QwtScaleWidget::getBorderDistHint(int &start, int &end) const +void QwtScaleWidget::getBorderDistHint( int &start, int &end ) const { - d_data->scaleDraw->getBorderDistHint(font(), start, end); + d_data->scaleDraw->getBorderDistHint( font(), start, end ); if ( start < d_data->minBorderDist[0] ) start = d_data->minBorderDist[0]; @@ -758,9 +793,11 @@ void QwtScaleWidget::getBorderDistHint(int &start, int &end) const are "jumping", when the tick labels or their positions change often. + \param start Minimum for the start border + \param end Minimum for the end border \sa getMinBorderDist(), getBorderDistHint() */ -void QwtScaleWidget::setMinBorderDist(int start, int end) +void QwtScaleWidget::setMinBorderDist( int start, int end ) { d_data->minBorderDist[0] = start; d_data->minBorderDist[1] = end; @@ -770,104 +807,136 @@ void QwtScaleWidget::setMinBorderDist(int start, int end) Get the minimum value for the distances of the scale's endpoints from the widget borders. + \param start Return parameter for the border width at + the beginning of the scale + \param end Return parameter for the border width at the + end of the scale + \sa setMinBorderDist(), getBorderDistHint() */ -void QwtScaleWidget::getMinBorderDist(int &start, int &end) const +void QwtScaleWidget::getMinBorderDist( int &start, int &end ) const { start = d_data->minBorderDist[0]; end = d_data->minBorderDist[1]; } -#if QT_VERSION < 0x040000 - -/*! - \brief Notify a change of the font - - This virtual function may be overloaded by derived widgets. - The default implementation resizes the scale and repaints - the widget. - \param oldFont Previous font -*/ -void QwtScaleWidget::fontChange(const QFont &oldFont) -{ - QWidget::fontChange( oldFont ); - layoutScale(); -} - -#endif - /*! \brief Assign a scale division The scale division determines where to set the tick marks. - \param transformation Transformation, needed to translate between - scale and pixal values \param scaleDiv Scale Division \sa For more information about scale divisions, see QwtScaleDiv. */ -void QwtScaleWidget::setScaleDiv( - QwtScaleTransformation *transformation, - const QwtScaleDiv &scaleDiv) +void QwtScaleWidget::setScaleDiv( const QwtScaleDiv &scaleDiv ) { QwtScaleDraw *sd = d_data->scaleDraw; - if (sd->scaleDiv() != scaleDiv || - sd->map().transformation()->type() != transformation->type() ) { - sd->setTransformation(transformation); - sd->setScaleDiv(scaleDiv); + if ( sd->scaleDiv() != scaleDiv ) + { + sd->setScaleDiv( scaleDiv ); layoutScale(); - emit scaleDivChanged(); - } else - delete transformation; + Q_EMIT scaleDivChanged(); + } } -void QwtScaleWidget::setColorBarEnabled(bool on) +/*! + Set the transformation + + \param transformation Transformation + \sa QwtAbstractScaleDraw::scaleDraw(), QwtScaleMap + */ +void QwtScaleWidget::setTransformation( QwtTransform *transformation ) { - if ( on != d_data->colorBar.isEnabled ) { + d_data->scaleDraw->setTransformation( transformation ); + layoutScale(); +} + +/*! + En/disable a color bar associated to the scale + \sa isColorBarEnabled(), setColorBarWidth() +*/ +void QwtScaleWidget::setColorBarEnabled( bool on ) +{ + if ( on != d_data->colorBar.isEnabled ) + { d_data->colorBar.isEnabled = on; layoutScale(); } } +/*! + \return true, when the color bar is enabled + \sa setColorBarEnabled(), setColorBarWidth() +*/ bool QwtScaleWidget::isColorBarEnabled() const { return d_data->colorBar.isEnabled; } +/*! + Set the width of the color bar -void QwtScaleWidget::setColorBarWidth(int width) + \param width Width + \sa colorBarWidth(), setColorBarEnabled() +*/ +void QwtScaleWidget::setColorBarWidth( int width ) { - if ( width != d_data->colorBar.width ) { + if ( width != d_data->colorBar.width ) + { d_data->colorBar.width = width; if ( isColorBarEnabled() ) layoutScale(); } } +/*! + \return Width of the color bar + \sa setColorBarEnabled(), setColorBarEnabled() +*/ int QwtScaleWidget::colorBarWidth() const { return d_data->colorBar.width; } -QwtDoubleInterval QwtScaleWidget::colorBarInterval() const +/*! + \return Value interval for the color bar + \sa setColorMap(), colorMap() +*/ +QwtInterval QwtScaleWidget::colorBarInterval() const { return d_data->colorBar.interval; } -void QwtScaleWidget::setColorMap(const QwtDoubleInterval &interval, - const QwtColorMap &colorMap) +/*! + Set the color map and value interval, that are used for displaying + the color bar. + + \param interval Value interval + \param colorMap Color map + + \sa colorMap(), colorBarInterval() +*/ +void QwtScaleWidget::setColorMap( + const QwtInterval &interval, QwtColorMap *colorMap ) { d_data->colorBar.interval = interval; - delete d_data->colorBar.colorMap; - d_data->colorBar.colorMap = colorMap.copy(); + if ( colorMap != d_data->colorBar.colorMap ) + { + delete d_data->colorBar.colorMap; + d_data->colorBar.colorMap = colorMap; + } if ( isColorBarEnabled() ) layoutScale(); } -const QwtColorMap &QwtScaleWidget::colorMap() const +/*! + \return Color map + \sa setColorMap(), colorBarInterval() +*/ +const QwtColorMap *QwtScaleWidget::colorMap() const { - return *d_data->colorBar.colorMap; + return d_data->colorBar.colorMap; } diff --git a/libs/qwt/qwt_scale_widget.h b/libs/qwt/qwt_scale_widget.h index d9dd0479f8..067723d760 100644 --- a/libs/qwt/qwt_scale_widget.h +++ b/libs/qwt/qwt_scale_widget.h @@ -10,17 +10,16 @@ #ifndef QWT_SCALE_WIDGET_H #define QWT_SCALE_WIDGET_H +#include "qwt_global.h" +#include "qwt_text.h" +#include "qwt_scale_draw.h" #include <qwidget.h> #include <qfont.h> #include <qcolor.h> #include <qstring.h> -#include "qwt_global.h" -#include "qwt_text.h" -#include "qwt_scale_draw.h" - class QPainter; -class QwtScaleTransformation; +class QwtTransform; class QwtScaleDiv; class QwtColorMap; @@ -36,97 +35,102 @@ class QWT_EXPORT QwtScaleWidget : public QWidget Q_OBJECT public: - explicit QwtScaleWidget(QWidget *parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtScaleWidget(QWidget *parent, const char *name); -#endif - explicit QwtScaleWidget(QwtScaleDraw::Alignment, QWidget *parent = NULL); + //! Layout flags of the title + enum LayoutFlag + { + /*! + The title of vertical scales is painted from top to bottom. + Otherwise it is painted from bottom to top. + */ + TitleInverted = 1 + }; + + //! Layout flags of the title + typedef QFlags<LayoutFlag> LayoutFlags; + + explicit QwtScaleWidget( QWidget *parent = NULL ); + explicit QwtScaleWidget( QwtScaleDraw::Alignment, QWidget *parent = NULL ); virtual ~QwtScaleWidget(); -signals: - //! Signal emitted, whenever the scale divison changes +Q_SIGNALS: + //! Signal emitted, whenever the scale division changes void scaleDivChanged(); public: - void setTitle(const QString &title); - void setTitle(const QwtText &title); + void setTitle( const QString &title ); + void setTitle( const QwtText &title ); QwtText title() const; - void setBorderDist(int start, int end); + void setLayoutFlag( LayoutFlag, bool on ); + bool testLayoutFlag( LayoutFlag ) const; + + void setBorderDist( int start, int end ); int startBorderDist() const; int endBorderDist() const; - void getBorderDistHint(int &start, int &end) const; + void getBorderDistHint( int &start, int &end ) const; - void getMinBorderDist(int &start, int &end) const; - void setMinBorderDist(int start, int end); + void getMinBorderDist( int &start, int &end ) const; + void setMinBorderDist( int start, int end ); - void setMargin(int); + void setMargin( int ); int margin() const; - void setSpacing(int td); + void setSpacing( int td ); int spacing() const; - void setPenWidth(int); - int penWidth() const; + void setScaleDiv( const QwtScaleDiv &sd ); + void setTransformation( QwtTransform * ); - void setScaleDiv(QwtScaleTransformation *, const QwtScaleDiv &sd); - - void setScaleDraw(QwtScaleDraw *); + void setScaleDraw( QwtScaleDraw * ); const QwtScaleDraw *scaleDraw() const; QwtScaleDraw *scaleDraw(); -#if QT_VERSION < 0x040000 - void setLabelAlignment(int); -#else - void setLabelAlignment(Qt::Alignment); -#endif - void setLabelRotation(double rotation); + void setLabelAlignment( Qt::Alignment ); + void setLabelRotation( double rotation ); - void setColorBarEnabled(bool); + void setColorBarEnabled( bool ); bool isColorBarEnabled() const; - void setColorBarWidth(int); + void setColorBarWidth( int ); int colorBarWidth() const; - void setColorMap(const QwtDoubleInterval &, const QwtColorMap &); + void setColorMap( const QwtInterval &, QwtColorMap * ); - QwtDoubleInterval colorBarInterval() const; - const QwtColorMap &colorMap() const; + QwtInterval colorBarInterval() const; + const QwtColorMap *colorMap() const; virtual QSize sizeHint() const; virtual QSize minimumSizeHint() const; - int titleHeightForWidth(int width) const; - int dimForLength(int length, const QFont &scaleFont) const; + int titleHeightForWidth( int width ) const; + int dimForLength( int length, const QFont &scaleFont ) const; - void drawColorBar(QPainter *painter, const QRect &rect) const; - void drawTitle(QPainter *painter, QwtScaleDraw::Alignment, - const QRect &rect) const; + void drawColorBar( QPainter *painter, const QRectF & ) const; + void drawTitle( QPainter *painter, QwtScaleDraw::Alignment, + const QRectF &rect ) const; - void setAlignment(QwtScaleDraw::Alignment); + void setAlignment( QwtScaleDraw::Alignment ); QwtScaleDraw::Alignment alignment() const; - QRect colorBarRect(const QRect&) const; + QRectF colorBarRect( const QRectF& ) const; protected: - virtual void paintEvent(QPaintEvent *e); - virtual void resizeEvent(QResizeEvent *e); + virtual void paintEvent( QPaintEvent * ); + virtual void resizeEvent( QResizeEvent * ); -#if QT_VERSION < 0x040000 - virtual void fontChange(const QFont &oldfont); -#endif - - void draw(QPainter *p) const; + void draw( QPainter *p ) const; void scaleChange(); void layoutScale( bool update = true ); private: - void initScale(QwtScaleDraw::Alignment); + void initScale( QwtScaleDraw::Alignment ); class PrivateData; PrivateData *d_data; }; +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtScaleWidget::LayoutFlags ) + #endif diff --git a/libs/qwt/qwt_series_data.cpp b/libs/qwt/qwt_series_data.cpp new file mode 100644 index 0000000000..319af41ff9 --- /dev/null +++ b/libs/qwt/qwt_series_data.cpp @@ -0,0 +1,346 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_series_data.h" +#include "qwt_math.h" + +static inline QRectF qwtBoundingRect( const QPointF &sample ) +{ + return QRectF( sample.x(), sample.y(), 0.0, 0.0 ); +} + +static inline QRectF qwtBoundingRect( const QwtPoint3D &sample ) +{ + return QRectF( sample.x(), sample.y(), 0.0, 0.0 ); +} + +static inline QRectF qwtBoundingRect( const QwtPointPolar &sample ) +{ + return QRectF( sample.azimuth(), sample.radius(), 0.0, 0.0 ); +} + +static inline QRectF qwtBoundingRect( const QwtIntervalSample &sample ) +{ + return QRectF( sample.interval.minValue(), sample.value, + sample.interval.maxValue() - sample.interval.minValue(), 0.0 ); +} + +static inline QRectF qwtBoundingRect( const QwtSetSample &sample ) +{ + double minY = sample.set[0]; + double maxY = sample.set[0]; + + for ( int i = 1; i < sample.set.size(); i++ ) + { + if ( sample.set[i] < minY ) + minY = sample.set[i]; + if ( sample.set[i] > maxY ) + maxY = sample.set[i]; + } + + double minX = sample.value; + double maxX = sample.value; + + return QRectF( minX, minY, maxX - minX, maxY - minY ); +} + +static inline QRectF qwtBoundingRect( const QwtOHLCSample &sample ) +{ + const QwtInterval interval = sample.boundingInterval(); + return QRectF( interval.minValue(), sample.time, interval.width(), 0.0 ); +} + +/*! + \brief Calculate the bounding rectangle of a series subset + + Slow implementation, that iterates over the series. + + \param series Series + \param from Index of the first sample, <= 0 means from the beginning + \param to Index of the last sample, < 0 means to the end + + \return Bounding rectangle +*/ + +template <class T> +QRectF qwtBoundingRectT( + const QwtSeriesData<T>& series, int from, int to ) +{ + QRectF boundingRect( 1.0, 1.0, -2.0, -2.0 ); // invalid; + + if ( from < 0 ) + from = 0; + + if ( to < 0 ) + to = series.size() - 1; + + if ( to < from ) + return boundingRect; + + int i; + for ( i = from; i <= to; i++ ) + { + const QRectF rect = qwtBoundingRect( series.sample( i ) ); + if ( rect.width() >= 0.0 && rect.height() >= 0.0 ) + { + boundingRect = rect; + i++; + break; + } + } + + for ( ; i <= to; i++ ) + { + const QRectF rect = qwtBoundingRect( series.sample( i ) ); + if ( rect.width() >= 0.0 && rect.height() >= 0.0 ) + { + boundingRect.setLeft( qMin( boundingRect.left(), rect.left() ) ); + boundingRect.setRight( qMax( boundingRect.right(), rect.right() ) ); + boundingRect.setTop( qMin( boundingRect.top(), rect.top() ) ); + boundingRect.setBottom( qMax( boundingRect.bottom(), rect.bottom() ) ); + } + } + + return boundingRect; +} + +/*! + \brief Calculate the bounding rectangle of a series subset + + Slow implementation, that iterates over the series. + + \param series Series + \param from Index of the first sample, <= 0 means from the beginning + \param to Index of the last sample, < 0 means to the end + + \return Bounding rectangle +*/ +QRectF qwtBoundingRect( + const QwtSeriesData<QPointF> &series, int from, int to ) +{ + return qwtBoundingRectT<QPointF>( series, from, to ); +} + +/*! + \brief Calculate the bounding rectangle of a series subset + + Slow implementation, that iterates over the series. + + \param series Series + \param from Index of the first sample, <= 0 means from the beginning + \param to Index of the last sample, < 0 means to the end + + \return Bounding rectangle +*/ +QRectF qwtBoundingRect( + const QwtSeriesData<QwtPoint3D> &series, int from, int to ) +{ + return qwtBoundingRectT<QwtPoint3D>( series, from, to ); +} + +/*! + \brief Calculate the bounding rectangle of a series subset + + The horizontal coordinates represent the azimuth, the + vertical coordinates the radius. + + Slow implementation, that iterates over the series. + + \param series Series + \param from Index of the first sample, <= 0 means from the beginning + \param to Index of the last sample, < 0 means to the end + + \return Bounding rectangle +*/ +QRectF qwtBoundingRect( + const QwtSeriesData<QwtPointPolar> &series, int from, int to ) +{ + return qwtBoundingRectT<QwtPointPolar>( series, from, to ); +} + +/*! + \brief Calculate the bounding rectangle of a series subset + + Slow implementation, that iterates over the series. + + \param series Series + \param from Index of the first sample, <= 0 means from the beginning + \param to Index of the last sample, < 0 means to the end + + \return Bounding rectangle +*/ +QRectF qwtBoundingRect( + const QwtSeriesData<QwtIntervalSample>& series, int from, int to ) +{ + return qwtBoundingRectT<QwtIntervalSample>( series, from, to ); +} + +/*! + \brief Calculate the bounding rectangle of a series subset + + Slow implementation, that iterates over the series. + + \param series Series + \param from Index of the first sample, <= 0 means from the beginning + \param to Index of the last sample, < 0 means to the end + + \return Bounding rectangle +*/ +QRectF qwtBoundingRect( + const QwtSeriesData<QwtOHLCSample>& series, int from, int to ) +{ + return qwtBoundingRectT<QwtOHLCSample>( series, from, to ); +} + +/*! + \brief Calculate the bounding rectangle of a series subset + + Slow implementation, that iterates over the series. + + \param series Series + \param from Index of the first sample, <= 0 means from the beginning + \param to Index of the last sample, < 0 means to the end + + \return Bounding rectangle +*/ +QRectF qwtBoundingRect( + const QwtSeriesData<QwtSetSample>& series, int from, int to ) +{ + return qwtBoundingRectT<QwtSetSample>( series, from, to ); +} + +/*! + Constructor + \param samples Samples +*/ +QwtPointSeriesData::QwtPointSeriesData( + const QVector<QPointF> &samples ): + QwtArraySeriesData<QPointF>( samples ) +{ +} + +/*! + \brief Calculate the bounding rectangle + + The bounding rectangle is calculated once by iterating over all + points and is stored for all following requests. + + \return Bounding rectangle +*/ +QRectF QwtPointSeriesData::boundingRect() const +{ + if ( d_boundingRect.width() < 0.0 ) + d_boundingRect = qwtBoundingRect( *this ); + + return d_boundingRect; +} + +/*! + Constructor + \param samples Samples +*/ +QwtPoint3DSeriesData::QwtPoint3DSeriesData( + const QVector<QwtPoint3D> &samples ): + QwtArraySeriesData<QwtPoint3D>( samples ) +{ +} + +/*! + \brief Calculate the bounding rectangle + + The bounding rectangle is calculated once by iterating over all + points and is stored for all following requests. + + \return Bounding rectangle +*/ +QRectF QwtPoint3DSeriesData::boundingRect() const +{ + if ( d_boundingRect.width() < 0.0 ) + d_boundingRect = qwtBoundingRect( *this ); + + return d_boundingRect; +} + +/*! + Constructor + \param samples Samples +*/ +QwtIntervalSeriesData::QwtIntervalSeriesData( + const QVector<QwtIntervalSample> &samples ): + QwtArraySeriesData<QwtIntervalSample>( samples ) +{ +} + +/*! + \brief Calculate the bounding rectangle + + The bounding rectangle is calculated once by iterating over all + points and is stored for all following requests. + + \return Bounding rectangle +*/ +QRectF QwtIntervalSeriesData::boundingRect() const +{ + if ( d_boundingRect.width() < 0.0 ) + d_boundingRect = qwtBoundingRect( *this ); + + return d_boundingRect; +} + +/*! + Constructor + \param samples Samples +*/ +QwtSetSeriesData::QwtSetSeriesData( + const QVector<QwtSetSample> &samples ): + QwtArraySeriesData<QwtSetSample>( samples ) +{ +} + +/*! + \brief Calculate the bounding rectangle + + The bounding rectangle is calculated once by iterating over all + points and is stored for all following requests. + + \return Bounding rectangle +*/ +QRectF QwtSetSeriesData::boundingRect() const +{ + if ( d_boundingRect.width() < 0.0 ) + d_boundingRect = qwtBoundingRect( *this ); + + return d_boundingRect; +} + +/*! + Constructor + \param samples Samples +*/ +QwtTradingChartData::QwtTradingChartData( + const QVector<QwtOHLCSample> &samples ): + QwtArraySeriesData<QwtOHLCSample>( samples ) +{ +} + +/*! + \brief Calculate the bounding rectangle + + The bounding rectangle is calculated once by iterating over all + points and is stored for all following requests. + + \return Bounding rectangle +*/ +QRectF QwtTradingChartData::boundingRect() const +{ + if ( d_boundingRect.width() < 0.0 ) + d_boundingRect = qwtBoundingRect( *this ); + + return d_boundingRect; +} diff --git a/libs/qwt/qwt_series_data.h b/libs/qwt/qwt_series_data.h new file mode 100644 index 0000000000..afd8b1ae99 --- /dev/null +++ b/libs/qwt/qwt_series_data.h @@ -0,0 +1,355 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_SERIES_DATA_H +#define QWT_SERIES_DATA_H 1 + +#include "qwt_global.h" +#include "qwt_samples.h" +#include "qwt_point_3d.h" +#include "qwt_point_polar.h" +#include <qvector.h> +#include <qrect.h> + +/*! + \brief Abstract interface for iterating over samples + + Qwt offers several implementations of the QwtSeriesData API, + but in situations, where data of an application specific format + needs to be displayed, without having to copy it, it is recommended + to implement an individual data access. + + A subclass of QwtSeriesData<QPointF> must implement: + + - size()\n + Should return number of data points. + + - sample()\n + Should return values x and y values of the sample at specific position + as QPointF object. + + - boundingRect()\n + Should return the bounding rectangle of the data series. + It is used for autoscaling and might help certain algorithms for displaying + the data. You can use qwtBoundingRect() for an implementation + but often it is possible to implement a more efficient algorithm + depending on the characteristics of the series. + The member d_boundingRect is intended for caching the calculated rectangle. + +*/ +template <typename T> +class QwtSeriesData +{ +public: + //! Constructor + QwtSeriesData(); + + //! Destructor + virtual ~QwtSeriesData(); + + //! \return Number of samples + virtual size_t size() const = 0; + + /*! + Return a sample + \param i Index + \return Sample at position i + */ + virtual T sample( size_t i ) const = 0; + + /*! + Calculate the bounding rect of all samples + + The bounding rect is necessary for autoscaling and can be used + for a couple of painting optimizations. + + qwtBoundingRect(...) offers slow implementations iterating + over the samples. For large sets it is recommended to implement + something faster f.e. by caching the bounding rectangle. + + \return Bounding rectangle + */ + virtual QRectF boundingRect() const = 0; + + /*! + Set a the "rect of interest" + + QwtPlotSeriesItem defines the current area of the plot canvas + as "rectangle of interest" ( QwtPlotSeriesItem::updateScaleDiv() ). + It can be used to implement different levels of details. + + The default implementation does nothing. + + \param rect Rectangle of interest + */ + virtual void setRectOfInterest( const QRectF &rect ); + +protected: + //! Can be used to cache a calculated bounding rectangle + mutable QRectF d_boundingRect; + +private: + QwtSeriesData<T> &operator=( const QwtSeriesData<T> & ); +}; + +template <typename T> +QwtSeriesData<T>::QwtSeriesData(): + d_boundingRect( 0.0, 0.0, -1.0, -1.0 ) +{ +} + +template <typename T> +QwtSeriesData<T>::~QwtSeriesData() +{ +} + +template <typename T> +void QwtSeriesData<T>::setRectOfInterest( const QRectF & ) +{ +} + +/*! + \brief Template class for data, that is organized as QVector + + QVector uses implicit data sharing and can be + passed around as argument efficiently. +*/ +template <typename T> +class QwtArraySeriesData: public QwtSeriesData<T> +{ +public: + //! Constructor + QwtArraySeriesData(); + + /*! + Constructor + \param samples Array of samples + */ + QwtArraySeriesData( const QVector<T> &samples ); + + /*! + Assign an array of samples + \param samples Array of samples + */ + void setSamples( const QVector<T> &samples ); + + //! \return Array of samples + const QVector<T> samples() const; + + //! \return Number of samples + virtual size_t size() const; + + /*! + \return Sample at a specific position + + \param index Index + \return Sample at position index + */ + virtual T sample( size_t index ) const; + +protected: + //! Vector of samples + QVector<T> d_samples; +}; + +template <typename T> +QwtArraySeriesData<T>::QwtArraySeriesData() +{ +} + +template <typename T> +QwtArraySeriesData<T>::QwtArraySeriesData( const QVector<T> &samples ): + d_samples( samples ) +{ +} + +template <typename T> +void QwtArraySeriesData<T>::setSamples( const QVector<T> &samples ) +{ + QwtSeriesData<T>::d_boundingRect = QRectF( 0.0, 0.0, -1.0, -1.0 ); + d_samples = samples; +} + +template <typename T> +const QVector<T> QwtArraySeriesData<T>::samples() const +{ + return d_samples; +} + +template <typename T> +size_t QwtArraySeriesData<T>::size() const +{ + return d_samples.size(); +} + +template <typename T> +T QwtArraySeriesData<T>::sample( size_t i ) const +{ + return d_samples[ static_cast<int>( i ) ]; +} + +//! Interface for iterating over an array of points +class QWT_EXPORT QwtPointSeriesData: public QwtArraySeriesData<QPointF> +{ +public: + QwtPointSeriesData( + const QVector<QPointF> & = QVector<QPointF>() ); + + virtual QRectF boundingRect() const; +}; + +//! Interface for iterating over an array of 3D points +class QWT_EXPORT QwtPoint3DSeriesData: public QwtArraySeriesData<QwtPoint3D> +{ +public: + QwtPoint3DSeriesData( + const QVector<QwtPoint3D> & = QVector<QwtPoint3D>() ); + virtual QRectF boundingRect() const; +}; + +//! Interface for iterating over an array of intervals +class QWT_EXPORT QwtIntervalSeriesData: public QwtArraySeriesData<QwtIntervalSample> +{ +public: + QwtIntervalSeriesData( + const QVector<QwtIntervalSample> & = QVector<QwtIntervalSample>() ); + + virtual QRectF boundingRect() const; +}; + +//! Interface for iterating over an array of samples +class QWT_EXPORT QwtSetSeriesData: public QwtArraySeriesData<QwtSetSample> +{ +public: + QwtSetSeriesData( + const QVector<QwtSetSample> & = QVector<QwtSetSample>() ); + + virtual QRectF boundingRect() const; +}; + +/*! + Interface for iterating over an array of OHLC samples +*/ +class QWT_EXPORT QwtTradingChartData: public QwtArraySeriesData<QwtOHLCSample> +{ +public: + QwtTradingChartData( + const QVector<QwtOHLCSample> & = QVector<QwtOHLCSample>() ); + + virtual QRectF boundingRect() const; +}; + +QWT_EXPORT QRectF qwtBoundingRect( + const QwtSeriesData<QPointF> &, int from = 0, int to = -1 ); + +QWT_EXPORT QRectF qwtBoundingRect( + const QwtSeriesData<QwtPoint3D> &, int from = 0, int to = -1 ); + +QWT_EXPORT QRectF qwtBoundingRect( + const QwtSeriesData<QwtPointPolar> &, int from = 0, int to = -1 ); + +QWT_EXPORT QRectF qwtBoundingRect( + const QwtSeriesData<QwtIntervalSample> &, int from = 0, int to = -1 ); + +QWT_EXPORT QRectF qwtBoundingRect( + const QwtSeriesData<QwtSetSample> &, int from = 0, int to = -1 ); + +QWT_EXPORT QRectF qwtBoundingRect( + const QwtSeriesData<QwtOHLCSample> &, int from = 0, int to = -1 ); + +/*! + Binary search for a sorted series of samples + + qwtUpperSampleIndex returns the index of sample that is the upper bound + of value. Is the the value smaller than the smallest value the return + value will be 0. Is the value greater or equal than the largest + value the return value will be -1. + + \par Example + The following example shows finds a point of curve from an x + coordinate + + \verbatim +#include <qwt_series_data.h> +#include <qwt_plot_curve.h> + +struct compareX +{ + inline bool operator()( const double x, const QPointF &pos ) const + { + return ( x < pos.x() ); + } +}; + +QLineF curveLineAt( const QwtPlotCurve *curve, double x ) +{ + int index = qwtUpperSampleIndex<QPointF>( + *curve->data(), x, compareX() ); + + if ( index == -1 && + x == curve->sample( curve->dataSize() - 1 ).x() ) + { + // the last sample is excluded from qwtUpperSampleIndex + index = curve->dataSize() - 1; + } + + QLineF line; // invalid + if ( index > 0 ) + { + line.setP1( curve->sample( index - 1 ) ); + line.setP2( curve->sample( index ) ); + } + + return line; +} + +\endverbatim + + + \param series Series of samples + \param value Value + \param lessThan Compare operation + + \note The samples must be sorted according to the order specified + by the lessThan object + +of the range [begin, end) and returns the position of the one-past-the-last occurrence of value. If no such item is found, returns the position where the item should be inserted. + */ +template <typename T, typename LessThan> +inline int qwtUpperSampleIndex( const QwtSeriesData<T> &series, + double value, LessThan lessThan ) +{ + const int indexMax = series.size() - 1; + + if ( indexMax < 0 || !lessThan( value, series.sample( indexMax ) ) ) + return -1; + + int indexMin = 0; + int n = indexMax; + + while ( n > 0 ) + { + const int half = n >> 1; + const int indexMid = indexMin + half; + + if ( lessThan( value, series.sample( indexMid ) ) ) + { + n = half; + } + else + { + indexMin = indexMid + 1; + n -= half + 1; + } + } + + return indexMin; +} + +#endif diff --git a/libs/qwt/qwt_series_store.h b/libs/qwt/qwt_series_store.h new file mode 100644 index 0000000000..cb841a498c --- /dev/null +++ b/libs/qwt/qwt_series_store.h @@ -0,0 +1,199 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_SERIES_STORE_H +#define QWT_SERIES_STORE_H + +#include "qwt_global.h" +#include "qwt_series_data.h" + +/*! + \brief Bridge between QwtSeriesStore and QwtPlotSeriesItem + + QwtAbstractSeriesStore is an abstract interface only + to make it possible to isolate the template based methods ( QwtSeriesStore ) + from the regular methods ( QwtPlotSeriesItem ) to make it possible + to derive from QwtPlotSeriesItem without any hassle with templates. +*/ +class QwtAbstractSeriesStore +{ +protected: + //! Destructor + virtual ~QwtAbstractSeriesStore() {} + + //! dataChanged() indicates, that the series has been changed. + virtual void dataChanged() = 0; + + /*! + Set a the "rectangle of interest" for the stored series + \sa QwtSeriesData<T>::setRectOfInterest() + */ + virtual void setRectOfInterest( const QRectF & ) = 0; + + //! \return Bounding rectangle of the stored series + virtual QRectF dataRect() const = 0; + + //! \return Number of samples + virtual size_t dataSize() const = 0; +}; + +/*! + \brief Class storing a QwtSeriesData object + + QwtSeriesStore and QwtPlotSeriesItem are intended as base classes for all + plot items iterating over a series of samples. Both classes share + a virtual base class ( QwtAbstractSeriesStore ) to bridge between them. + + QwtSeriesStore offers the template based part for the plot item API, so + that QwtPlotSeriesItem can be derived without any hassle with templates. + */ +template <typename T> +class QwtSeriesStore: public virtual QwtAbstractSeriesStore +{ +public: + /*! + \brief Constructor + The store contains no series + */ + explicit QwtSeriesStore<T>(); + + //! Destructor + ~QwtSeriesStore<T>(); + + /*! + Assign a series of samples + + \param series Data + \warning The item takes ownership of the data object, deleting + it when its not used anymore. + */ + void setData( QwtSeriesData<T> *series ); + + //! \return the the series data + QwtSeriesData<T> *data(); + + //! \return the the series data + const QwtSeriesData<T> *data() const; + + /*! + \param index Index + \return Sample at position index + */ + T sample( int index ) const; + + /*! + \return Number of samples of the series + \sa setData(), QwtSeriesData<T>::size() + */ + virtual size_t dataSize() const; + + /*! + \return Bounding rectangle of the series + or an invalid rectangle, when no series is stored + + \sa QwtSeriesData<T>::boundingRect() + */ + virtual QRectF dataRect() const; + + /*! + Set a the "rect of interest" for the series + + \param rect Rectangle of interest + \sa QwtSeriesData<T>::setRectOfInterest() + */ + virtual void setRectOfInterest( const QRectF &rect ); + + /*! + Replace a series without deleting the previous one + + \param series New series + \return Previously assigned series + */ + QwtSeriesData<T> *swapData( QwtSeriesData<T> *series ); + +private: + QwtSeriesData<T> *d_series; +}; + +template <typename T> +QwtSeriesStore<T>::QwtSeriesStore(): + d_series( NULL ) +{ +} + +template <typename T> +QwtSeriesStore<T>::~QwtSeriesStore() +{ + delete d_series; +} + +template <typename T> +inline QwtSeriesData<T> *QwtSeriesStore<T>::data() +{ + return d_series; +} + +template <typename T> +inline const QwtSeriesData<T> *QwtSeriesStore<T>::data() const +{ + return d_series; +} + +template <typename T> +inline T QwtSeriesStore<T>::sample( int index ) const +{ + return d_series ? d_series->sample( index ) : T(); +} + +template <typename T> +void QwtSeriesStore<T>::setData( QwtSeriesData<T> *series ) +{ + if ( d_series != series ) + { + delete d_series; + d_series = series; + dataChanged(); + } +} + +template <typename T> +size_t QwtSeriesStore<T>::dataSize() const +{ + if ( d_series == NULL ) + return 0; + + return d_series->size(); +} + +template <typename T> +QRectF QwtSeriesStore<T>::dataRect() const +{ + if ( d_series == NULL ) + return QRectF( 1.0, 1.0, -2.0, -2.0 ); // invalid + + return d_series->boundingRect(); +} + +template <typename T> +void QwtSeriesStore<T>::setRectOfInterest( const QRectF &rect ) +{ + if ( d_series ) + d_series->setRectOfInterest( rect ); +} + +template <typename T> +QwtSeriesData<T>* QwtSeriesStore<T>::swapData( QwtSeriesData<T> *series ) +{ + QwtSeriesData<T> * swappedSeries = d_series; + d_series = series; + + return swappedSeries; +} + +#endif diff --git a/libs/qwt/qwt_slider.cpp b/libs/qwt/qwt_slider.cpp index 0c3a97be92..e4e3942685 100644 --- a/libs/qwt/qwt_slider.cpp +++ b/libs/qwt/qwt_slider.cpp @@ -7,298 +7,326 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <math.h> -#include <qevent.h> -#include <qdrawutil.h> -#include <qpainter.h> +#include "qwt_slider.h" #include "qwt_painter.h" -#include "qwt_paint_buffer.h" #include "qwt_scale_draw.h" #include "qwt_scale_map.h" -#include "qwt_slider.h" +#include <qevent.h> +#include <qdrawutil.h> +#include <qpainter.h> +#include <qalgorithms.h> +#include <qmath.h> +#include <qstyle.h> +#include <qstyleoption.h> +#include <qapplication.h> + +static QSize qwtHandleSize( const QSize &size, + Qt::Orientation orientation, bool hasTrough ) +{ + QSize handleSize = size; + + if ( handleSize.isEmpty() ) + { + const int handleThickness = 16; + handleSize.setWidth( 2 * handleThickness ); + handleSize.setHeight( handleThickness ); + + if ( !hasTrough ) + handleSize.transpose(); + + if ( orientation == Qt::Vertical ) + handleSize.transpose(); + } + + return handleSize; +} + +static QwtScaleDraw::Alignment qwtScaleDrawAlignment( + Qt::Orientation orientation, QwtSlider::ScalePosition scalePos ) +{ + QwtScaleDraw::Alignment align; + + if ( orientation == Qt::Vertical ) + { + // NoScale lays out like Left + if ( scalePos == QwtSlider::LeadingScale ) + align = QwtScaleDraw::RightScale; + else + align = QwtScaleDraw::LeftScale; + } + else + { + // NoScale lays out like Bottom + if ( scalePos == QwtSlider::TrailingScale ) + align = QwtScaleDraw::TopScale; + else + align = QwtScaleDraw::BottomScale; + } + + return align; +} class QwtSlider::PrivateData { public: + PrivateData(): + repeatTimerId( 0 ), + updateInterval( 150 ), + stepsIncrement( 0 ), + pendingValueChange( false ), + borderWidth( 2 ), + spacing( 4 ), + scalePosition( QwtSlider::TrailingScale ), + hasTrough( true ), + hasGroove( false ), + mouseOffset( 0 ) + { + } + + int repeatTimerId; + bool timerTick; + int updateInterval; + int stepsIncrement; + bool pendingValueChange; + QRect sliderRect; - int thumbLength; - int thumbWidth; + QSize handleSize; int borderWidth; - int scaleDist; - int xMargin; - int yMargin; + int spacing; - QwtSlider::ScalePos scalePos; - QwtSlider::BGSTYLE bgStyle; + Qt::Orientation orientation; + QwtSlider::ScalePosition scalePosition; + + bool hasTrough; + bool hasGroove; + + int mouseOffset; - /* - Scale and values might have different maps. This is - confusing and I can't see strong arguments for such - a feature. TODO ... - */ - QwtScaleMap map; // linear map mutable QSize sizeHintCache; }; - /*! - \brief Constructor - \param parent parent widget - \param orientation Orientation of the slider. Can be Qt::Horizontal - or Qt::Vertical. Defaults to Qt::Horizontal. - \param scalePos Position of the scale. - Defaults to QwtSlider::NoScale. - \param bgStyle Background style. QwtSlider::BgTrough draws the - slider button in a trough, QwtSlider::BgSlot draws - a slot underneath the button. An or-combination of both - may also be used. The default is QwtSlider::BgTrough. - - QwtSlider enforces valid combinations of its orientation and scale position. - If the combination is invalid, the scale position will be set to NoScale. - Valid combinations are: - - Qt::Horizonal with NoScale, TopScale, or BottomScale; - - Qt::Vertical with NoScale, LeftScale, or RightScale. + Construct vertical slider in QwtSlider::Trough style + with a scale to the left. + + The scale is initialized to [0.0, 100.0] and the value set to 0.0. + + \param parent Parent widget + + \sa setOrientation(), setScalePosition(), setBackgroundStyle() */ -QwtSlider::QwtSlider(QWidget *parent, - Qt::Orientation orientation, ScalePos scalePos, BGSTYLE bgStyle): - QwtAbstractSlider(orientation, parent) +QwtSlider::QwtSlider( QWidget *parent ): + QwtAbstractSlider( parent ) { - initSlider(orientation, scalePos, bgStyle); + initSlider( Qt::Vertical ); } -#if QT_VERSION < 0x040000 /*! - \brief Constructor + Construct a slider in QwtSlider::Trough style + + When orientation is Qt::Vertical the scale will be aligned to + the left - otherwise at the the top of the slider. - Build a horizontal slider with no scale and BgTrough as - background style + The scale is initialized to [0.0, 100.0] and the value set to 0.0. - \param parent parent widget - \param name Object name + \param parent Parent widget + \param orientation Orientation of the slider. */ -QwtSlider::QwtSlider(QWidget *parent, const char* name): - QwtAbstractSlider(Qt::Horizontal, parent) +QwtSlider::QwtSlider( Qt::Orientation orientation, QWidget *parent ): + QwtAbstractSlider( parent ) { - setName(name); - initSlider(Qt::Horizontal, NoScale, BgTrough); + initSlider( orientation ); } -#endif -void QwtSlider::initSlider(Qt::Orientation orientation, - ScalePos scalePos, BGSTYLE bgStyle) +//! Destructor +QwtSlider::~QwtSlider() { - if (orientation == Qt::Vertical) - setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Expanding); - else - setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); - -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif + delete d_data; +} +void QwtSlider::initSlider( Qt::Orientation orientation ) +{ + if ( orientation == Qt::Vertical ) + setSizePolicy( QSizePolicy::Fixed, QSizePolicy::Expanding ); + else + setSizePolicy( QSizePolicy::Expanding, QSizePolicy::Fixed ); -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#endif + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); d_data = new QwtSlider::PrivateData; - d_data->borderWidth = 2; - d_data->scaleDist = 4; - d_data->scalePos = scalePos; - d_data->xMargin = 0; - d_data->yMargin = 0; - d_data->bgStyle = bgStyle; + d_data->orientation = orientation; - if (bgStyle == BgSlot) { - d_data->thumbLength = 16; - d_data->thumbWidth = 30; - } else { - d_data->thumbLength = 31; - d_data->thumbWidth = 16; - } - - d_data->sliderRect.setRect(0,0,8,8); + scaleDraw()->setAlignment( + qwtScaleDrawAlignment( orientation, d_data->scalePosition ) ); + scaleDraw()->setLength( 100 ); - QwtScaleDraw::Alignment align; - if ( orientation == Qt::Vertical ) { - // enforce a valid combination of scale position and orientation - if ((d_data->scalePos == BottomScale) || (d_data->scalePos == TopScale)) - d_data->scalePos = NoScale; - // adopt the policy of layoutSlider (NoScale lays out like Left) - if (d_data->scalePos == RightScale) - align = QwtScaleDraw::RightScale; - else - align = QwtScaleDraw::LeftScale; - } else { - // enforce a valid combination of scale position and orientation - if ((d_data->scalePos == LeftScale) || (d_data->scalePos == RightScale)) - d_data->scalePos = NoScale; - // adopt the policy of layoutSlider (NoScale lays out like Bottom) - if (d_data->scalePos == TopScale) - align = QwtScaleDraw::TopScale; - else - align = QwtScaleDraw::BottomScale; - } - - scaleDraw()->setAlignment(align); - scaleDraw()->setLength(100); - - setRange(0.0, 100.0, 1.0); - setValue(0.0); -} - -QwtSlider::~QwtSlider() -{ - delete d_data; + setScale( 0.0, 100.0 ); + setValue( 0.0 ); } /*! \brief Set the orientation. - \param o Orientation. Allowed values are Qt::Horizontal and Qt::Vertical. + \param orientation Allowed values are Qt::Horizontal and Qt::Vertical. - If the new orientation and the old scale position are an invalid combination, - the scale position will be set to QwtSlider::NoScale. - \sa QwtAbstractSlider::orientation() + \sa orientation(), scalePosition() */ -void QwtSlider::setOrientation(Qt::Orientation o) +void QwtSlider::setOrientation( Qt::Orientation orientation ) { - if ( o == orientation() ) + if ( orientation == d_data->orientation ) return; - if (o == Qt::Horizontal) { - if ((d_data->scalePos == LeftScale) || (d_data->scalePos == RightScale)) - d_data->scalePos = NoScale; - } else { // if (o == Qt::Vertical) - if ((d_data->scalePos == BottomScale) || (d_data->scalePos == TopScale)) - d_data->scalePos = NoScale; - } + d_data->orientation = orientation; -#if QT_VERSION >= 0x040000 - if ( !testAttribute(Qt::WA_WState_OwnSizePolicy) ) -#else - if ( !testWState( WState_OwnSizePolicy ) ) -#endif + scaleDraw()->setAlignment( + qwtScaleDrawAlignment( orientation, d_data->scalePosition ) ); + + if ( !testAttribute( Qt::WA_WState_OwnSizePolicy ) ) { QSizePolicy sp = sizePolicy(); sp.transpose(); - setSizePolicy(sp); + setSizePolicy( sp ); -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); } - QwtAbstractSlider::setOrientation(o); - layoutSlider(); + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); } /*! - \brief Change the scale position (and slider orientation). + \return Orientation + \sa setOrientation() +*/ +Qt::Orientation QwtSlider::orientation() const +{ + return d_data->orientation; +} - \param s Position of the scale. +/*! + \brief Change the position of the scale + \param scalePosition Position of the scale. - A valid combination of scale position and orientation is enforced: - - if the new scale position is Left or Right, the scale orientation will - become Qt::Vertical; - - if the new scale position is Bottom or Top the scale orientation will - become Qt::Horizontal; - - if the new scale position is QwtSlider::NoScale, the scale - orientation will not change. + \sa ScalePosition, scalePosition() */ -void QwtSlider::setScalePosition(ScalePos s) +void QwtSlider::setScalePosition( ScalePosition scalePosition ) { - if ( d_data->scalePos == s ) + if ( d_data->scalePosition == scalePosition ) return; - d_data->scalePos = s; + d_data->scalePosition = scalePosition; + scaleDraw()->setAlignment( + qwtScaleDrawAlignment( d_data->orientation, scalePosition ) ); - switch(d_data->scalePos) { - case BottomScale: { - setOrientation(Qt::Horizontal); - scaleDraw()->setAlignment(QwtScaleDraw::BottomScale); - break; - } - case TopScale: { - setOrientation(Qt::Horizontal); - scaleDraw()->setAlignment(QwtScaleDraw::TopScale); - break; - } - case LeftScale: { - setOrientation(Qt::Vertical); - scaleDraw()->setAlignment(QwtScaleDraw::LeftScale); - break; - } - case RightScale: { - setOrientation(Qt::Vertical); - scaleDraw()->setAlignment(QwtScaleDraw::RightScale); - break; - } - default: { - // nothing - } - } - - layoutSlider(); + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); } -//! Return the scale position. -QwtSlider::ScalePos QwtSlider::scalePosition() const +/*! + \return Position of the scale + \sa setScalePosition() + */ +QwtSlider::ScalePosition QwtSlider::scalePosition() const { - return d_data->scalePos; + return d_data->scalePosition; } /*! \brief Change the slider's border width - \param bd border width + + The border width is used for drawing the slider handle and the + trough. + + \param width Border width + \sa borderWidth() */ -void QwtSlider::setBorderWidth(int bd) +void QwtSlider::setBorderWidth( int width ) { - if ( bd < 0 ) - bd = 0; + if ( width < 0 ) + width = 0; + + if ( width != d_data->borderWidth ) + { + d_data->borderWidth = width; - if ( bd != d_data->borderWidth ) { - d_data->borderWidth = bd; - layoutSlider(); + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); } } /*! - \brief Set the slider's thumb length - \param thumbLength new length + \return the border width. + \sa setBorderWidth() */ -void QwtSlider::setThumbLength(int thumbLength) +int QwtSlider::borderWidth() const { - if ( thumbLength < 8 ) - thumbLength = 8; + return d_data->borderWidth; +} + +/*! + \brief Change the spacing between trough and scale + + A spacing of 0 means, that the backbone of the scale is covered + by the trough. + + The default setting is 4 pixels. - if ( thumbLength != d_data->thumbLength ) { - d_data->thumbLength = thumbLength; - layoutSlider(); + \param spacing Number of pixels + \sa spacing(); +*/ +void QwtSlider::setSpacing( int spacing ) +{ + if ( spacing <= 0 ) + spacing = 0; + + if ( spacing != d_data->spacing ) + { + d_data->spacing = spacing; + + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); } } /*! - \brief Change the width of the thumb - \param w new width + \return Number of pixels between slider and scale + \sa setSpacing() */ -void QwtSlider::setThumbWidth(int w) +int QwtSlider::spacing() const { - if ( w < 4 ) - w = 4; + return d_data->spacing; +} + +/*! + \brief Set the slider's handle size + + When the size is empty the slider handle will be painted with a + default size depending on its orientation() and backgroundStyle(). + + \param size New size - if ( d_data->thumbWidth != w ) { - d_data->thumbWidth = w; - layoutSlider(); + \sa handleSize() +*/ +void QwtSlider::setHandleSize( const QSize &size ) +{ + if ( size != d_data->handleSize ) + { + d_data->handleSize = size; + + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); } } +/*! + \return Size of the handle. + \sa setHandleSize() +*/ +QSize QwtSlider::handleSize() const +{ + return d_data->handleSize; +} + /*! \brief Set a scale draw @@ -307,20 +335,24 @@ void QwtSlider::setThumbWidth(int w) overload QwtScaleDraw::label(). \param scaleDraw ScaleDraw object, that has to be created with - new and will be deleted in ~QwtSlider or the next + new and will be deleted in ~QwtSlider() or the next call of setScaleDraw(). + + \sa scaleDraw() */ -void QwtSlider::setScaleDraw(QwtScaleDraw *scaleDraw) +void QwtSlider::setScaleDraw( QwtScaleDraw *scaleDraw ) { const QwtScaleDraw *previousScaleDraw = this->scaleDraw(); if ( scaleDraw == NULL || scaleDraw == previousScaleDraw ) return; if ( previousScaleDraw ) - scaleDraw->setAlignment(previousScaleDraw->alignment()); + scaleDraw->setAlignment( previousScaleDraw->alignment() ); + + setAbstractScaleDraw( scaleDraw ); - setAbstractScaleDraw(scaleDraw); - layoutSlider(); + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); } /*! @@ -329,7 +361,7 @@ void QwtSlider::setScaleDraw(QwtScaleDraw *scaleDraw) */ const QwtScaleDraw *QwtSlider::scaleDraw() const { - return (QwtScaleDraw *)abstractScaleDraw(); + return static_cast<const QwtScaleDraw *>( abstractScaleDraw() ); } /*! @@ -338,496 +370,622 @@ const QwtScaleDraw *QwtSlider::scaleDraw() const */ QwtScaleDraw *QwtSlider::scaleDraw() { - return (QwtScaleDraw *)abstractScaleDraw(); + return static_cast<QwtScaleDraw *>( abstractScaleDraw() ); } //! Notify changed scale void QwtSlider::scaleChange() { - layoutSlider(); -} - - -//! Notify change in font -void QwtSlider::fontChange(const QFont &f) -{ - QwtAbstractSlider::fontChange( f ); - layoutSlider(); -} - -//! Draw the slider into the specified rectangle. -void QwtSlider::drawSlider(QPainter *p, const QRect &r) -{ - QRect cr(r); - - if (d_data->bgStyle & BgTrough) { - qDrawShadePanel(p, r.x(), r.y(), - r.width(), r.height(), -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - true, d_data->borderWidth,0); - - cr.setRect(r.x() + d_data->borderWidth, - r.y() + d_data->borderWidth, - r.width() - 2 * d_data->borderWidth, - r.height() - 2 * d_data->borderWidth); - - p->fillRect(cr.x(), cr.y(), cr.width(), cr.height(), -#if QT_VERSION < 0x040000 - colorGroup().brush(QColorGroup::Mid) -#else - palette().brush(QPalette::Mid) -#endif - ); - } - - if ( d_data->bgStyle & BgSlot) { - int ws = 4; - int ds = d_data->thumbLength / 2 - 4; - if ( ds < 1 ) - ds = 1; - - QRect rSlot; - if (orientation() == Qt::Horizontal) { - if ( cr.height() & 1 ) - ws++; - rSlot = QRect(cr.x() + ds, - cr.y() + (cr.height() - ws) / 2, - cr.width() - 2 * ds, ws); - } else { - if ( cr.width() & 1 ) - ws++; - rSlot = QRect(cr.x() + (cr.width() - ws) / 2, - cr.y() + ds, - ws, cr.height() - 2 * ds); + QwtAbstractSlider::scaleChange(); + + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); +} + +/*! + \brief Specify the update interval for automatic scrolling + + The minimal accepted value is 50 ms. + + \param interval Update interval in milliseconds + + \sa setUpdateInterval() +*/ +void QwtSlider::setUpdateInterval( int interval ) +{ + d_data->updateInterval = qMax( interval, 50 ); +} + +/*! + \return Update interval in milliseconds for automatic scrolling + \sa setUpdateInterval() + */ +int QwtSlider::updateInterval() const +{ + return d_data->updateInterval; +} + +/*! + Draw the slider into the specified rectangle. + + \param painter Painter + \param sliderRect Bounding rectangle of the slider +*/ +void QwtSlider::drawSlider( + QPainter *painter, const QRect &sliderRect ) const +{ + QRect innerRect( sliderRect ); + + if ( d_data->hasTrough ) + { + const int bw = d_data->borderWidth; + innerRect = sliderRect.adjusted( bw, bw, -bw, -bw ); + + painter->fillRect( innerRect, palette().brush( QPalette::Mid ) ); + qDrawShadePanel( painter, sliderRect, palette(), true, bw, NULL ); + } + + const QSize handleSize = qwtHandleSize( d_data->handleSize, + d_data->orientation, d_data->hasTrough ); + + if ( d_data->hasGroove ) + { + const int slotExtent = 4; + const int slotMargin = 4; + + QRect slotRect; + if ( orientation() == Qt::Horizontal ) + { + int slotOffset = qMax( 1, handleSize.width() / 2 - slotMargin ); + int slotHeight = slotExtent + ( innerRect.height() % 2 ); + + slotRect.setWidth( innerRect.width() - 2 * slotOffset ); + slotRect.setHeight( slotHeight ); } - p->fillRect(rSlot.x(), rSlot.y(), rSlot.width(), rSlot.height(), -#if QT_VERSION < 0x040000 - colorGroup().brush(QColorGroup::Dark) -#else - palette().brush(QPalette::Dark) -#endif - ); - qDrawShadePanel(p, rSlot.x(), rSlot.y(), - rSlot.width(), rSlot.height(), -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - true, 1 ,0); + else + { + int slotOffset = qMax( 1, handleSize.height() / 2 - slotMargin ); + int slotWidth = slotExtent + ( innerRect.width() % 2 ); + + slotRect.setWidth( slotWidth ); + slotRect.setHeight( innerRect.height() - 2 * slotOffset ); + } + + slotRect.moveCenter( innerRect.center() ); + + QBrush brush = palette().brush( QPalette::Dark ); + qDrawShadePanel( painter, slotRect, palette(), true, 1 , &brush ); } if ( isValid() ) - drawThumb(p, cr, xyPosition(value())); + drawHandle( painter, handleRect(), transform( value() ) ); } -//! Draw the thumb at a position -void QwtSlider::drawThumb(QPainter *p, const QRect &sliderRect, int pos) +/*! + Draw the thumb at a position + + \param painter Painter + \param handleRect Bounding rectangle of the handle + \param pos Position of the handle marker in widget coordinates +*/ +void QwtSlider::drawHandle( QPainter *painter, + const QRect &handleRect, int pos ) const { + const int bw = d_data->borderWidth; + + qDrawShadePanel( painter, + handleRect, palette(), false, bw, + &palette().brush( QPalette::Button ) ); + pos++; // shade line points one pixel below - if (orientation() == Qt::Horizontal) { - qDrawShadePanel(p, pos - d_data->thumbLength / 2, - sliderRect.y(), d_data->thumbLength, sliderRect.height(), -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - false, d_data->borderWidth, -#if QT_VERSION < 0x040000 - &colorGroup().brush(QColorGroup::Button) -#else - &palette().brush(QPalette::Button) -#endif - ); - - qDrawShadeLine(p, pos, sliderRect.y(), - pos, sliderRect.y() + sliderRect.height() - 2, -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - true, 1); - } else { // Vertical - qDrawShadePanel(p,sliderRect.x(), pos - d_data->thumbLength / 2, - sliderRect.width(), d_data->thumbLength, -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - false, d_data->borderWidth, -#if QT_VERSION < 0x040000 - &colorGroup().brush(QColorGroup::Button) -#else - &palette().brush(QPalette::Button) -#endif - ); - - qDrawShadeLine(p, sliderRect.x(), pos, - sliderRect.x() + sliderRect.width() - 2, pos, -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - true, 1); - } -} - -//! Find the x/y position for a given value v -int QwtSlider::xyPosition(double v) const -{ - return d_data->map.transform(v); -} - -//! Determine the value corresponding to a specified mouse location. -double QwtSlider::getValue(const QPoint &p) -{ - return d_data->map.invTransform( - orientation() == Qt::Horizontal ? p.x() : p.y()); -} - - -/*! - \brief Determine scrolling mode and direction - \param p point - \param scrollMode Scrolling mode - \param direction Direction + if ( orientation() == Qt::Horizontal ) + { + qDrawShadeLine( painter, pos, handleRect.top() + bw, + pos, handleRect.bottom() - bw, palette(), true, 1 ); + } + else // Vertical + { + qDrawShadeLine( painter, handleRect.left() + bw, pos, + handleRect.right() - bw, pos, palette(), true, 1 ); + } +} + +/*! + \brief Determine what to do when the user presses a mouse button. + + \param pos Mouse position + + \retval True, when handleRect() contains pos + \sa scrolledTo() */ -void QwtSlider::getScrollMode(const QPoint &p, - int &scrollMode, int &direction ) +bool QwtSlider::isScrollPosition( const QPoint &pos ) const { - if (!d_data->sliderRect.contains(p)) { - scrollMode = ScrNone; - direction = 0; - return; + if ( handleRect().contains( pos ) ) + { + const double v = ( orientation() == Qt::Horizontal ) + ? pos.x() : pos.y(); + + d_data->mouseOffset = v - transform( value() ); + return true; } - const int pos = ( orientation() == Qt::Horizontal ) ? p.x() : p.y(); - const int markerPos = xyPosition(value()); + return false; +} + +/*! + \brief Determine the value for a new position of the + slider handle. + + \param pos Mouse position + + \return Value for the mouse position + \sa isScrollPosition() +*/ +double QwtSlider::scrolledTo( const QPoint &pos ) const +{ + int p = ( orientation() == Qt::Horizontal ) + ? pos.x() : pos.y(); + + p -= d_data->mouseOffset; + + int min = transform( lowerBound() ); + int max = transform( upperBound() ); + if ( min > max ) + qSwap( min, max ); - if ((pos > markerPos - d_data->thumbLength / 2) - && (pos < markerPos + d_data->thumbLength / 2)) { - scrollMode = ScrMouse; - direction = 0; + p = qBound( min, p, max ); + + return invTransform( p ); +} + +/*! + Mouse press event handler + \param event Mouse event +*/ +void QwtSlider::mousePressEvent( QMouseEvent *event ) +{ + if ( isReadOnly() ) + { + event->ignore(); return; } - scrollMode = ScrPage; - direction = (pos > markerPos) ? 1 : -1; + const QPoint pos = event->pos(); + + if ( isValid() && d_data->sliderRect.contains( pos ) ) + { + if ( !handleRect().contains( pos ) ) + { + const int markerPos = transform( value() ); + + d_data->stepsIncrement = pageSteps(); + + if ( d_data->orientation == Qt::Horizontal ) + { + if ( pos.x() < markerPos ) + d_data->stepsIncrement = -d_data->stepsIncrement; + } + else + { + if ( pos.y() < markerPos ) + d_data->stepsIncrement = -d_data->stepsIncrement; + } + + if ( isInverted() ) + d_data->stepsIncrement = -d_data->stepsIncrement; + + d_data->timerTick = false; + d_data->repeatTimerId = startTimer( qMax( 250, 2 * updateInterval() ) ); + + return; + } + } + + QwtAbstractSlider::mousePressEvent( event ); +} + +/*! + Mouse release event handler + \param event Mouse event +*/ +void QwtSlider::mouseReleaseEvent( QMouseEvent *event ) +{ + if ( d_data->repeatTimerId > 0 ) + { + killTimer( d_data->repeatTimerId ); + d_data->repeatTimerId = 0; + d_data->timerTick = false; + d_data->stepsIncrement = 0; + } + + if ( d_data->pendingValueChange ) + { + d_data->pendingValueChange = false; + Q_EMIT valueChanged( value() ); + } - if ( scaleDraw()->map().p1() > scaleDraw()->map().p2() ) - direction = -direction; + QwtAbstractSlider::mouseReleaseEvent( event ); } -//! Qt paint event -void QwtSlider::paintEvent(QPaintEvent *e) +/*! + Timer event handler + + Handles the timer, when the mouse stays pressed + inside the sliderRect(). + + \param event Mouse event +*/ +void QwtSlider::timerEvent( QTimerEvent *event ) { - const QRect &ur = e->rect(); - if ( ur.isValid() ) { -#if QT_VERSION < 0x040000 - QwtPaintBuffer paintBuffer(this, ur); - draw(paintBuffer.painter(), ur); -#else - QPainter painter(this); - draw(&painter, ur); -#endif + if ( event->timerId() != d_data->repeatTimerId ) + { + QwtAbstractSlider::timerEvent( event ); + return; + } + + if ( !isValid() ) + { + killTimer( d_data->repeatTimerId ); + d_data->repeatTimerId = 0; + return; + } + + const double v = value(); + incrementValue( d_data->stepsIncrement ); + + if ( v != value() ) + { + if ( isTracking() ) + Q_EMIT valueChanged( value() ); + else + d_data->pendingValueChange = true; + + Q_EMIT sliderMoved( value() ); } + + if ( !d_data->timerTick ) + { + // restart the timer with a shorter interval + killTimer( d_data->repeatTimerId ); + d_data->repeatTimerId = startTimer( updateInterval() ); + + d_data->timerTick = true; + } } -//! Draw the QwtSlider -void QwtSlider::draw(QPainter *painter, const QRect&) +/*! + Qt paint event handler + \param event Paint event +*/ +void QwtSlider::paintEvent( QPaintEvent *event ) { - if (d_data->scalePos != NoScale) { -#if QT_VERSION < 0x040000 - scaleDraw()->draw(painter, colorGroup()); -#else - scaleDraw()->draw(painter, palette()); -#endif + QPainter painter( this ); + painter.setClipRegion( event->region() ); + + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); + + if ( d_data->scalePosition != QwtSlider::NoScale ) + { + if ( !d_data->sliderRect.contains( event->rect() ) ) + scaleDraw()->draw( &painter, palette() ); } - drawSlider(painter, d_data->sliderRect); + drawSlider( &painter, d_data->sliderRect ); if ( hasFocus() ) - QwtPainter::drawFocusRect(painter, this, d_data->sliderRect); + QwtPainter::drawFocusRect( &painter, this, d_data->sliderRect ); } -//! Qt resize event -void QwtSlider::resizeEvent(QResizeEvent *) +/*! + Qt resize event handler + \param event Resize event +*/ +void QwtSlider::resizeEvent( QResizeEvent *event ) { + Q_UNUSED( event ); + layoutSlider( false ); } +/*! + Handles QEvent::StyleChange and QEvent::FontChange events + \param event Change event +*/ +void QwtSlider::changeEvent( QEvent *event ) +{ + if ( event->type() == QEvent::StyleChange || + event->type() == QEvent::FontChange ) + { + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); + } + + QwtAbstractSlider::changeEvent( event ); +} + /*! Recalculate the slider's geometry and layout based on - the current rect and fonts. + the current geometry and fonts. + \param update_geometry notify the layout system and call update to redraw the scale */ void QwtSlider::layoutSlider( bool update_geometry ) { - int sliderWidth = d_data->thumbWidth; - int sld1 = d_data->thumbLength / 2 - 1; - int sld2 = d_data->thumbLength / 2 + d_data->thumbLength % 2; - if ( d_data->bgStyle & BgTrough ) { - sliderWidth += 2 * d_data->borderWidth; - sld1 += d_data->borderWidth; - sld2 += d_data->borderWidth; - } + int bw = 0; + if ( d_data->hasTrough ) + bw = d_data->borderWidth; - int scd = 0; - if ( d_data->scalePos != NoScale ) { - int d1, d2; - scaleDraw()->getBorderDistHint(font(), d1, d2); - scd = qwtMax(d1, d2); - } + const QSize handleSize = qwtHandleSize( d_data->handleSize, + d_data->orientation, d_data->hasTrough ); - int slo = scd - sld1; - if ( slo < 0 ) - slo = 0; + QRect sliderRect = contentsRect(); - int x, y, length; + /* + The marker line of the handle needs to be aligned to + the scale. But the marker is in the center + and we need space enough to display the rest of the handle. - const QRect r = rect(); - if (orientation() == Qt::Horizontal) { - switch (d_data->scalePos) { - case TopScale: { - d_data->sliderRect.setRect( - r.x() + d_data->xMargin + slo, - r.y() + r.height() - - d_data->yMargin - sliderWidth, - r.width() - 2 * d_data->xMargin - 2 * slo, - sliderWidth); + But the scale itself usually needs margins for displaying + the tick labels, that also might needs space beyond the + backbone. - x = d_data->sliderRect.x() + sld1; - y = d_data->sliderRect.y() - d_data->scaleDist; + Now it depends on what needs more margins. If it is the + slider the scale gets shrunk, otherwise the slider. + */ - break; - } + int scaleMargin = 0; + if ( d_data->scalePosition != QwtSlider::NoScale ) + { + int d1, d2; + scaleDraw()->getBorderDistHint( font(), d1, d2 ); + + scaleMargin = qMax( d1, d2 ) - bw; + } - case BottomScale: { - d_data->sliderRect.setRect( - r.x() + d_data->xMargin + slo, - r.y() + d_data->yMargin, - r.width() - 2 * d_data->xMargin - 2 * slo, - sliderWidth); + int scaleX, scaleY, scaleLength; - x = d_data->sliderRect.x() + sld1; - y = d_data->sliderRect.y() + d_data->sliderRect.height() - + d_data->scaleDist; + if ( d_data->orientation == Qt::Horizontal ) + { + const int handleMargin = handleSize.width() / 2 - 1; + if ( scaleMargin > handleMargin ) + { + int off = scaleMargin - handleMargin; + sliderRect.adjust( off, 0, -off, 0 ); + } - break; + scaleX = sliderRect.left() + bw + handleSize.width() / 2 - 1; + scaleLength = sliderRect.width() - handleSize.width(); + } + else + { + int handleMargin = handleSize.height() / 2 - 1; + if ( scaleMargin > handleMargin ) + { + int off = scaleMargin - handleMargin; + sliderRect.adjust( 0, off, 0, -off ); } - case NoScale: // like Bottom, but no scale. See QwtSlider(). - default: { // inconsistent orientation and scale position - d_data->sliderRect.setRect( - r.x() + d_data->xMargin + slo, - r.y() + d_data->yMargin, - r.width() - 2 * d_data->xMargin - 2 * slo, - sliderWidth); + scaleY = sliderRect.top() + bw + handleSize.height() / 2 - 1; + scaleLength = sliderRect.height() - handleSize.height(); + } + + scaleLength -= 2 * bw; - x = d_data->sliderRect.x() + sld1; - y = 0; + // now align slider and scale according to the ScalePosition - break; + if ( d_data->orientation == Qt::Horizontal ) + { + const int h = handleSize.height() + 2 * bw; + + if ( d_data->scalePosition == QwtSlider::TrailingScale ) + { + sliderRect.setTop( sliderRect.bottom() + 1 - h ); + scaleY = sliderRect.top() - d_data->spacing; } + else + { + sliderRect.setHeight( h ); + scaleY = sliderRect.bottom() + 1 + d_data->spacing; } - length = d_data->sliderRect.width() - (sld1 + sld2); - } else { // if (orientation() == Qt::Vertical - switch (d_data->scalePos) { - case RightScale: - d_data->sliderRect.setRect( - r.x() + d_data->xMargin, - r.y() + d_data->yMargin + slo, - sliderWidth, - r.height() - 2 * d_data->yMargin - 2 * slo); - - x = d_data->sliderRect.x() + d_data->sliderRect.width() - + d_data->scaleDist; - y = d_data->sliderRect.y() + sld1; - - break; - - case LeftScale: - d_data->sliderRect.setRect( - r.x() + r.width() - sliderWidth - d_data->xMargin, - r.y() + d_data->yMargin + slo, - sliderWidth, - r.height() - 2 * d_data->yMargin - 2 * slo); - - x = d_data->sliderRect.x() - d_data->scaleDist; - y = d_data->sliderRect.y() + sld1; - - break; - - case NoScale: // like Left, but no scale. See QwtSlider(). - default: // inconsistent orientation and scale position - d_data->sliderRect.setRect( - r.x() + r.width() - sliderWidth - d_data->xMargin, - r.y() + d_data->yMargin + slo, - sliderWidth, - r.height() - 2 * d_data->yMargin - 2 * slo); - - x = 0; - y = d_data->sliderRect.y() + sld1; - - break; + } + else // Qt::Vertical + { + const int w = handleSize.width() + 2 * bw; + + if ( d_data->scalePosition == QwtSlider::LeadingScale ) + { + sliderRect.setWidth( w ); + scaleX = sliderRect.right() + 1 + d_data->spacing; + } + else + { + sliderRect.setLeft( sliderRect.right() + 1 - w ); + scaleX = sliderRect.left() - d_data->spacing; } - length = d_data->sliderRect.height() - (sld1 + sld2); } - scaleDraw()->move(x, y); - scaleDraw()->setLength(length); + d_data->sliderRect = sliderRect; - d_data->map.setPaintXInterval(scaleDraw()->map().p1(), - scaleDraw()->map().p2()); + scaleDraw()->move( scaleX, scaleY ); + scaleDraw()->setLength( scaleLength ); - if ( update_geometry ) { + if ( update_geometry ) + { d_data->sizeHintCache = QSize(); // invalidate updateGeometry(); update(); } } -//! Notify change of value -void QwtSlider::valueChange() -{ - QwtAbstractSlider::valueChange(); - update(); -} - - -//! Notify change of range -void QwtSlider::rangeChange() -{ - d_data->map.setScaleInterval(minValue(), maxValue()); - - if (autoScale()) - rescale(minValue(), maxValue()); +/*! + En/Disable the trough - QwtAbstractSlider::rangeChange(); - layoutSlider(); -} + The slider can be cutomized by showing a trough for the + handle. -/*! - \brief Set distances between the widget's border and internals. - \param xMargin Horizontal margin - \param yMargin Vertical margin -*/ -void QwtSlider::setMargins(int xMargin, int yMargin) + \param on When true, the groove is visible + \sa hasTrough(), setGroove() + */ +void QwtSlider::setTrough( bool on ) { - if ( xMargin < 0 ) - xMargin = 0; - if ( yMargin < 0 ) - yMargin = 0; + if ( d_data->hasTrough != on ) + { + d_data->hasTrough = on; - if ( xMargin != d_data->xMargin || yMargin != d_data->yMargin ) { - d_data->xMargin = xMargin; - d_data->yMargin = yMargin; - layoutSlider(); + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); } } /*! - Set the background style. -*/ -void QwtSlider::setBgStyle(BGSTYLE st) + \return True, when the trough is visisble + \sa setTrough(), hasGroove() + */ +bool QwtSlider::hasTrough() const { - d_data->bgStyle = st; - layoutSlider(); + return d_data->hasTrough; } /*! - \return the background style. -*/ -QwtSlider::BGSTYLE QwtSlider::bgStyle() const -{ - return d_data->bgStyle; -} + En/Disable the groove -/*! - \return the thumb length. -*/ -int QwtSlider::thumbLength() const -{ - return d_data->thumbLength; -} + The slider can be cutomized by showing a groove for the + handle. -/*! - \return the thumb width. -*/ -int QwtSlider::thumbWidth() const + \param on When true, the groove is visible + \sa hasGroove(), setThrough() + */ +void QwtSlider::setGroove( bool on ) { - return d_data->thumbWidth; + if ( d_data->hasGroove != on ) + { + d_data->hasGroove = on; + + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutSlider( true ); + } } /*! - \return the border width. -*/ -int QwtSlider::borderWidth() const + \return True, when the groove is visisble + \sa setGroove(), hasTrough() + */ +bool QwtSlider::hasGroove() const { - return d_data->borderWidth; -} + return d_data->hasGroove; +} /*! - \return QwtSlider::minimumSizeHint() + \return minimumSizeHint() */ QSize QwtSlider::sizeHint() const { - return minimumSizeHint(); + const QSize hint = minimumSizeHint(); + return hint.expandedTo( QApplication::globalStrut() ); } /*! - \brief Return a minimum size hint - \warning The return value of QwtSlider::minimumSizeHint() depends on - the font and the scale. + \return Minimum size hint + \sa sizeHint() */ QSize QwtSlider::minimumSizeHint() const { - if (!d_data->sizeHintCache.isEmpty()) + if ( !d_data->sizeHintCache.isEmpty() ) return d_data->sizeHintCache; - int sliderWidth = d_data->thumbWidth; - if (d_data->bgStyle & BgTrough) - sliderWidth += 2 * d_data->borderWidth; + const QSize handleSize = qwtHandleSize( d_data->handleSize, + d_data->orientation, d_data->hasTrough ); + + int bw = 0; + if ( d_data->hasTrough ) + bw = d_data->borderWidth; + + int sliderLength = 0; + int scaleExtent = 0; - int w = 0, h = 0; - if (d_data->scalePos != NoScale) { + if ( d_data->scalePosition != QwtSlider::NoScale ) + { int d1, d2; - scaleDraw()->getBorderDistHint(font(), d1, d2); - int msMbd = qwtMax(d1, d2); + scaleDraw()->getBorderDistHint( font(), d1, d2 ); - int mbd = d_data->thumbLength / 2; - if (d_data->bgStyle & BgTrough) - mbd += d_data->borderWidth; + const int scaleBorderDist = 2 * ( qMax( d1, d2 ) - bw ); - if ( mbd < msMbd ) - mbd = msMbd; + int handleBorderDist; + if ( d_data->orientation == Qt::Horizontal ) + handleBorderDist = handleSize.width(); + else + handleBorderDist = handleSize.height(); - const int sdExtent = scaleDraw()->extent( QPen(), font() ); - const int sdLength = scaleDraw()->minLength( QPen(), font() ); + sliderLength = scaleDraw()->minLength( font() ); + if ( handleBorderDist > scaleBorderDist ) + { + // We need additional space for the overlapping handle + sliderLength += handleBorderDist - scaleBorderDist; + } - h = sliderWidth + sdExtent + d_data->scaleDist; - w = sdLength - 2 * msMbd + 2 * mbd; - } else { // no scale - w = 200; - h = sliderWidth; + scaleExtent += d_data->spacing; + scaleExtent += qCeil( scaleDraw()->extent( font() ) ); } - if ( orientation() == Qt::Vertical ) - qSwap(w, h); + sliderLength = qMax( sliderLength, 84 ); // from QSlider - w += 2 * d_data->xMargin; - h += 2 * d_data->yMargin; + int w = 0; + int h = 0; - d_data->sizeHintCache = QSize(w, h); + if ( d_data->orientation == Qt::Horizontal ) + { + w = sliderLength; + h = handleSize.height() + 2 * bw + scaleExtent; + } + else + { + w = handleSize.width() + 2 * bw + scaleExtent; + h = sliderLength; + } + + // finally add margins + int left, right, top, bottom; + getContentsMargins( &left, &top, &right, &bottom ); + + w += left + right; + h += top + bottom; + + d_data->sizeHintCache = QSize( w, h ); return d_data->sizeHintCache; } + +/*! + \return Bounding rectangle of the slider handle + */ +QRect QwtSlider::handleRect() const +{ + if ( !isValid() ) + return QRect(); + + const int markerPos = transform( value() ); + + QPoint center = d_data->sliderRect.center(); + if ( d_data->orientation == Qt::Horizontal ) + center.setX( markerPos ); + else + center.setY( markerPos ); + + QRect rect; + rect.setSize( qwtHandleSize( d_data->handleSize, + d_data->orientation, d_data->hasTrough ) ); + rect.moveCenter( center ); + + return rect; +} + +/*! + \return Bounding rectangle of the slider - without the scale + */ +QRect QwtSlider::sliderRect() const +{ + return d_data->sliderRect; +} diff --git a/libs/qwt/qwt_slider.h b/libs/qwt/qwt_slider.h index 7eebe11fef..d1b36badbe 100644 --- a/libs/qwt/qwt_slider.h +++ b/libs/qwt/qwt_slider.h @@ -7,13 +7,10 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_SLIDER_H #define QWT_SLIDER_H #include "qwt_global.h" -#include "qwt_abstract_scale.h" #include "qwt_abstract_slider.h" class QwtScaleDraw; @@ -22,112 +19,109 @@ class QwtScaleDraw; \brief The Slider Widget QwtSlider is a slider widget which operates on an interval - of type double. QwtSlider supports different layouts as - well as a scale. + of type double. Its position is related to a scale showing + the current value. - \image html sliders.png + The slider can be customized by having a through, a groove - or both. - \sa QwtAbstractSlider and QwtAbstractScale for the descriptions - of the inherited members. + \image html sliders.png */ -class QWT_EXPORT QwtSlider : public QwtAbstractSlider, public QwtAbstractScale +class QWT_EXPORT QwtSlider: public QwtAbstractSlider { Q_OBJECT - Q_ENUMS( ScalePos ) - Q_ENUMS( BGSTYLE ) - Q_PROPERTY( ScalePos scalePosition READ scalePosition - WRITE setScalePosition ) - Q_PROPERTY( BGSTYLE bgStyle READ bgStyle WRITE setBgStyle ) - Q_PROPERTY( int thumbLength READ thumbLength WRITE setThumbLength ) - Q_PROPERTY( int thumbWidth READ thumbWidth WRITE setThumbWidth ) + + Q_ENUMS( ScalePosition BackgroundStyle ) + + Q_PROPERTY( Qt::Orientation orientation + READ orientation WRITE setOrientation ) + Q_PROPERTY( ScalePosition scalePosition READ scalePosition + WRITE setScalePosition ) + + Q_PROPERTY( bool trough READ hasTrough WRITE setTrough ) + Q_PROPERTY( bool groove READ hasGroove WRITE setGroove ) + + Q_PROPERTY( QSize handleSize READ handleSize WRITE setHandleSize ) Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) + Q_PROPERTY( int spacing READ spacing WRITE setSpacing ) public: /*! - Scale position. QwtSlider tries to enforce valid combinations of its - orientation and scale position: - - Qt::Horizonal combines with NoScale, TopScale and BottomScale - - Qt::Vertical combines with NoScale, LeftScale and RightScale - - \sa QwtSlider::QwtSlider + Position of the scale + \sa QwtSlider(), setScalePosition(), setOrientation() */ - enum ScalePos { + enum ScalePosition + { + //! The slider has no scale NoScale, - LeftScale, - RightScale, - TopScale, - BottomScale - }; + //! The scale is right of a vertical or below a horizontal slider + LeadingScale, - /*! - Background style. - \sa QwtSlider::QwtSlider - */ - enum BGSTYLE { - BgTrough = 0x1, - BgSlot = 0x2, - BgBoth = BgTrough | BgSlot + //! The scale is left of a vertical or above a horizontal slider + TrailingScale }; - explicit QwtSlider(QWidget *parent, - Qt::Orientation = Qt::Horizontal, - ScalePos = NoScale, BGSTYLE bgStyle = BgTrough); -#if QT_VERSION < 0x040000 - explicit QwtSlider(QWidget *parent, const char *name); -#endif + explicit QwtSlider( QWidget *parent = NULL ); + explicit QwtSlider( Qt::Orientation, QWidget *parent = NULL ); virtual ~QwtSlider(); - virtual void setOrientation(Qt::Orientation); + void setOrientation( Qt::Orientation ); + Qt::Orientation orientation() const; + + void setScalePosition( ScalePosition ); + ScalePosition scalePosition() const; - void setBgStyle(BGSTYLE); - BGSTYLE bgStyle() const; + void setTrough( bool ); + bool hasTrough() const; - void setScalePosition(ScalePos s); - ScalePos scalePosition() const; + void setGroove( bool ); + bool hasGroove() const; - int thumbLength() const; - int thumbWidth() const; + void setHandleSize( const QSize & ); + QSize handleSize() const; + + void setBorderWidth( int bw ); int borderWidth() const; - void setThumbLength(int l); - void setThumbWidth(int w); - void setBorderWidth(int bw); - void setMargins(int x, int y); + void setSpacing( int ); + int spacing() const; virtual QSize sizeHint() const; virtual QSize minimumSizeHint() const; - void setScaleDraw(QwtScaleDraw *); + void setScaleDraw( QwtScaleDraw * ); const QwtScaleDraw *scaleDraw() const; + void setUpdateInterval( int ); + int updateInterval() const; + protected: - virtual double getValue(const QPoint &p); - virtual void getScrollMode(const QPoint &p, - int &scrollMode, int &direction); + virtual double scrolledTo( const QPoint & ) const; + virtual bool isScrollPosition( const QPoint & ) const; - void draw(QPainter *p, const QRect& update_rect); - virtual void drawSlider (QPainter *p, const QRect &r); - virtual void drawThumb(QPainter *p, const QRect &, int pos); + virtual void drawSlider ( QPainter *, const QRect & ) const; + virtual void drawHandle( QPainter *, const QRect &, int pos ) const; - virtual void resizeEvent(QResizeEvent *e); - virtual void paintEvent (QPaintEvent *e); + virtual void mousePressEvent( QMouseEvent * ); + virtual void mouseReleaseEvent( QMouseEvent * ); + virtual void resizeEvent( QResizeEvent * ); + virtual void paintEvent ( QPaintEvent * ); + virtual void changeEvent( QEvent * ); + virtual void timerEvent( QTimerEvent * ); - virtual void valueChange(); - virtual void rangeChange(); virtual void scaleChange(); - virtual void fontChange(const QFont &oldFont); - void layoutSlider( bool update = true ); - int xyPosition(double v) const; + QRect sliderRect() const; + QRect handleRect() const; +private: QwtScaleDraw *scaleDraw(); -private: - void initSlider(Qt::Orientation, ScalePos scalePos, BGSTYLE bgStyle); + void layoutSlider( bool ); + void initSlider( Qt::Orientation ); class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_spline.cpp b/libs/qwt/qwt_spline.cpp index d6c5ee7c70..5952b1801a 100644 --- a/libs/qwt/qwt_spline.cpp +++ b/libs/qwt/qwt_spline.cpp @@ -9,55 +9,49 @@ #include "qwt_spline.h" #include "qwt_math.h" -#include "qwt_array.h" class QwtSpline::PrivateData { public: PrivateData(): - splineType(QwtSpline::Natural) { + splineType( QwtSpline::Natural ) + { } QwtSpline::SplineType splineType; // coefficient vectors - QwtArray<double> a; - QwtArray<double> b; - QwtArray<double> c; + QVector<double> a; + QVector<double> b; + QVector<double> c; // control points -#if QT_VERSION < 0x040000 - QwtArray<QwtDoublePoint> points; -#else QPolygonF points; -#endif }; -#if QT_VERSION < 0x040000 -static int lookup(double x, const QwtArray<QwtDoublePoint> &values) -#else -static int lookup(double x, const QPolygonF &values) -#endif +static int lookup( double x, const QPolygonF &values ) { #if 0 -//qLowerBiund/qHigherBound ??? +//qLowerBound/qHigherBound ??? #endif int i1; - const int size = (int)values.size(); + const int size = values.size(); - if (x <= values[0].x()) + if ( x <= values[0].x() ) i1 = 0; - else if (x >= values[size - 2].x()) + else if ( x >= values[size - 2].x() ) i1 = size - 2; - else { + else + { i1 = 0; int i2 = size - 2; int i3 = 0; - while ( i2 - i1 > 1 ) { - i3 = i1 + ((i2 - i1) >> 1); + while ( i2 - i1 > 1 ) + { + i3 = i1 + ( ( i2 - i1 ) >> 1 ); - if (values[i3].x() > x) + if ( values[i3].x() > x ) i2 = i3; else i1 = i3; @@ -72,12 +66,21 @@ QwtSpline::QwtSpline() d_data = new PrivateData; } -QwtSpline::QwtSpline(const QwtSpline& other) +/*! + Copy constructor + \param other Spline used for initialization +*/ +QwtSpline::QwtSpline( const QwtSpline& other ) { - d_data = new PrivateData(*other.d_data); + d_data = new PrivateData( *other.d_data ); } -QwtSpline &QwtSpline::operator=( const QwtSpline &other) +/*! + Assignment operator + \param other Spline used for initialization + \return *this +*/ +QwtSpline &QwtSpline::operator=( const QwtSpline & other ) { *d_data = *other.d_data; return *this; @@ -89,18 +92,26 @@ QwtSpline::~QwtSpline() delete d_data; } -void QwtSpline::setSplineType(SplineType splineType) +/*! + Select the algorithm used for calculating the spline + + \param splineType Spline type + \sa splineType() +*/ +void QwtSpline::setSplineType( SplineType splineType ) { d_data->splineType = splineType; } +/*! + \return the spline type + \sa setSplineType() +*/ QwtSpline::SplineType QwtSpline::splineType() const { return d_data->splineType; } -//! Determine the function table index corresponding to a value x - /*! \brief Calculate the spline coefficients @@ -108,69 +119,73 @@ QwtSpline::SplineType QwtSpline::splineType() const will determine the coefficients for a natural or a periodic spline and store them internally. - \param x - \param y points - \param size number of points - \param periodic if true, calculate periodic spline + \param points Points \return true if successful \warning The sequence of x (but not y) values has to be strictly monotone - increasing, which means <code>x[0] < x[1] < .... < x[n-1]</code>. + increasing, which means <code>points[i].x() < points[i+1].x()</code>. If this is not the case, the function will return false */ -#if QT_VERSION < 0x040000 -bool QwtSpline::setPoints(const QwtArray<QwtDoublePoint>& points) -#else -bool QwtSpline::setPoints(const QPolygonF& points) -#endif +bool QwtSpline::setPoints( const QPolygonF& points ) { const int size = points.size(); - if (size <= 2) { + if ( size <= 2 ) + { reset(); return false; } -#if QT_VERSION < 0x040000 - d_data->points = points.copy(); // Qt3: deep copy -#else d_data->points = points; -#endif - d_data->a.resize(size-1); - d_data->b.resize(size-1); - d_data->c.resize(size-1); + d_data->a.resize( size - 1 ); + d_data->b.resize( size - 1 ); + d_data->c.resize( size - 1 ); bool ok; if ( d_data->splineType == Periodic ) - ok = buildPeriodicSpline(points); + ok = buildPeriodicSpline( points ); else - ok = buildNaturalSpline(points); + ok = buildNaturalSpline( points ); - if (!ok) + if ( !ok ) reset(); return ok; } /*! - Return points passed by setPoints + \return Points, that have been by setPoints() */ -#if QT_VERSION < 0x040000 -QwtArray<QwtDoublePoint> QwtSpline::points() const -#else QPolygonF QwtSpline::points() const -#endif { return d_data->points; } +//! \return A coefficients +const QVector<double> &QwtSpline::coefficientsA() const +{ + return d_data->a; +} + +//! \return B coefficients +const QVector<double> &QwtSpline::coefficientsB() const +{ + return d_data->b; +} + +//! \return C coefficients +const QVector<double> &QwtSpline::coefficientsC() const +{ + return d_data->c; +} + //! Free allocated memory and set size to 0 void QwtSpline::reset() { - d_data->a.resize(0); - d_data->b.resize(0); - d_data->c.resize(0); - d_data->points.resize(0); + d_data->a.resize( 0 ); + d_data->b.resize( 0 ); + d_data->c.resize( 0 ); + d_data->points.resize( 0 ); } //! True if valid @@ -182,36 +197,31 @@ bool QwtSpline::isValid() const /*! Calculate the interpolated function value corresponding to a given argument x. + + \param x Coordinate + \return Interpolated coordinate */ -double QwtSpline::value(double x) const +double QwtSpline::value( double x ) const { - if (d_data->a.size() == 0) + if ( d_data->a.size() == 0 ) return 0.0; - const int i = lookup(x, d_data->points); + const int i = lookup( x, d_data->points ); const double delta = x - d_data->points[i].x(); - return( ( ( ( d_data->a[i] * delta) + d_data->b[i] ) - * delta + d_data->c[i] ) * delta + d_data->points[i].y() ); + return( ( ( ( d_data->a[i] * delta ) + d_data->b[i] ) + * delta + d_data->c[i] ) * delta + d_data->points[i].y() ); } /*! \brief Determines the coefficients for a natural spline \return true if successful */ -#if QT_VERSION < 0x040000 -bool QwtSpline::buildNaturalSpline(const QwtArray<QwtDoublePoint> &points) -#else -bool QwtSpline::buildNaturalSpline(const QPolygonF &points) -#endif +bool QwtSpline::buildNaturalSpline( const QPolygonF &points ) { int i; -#if QT_VERSION < 0x040000 - const QwtDoublePoint *p = points.data(); -#else const QPointF *p = points.data(); -#endif const int size = points.size(); double *a = d_data->a.data(); @@ -220,21 +230,23 @@ bool QwtSpline::buildNaturalSpline(const QPolygonF &points) // set up tridiagonal equation system; use coefficient // vectors as temporary buffers - QwtArray<double> h(size-1); - for (i = 0; i < size - 1; i++) { + QVector<double> h( size - 1 ); + for ( i = 0; i < size - 1; i++ ) + { h[i] = p[i+1].x() - p[i].x(); - if (h[i] <= 0) + if ( h[i] <= 0 ) return false; } - QwtArray<double> d(size-1); - double dy1 = (p[1].y() - p[0].y()) / h[0]; - for (i = 1; i < size - 1; i++) { + QVector<double> d( size - 1 ); + double dy1 = ( p[1].y() - p[0].y() ) / h[0]; + for ( i = 1; i < size - 1; i++ ) + { b[i] = c[i] = h[i]; - a[i] = 2.0 * (h[i-1] + h[i]); + a[i] = 2.0 * ( h[i-1] + h[i] ); - const double dy2 = (p[i+1].y() - p[i].y()) / h[i]; - d[i] = 6.0 * ( dy1 - dy2); + const double dy2 = ( p[i+1].y() - p[i].y() ) / h[i]; + d[i] = 6.0 * ( dy1 - dy2 ); dy1 = dy2; } @@ -243,31 +255,33 @@ bool QwtSpline::buildNaturalSpline(const QPolygonF &points) // // L-U Factorization - for(i = 1; i < size - 2; i++) { + for ( i = 1; i < size - 2; i++ ) + { c[i] /= a[i]; a[i+1] -= b[i] * c[i]; } // forward elimination - QwtArray<double> s(size); + QVector<double> s( size ); s[1] = d[1]; - for ( i = 2; i < size - 1; i++) + for ( i = 2; i < size - 1; i++ ) s[i] = d[i] - c[i-1] * s[i-1]; // backward elimination s[size - 2] = - s[size - 2] / a[size - 2]; - for (i = size -3; i > 0; i--) - s[i] = - (s[i] + b[i] * s[i+1]) / a[i]; + for ( i = size - 3; i > 0; i-- ) + s[i] = - ( s[i] + b[i] * s[i+1] ) / a[i]; s[size - 1] = s[0] = 0.0; // // Finally, determine the spline coefficients // - for (i = 0; i < size - 1; i++) { - a[i] = ( s[i+1] - s[i] ) / ( 6.0 * h[i]); + for ( i = 0; i < size - 1; i++ ) + { + a[i] = ( s[i+1] - s[i] ) / ( 6.0 * h[i] ); b[i] = 0.5 * s[i]; c[i] = ( p[i+1].y() - p[i].y() ) / h[i] - - (s[i+1] + 2.0 * s[i] ) * h[i] / 6.0; + - ( s[i+1] + 2.0 * s[i] ) * h[i] / 6.0; } return true; @@ -277,48 +291,41 @@ bool QwtSpline::buildNaturalSpline(const QPolygonF &points) \brief Determines the coefficients for a periodic spline \return true if successful */ -#if QT_VERSION < 0x040000 -bool QwtSpline::buildPeriodicSpline( - const QwtArray<QwtDoublePoint> &points) -#else -bool QwtSpline::buildPeriodicSpline(const QPolygonF &points) -#endif +bool QwtSpline::buildPeriodicSpline( const QPolygonF &points ) { int i; -#if QT_VERSION < 0x040000 - const QwtDoublePoint *p = points.data(); -#else const QPointF *p = points.data(); -#endif const int size = points.size(); double *a = d_data->a.data(); double *b = d_data->b.data(); double *c = d_data->c.data(); - QwtArray<double> d(size-1); - QwtArray<double> h(size-1); - QwtArray<double> s(size); + QVector<double> d( size - 1 ); + QVector<double> h( size - 1 ); + QVector<double> s( size ); // // setup equation system; use coefficient // vectors as temporary buffers // - for (i = 0; i < size - 1; i++) { + for ( i = 0; i < size - 1; i++ ) + { h[i] = p[i+1].x() - p[i].x(); - if (h[i] <= 0.0) + if ( h[i] <= 0.0 ) return false; } const int imax = size - 2; double htmp = h[imax]; - double dy1 = (p[0].y() - p[imax].y()) / htmp; - for (i = 0; i <= imax; i++) { + double dy1 = ( p[0].y() - p[imax].y() ) / htmp; + for ( i = 0; i <= imax; i++ ) + { b[i] = c[i] = h[i]; - a[i] = 2.0 * (htmp + h[i]); - const double dy2 = (p[i+1].y() - p[i].y()) / h[i]; - d[i] = 6.0 * ( dy1 - dy2); + a[i] = 2.0 * ( htmp + h[i] ); + const double dy2 = ( p[i+1].y() - p[i].y() ) / h[i]; + d[i] = 6.0 * ( dy1 - dy2 ); dy1 = dy2; htmp = h[i]; } @@ -328,46 +335,49 @@ bool QwtSpline::buildPeriodicSpline(const QPolygonF &points) // // L-U Factorization - a[0] = sqrt(a[0]); + a[0] = qSqrt( a[0] ); c[0] = h[imax] / a[0]; double sum = 0; - for( i = 0; i < imax - 1; i++) { + for ( i = 0; i < imax - 1; i++ ) + { b[i] /= a[i]; - if (i > 0) + if ( i > 0 ) c[i] = - c[i-1] * b[i-1] / a[i]; - a[i+1] = sqrt( a[i+1] - qwtSqr(b[i])); - sum += qwtSqr(c[i]); + a[i+1] = qSqrt( a[i+1] - qwtSqr( b[i] ) ); + sum += qwtSqr( c[i] ); } - b[imax-1] = (b[imax-1] - c[imax-2] * b[imax-2]) / a[imax-1]; - a[imax] = sqrt(a[imax] - qwtSqr(b[imax-1]) - sum); + b[imax-1] = ( b[imax-1] - c[imax-2] * b[imax-2] ) / a[imax-1]; + a[imax] = qSqrt( a[imax] - qwtSqr( b[imax-1] ) - sum ); // forward elimination s[0] = d[0] / a[0]; sum = 0; - for( i = 1; i < imax; i++) { - s[i] = (d[i] - b[i-1] * s[i-1]) / a[i]; + for ( i = 1; i < imax; i++ ) + { + s[i] = ( d[i] - b[i-1] * s[i-1] ) / a[i]; sum += c[i-1] * s[i-1]; } - s[imax] = (d[imax] - b[imax-1] * s[imax-1] - sum) / a[imax]; + s[imax] = ( d[imax] - b[imax-1] * s[imax-1] - sum ) / a[imax]; // backward elimination s[imax] = - s[imax] / a[imax]; - s[imax-1] = -(s[imax-1] + b[imax-1] * s[imax]) / a[imax-1]; - for (i= imax - 2; i >= 0; i--) - s[i] = - (s[i] + b[i] * s[i+1] + c[i] * s[imax]) / a[i]; + s[imax-1] = -( s[imax-1] + b[imax-1] * s[imax] ) / a[imax-1]; + for ( i = imax - 2; i >= 0; i-- ) + s[i] = - ( s[i] + b[i] * s[i+1] + c[i] * s[imax] ) / a[i]; // // Finally, determine the spline coefficients // s[size-1] = s[0]; - for ( i=0; i < size-1; i++) { - a[i] = ( s[i+1] - s[i] ) / ( 6.0 * h[i]); + for ( i = 0; i < size - 1; i++ ) + { + a[i] = ( s[i+1] - s[i] ) / ( 6.0 * h[i] ); b[i] = 0.5 * s[i]; c[i] = ( p[i+1].y() - p[i].y() ) - / h[i] - (s[i+1] + 2.0 * s[i] ) * h[i] / 6.0; + / h[i] - ( s[i+1] + 2.0 * s[i] ) * h[i] / 6.0; } return true; diff --git a/libs/qwt/qwt_spline.h b/libs/qwt/qwt_spline.h index aef78e43d7..802e1da320 100644 --- a/libs/qwt/qwt_spline.h +++ b/libs/qwt/qwt_spline.h @@ -11,28 +11,8 @@ #define QWT_SPLINE_H #include "qwt_global.h" -#include "qwt_double_rect.h" - -#if QT_VERSION >= 0x040000 -#include <QPolygonF> -#else -#include "qwt_array.h" -#endif - -// MOC_SKIP_BEGIN - -#if defined(QWT_TEMPLATEDLL) - -#if QT_VERSION < 0x040000 -#ifndef QWTARRAY_TEMPLATE_QWTDOUBLEPOINT // by mjo3 -#define QWTARRAY_TEMPLATE_QWTDOUBLEPOINT -template class QWT_EXPORT QwtArray<QwtDoublePoint>; -#endif //end of QWTARRAY_TEMPLATE_QWTDOUBLEPOINT -#endif - -#endif - -// MOC_SKIP_END +#include <qpolygon.h> +#include <qvector.h> /*! \brief A class for spline interpolation @@ -77,8 +57,13 @@ QPolygonF interpolate(const QPolygonF& points, int numValues) class QWT_EXPORT QwtSpline { public: - enum SplineType { + //! Spline type + enum SplineType + { + //! A natural spline Natural, + + //! A periodic spline Periodic }; @@ -89,34 +74,26 @@ public: QwtSpline &operator=( const QwtSpline & ); - void setSplineType(SplineType); + void setSplineType( SplineType ); SplineType splineType() const; -#if QT_VERSION < 0x040000 - bool setPoints(const QwtArray<QwtDoublePoint>& points); - QwtArray<QwtDoublePoint> points() const; -#else - bool setPoints(const QPolygonF& points); + bool setPoints( const QPolygonF& points ); QPolygonF points() const; -#endif void reset(); bool isValid() const; - double value(double x) const; + double value( double x ) const; -protected: + const QVector<double> &coefficientsA() const; + const QVector<double> &coefficientsB() const; + const QVector<double> &coefficientsC() const; -#if QT_VERSION < 0x040000 - bool buildNaturalSpline( - const QwtArray<QwtDoublePoint> &); - bool buildPeriodicSpline( - const QwtArray<QwtDoublePoint> &); -#else - bool buildNaturalSpline(const QPolygonF &); - bool buildPeriodicSpline(const QPolygonF &); -#endif +protected: + bool buildNaturalSpline( const QPolygonF & ); + bool buildPeriodicSpline( const QPolygonF & ); +private: class PrivateData; PrivateData *d_data; }; diff --git a/libs/qwt/qwt_symbol.cpp b/libs/qwt/qwt_symbol.cpp index 453e571cb0..97700554b3 100644 --- a/libs/qwt/qwt_symbol.cpp +++ b/libs/qwt/qwt_symbol.cpp @@ -7,24 +7,843 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qpainter.h> -#include <qapplication.h> -#include "qwt_painter.h" -#include "qwt_polygon.h" #include "qwt_symbol.h" +#include "qwt_painter.h" +#include "qwt_graphic.h" +#include <qapplication.h> +#include <qpainter.h> +#include <qpainterpath.h> +#include <qpixmap.h> +#include <qpaintengine.h> +#include <qmath.h> +#ifndef QWT_NO_SVG +#include <qsvgrenderer.h> +#endif + +namespace QwtTriangle +{ + enum Type + { + Left, + Right, + Up, + Down + }; +} + +static QwtGraphic qwtPathGraphic( const QPainterPath &path, + const QPen &pen, const QBrush& brush ) +{ + QwtGraphic graphic; + graphic.setRenderHint( QwtGraphic::RenderPensUnscaled ); + + QPainter painter( &graphic ); + painter.setPen( pen ); + painter.setBrush( brush ); + painter.drawPath( path ); + painter.end(); + + return graphic; +} + +static inline QRectF qwtScaledBoundingRect( + const QwtGraphic &graphic, const QSizeF size ) +{ + QSizeF scaledSize = size; + if ( scaledSize.isEmpty() ) + scaledSize = graphic.defaultSize(); + + const QSizeF sz = graphic.controlPointRect().size(); + + double sx = 1.0; + if ( sz.width() > 0.0 ) + sx = scaledSize.width() / sz.width(); + + double sy = 1.0; + if ( sz.height() > 0.0 ) + sy = scaledSize.height() / sz.height(); + + return graphic.scaledBoundingRect( sx, sy ); +} + +static inline void qwtDrawPixmapSymbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + QSize size = symbol.size(); + if ( size.isEmpty() ) + size = symbol.pixmap().size(); + + const QTransform transform = painter->transform(); + if ( transform.isScaling() ) + { + const QRect r( 0, 0, size.width(), size.height() ); + size = transform.mapRect( r ).size(); + } + + QPixmap pm = symbol.pixmap(); + if ( pm.size() != size ) + pm = pm.scaled( size ); + + QPointF pinPoint( 0.5 * size.width(), 0.5 * size.height() ); + if ( symbol.isPinPointEnabled() ) + pinPoint = symbol.pinPoint(); + + painter->resetTransform(); + + for ( int i = 0; i < numPoints; i++ ) + { + const QPointF pos = transform.map( points[i] ) - pinPoint; + + QwtPainter::drawPixmap( painter, + QRect( pos.toPoint(), pm.size() ), pm ); + } +} + +#ifndef QWT_NO_SVG + +static inline void qwtDrawSvgSymbols( QPainter *painter, + const QPointF *points, int numPoints, + QSvgRenderer *renderer, const QwtSymbol &symbol ) +{ + if ( renderer == NULL || !renderer->isValid() ) + return; + + const QRectF viewBox = renderer->viewBoxF(); + if ( viewBox.isEmpty() ) + return; + + QSizeF sz = symbol.size(); + if ( !sz.isValid() ) + sz = viewBox.size(); + + const double sx = sz.width() / viewBox.width(); + const double sy = sz.height() / viewBox.height(); + + QPointF pinPoint = viewBox.center(); + if ( symbol.isPinPointEnabled() ) + pinPoint = symbol.pinPoint(); + + const double dx = sx * ( pinPoint.x() - viewBox.left() ); + const double dy = sy * ( pinPoint.y() - viewBox.top() ); + + for ( int i = 0; i < numPoints; i++ ) + { + const double x = points[i].x() - dx; + const double y = points[i].y() - dy; + + renderer->render( painter, + QRectF( x, y, sz.width(), sz.height() ) ); + } +} + +#endif + +static inline void qwtDrawGraphicSymbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtGraphic &graphic, + const QwtSymbol &symbol ) +{ + const QRectF pointRect = graphic.controlPointRect(); + if ( pointRect.isEmpty() ) + return; + + double sx = 1.0; + double sy = 1.0; + + const QSize sz = symbol.size(); + if ( sz.isValid() ) + { + sx = sz.width() / pointRect.width(); + sy = sz.height() / pointRect.height(); + } + + QPointF pinPoint = pointRect.center(); + if ( symbol.isPinPointEnabled() ) + pinPoint = symbol.pinPoint(); + + const QTransform transform = painter->transform(); + + for ( int i = 0; i < numPoints; i++ ) + { + QTransform tr = transform; + tr.translate( points[i].x(), points[i].y() ); + tr.scale( sx, sy ); + tr.translate( -pinPoint.x(), -pinPoint.y() ); + + painter->setTransform( tr ); + + graphic.render( painter ); + } + + painter->setTransform( transform ); +} + +static inline void qwtDrawEllipseSymbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + painter->setBrush( symbol.brush() ); + painter->setPen( symbol.pen() ); + + const QSize size = symbol.size(); + + if ( QwtPainter::roundingAlignment( painter ) ) + { + const int sw = size.width(); + const int sh = size.height(); + const int sw2 = size.width() / 2; + const int sh2 = size.height() / 2; + + for ( int i = 0; i < numPoints; i++ ) + { + const int x = qRound( points[i].x() ); + const int y = qRound( points[i].y() ); + + const QRectF r( x - sw2, y - sh2, sw, sh ); + QwtPainter::drawEllipse( painter, r ); + } + } + else + { + const double sw = size.width(); + const double sh = size.height(); + const double sw2 = 0.5 * size.width(); + const double sh2 = 0.5 * size.height(); + + for ( int i = 0; i < numPoints; i++ ) + { + const double x = points[i].x(); + const double y = points[i].y(); + + const QRectF r( x - sw2, y - sh2, sw, sh ); + QwtPainter::drawEllipse( painter, r ); + } + } +} + +static inline void qwtDrawRectSymbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + const QSize size = symbol.size(); + + QPen pen = symbol.pen(); + pen.setJoinStyle( Qt::MiterJoin ); + painter->setPen( pen ); + painter->setBrush( symbol.brush() ); + painter->setRenderHint( QPainter::Antialiasing, false ); + + if ( QwtPainter::roundingAlignment( painter ) ) + { + const int sw = size.width(); + const int sh = size.height(); + const int sw2 = size.width() / 2; + const int sh2 = size.height() / 2; + + for ( int i = 0; i < numPoints; i++ ) + { + const int x = qRound( points[i].x() ); + const int y = qRound( points[i].y() ); + + const QRect r( x - sw2, y - sh2, sw, sh ); + QwtPainter::drawRect( painter, r ); + } + } + else + { + const double sw = size.width(); + const double sh = size.height(); + const double sw2 = 0.5 * size.width(); + const double sh2 = 0.5 * size.height(); + + for ( int i = 0; i < numPoints; i++ ) + { + const double x = points[i].x(); + const double y = points[i].y(); + + const QRectF r( x - sw2, y - sh2, sw, sh ); + QwtPainter::drawRect( painter, r ); + } + } +} + +static inline void qwtDrawDiamondSymbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + const QSize size = symbol.size(); + + QPen pen = symbol.pen(); + pen.setJoinStyle( Qt::MiterJoin ); + painter->setPen( pen ); + painter->setBrush( symbol.brush() ); + + if ( QwtPainter::roundingAlignment( painter ) ) + { + for ( int i = 0; i < numPoints; i++ ) + { + const int x = qRound( points[i].x() ); + const int y = qRound( points[i].y() ); + + const int x1 = x - size.width() / 2; + const int y1 = y - size.height() / 2; + const int x2 = x1 + size.width(); + const int y2 = y1 + size.height(); + + QPolygonF polygon; + polygon += QPointF( x, y1 ); + polygon += QPointF( x1, y ); + polygon += QPointF( x, y2 ); + polygon += QPointF( x2, y ); + + QwtPainter::drawPolygon( painter, polygon ); + } + } + else + { + for ( int i = 0; i < numPoints; i++ ) + { + const QPointF &pos = points[i]; + + const double x1 = pos.x() - 0.5 * size.width(); + const double y1 = pos.y() - 0.5 * size.height(); + const double x2 = x1 + size.width(); + const double y2 = y1 + size.height(); + + QPolygonF polygon; + polygon += QPointF( pos.x(), y1 ); + polygon += QPointF( x2, pos.y() ); + polygon += QPointF( pos.x(), y2 ); + polygon += QPointF( x1, pos.y() ); + + QwtPainter::drawPolygon( painter, polygon ); + } + } +} + +static inline void qwtDrawTriangleSymbols( + QPainter *painter, QwtTriangle::Type type, + const QPointF *points, int numPoints, + const QwtSymbol &symbol ) +{ + const QSize size = symbol.size(); + + QPen pen = symbol.pen(); + pen.setJoinStyle( Qt::MiterJoin ); + painter->setPen( pen ); + + painter->setBrush( symbol.brush() ); + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double sw2 = 0.5 * size.width(); + double sh2 = 0.5 * size.height(); + + if ( doAlign ) + { + sw2 = qFloor( sw2 ); + sh2 = qFloor( sh2 ); + } + + QPolygonF triangle( 3 ); + QPointF *trianglePoints = triangle.data(); + + for ( int i = 0; i < numPoints; i++ ) + { + const QPointF &pos = points[i]; + + double x = pos.x(); + double y = pos.y(); + + if ( doAlign ) + { + x = qRound( x ); + y = qRound( y ); + } + + const double x1 = x - sw2; + const double x2 = x1 + size.width(); + const double y1 = y - sh2; + const double y2 = y1 + size.height(); + + switch ( type ) + { + case QwtTriangle::Left: + { + trianglePoints[0].rx() = x2; + trianglePoints[0].ry() = y1; + + trianglePoints[1].rx() = x1; + trianglePoints[1].ry() = y; + + trianglePoints[2].rx() = x2; + trianglePoints[2].ry() = y2; + + break; + } + case QwtTriangle::Right: + { + trianglePoints[0].rx() = x1; + trianglePoints[0].ry() = y1; + + trianglePoints[1].rx() = x2; + trianglePoints[1].ry() = y; + + trianglePoints[2].rx() = x1; + trianglePoints[2].ry() = y2; + + break; + } + case QwtTriangle::Up: + { + trianglePoints[0].rx() = x1; + trianglePoints[0].ry() = y2; + + trianglePoints[1].rx() = x; + trianglePoints[1].ry() = y1; + + trianglePoints[2].rx() = x2; + trianglePoints[2].ry() = y2; + + break; + } + case QwtTriangle::Down: + { + trianglePoints[0].rx() = x1; + trianglePoints[0].ry() = y1; + + trianglePoints[1].rx() = x; + trianglePoints[1].ry() = y2; + + trianglePoints[2].rx() = x2; + trianglePoints[2].ry() = y1; + + break; + } + } + QwtPainter::drawPolygon( painter, triangle ); + } +} + +static inline void qwtDrawLineSymbols( + QPainter *painter, int orientations, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + const QSize size = symbol.size(); + + int off = 0; + + QPen pen = symbol.pen(); + if ( pen.width() > 1 ) + { + pen.setCapStyle( Qt::FlatCap ); + off = 1; + } + + painter->setPen( pen ); + painter->setRenderHint( QPainter::Antialiasing, false ); + + if ( QwtPainter::roundingAlignment( painter ) ) + { + const int sw = qFloor( size.width() ); + const int sh = qFloor( size.height() ); + const int sw2 = size.width() / 2; + const int sh2 = size.height() / 2; + + for ( int i = 0; i < numPoints; i++ ) + { + if ( orientations & Qt::Horizontal ) + { + const int x = qRound( points[i].x() ) - sw2; + const int y = qRound( points[i].y() ); + + QwtPainter::drawLine( painter, x, y, x + sw + off, y ); + } + if ( orientations & Qt::Vertical ) + { + const int x = qRound( points[i].x() ); + const int y = qRound( points[i].y() ) - sh2; + + QwtPainter::drawLine( painter, x, y, x, y + sh + off ); + } + } + } + else + { + const double sw = size.width(); + const double sh = size.height(); + const double sw2 = 0.5 * size.width(); + const double sh2 = 0.5 * size.height(); + + for ( int i = 0; i < numPoints; i++ ) + { + if ( orientations & Qt::Horizontal ) + { + const double x = points[i].x() - sw2; + const double y = points[i].y(); + + QwtPainter::drawLine( painter, x, y, x + sw, y ); + } + if ( orientations & Qt::Vertical ) + { + const double y = points[i].y() - sh2; + const double x = points[i].x(); + + QwtPainter::drawLine( painter, x, y, x, y + sh ); + } + } + } +} + +static inline void qwtDrawXCrossSymbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + const QSize size = symbol.size(); + int off = 0; + + QPen pen = symbol.pen(); + if ( pen.width() > 1 ) + { + pen.setCapStyle( Qt::FlatCap ); + off = 1; + } + painter->setPen( pen ); + + + if ( QwtPainter::roundingAlignment( painter ) ) + { + const int sw = size.width(); + const int sh = size.height(); + const int sw2 = size.width() / 2; + const int sh2 = size.height() / 2; + + for ( int i = 0; i < numPoints; i++ ) + { + const QPointF &pos = points[i]; + + const int x = qRound( pos.x() ); + const int y = qRound( pos.y() ); + + const int x1 = x - sw2; + const int x2 = x1 + sw + off; + const int y1 = y - sh2; + const int y2 = y1 + sh + off; + + QwtPainter::drawLine( painter, x1, y1, x2, y2 ); + QwtPainter::drawLine( painter, x2, y1, x1, y2 ); + } + } + else + { + const double sw = size.width(); + const double sh = size.height(); + const double sw2 = 0.5 * size.width(); + const double sh2 = 0.5 * size.height(); + + for ( int i = 0; i < numPoints; i++ ) + { + const QPointF &pos = points[i]; + + const double x1 = pos.x() - sw2; + const double x2 = x1 + sw; + const double y1 = pos.y() - sh2; + const double y2 = y1 + sh; + + QwtPainter::drawLine( painter, x1, y1, x2, y2 ); + QwtPainter::drawLine( painter, x1, y2, x2, y1 ); + } + } +} + +static inline void qwtDrawStar1Symbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + const QSize size = symbol.size(); + painter->setPen( symbol.pen() ); + + if ( QwtPainter::roundingAlignment( painter ) ) + { + QRect r( 0, 0, size.width(), size.height() ); + + for ( int i = 0; i < numPoints; i++ ) + { + r.moveCenter( points[i].toPoint() ); + + const double sqrt1_2 = 0.70710678118654752440; /* 1/sqrt(2) */ + + const double d1 = r.width() / 2.0 * ( 1.0 - sqrt1_2 ); + + QwtPainter::drawLine( painter, + qRound( r.left() + d1 ), qRound( r.top() + d1 ), + qRound( r.right() - d1 ), qRound( r.bottom() - d1 ) ); + QwtPainter::drawLine( painter, + qRound( r.left() + d1 ), qRound( r.bottom() - d1 ), + qRound( r .right() - d1), qRound( r.top() + d1 ) ); + + const QPoint c = r.center(); + + QwtPainter::drawLine( painter, + c.x(), r.top(), c.x(), r.bottom() ); + QwtPainter::drawLine( painter, + r.left(), c.y(), r.right(), c.y() ); + } + } + else + { + QRectF r( 0, 0, size.width(), size.height() ); + + for ( int i = 0; i < numPoints; i++ ) + { + r.moveCenter( points[i] ); + + const double sqrt1_2 = 0.70710678118654752440; /* 1/sqrt(2) */ + + const QPointF c = r.center(); + const double d1 = r.width() / 2.0 * ( 1.0 - sqrt1_2 ); + + QwtPainter::drawLine( painter, + r.left() + d1, r.top() + d1, + r.right() - d1, r.bottom() - d1 ); + QwtPainter::drawLine( painter, + r.left() + d1, r.bottom() - d1, + r.right() - d1, r.top() + d1 ); + QwtPainter::drawLine( painter, + c.x(), r.top(), + c.x(), r.bottom() ); + QwtPainter::drawLine( painter, + r.left(), c.y(), + r.right(), c.y() ); + } + } +} + +static inline void qwtDrawStar2Symbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + QPen pen = symbol.pen(); + if ( pen.width() > 1 ) + pen.setCapStyle( Qt::FlatCap ); + pen.setJoinStyle( Qt::MiterJoin ); + painter->setPen( pen ); + + painter->setBrush( symbol.brush() ); + + const double cos30 = 0.866025; // cos(30°) + + const double dy = 0.25 * symbol.size().height(); + const double dx = 0.5 * symbol.size().width() * cos30 / 3.0; + + QPolygonF star( 12 ); + QPointF *starPoints = star.data(); + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + for ( int i = 0; i < numPoints; i++ ) + { + double x = points[i].x(); + double y = points[i].y(); + if ( doAlign ) + { + x = qRound( x ); + y = qRound( y ); + } + + double x1 = x - 3 * dx; + double y1 = y - 2 * dy; + if ( doAlign ) + { + x1 = qRound( x - 3 * dx ); + y1 = qRound( y - 2 * dy ); + } + + const double x2 = x1 + 1 * dx; + const double x3 = x1 + 2 * dx; + const double x4 = x1 + 3 * dx; + const double x5 = x1 + 4 * dx; + const double x6 = x1 + 5 * dx; + const double x7 = x1 + 6 * dx; + + const double y2 = y1 + 1 * dy; + const double y3 = y1 + 2 * dy; + const double y4 = y1 + 3 * dy; + const double y5 = y1 + 4 * dy; + + starPoints[0].rx() = x4; + starPoints[0].ry() = y1; + + starPoints[1].rx() = x5; + starPoints[1].ry() = y2; + + starPoints[2].rx() = x7; + starPoints[2].ry() = y2; + + starPoints[3].rx() = x6; + starPoints[3].ry() = y3; + + starPoints[4].rx() = x7; + starPoints[4].ry() = y4; + + starPoints[5].rx() = x5; + starPoints[5].ry() = y4; + + starPoints[6].rx() = x4; + starPoints[6].ry() = y5; + + starPoints[7].rx() = x3; + starPoints[7].ry() = y4; + + starPoints[8].rx() = x1; + starPoints[8].ry() = y4; + + starPoints[9].rx() = x2; + starPoints[9].ry() = y3; + + starPoints[10].rx() = x1; + starPoints[10].ry() = y2; + + starPoints[11].rx() = x3; + starPoints[11].ry() = y2; + + QwtPainter::drawPolygon( painter, star ); + } +} + +static inline void qwtDrawHexagonSymbols( QPainter *painter, + const QPointF *points, int numPoints, const QwtSymbol &symbol ) +{ + painter->setBrush( symbol.brush() ); + painter->setPen( symbol.pen() ); + + const double cos30 = 0.866025; // cos(30°) + const double dx = 0.5 * ( symbol.size().width() - cos30 ); + + const double dy = 0.25 * symbol.size().height(); + + QPolygonF hexaPolygon( 6 ); + QPointF *hexaPoints = hexaPolygon.data(); + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + for ( int i = 0; i < numPoints; i++ ) + { + double x = points[i].x(); + double y = points[i].y(); + if ( doAlign ) + { + x = qRound( x ); + y = qRound( y ); + } + + double x1 = x - dx; + double y1 = y - 2 * dy; + if ( doAlign ) + { + x1 = qCeil( x1 ); + y1 = qCeil( y1 ); + } + + const double x2 = x1 + 1 * dx; + const double x3 = x1 + 2 * dx; + + const double y2 = y1 + 1 * dy; + const double y3 = y1 + 3 * dy; + const double y4 = y1 + 4 * dy; + + hexaPoints[0].rx() = x2; + hexaPoints[0].ry() = y1; + + hexaPoints[1].rx() = x3; + hexaPoints[1].ry() = y2; + + hexaPoints[2].rx() = x3; + hexaPoints[2].ry() = y3; + + hexaPoints[3].rx() = x2; + hexaPoints[3].ry() = y4; + + hexaPoints[4].rx() = x1; + hexaPoints[4].ry() = y3; + + hexaPoints[5].rx() = x1; + hexaPoints[5].ry() = y2; + + QwtPainter::drawPolygon( painter, hexaPolygon ); + } +} + +class QwtSymbol::PrivateData +{ +public: + PrivateData( QwtSymbol::Style st, const QBrush &br, + const QPen &pn, const QSize &sz ): + style( st ), + size( sz ), + brush( br ), + pen( pn ), + isPinPointEnabled( false ) + { + cache.policy = QwtSymbol::AutoCache; +#ifndef QWT_NO_SVG + svg.renderer = NULL; +#endif + } + + ~PrivateData() + { +#ifndef QWT_NO_SVG + delete svg.renderer; +#endif + } + + Style style; + QSize size; + QBrush brush; + QPen pen; + + bool isPinPointEnabled; + QPointF pinPoint; + + struct Path + { + QPainterPath path; + QwtGraphic graphic; + + } path; + + struct Pixmap + { + QPixmap pixmap; + + } pixmap; + + struct Graphic + { + QwtGraphic graphic; + + } graphic; + +#ifndef QWT_NO_SVG + struct SVG + { + QSvgRenderer *renderer; + } svg; +#endif + + struct PaintCache + { + QwtSymbol::CachePolicy policy; + QPixmap pixmap; + + } cache; +}; /*! Default Constructor + \param style Symbol Style The symbol is constructed with gray interior, black outline with zero width, no size and style 'NoSymbol'. */ -QwtSymbol::QwtSymbol(): - d_brush(Qt::gray), - d_pen(Qt::black), - d_size(0,0), - d_style(QwtSymbol::NoSymbol) +QwtSymbol::QwtSymbol( Style style ) { + d_data = new PrivateData( style, QBrush( Qt::gray ), + QPen( Qt::black, 0 ), QSize() ); } /*! @@ -33,309 +852,916 @@ QwtSymbol::QwtSymbol(): \param brush brush to fill the interior \param pen outline pen \param size size + + \sa setStyle(), setBrush(), setPen(), setSize() +*/ +QwtSymbol::QwtSymbol( QwtSymbol::Style style, const QBrush &brush, + const QPen &pen, const QSize &size ) +{ + d_data = new PrivateData( style, brush, pen, size ); +} + +/*! + \brief Constructor + + The symbol gets initialized by a painter path. The style is + set to QwtSymbol::Path, the size is set to empty ( the path + is displayed unscaled ). + + \param path painter path + \param brush brush to fill the interior + \param pen outline pen + + \sa setPath(), setBrush(), setPen(), setSize() */ -QwtSymbol::QwtSymbol(QwtSymbol::Style style, const QBrush &brush, - const QPen &pen, const QSize &size): - d_brush(brush), - d_pen(pen), - d_size(size), - d_style(style) + +QwtSymbol::QwtSymbol( const QPainterPath &path, + const QBrush &brush, const QPen &pen ) { + d_data = new PrivateData( QwtSymbol::Path, brush, pen, QSize() ); + setPath( path ); } //! Destructor QwtSymbol::~QwtSymbol() { + delete d_data; } -QwtSymbol *QwtSymbol::clone() const +/*! + Change the cache policy + + The default policy is AutoCache + + \param policy Cache policy + \sa CachePolicy, cachePolicy() +*/ +void QwtSymbol::setCachePolicy( + QwtSymbol::CachePolicy policy ) { - QwtSymbol *other = new QwtSymbol; - *other = *this; + if ( d_data->cache.policy != policy ) + { + d_data->cache.policy = policy; + invalidateCache(); + } +} - return other; +/*! + \return Cache policy + \sa CachePolicy, setCachePolicy() +*/ +QwtSymbol::CachePolicy QwtSymbol::cachePolicy() const +{ + return d_data->cache.policy; } +/*! + \brief Set a painter path as symbol + + The symbol is represented by a painter path, where the + origin ( 0, 0 ) of the path coordinate system is mapped to + the position of the symbol. + + When the symbol has valid size the painter path gets scaled + to fit into the size. Otherwise the symbol size depends on + the bounding rectangle of the path. + + The following code defines a symbol drawing an arrow: + + \verbatim +#include <qwt_symbol.h> + +QwtSymbol *symbol = new QwtSymbol(); + +QPen pen( Qt::black, 2 ); +pen.setJoinStyle( Qt::MiterJoin ); + +symbol->setPen( pen ); +symbol->setBrush( Qt::red ); + +QPainterPath path; +path.moveTo( 0, 8 ); +path.lineTo( 0, 5 ); +path.lineTo( -3, 5 ); +path.lineTo( 0, 0 ); +path.lineTo( 3, 5 ); +path.lineTo( 0, 5 ); + +QTransform transform; +transform.rotate( -30.0 ); +path = transform.map( path ); + +symbol->setPath( path ); +symbol->setPinPoint( QPointF( 0.0, 0.0 ) ); + +setSize( 10, 14 ); +\endverbatim + + \param path Painter path + + \note The style is implicitely set to QwtSymbol::Path. + \sa path(), setSize() + */ +void QwtSymbol::setPath( const QPainterPath &path ) +{ + d_data->style = QwtSymbol::Path; + d_data->path.path = path; + d_data->path.graphic.reset(); +} + +/*! + \return Painter path for displaying the symbol + \sa setPath() +*/ +const QPainterPath &QwtSymbol::path() const +{ + return d_data->path.path; +} + +/*! + Set a pixmap as symbol + + \param pixmap Pixmap + + \sa pixmap(), setGraphic() + + \note the style() is set to QwtSymbol::Pixmap + \note brush() and pen() have no effect + */ +void QwtSymbol::setPixmap( const QPixmap &pixmap ) +{ + d_data->style = QwtSymbol::Pixmap; + d_data->pixmap.pixmap = pixmap; +} + +/*! + \return Assigned pixmap + \sa setPixmap() + */ +const QPixmap &QwtSymbol::pixmap() const +{ + return d_data->pixmap.pixmap; +} + +/*! + Set a graphic as symbol + + \param graphic Graphic + + \sa graphic(), setPixmap() + + \note the style() is set to QwtSymbol::Graphic + \note brush() and pen() have no effect + */ +void QwtSymbol::setGraphic( const QwtGraphic &graphic ) +{ + d_data->style = QwtSymbol::Graphic; + d_data->graphic.graphic = graphic; +} + +/*! + \return Assigned graphic + \sa setGraphic() + */ +const QwtGraphic &QwtSymbol::graphic() const +{ + return d_data->graphic.graphic; +} + +#ifndef QWT_NO_SVG + +/*! + Set a SVG icon as symbol + + \param svgDocument SVG icon + + \sa setGraphic(), setPixmap() + + \note the style() is set to QwtSymbol::SvgDocument + \note brush() and pen() have no effect + */ +void QwtSymbol::setSvgDocument( const QByteArray &svgDocument ) +{ + d_data->style = QwtSymbol::SvgDocument; + if ( d_data->svg.renderer == NULL ) + d_data->svg.renderer = new QSvgRenderer(); + + d_data->svg.renderer->load( svgDocument ); +} + +#endif + /*! \brief Specify the symbol's size If the 'h' parameter is left out or less than 0, and the 'w' parameter is greater than or equal to 0, the symbol size will be set to (w,w). - \param w width - \param h height (defaults to -1) + + \param width Width + \param height Height (defaults to -1) + + \sa size() */ -void QwtSymbol::setSize(int w, int h) +void QwtSymbol::setSize( int width, int height ) { - if ((w >= 0) && (h < 0)) - h = w; - d_size = QSize(w,h); + if ( ( width >= 0 ) && ( height < 0 ) ) + height = width; + + setSize( QSize( width, height ) ); } -//! Set the symbol's size -void QwtSymbol::setSize(const QSize &s) +/*! + Set the symbol's size + \param size Size + + \sa size() +*/ +void QwtSymbol::setSize( const QSize &size ) { - if (s.isValid()) - d_size = s; + if ( size.isValid() && size != d_data->size ) + { + d_data->size = size; + invalidateCache(); + } +} + +/*! + \return Size + \sa setSize() +*/ +const QSize& QwtSymbol::size() const +{ + return d_data->size; } /*! \brief Assign a brush The brush is used to draw the interior of the symbol. - \param br brush + \param brush Brush + + \sa brush() */ -void QwtSymbol::setBrush(const QBrush &br) +void QwtSymbol::setBrush( const QBrush &brush ) { - d_brush = br; + if ( brush != d_data->brush ) + { + d_data->brush = brush; + invalidateCache(); + + if ( d_data->style == QwtSymbol::Path ) + d_data->path.graphic.reset(); + } } /*! - \brief Assign a pen + \return Brush + \sa setBrush() +*/ +const QBrush& QwtSymbol::brush() const +{ + return d_data->brush; +} + +/*! + Build and assign a pen + + In Qt5 the default pen width is 1.0 ( 0.0 in Qt4 ) + what makes it non cosmetic ( see QPen::isCosmetic() ). + This method has been introduced to hide this incompatibility. + + \param color Pen color + \param width Pen width + \param style Pen style + + \sa pen(), brush() + */ +void QwtSymbol::setPen( const QColor &color, + qreal width, Qt::PenStyle style ) +{ + setPen( QPen( color, width, style ) ); +} + +/*! + Assign a pen The pen is used to draw the symbol's outline. - \param pn pen + \param pen Pen + \sa pen(), setBrush() +*/ +void QwtSymbol::setPen( const QPen &pen ) +{ + if ( pen != d_data->pen ) + { + d_data->pen = pen; + invalidateCache(); + + if ( d_data->style == QwtSymbol::Path ) + d_data->path.graphic.reset(); + } +} + +/*! + \return Pen + \sa setPen(), brush() */ -void QwtSymbol::setPen(const QPen &pn) +const QPen& QwtSymbol::pen() const { - d_pen = pn; + return d_data->pen; } /*! - \brief Draw the symbol at a point (x,y). + \brief Set the color of the symbol + + Change the color of the brush for symbol types with a filled area. + For all other symbol types the color will be assigned to the pen. + + \param color Color + + \sa setBrush(), setPen(), brush(), pen() */ -void QwtSymbol::draw(QPainter *painter, int x, int y) const +void QwtSymbol::setColor( const QColor &color ) +{ + switch ( d_data->style ) + { + case QwtSymbol::Ellipse: + case QwtSymbol::Rect: + case QwtSymbol::Diamond: + case QwtSymbol::Triangle: + case QwtSymbol::UTriangle: + case QwtSymbol::DTriangle: + case QwtSymbol::RTriangle: + case QwtSymbol::LTriangle: + case QwtSymbol::Star2: + case QwtSymbol::Hexagon: + { + if ( d_data->brush.color() != color ) + { + d_data->brush.setColor( color ); + invalidateCache(); + } + break; + } + case QwtSymbol::Cross: + case QwtSymbol::XCross: + case QwtSymbol::HLine: + case QwtSymbol::VLine: + case QwtSymbol::Star1: + { + if ( d_data->pen.color() != color ) + { + d_data->pen.setColor( color ); + invalidateCache(); + } + break; + } + default: + { + if ( d_data->brush.color() != color || + d_data->pen.color() != color ) + { + invalidateCache(); + } + + d_data->brush.setColor( color ); + d_data->pen.setColor( color ); + } + } +} + +/*! + \brief Set and enable a pin point + + The position of a complex symbol is not always aligned to its center + ( f.e an arrow, where the peak points to a position ). The pin point + defines the position inside of a Pixmap, Graphic, SvgDocument + or PainterPath symbol where the represented point has to + be aligned to. + + \param pos Position + \param enable En/Disable the pin point alignment + + \sa pinPoint(), setPinPointEnabled() + */ +void QwtSymbol::setPinPoint( const QPointF &pos, bool enable ) +{ + if ( d_data->pinPoint != pos ) + { + d_data->pinPoint = pos; + if ( d_data->isPinPointEnabled ) + { + invalidateCache(); + } + } + + setPinPointEnabled( enable ); +} + +/*! + \return Pin point + \sa setPinPoint(), setPinPointEnabled() + */ +QPointF QwtSymbol::pinPoint() const { - draw(painter, QPoint(x, y)); + return d_data->pinPoint; +} + +/*! + En/Disable the pin point alignment + + \param on Enabled, when on is true + \sa setPinPoint(), isPinPointEnabled() + */ +void QwtSymbol::setPinPointEnabled( bool on ) +{ + if ( d_data->isPinPointEnabled != on ) + { + d_data->isPinPointEnabled = on; + invalidateCache(); + } } +/*! + \return True, when the pin point translation is enabled + \sa setPinPoint(), setPinPointEnabled() + */ +bool QwtSymbol::isPinPointEnabled() const +{ + return d_data->isPinPointEnabled; +} /*! - \brief Draw the symbol into a bounding rectangle. + Render an array of symbols - This function assumes that the painter has been initialized with - brush and pen before. This allows a much more performant implementation - when painting many symbols with the same brush and pen like in curves. + Painting several symbols is more effective than drawing symbols + one by one, as a couple of layout calculations and setting of pen/brush + can be done once for the complete array. \param painter Painter - \param r Bounding rectangle + \param points Array of points + \param numPoints Number of points */ -void QwtSymbol::draw(QPainter *painter, const QRect& r) const -{ - switch(d_style) { - case QwtSymbol::Ellipse: - QwtPainter::drawEllipse(painter, r); - break; - case QwtSymbol::Rect: - QwtPainter::drawRect(painter, r); - break; - case QwtSymbol::Diamond: { - const int w2 = r.width() / 2; - const int h2 = r.height() / 2; - - QwtPolygon pa(4); - pa.setPoint(0, r.x() + w2, r.y()); - pa.setPoint(1, r.right(), r.y() + h2); - pa.setPoint(2, r.x() + w2, r.bottom()); - pa.setPoint(3, r.x(), r.y() + h2); - QwtPainter::drawPolygon(painter, pa); - break; - } - case QwtSymbol::Cross: { - const int w2 = r.width() / 2; - const int h2 = r.height() / 2; - - QwtPainter::drawLine(painter, r.x() + w2, r.y(), - r.x() + w2, r.bottom()); - QwtPainter::drawLine(painter, r.x(), r.y() + h2, - r.right(), r.y() + h2); - break; - } - case QwtSymbol::XCross: { - QwtPainter::drawLine(painter, r.left(), r.top(), - r.right(), r.bottom()); - QwtPainter::drawLine(painter, r.left(), r.bottom(), - r.right(), r.top()); - break; - } - case QwtSymbol::Triangle: - case QwtSymbol::UTriangle: { - const int w2 = r.width() / 2; - - QwtPolygon pa(3); - pa.setPoint(0, r.x() + w2, r.y()); - pa.setPoint(1, r.right(), r.bottom()); - pa.setPoint(2, r.x(), r.bottom()); - QwtPainter::drawPolygon(painter, pa); - break; - } - case QwtSymbol::DTriangle: { - const int w2 = r.width() / 2; - - QwtPolygon pa(3); - pa.setPoint(0, r.x(), r.y()); - pa.setPoint(1, r.right(), r.y()); - pa.setPoint(2, r.x() + w2, r.bottom()); - QwtPainter::drawPolygon(painter, pa); - break; - } - case QwtSymbol::RTriangle: { - const int h2 = r.height() / 2; - - QwtPolygon pa(3); - pa.setPoint(0, r.x(), r.y()); - pa.setPoint(1, r.right(), r.y() + h2); - pa.setPoint(2, r.x(), r.bottom()); - QwtPainter::drawPolygon(painter, pa); - break; - } - case QwtSymbol::LTriangle: { - const int h2 = r.height() / 2; - - QwtPolygon pa(3); - pa.setPoint(0, r.right(), r.y()); - pa.setPoint(1, r.x(), r.y() + h2); - pa.setPoint(2, r.right(), r.bottom()); - QwtPainter::drawPolygon(painter, pa); - break; - } - case QwtSymbol::HLine: { - const int h2 = r.height() / 2; - QwtPainter::drawLine(painter, r.left(), r.top() + h2, - r.right(), r.top() + h2); - break; - } - case QwtSymbol::VLine: { - const int w2 = r.width() / 2; - QwtPainter::drawLine(painter, r.left() + w2, r.top(), - r.left() + w2, r.bottom()); - break; - } - case QwtSymbol::Star1: { - const double sqrt1_2 = 0.70710678118654752440; /* 1/sqrt(2) */ - - const int w2 = r.width() / 2; - const int h2 = r.height() / 2; - const int d1 = (int)( (double)w2 * (1.0 - sqrt1_2) ); - - QwtPainter::drawLine(painter, r.left() + d1, r.top() + d1, - r.right() - d1, r.bottom() - d1); - QwtPainter::drawLine(painter, r.left() + d1, r.bottom() - d1, - r.right() - d1, r.top() + d1); - QwtPainter::drawLine(painter, r.left() + w2, r.top(), - r.left() + w2, r.bottom()); - QwtPainter::drawLine(painter, r.left(), r.top() + h2, - r.right(), r.top() + h2); - break; - } - case QwtSymbol::Star2: { - const int w = r.width(); - const int side = (int)(((double)r.width() * (1.0 - 0.866025)) / - 2.0); // 0.866025 = cos(30°) - const int h4 = r.height() / 4; - const int h2 = r.height() / 2; - const int h34 = (r.height() * 3) / 4; - - QwtPolygon pa(12); - pa.setPoint(0, r.left() + (w / 2), r.top()); - pa.setPoint(1, r.right() - (side + (w - 2 * side) / 3), - r.top() + h4 ); - pa.setPoint(2, r.right() - side, r.top() + h4); - pa.setPoint(3, r.right() - (side + (w / 2 - side) / 3), - r.top() + h2 ); - pa.setPoint(4, r.right() - side, r.top() + h34); - pa.setPoint(5, r.right() - (side + (w - 2 * side) / 3), - r.top() + h34 ); - pa.setPoint(6, r.left() + (w / 2), r.bottom()); - pa.setPoint(7, r.left() + (side + (w - 2 * side) / 3), - r.top() + h34 ); - pa.setPoint(8, r.left() + side, r.top() + h34); - pa.setPoint(9, r.left() + (side + (w / 2 - side) / 3), - r.top() + h2 ); - pa.setPoint(10, r.left() + side, r.top() + h4); - pa.setPoint(11, r.left() + (side + (w - 2 * side) / 3), - r.top() + h4 ); - QwtPainter::drawPolygon(painter, pa); - break; - } - case QwtSymbol::Hexagon: { - const int w2 = r.width() / 2; - const int side = (int)(((double)r.width() * (1.0 - 0.866025)) / - 2.0); // 0.866025 = cos(30°) - const int h4 = r.height() / 4; - const int h34 = (r.height() * 3) / 4; - - QwtPolygon pa(6); - pa.setPoint(0, r.left() + w2, r.top()); - pa.setPoint(1, r.right() - side, r.top() + h4); - pa.setPoint(2, r.right() - side, r.top() + h34); - pa.setPoint(3, r.left() + w2, r.bottom()); - pa.setPoint(4, r.left() + side, r.top() + h34); - pa.setPoint(5, r.left() + side, r.top() + h4); - QwtPainter::drawPolygon(painter, pa); - break; - } - default: - ; - } -} - -/*! - \brief Draw the symbol at a specified point +void QwtSymbol::drawSymbols( QPainter *painter, + const QPointF *points, int numPoints ) const +{ + if ( numPoints <= 0 ) + return; + + bool useCache = false; + + // Don't use the pixmap, when the paint device + // could generate scalable vectors + + if ( QwtPainter::roundingAlignment( painter ) && + !painter->transform().isScaling() ) + { + if ( d_data->cache.policy == QwtSymbol::Cache ) + { + useCache = true; + } + else if ( d_data->cache.policy == QwtSymbol::AutoCache ) + { + if ( painter->paintEngine()->type() == QPaintEngine::Raster ) + { + useCache = true; + } + else + { + switch( d_data->style ) + { + case QwtSymbol::XCross: + case QwtSymbol::HLine: + case QwtSymbol::VLine: + case QwtSymbol::Cross: + break; + + case QwtSymbol::Pixmap: + { + if ( !d_data->size.isEmpty() && + d_data->size != d_data->pixmap.pixmap.size() ) + { + useCache = true; + } + break; + } + default: + useCache = true; + } + } + } + } + + if ( useCache ) + { + const QRect br = boundingRect(); + + const QRect rect( 0, 0, br.width(), br.height() ); + + if ( d_data->cache.pixmap.isNull() ) + { + d_data->cache.pixmap = QwtPainter::backingStore( NULL, br.size() ); + d_data->cache.pixmap.fill( Qt::transparent ); + + QPainter p( &d_data->cache.pixmap ); + p.setRenderHints( painter->renderHints() ); + p.translate( -br.topLeft() ); + + const QPointF pos; + renderSymbols( &p, &pos, 1 ); + } + + const int dx = br.left(); + const int dy = br.top(); + + for ( int i = 0; i < numPoints; i++ ) + { + const int left = qRound( points[i].x() ) + dx; + const int top = qRound( points[i].y() ) + dy; + + painter->drawPixmap( left, top, d_data->cache.pixmap ); + } + } + else + { + painter->save(); + renderSymbols( painter, points, numPoints ); + painter->restore(); + } +} + +/*! + \brief Draw the symbol into a rectangle + + The symbol is painted centered and scaled into the target rectangle. + It is always painted uncached and the pin point is ignored. + + This method is primarily intended for drawing a symbol to + the legend. \param painter Painter - \param pos Center of the symbol + \param rect Target rectangle for the symbol */ -void QwtSymbol::draw(QPainter *painter, const QPoint &pos) const +void QwtSymbol::drawSymbol( QPainter *painter, const QRectF &rect ) const { - QRect rect; - rect.setSize(QwtPainter::metricsMap().screenToLayout(d_size)); - rect.moveCenter(pos); + if ( d_data->style == QwtSymbol::NoSymbol ) + return; + + if ( d_data->style == QwtSymbol::Graphic ) + { + d_data->graphic.graphic.render( + painter, rect, Qt::KeepAspectRatio ); + } + else if ( d_data->style == QwtSymbol::Path ) + { + if ( d_data->path.graphic.isNull() ) + { + d_data->path.graphic = qwtPathGraphic( + d_data->path.path, d_data->pen, d_data->brush ); + } + + d_data->path.graphic.render( + painter, rect, Qt::KeepAspectRatio ); + return; + } + else if ( d_data->style == QwtSymbol::SvgDocument ) + { +#ifndef QWT_NO_SVG + if ( d_data->svg.renderer ) + { + QRectF scaledRect; + + QSizeF sz = d_data->svg.renderer->viewBoxF().size(); + if ( !sz.isEmpty() ) + { + sz.scale( rect.size(), Qt::KeepAspectRatio ); + scaledRect.setSize( sz ); + scaledRect.moveCenter( rect.center() ); + } + else + { + scaledRect = rect; + } + + d_data->svg.renderer->render( + painter, scaledRect ); + } +#endif + } + else + { + const QRect br = boundingRect(); + + // scale the symbol size to fit into rect. + + const double ratio = qMin( rect.width() / br.width(), + rect.height() / br.height() ); + + painter->save(); + + painter->translate( rect.center() ); + painter->scale( ratio, ratio ); - painter->setBrush(d_brush); - painter->setPen(d_pen); + const bool isPinPointEnabled = d_data->isPinPointEnabled; + d_data->isPinPointEnabled = false; - draw(painter, rect); + const QPointF pos; + renderSymbols( painter, &pos, 1 ); + + d_data->isPinPointEnabled = isPinPointEnabled; + + painter->restore(); + } } /*! - \brief Specify the symbol style + Render the symbol to series of points - The following styles are defined:<dl> - <dt>NoSymbol<dd>No Style. The symbol cannot be drawn. - <dt>Ellipse<dd>Ellipse or circle - <dt>Rect<dd>Rectangle - <dt>Diamond<dd>Diamond - <dt>Triangle<dd>Triangle pointing upwards - <dt>DTriangle<dd>Triangle pointing downwards - <dt>UTriangle<dd>Triangle pointing upwards - <dt>LTriangle<dd>Triangle pointing left - <dt>RTriangle<dd>Triangle pointing right - <dt>Cross<dd>Cross (+) - <dt>XCross<dd>Diagonal cross (X) - <dt>HLine<dd>Horizontal line - <dt>VLine<dd>Vertical line - <dt>Star1<dd>X combined with + - <dt>Star2<dd>Six-pointed star - <dt>Hexagon<dd>Hexagon</dl> + \param painter Qt painter + \param points Positions of the symbols + \param numPoints Number of points + */ +void QwtSymbol::renderSymbols( QPainter *painter, + const QPointF *points, int numPoints ) const +{ + switch ( d_data->style ) + { + case QwtSymbol::Ellipse: + { + qwtDrawEllipseSymbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Rect: + { + qwtDrawRectSymbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Diamond: + { + qwtDrawDiamondSymbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Cross: + { + qwtDrawLineSymbols( painter, Qt::Horizontal | Qt::Vertical, + points, numPoints, *this ); + break; + } + case QwtSymbol::XCross: + { + qwtDrawXCrossSymbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Triangle: + case QwtSymbol::UTriangle: + { + qwtDrawTriangleSymbols( painter, QwtTriangle::Up, + points, numPoints, *this ); + break; + } + case QwtSymbol::DTriangle: + { + qwtDrawTriangleSymbols( painter, QwtTriangle::Down, + points, numPoints, *this ); + break; + } + case QwtSymbol::RTriangle: + { + qwtDrawTriangleSymbols( painter, QwtTriangle::Right, + points, numPoints, *this ); + break; + } + case QwtSymbol::LTriangle: + { + qwtDrawTriangleSymbols( painter, QwtTriangle::Left, + points, numPoints, *this ); + break; + } + case QwtSymbol::HLine: + { + qwtDrawLineSymbols( painter, Qt::Horizontal, + points, numPoints, *this ); + break; + } + case QwtSymbol::VLine: + { + qwtDrawLineSymbols( painter, Qt::Vertical, + points, numPoints, *this ); + break; + } + case QwtSymbol::Star1: + { + qwtDrawStar1Symbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Star2: + { + qwtDrawStar2Symbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Hexagon: + { + qwtDrawHexagonSymbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Path: + { + if ( d_data->path.graphic.isNull() ) + { + d_data->path.graphic = qwtPathGraphic( d_data->path.path, + d_data->pen, d_data->brush ); + } - \param s style -*/ -void QwtSymbol::setStyle(QwtSymbol::Style s) + qwtDrawGraphicSymbols( painter, points, numPoints, + d_data->path.graphic, *this ); + break; + } + case QwtSymbol::Pixmap: + { + qwtDrawPixmapSymbols( painter, points, numPoints, *this ); + break; + } + case QwtSymbol::Graphic: + { + qwtDrawGraphicSymbols( painter, points, numPoints, + d_data->graphic.graphic, *this ); + break; + } + case QwtSymbol::SvgDocument: + { +#ifndef QWT_NO_SVG + qwtDrawSvgSymbols( painter, points, numPoints, + d_data->svg.renderer, *this ); +#endif + break; + } + default:; + } +} + +/*! + Calculate the bounding rectangle for a symbol + at position (0,0). + + \return Bounding rectangle + */ +QRect QwtSymbol::boundingRect() const +{ + QRectF rect; + + switch ( d_data->style ) + { + case QwtSymbol::Ellipse: + case QwtSymbol::Rect: + case QwtSymbol::Hexagon: + { + qreal pw = 0.0; + if ( d_data->pen.style() != Qt::NoPen ) + pw = qMax( d_data->pen.widthF(), qreal( 1.0 ) ); + + rect.setSize( d_data->size + QSizeF( pw, pw ) ); + rect.moveCenter( QPointF( 0.0, 0.0 ) ); + + break; + } + case QwtSymbol::XCross: + case QwtSymbol::Diamond: + case QwtSymbol::Triangle: + case QwtSymbol::UTriangle: + case QwtSymbol::DTriangle: + case QwtSymbol::RTriangle: + case QwtSymbol::LTriangle: + case QwtSymbol::Star1: + case QwtSymbol::Star2: + { + qreal pw = 0.0; + if ( d_data->pen.style() != Qt::NoPen ) + pw = qMax( d_data->pen.widthF(), qreal( 1.0 ) ); + + rect.setSize( d_data->size + QSizeF( 2 * pw, 2 * pw ) ); + rect.moveCenter( QPointF( 0.0, 0.0 ) ); + break; + } + case QwtSymbol::Path: + { + if ( d_data->path.graphic.isNull() ) + { + d_data->path.graphic = qwtPathGraphic( + d_data->path.path, d_data->pen, d_data->brush ); + } + + rect = qwtScaledBoundingRect( + d_data->path.graphic, d_data->size ); + + break; + } + case QwtSymbol::Pixmap: + { + if ( d_data->size.isEmpty() ) + rect.setSize( d_data->pixmap.pixmap.size() ); + else + rect.setSize( d_data->size ); + + rect.moveCenter( QPointF( 0.0, 0.0 ) ); + + // pinpoint ??? + break; + } + case QwtSymbol::Graphic: + { + rect = qwtScaledBoundingRect( + d_data->graphic.graphic, d_data->size ); + + break; + } +#ifndef QWT_NO_SVG + case QwtSymbol::SvgDocument: + { + if ( d_data->svg.renderer ) + rect = d_data->svg.renderer->viewBoxF(); + + if ( d_data->size.isValid() && !rect.isEmpty() ) + { + QSizeF sz = rect.size(); + + const double sx = d_data->size.width() / sz.width(); + const double sy = d_data->size.height() / sz.height(); + + QTransform transform; + transform.scale( sx, sy ); + + rect = transform.mapRect( rect ); + } + break; + } +#endif + default: + { + rect.setSize( d_data->size ); + rect.moveCenter( QPointF( 0.0, 0.0 ) ); + } + } + + if ( d_data->style == QwtSymbol::Graphic || + d_data->style == QwtSymbol::SvgDocument || d_data->style == QwtSymbol::Path ) + { + QPointF pinPoint( 0.0, 0.0 ); + if ( d_data->isPinPointEnabled ) + pinPoint = rect.center() - d_data->pinPoint; + + rect.moveCenter( pinPoint ); + } + + QRect r; + r.setLeft( qFloor( rect.left() ) ); + r.setTop( qFloor( rect.top() ) ); + r.setRight( qCeil( rect.right() ) ); + r.setBottom( qCeil( rect.bottom() ) ); + + if ( d_data->style != QwtSymbol::Pixmap ) + r.adjust( -1, -1, 1, 1 ); // for antialiasing + + return r; +} + +/*! + Invalidate the cached symbol pixmap + + The symbol invalidates its cache, whenever an attribute is changed + that has an effect ob how to display a symbol. In case of derived + classes with individual styles ( >= QwtSymbol::UserStyle ) it + might be necessary to call invalidateCache() for attributes + that are relevant for this style. + + \sa CachePolicy, setCachePolicy(), drawSymbols() + */ +void QwtSymbol::invalidateCache() { - d_style = s; + if ( !d_data->cache.pixmap.isNull() ) + d_data->cache.pixmap = QPixmap(); } -//! == operator -bool QwtSymbol::operator==(const QwtSymbol &other) const +/*! + Specify the symbol style + + \param style Style + \sa style() +*/ +void QwtSymbol::setStyle( QwtSymbol::Style style ) { - return brush() == other.brush() && pen() == other.pen() - && style() == other.style() && size() == other.size(); + if ( d_data->style != style ) + { + d_data->style = style; + invalidateCache(); + } } -//! != operator -bool QwtSymbol::operator!=(const QwtSymbol &other) const +/*! + \return Current symbol style + \sa setStyle() +*/ +QwtSymbol::Style QwtSymbol::style() const { - return !(*this == other); + return d_data->style; } diff --git a/libs/qwt/qwt_symbol.h b/libs/qwt/qwt_symbol.h index a436edcc40..ea16d885f1 100644 --- a/libs/qwt/qwt_symbol.h +++ b/libs/qwt/qwt_symbol.h @@ -10,86 +10,249 @@ #ifndef QWT_SYMBOL_H #define QWT_SYMBOL_H -#include <qbrush.h> -#include <qpen.h> -#include <qsize.h> #include "qwt_global.h" +#include <qpolygon.h> class QPainter; class QRect; +class QSize; +class QBrush; +class QPen; +class QColor; +class QPointF; +class QPolygonF; +class QPainterPath; +class QPixmap; +class QByteArray; +class QwtGraphic; //! A class for drawing symbols class QWT_EXPORT QwtSymbol { public: /*! - Style - \sa setStyle(), style() + Symbol Style + \sa setStyle(), style() */ - enum Style { + enum Style + { + //! No Style. The symbol cannot be drawn. NoSymbol = -1, + //! Ellipse or circle Ellipse, + + //! Rectangle Rect, + + //! Diamond Diamond, + + //! Triangle pointing upwards Triangle, + + //! Triangle pointing downwards DTriangle, + + //! Triangle pointing upwards UTriangle, + + //! Triangle pointing left LTriangle, + + //! Triangle pointing right RTriangle, + + //! Cross (+) Cross, + + //! Diagonal cross (X) XCross, + + //! Horizontal line HLine, + + //! Vertical line VLine, + + //! X combined with + Star1, + + //! Six-pointed star Star2, + + //! Hexagon Hexagon, - StyleCnt + /*! + The symbol is represented by a painter path, where the + origin ( 0, 0 ) of the path coordinate system is mapped to + the position of the symbol. + + \sa setPath(), path() + */ + Path, + + /*! + The symbol is represented by a pixmap. The pixmap is centered + or aligned to its pin point. + + \sa setPinPoint() + */ + Pixmap, + + /*! + The symbol is represented by a graphic. The graphic is centered + or aligned to its pin point. + + \sa setPinPoint() + */ + Graphic, + + /*! + The symbol is represented by a SVG graphic. The graphic is centered + or aligned to its pin point. + + \sa setPinPoint() + */ + SvgDocument, + + /*! + Styles >= QwtSymbol::UserSymbol are reserved for derived + classes of QwtSymbol that overload drawSymbols() with + additional application specific symbol types. + */ + UserStyle = 1000 + }; + + /*! + Depending on the render engine and the complexity of the + symbol shape it might be faster to render the symbol + to a pixmap and to paint this pixmap. + + F.e. the raster paint engine is a pure software renderer + where in cache mode a draw operation usually ends in + raster operation with the the backing store, that are usually + faster, than the algorithms for rendering polygons. + But the opposite can be expected for graphic pipelines + that can make use of hardware acceleration. + + The default setting is AutoCache + + \sa setCachePolicy(), cachePolicy() + + \note The policy has no effect, when the symbol is painted + to a vector graphics format ( PDF, SVG ). + \warning Since Qt 4.8 raster is the default backend on X11 + */ + + enum CachePolicy + { + //! Don't use a pixmap cache + NoCache, + + //! Always use a pixmap cache + Cache, + + /*! + Use a cache when one of the following conditions is true: + + - The symbol is rendered with the software + renderer ( QPaintEngine::Raster ) + */ + AutoCache }; public: - QwtSymbol(); - QwtSymbol(Style st, const QBrush &bd, const QPen &pn, const QSize &s); + QwtSymbol( Style = NoSymbol ); + QwtSymbol( Style, const QBrush &, const QPen &, const QSize & ); + QwtSymbol( const QPainterPath &, const QBrush &, const QPen & ); + virtual ~QwtSymbol(); - bool operator!=(const QwtSymbol &) const; - virtual bool operator==(const QwtSymbol &) const; - - virtual QwtSymbol *clone() const; - - void setSize(const QSize &s); - void setSize(int a, int b = -1); - void setBrush(const QBrush& b); - void setPen(const QPen &p); - void setStyle (Style s); - - //! Return Brush - const QBrush& brush() const { - return d_brush; - } - //! Return Pen - const QPen& pen() const { - return d_pen; - } - //! Return Size - const QSize& size() const { - return d_size; - } - //! Return Style - Style style() const { - return d_style; - } - - void draw(QPainter *p, const QPoint &pt) const; - void draw(QPainter *p, int x, int y) const; - virtual void draw(QPainter *p, const QRect &r) const; + void setCachePolicy( CachePolicy ); + CachePolicy cachePolicy() const; + + void setSize( const QSize & ); + void setSize( int width, int height = -1 ); + const QSize& size() const; + + void setPinPoint( const QPointF &pos, bool enable = true ); + QPointF pinPoint() const; + + void setPinPointEnabled( bool ); + bool isPinPointEnabled() const; + + virtual void setColor( const QColor & ); + + void setBrush( const QBrush& b ); + const QBrush& brush() const; + + void setPen( const QColor &, qreal width = 0.0, Qt::PenStyle = Qt::SolidLine ); + void setPen( const QPen & ); + const QPen& pen() const; + + void setStyle( Style ); + Style style() const; + + void setPath( const QPainterPath & ); + const QPainterPath &path() const; + + void setPixmap( const QPixmap & ); + const QPixmap &pixmap() const; + + void setGraphic( const QwtGraphic & ); + const QwtGraphic &graphic() const; + +#ifndef QWT_NO_SVG + void setSvgDocument( const QByteArray & ); +#endif + + void drawSymbol( QPainter *, const QRectF & ) const; + void drawSymbol( QPainter *, const QPointF & ) const; + void drawSymbols( QPainter *, const QPolygonF & ) const; + void drawSymbols( QPainter *, + const QPointF *, int numPoints ) const; + + virtual QRect boundingRect() const; + void invalidateCache(); + +protected: + virtual void renderSymbols( QPainter *, + const QPointF *, int numPoints ) const; private: - QBrush d_brush; - QPen d_pen; - QSize d_size; - Style d_style; + // Disabled copy constructor and operator= + QwtSymbol( const QwtSymbol & ); + QwtSymbol &operator=( const QwtSymbol & ); + + class PrivateData; + PrivateData *d_data; }; +/*! + \brief Draw the symbol at a specified position + + \param painter Painter + \param pos Position of the symbol in screen coordinates +*/ +inline void QwtSymbol::drawSymbol( + QPainter *painter, const QPointF &pos ) const +{ + drawSymbols( painter, &pos, 1 ); +} + +/*! + \brief Draw symbols at the specified points + + \param painter Painter + \param points Positions of the symbols in screen coordinates +*/ + +inline void QwtSymbol::drawSymbols( + QPainter *painter, const QPolygonF &points ) const +{ + drawSymbols( painter, points.data(), points.size() ); +} + #endif diff --git a/libs/qwt/qwt_system_clock.cpp b/libs/qwt/qwt_system_clock.cpp new file mode 100644 index 0000000000..fb0c5be3c3 --- /dev/null +++ b/libs/qwt/qwt_system_clock.cpp @@ -0,0 +1,396 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_system_clock.h" + +#if QT_VERSION >= 0x040800 +#define USE_ELAPSED_TIMER 1 +#endif + +#if USE_ELAPSED_TIMER + +#include <qelapsedtimer.h> + +class QwtSystemClock::PrivateData +{ +public: + QElapsedTimer timer; +}; + +QwtSystemClock::QwtSystemClock() +{ + d_data = new PrivateData(); +} + +QwtSystemClock::~QwtSystemClock() +{ + delete d_data; +} + +bool QwtSystemClock::isNull() const +{ + return d_data->timer.isValid(); +} + +void QwtSystemClock::start() +{ + d_data->timer.start(); +} + +double QwtSystemClock::restart() +{ + const qint64 nsecs = d_data->timer.restart(); + return nsecs / 1e6; +} + +double QwtSystemClock::elapsed() const +{ + const qint64 nsecs = d_data->timer.nsecsElapsed(); + return nsecs / 1e6; +} + +#else // !USE_ELAPSED_TIMER + +#include <qdatetime.h> + +#if !defined(Q_OS_WIN) +#include <unistd.h> +#endif + +#if defined(Q_OS_MAC) +#include <stdint.h> +#include <mach/mach_time.h> +#define QWT_HIGH_RESOLUTION_CLOCK +#elif defined(_POSIX_TIMERS) +#include <time.h> +#define QWT_HIGH_RESOLUTION_CLOCK +#elif defined(Q_OS_WIN) +#define QWT_HIGH_RESOLUTION_CLOCK +#include <qt_windows.h> +#endif + +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + +class QwtHighResolutionClock +{ +public: + QwtHighResolutionClock(); + + void start(); + double restart(); + double elapsed() const; + + bool isNull() const; + + static double precision(); + +private: + +#if defined(Q_OS_MAC) + static double msecsTo( uint64_t, uint64_t ); + + uint64_t d_timeStamp; +#elif defined(_POSIX_TIMERS) + + static double msecsTo( const struct timespec &, + const struct timespec & ); + + static bool isMonotonic(); + + struct timespec d_timeStamp; + clockid_t d_clockId; + +#elif defined(Q_OS_WIN) + + LARGE_INTEGER d_startTicks; + LARGE_INTEGER d_ticksPerSecond; +#endif +}; + +#if defined(Q_OS_MAC) +QwtHighResolutionClock::QwtHighResolutionClock(): + d_timeStamp( 0 ) +{ +} + +double QwtHighResolutionClock::precision() +{ + return 1e-6; +} + +void QwtHighResolutionClock::start() +{ + d_timeStamp = mach_absolute_time(); +} + +double QwtHighResolutionClock::restart() +{ + const uint64_t timeStamp = mach_absolute_time(); + const double elapsed = msecsTo( d_timeStamp, timeStamp ); + d_timeStamp = timeStamp; + + return elapsed; +} + +double QwtHighResolutionClock::elapsed() const +{ + return msecsTo( d_timeStamp, mach_absolute_time() ); +} + +bool QwtHighResolutionClock::isNull() const +{ + return d_timeStamp == 0; +} + +double QwtHighResolutionClock::msecsTo( + uint64_t from, uint64_t to ) +{ + const uint64_t difference = to - from; + + static double conversion = 0.0; + if ( conversion == 0.0 ) + { + mach_timebase_info_data_t info; + kern_return_t err = mach_timebase_info( &info ); + + // convert the timebase into ms + if ( err == 0 ) + conversion = 1e-6 * ( double ) info.numer / ( double ) info.denom; + } + + return conversion * ( double ) difference; +} + +#elif defined(_POSIX_TIMERS) + +QwtHighResolutionClock::QwtHighResolutionClock() +{ + d_clockId = isMonotonic() ? CLOCK_MONOTONIC : CLOCK_REALTIME; + d_timeStamp.tv_sec = d_timeStamp.tv_nsec = 0; +} + +double QwtHighResolutionClock::precision() +{ + struct timespec resolution; + + int clockId = isMonotonic() ? CLOCK_MONOTONIC : CLOCK_REALTIME; + ::clock_getres( clockId, &resolution ); + + return resolution.tv_nsec / 1e3; +} + +inline bool QwtHighResolutionClock::isNull() const +{ + return d_timeStamp.tv_sec <= 0 && d_timeStamp.tv_nsec <= 0; +} + +inline void QwtHighResolutionClock::start() +{ + ::clock_gettime( d_clockId, &d_timeStamp ); +} + +double QwtHighResolutionClock::restart() +{ + struct timespec timeStamp; + ::clock_gettime( d_clockId, &timeStamp ); + + const double elapsed = msecsTo( d_timeStamp, timeStamp ); + + d_timeStamp = timeStamp; + return elapsed; +} + +inline double QwtHighResolutionClock::elapsed() const +{ + struct timespec timeStamp; + ::clock_gettime( d_clockId, &timeStamp ); + + return msecsTo( d_timeStamp, timeStamp ); +} + +inline double QwtHighResolutionClock::msecsTo( + const struct timespec &t1, const struct timespec &t2 ) +{ + return ( t2.tv_sec - t1.tv_sec ) * 1e3 + + ( t2.tv_nsec - t1.tv_nsec ) * 1e-6; +} + +bool QwtHighResolutionClock::isMonotonic() +{ + // code copied from qcore_unix.cpp + +#if (_POSIX_MONOTONIC_CLOCK-0 > 0) + return true; +#else + static int returnValue = 0; + + if ( returnValue == 0 ) + { +#if (_POSIX_MONOTONIC_CLOCK-0 < 0) || !defined(_SC_MONOTONIC_CLOCK) + returnValue = -1; +#elif (_POSIX_MONOTONIC_CLOCK == 0) + // detect if the system support monotonic timers + const long x = sysconf( _SC_MONOTONIC_CLOCK ); + returnValue = ( x >= 200112L ) ? 1 : -1; +#endif + } + + return returnValue != -1; +#endif +} + +#elif defined(Q_OS_WIN) + +QwtHighResolutionClock::QwtHighResolutionClock() +{ + d_startTicks.QuadPart = 0; + QueryPerformanceFrequency( &d_ticksPerSecond ); +} + +double QwtHighResolutionClock::precision() +{ + LARGE_INTEGER ticks; + if ( QueryPerformanceFrequency( &ticks ) && ticks.QuadPart > 0 ) + return 1e3 / ticks.QuadPart; + + return 0.0; +} + +inline bool QwtHighResolutionClock::isNull() const +{ + return d_startTicks.QuadPart <= 0; +} + +inline void QwtHighResolutionClock::start() +{ + QueryPerformanceCounter( &d_startTicks ); +} + +inline double QwtHighResolutionClock::restart() +{ + LARGE_INTEGER ticks; + QueryPerformanceCounter( &ticks ); + + const double dt = ticks.QuadPart - d_startTicks.QuadPart; + d_startTicks = ticks; + + return dt / d_ticksPerSecond.QuadPart * 1e3; +} + +inline double QwtHighResolutionClock::elapsed() const +{ + LARGE_INTEGER ticks; + QueryPerformanceCounter( &ticks ); + + const double dt = ticks.QuadPart - d_startTicks.QuadPart; + return dt / d_ticksPerSecond.QuadPart * 1e3; +} + +#endif + +#endif // QWT_HIGH_RESOLUTION_CLOCK + +class QwtSystemClock::PrivateData +{ +public: +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + QwtHighResolutionClock *clock; +#endif + QTime time; +}; + +//! Constructs a null clock object. +QwtSystemClock::QwtSystemClock() +{ + d_data = new PrivateData; + +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + d_data->clock = NULL; + if ( QwtHighResolutionClock::precision() > 0.0 ) + d_data->clock = new QwtHighResolutionClock; +#endif +} + +//! Destructor +QwtSystemClock::~QwtSystemClock() +{ +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + delete d_data->clock; +#endif + delete d_data; +} + +/*! + \return true if the clock has never been started. +*/ +bool QwtSystemClock::isNull() const +{ +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + if ( d_data->clock ) + return d_data->clock->isNull(); +#endif + + return d_data->time.isNull(); +} + +/*! + Sets the start time to the current time. +*/ +void QwtSystemClock::start() +{ +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + if ( d_data->clock ) + { + d_data->clock->start(); + return; + } +#endif + + d_data->time.start(); +} + +/*! + Set the start time to the current time + \return Time, that is elapsed since the previous start time. +*/ +double QwtSystemClock::restart() +{ +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + if ( d_data->clock ) + return d_data->clock->restart(); +#endif + + return d_data->time.restart(); +} + +/*! + \return Number of milliseconds that have elapsed since the last time + start() or restart() was called or 0.0 for null clocks. +*/ +double QwtSystemClock::elapsed() const +{ + double elapsed = 0.0; + +#if defined(QWT_HIGH_RESOLUTION_CLOCK) + if ( d_data->clock ) + { + if ( !d_data->clock->isNull() ) + elapsed = d_data->clock->elapsed(); + + return elapsed; + } +#endif + + if ( !d_data->time.isNull() ) + elapsed = d_data->time.elapsed(); + + return elapsed; +} + +#endif diff --git a/libs/qwt/qwt_system_clock.h b/libs/qwt/qwt_system_clock.h new file mode 100644 index 0000000000..b134b11fc6 --- /dev/null +++ b/libs/qwt/qwt_system_clock.h @@ -0,0 +1,47 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_SYSTEM_CLOCK_H +#define QWT_SYSTEM_CLOCK_H + +#include "qwt_global.h" + +/*! + \brief QwtSystemClock provides high resolution clock time functions. + + Sometimes the resolution offered by QTime ( millisecond ) is not accurate + enough for implementing time measurements ( f.e. sampling ). + QwtSystemClock offers a subset of the QTime functionality using higher + resolution timers ( if possible ). + + Precision and time intervals are multiples of milliseconds (ms). + + \note The implementation uses high-resolution performance counter on Windows, + mach_absolute_time() on the Mac or POSIX timers on other systems. + If none is available it falls back on QTimer. +*/ + +class QWT_EXPORT QwtSystemClock +{ +public: + QwtSystemClock(); + virtual ~QwtSystemClock(); + + bool isNull() const; + + void start(); + double restart(); + double elapsed() const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/libs/qwt/qwt_text.cpp b/libs/qwt/qwt_text.cpp index 6da69802b3..b93798a492 100644 --- a/libs/qwt/qwt_text.cpp +++ b/libs/qwt/qwt_text.cpp @@ -7,91 +7,99 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_text.h" +#include "qwt_painter.h" +#include "qwt_text_engine.h" #include <qmap.h> #include <qfont.h> #include <qcolor.h> #include <qpen.h> #include <qbrush.h> #include <qpainter.h> -#include "qwt_painter.h" -#include "qwt_text_engine.h" -#include "qwt_text.h" -#if QT_VERSION >= 0x040000 #include <qapplication.h> #include <qdesktopwidget.h> -#endif +#include <qmath.h> class QwtTextEngineDict { public: - QwtTextEngineDict(); - ~QwtTextEngineDict(); + static QwtTextEngineDict &dict(); - void setTextEngine(QwtText::TextFormat, QwtTextEngine *); - const QwtTextEngine *textEngine(QwtText::TextFormat) const; - const QwtTextEngine *textEngine(const QString &, - QwtText::TextFormat) const; + void setTextEngine( QwtText::TextFormat, QwtTextEngine * ); + + const QwtTextEngine *textEngine( QwtText::TextFormat ) const; + const QwtTextEngine *textEngine( const QString &, + QwtText::TextFormat ) const; private: + QwtTextEngineDict(); + ~QwtTextEngineDict(); + typedef QMap<int, QwtTextEngine *> EngineMap; - inline const QwtTextEngine *engine(EngineMap::const_iterator &it) const { -#if QT_VERSION < 0x040000 - return it.data(); -#else + inline const QwtTextEngine *engine( EngineMap::const_iterator &it ) const + { return it.value(); -#endif } EngineMap d_map; }; +QwtTextEngineDict &QwtTextEngineDict::dict() +{ + static QwtTextEngineDict engineDict; + return engineDict; +} + QwtTextEngineDict::QwtTextEngineDict() { - d_map.insert(QwtText::PlainText, new QwtPlainTextEngine()); + d_map.insert( QwtText::PlainText, new QwtPlainTextEngine() ); #ifndef QT_NO_RICHTEXT - d_map.insert(QwtText::RichText, new QwtRichTextEngine()); + d_map.insert( QwtText::RichText, new QwtRichTextEngine() ); #endif } QwtTextEngineDict::~QwtTextEngineDict() { for ( EngineMap::const_iterator it = d_map.begin(); - it != d_map.end(); ++it ) { - QwtTextEngine *textEngine = (QwtTextEngine *)engine(it); + it != d_map.end(); ++it ) + { + const QwtTextEngine *textEngine = engine( it ); delete textEngine; } } -const QwtTextEngine *QwtTextEngineDict::textEngine(const QString& text, - QwtText::TextFormat format) const +const QwtTextEngine *QwtTextEngineDict::textEngine( const QString& text, + QwtText::TextFormat format ) const { - if ( format == QwtText::AutoText ) { + if ( format == QwtText::AutoText ) + { for ( EngineMap::const_iterator it = d_map.begin(); - it != d_map.end(); ++it ) { - if ( it.key() != QwtText::PlainText ) { - const QwtTextEngine *e = engine(it); - if ( e && e->mightRender(text) ) - return (QwtTextEngine *)e; + it != d_map.end(); ++it ) + { + if ( it.key() != QwtText::PlainText ) + { + const QwtTextEngine *e = engine( it ); + if ( e && e->mightRender( text ) ) + return e; } } } - EngineMap::const_iterator it = d_map.find(format); - if ( it != d_map.end() ) { - const QwtTextEngine *e = engine(it); + EngineMap::const_iterator it = d_map.find( format ); + if ( it != d_map.end() ) + { + const QwtTextEngine *e = engine( it ); if ( e ) return e; } - it = d_map.find(QwtText::PlainText); - return engine(it); + it = d_map.find( QwtText::PlainText ); + return engine( it ); } -void QwtTextEngineDict::setTextEngine(QwtText::TextFormat format, - QwtTextEngine *engine) +void QwtTextEngineDict::setTextEngine( QwtText::TextFormat format, + QwtTextEngine *engine ) { if ( format == QwtText::AutoText ) return; @@ -99,54 +107,56 @@ void QwtTextEngineDict::setTextEngine(QwtText::TextFormat format, if ( format == QwtText::PlainText && engine == NULL ) return; - EngineMap::const_iterator it = d_map.find(format); - if ( it != d_map.end() ) { - const QwtTextEngine *e = this->engine(it); + EngineMap::const_iterator it = d_map.find( format ); + if ( it != d_map.end() ) + { + const QwtTextEngine *e = this->engine( it ); if ( e ) delete e; - d_map.remove(format); + d_map.remove( format ); } if ( engine != NULL ) - d_map.insert(format, engine); + d_map.insert( format, engine ); } const QwtTextEngine *QwtTextEngineDict::textEngine( - QwtText::TextFormat format) const + QwtText::TextFormat format ) const { const QwtTextEngine *e = NULL; - EngineMap::const_iterator it = d_map.find(format); + EngineMap::const_iterator it = d_map.find( format ); if ( it != d_map.end() ) - e = engine(it); + e = engine( it ); return e; } -static QwtTextEngineDict *engineDict = NULL; - class QwtText::PrivateData { public: PrivateData(): - renderFlags(Qt::AlignCenter), - backgroundPen(Qt::NoPen), - backgroundBrush(Qt::NoBrush), - paintAttributes(0), - layoutAttributes(0), - textEngine(NULL) { + renderFlags( Qt::AlignCenter ), + borderRadius( 0 ), + borderPen( Qt::NoPen ), + backgroundBrush( Qt::NoBrush ), + paintAttributes( 0 ), + layoutAttributes( 0 ), + textEngine( NULL ) + { } int renderFlags; QString text; QFont font; QColor color; - QPen backgroundPen; + double borderRadius; + QPen borderPen; QBrush backgroundBrush; - int paintAttributes; - int layoutAttributes; + QwtText::PaintAttributes paintAttributes; + QwtText::LayoutAttributes layoutAttributes; const QwtTextEngine *textEngine; }; @@ -154,12 +164,13 @@ public: class QwtText::LayoutCache { public: - void invalidate() { - textSize = QSize(); + void invalidate() + { + textSize = QSizeF(); } QFont font; - QSize textSize; + QSizeF textSize; }; /*! @@ -168,17 +179,17 @@ public: \param text Text content \param textFormat Text format */ -QwtText::QwtText(const QString &text, QwtText::TextFormat textFormat) +QwtText::QwtText( const QString &text, QwtText::TextFormat textFormat ) { d_data = new PrivateData; d_data->text = text; - d_data->textEngine = textEngine(text, textFormat); + d_data->textEngine = textEngine( text, textFormat ); d_layoutCache = new LayoutCache; } //! Copy constructor -QwtText::QwtText(const QwtText &other) +QwtText::QwtText( const QwtText &other ) { d_data = new PrivateData; *d_data = *other.d_data; @@ -194,29 +205,32 @@ QwtText::~QwtText() delete d_layoutCache; } -//! Assignement operator -QwtText &QwtText::operator=(const QwtText &other) +//! Assignment operator +QwtText &QwtText::operator=( const QwtText & other ) { *d_data = *other.d_data; *d_layoutCache = *other.d_layoutCache; return *this; } -int QwtText::operator==(const QwtText &other) const +//! Relational operator +bool QwtText::operator==( const QwtText &other ) const { return d_data->renderFlags == other.d_data->renderFlags && - d_data->text == other.d_data->text && - d_data->font == other.d_data->font && - d_data->color == other.d_data->color && - d_data->backgroundPen == other.d_data->backgroundPen && - d_data->backgroundBrush == other.d_data->backgroundBrush && - d_data->paintAttributes == other.d_data->paintAttributes && - d_data->textEngine == other.d_data->textEngine; + d_data->text == other.d_data->text && + d_data->font == other.d_data->font && + d_data->color == other.d_data->color && + d_data->borderRadius == other.d_data->borderRadius && + d_data->borderPen == other.d_data->borderPen && + d_data->backgroundBrush == other.d_data->backgroundBrush && + d_data->paintAttributes == other.d_data->paintAttributes && + d_data->textEngine == other.d_data->textEngine; } -int QwtText::operator!=(const QwtText &other) const // invalidate +//! Relational operator +bool QwtText::operator!=( const QwtText &other ) const // invalidate { - return !(other == *this); + return !( other == *this ); } /*! @@ -224,18 +238,20 @@ int QwtText::operator!=(const QwtText &other) const // invalidate \param text Text content \param textFormat Text format + + \sa text() */ -void QwtText::setText(const QString &text, - QwtText::TextFormat textFormat) +void QwtText::setText( const QString &text, + QwtText::TextFormat textFormat ) { d_data->text = text; - d_data->textEngine = textEngine(text, textFormat); + d_data->textEngine = textEngine( text, textFormat ); d_layoutCache->invalidate(); } /*! - Return the text. - \sa setText + \return Text as QString. + \sa setText() */ QString QwtText::text() const { @@ -247,14 +263,15 @@ QString QwtText::text() const The default setting is Qt::AlignCenter - \param renderFlags Bitwise OR of the flags used like in QPainter::drawText + \param renderFlags Bitwise OR of the flags used like in QPainter::drawText() - \sa renderFlags, QwtTextEngine::draw + \sa renderFlags(), QwtTextEngine::draw() \note Some renderFlags might have no effect, depending on the text format. */ -void QwtText::setRenderFlags(int renderFlags) +void QwtText::setRenderFlags( int renderFlags ) { - if ( renderFlags != d_data->renderFlags ) { + if ( renderFlags != d_data->renderFlags ) + { d_data->renderFlags = renderFlags; d_layoutCache->invalidate(); } @@ -262,7 +279,7 @@ void QwtText::setRenderFlags(int renderFlags) /*! \return Render flags - \sa setRenderFlags + \sa setRenderFlags() */ int QwtText::renderFlags() const { @@ -276,10 +293,10 @@ int QwtText::renderFlags() const \note Setting the font might have no effect, when the text contains control sequences for setting fonts. */ -void QwtText::setFont(const QFont &font) +void QwtText::setFont( const QFont &font ) { d_data->font = font; - setPaintAttribute(PaintUsingTextFont); + setPaintAttribute( PaintUsingTextFont ); } //! Return the font. @@ -289,13 +306,15 @@ QFont QwtText::font() const } /*! - Return the font of the text, if it has one. - Otherwise return defaultFont. + Return the font of the text, if it has one. + Otherwise return defaultFont. + + \param defaultFont Default font + \return Font used for drawing the text - \param defaultFont Default font - \sa setFont, font, PaintAttributes + \sa setFont(), font(), PaintAttributes */ -QFont QwtText::usedFont(const QFont &defaultFont) const +QFont QwtText::usedFont( const QFont &defaultFont ) const { if ( d_data->paintAttributes & PaintUsingTextFont ) return d_data->font; @@ -304,16 +323,16 @@ QFont QwtText::usedFont(const QFont &defaultFont) const } /*! - Set the pen color used for painting the text. + Set the pen color used for drawing the text. \param color Color \note Setting the color might have no effect, when the text contains control sequences for setting colors. */ -void QwtText::setColor(const QColor &color) +void QwtText::setColor( const QColor &color ) { d_data->color = color; - setPaintAttribute(PaintUsingTextColor); + setPaintAttribute( PaintUsingTextColor ); } //! Return the pen color, used for painting the text @@ -327,9 +346,11 @@ QColor QwtText::color() const Otherwise return defaultColor. \param defaultColor Default color - \sa setColor, color, PaintAttributes + \return Color used for drawing the text + + \sa setColor(), color(), PaintAttributes */ -QColor QwtText::usedColor(const QColor &defaultColor) const +QColor QwtText::usedColor( const QColor &defaultColor ) const { if ( d_data->paintAttributes & PaintUsingTextColor ) return d_data->color; @@ -337,42 +358,62 @@ QColor QwtText::usedColor(const QColor &defaultColor) const return defaultColor; } +/*! + Set the radius for the corners of the border frame + + \param radius Radius of a rounded corner + \sa borderRadius(), setBorderPen(), setBackgroundBrush() +*/ +void QwtText::setBorderRadius( double radius ) +{ + d_data->borderRadius = qMax( 0.0, radius ); +} + +/*! + \return Radius for the corners of the border frame + \sa setBorderRadius(), borderPen(), backgroundBrush() +*/ +double QwtText::borderRadius() const +{ + return d_data->borderRadius; +} + /*! Set the background pen \param pen Background pen - \sa backgroundPen, setBackgroundBrush + \sa borderPen(), setBackgroundBrush() */ -void QwtText::setBackgroundPen(const QPen &pen) +void QwtText::setBorderPen( const QPen &pen ) { - d_data->backgroundPen = pen; - setPaintAttribute(PaintBackground); + d_data->borderPen = pen; + setPaintAttribute( PaintBackground ); } /*! \return Background pen - \sa setBackgroundPen, backgroundBrush + \sa setBorderPen(), backgroundBrush() */ -QPen QwtText::backgroundPen() const +QPen QwtText::borderPen() const { - return d_data->backgroundPen; + return d_data->borderPen; } /*! Set the background brush \param brush Background brush - \sa backgroundBrush, setBackgroundPen + \sa backgroundBrush(), setBorderPen() */ -void QwtText::setBackgroundBrush(const QBrush &brush) +void QwtText::setBackgroundBrush( const QBrush &brush ) { d_data->backgroundBrush = brush; - setPaintAttribute(PaintBackground); + setPaintAttribute( PaintBackground ); } /*! \return Background brush - \sa setBackgroundBrush, backgroundPen + \sa setBackgroundBrush(), borderPen() */ QBrush QwtText::backgroundBrush() const { @@ -385,10 +426,11 @@ QBrush QwtText::backgroundBrush() const \param attribute Paint attribute \param on On/Off - \note Used by setFont, setColor, setBackgroundPen and setBackgroundBrush - \sa testPaintAttribute + \note Used by setFont(), setColor(), + setBorderPen() and setBackgroundBrush() + \sa testPaintAttribute() */ -void QwtText::setPaintAttribute(PaintAttribute attribute, bool on) +void QwtText::setPaintAttribute( PaintAttribute attribute, bool on ) { if ( on ) d_data->paintAttributes |= attribute; @@ -402,9 +444,9 @@ void QwtText::setPaintAttribute(PaintAttribute attribute, bool on) \param attribute Paint attribute \return true, if attribute is enabled - \sa setPaintAttribute + \sa setPaintAttribute() */ -bool QwtText::testPaintAttribute(PaintAttribute attribute) const +bool QwtText::testPaintAttribute( PaintAttribute attribute ) const { return d_data->paintAttributes & attribute; } @@ -414,9 +456,9 @@ bool QwtText::testPaintAttribute(PaintAttribute attribute) const \param attribute Layout attribute \param on On/Off - \sa testLayoutAttribute + \sa testLayoutAttribute() */ -void QwtText::setLayoutAttribute(LayoutAttribute attribute, bool on) +void QwtText::setLayoutAttribute( LayoutAttribute attribute, bool on ) { if ( on ) d_data->layoutAttributes |= attribute; @@ -430,9 +472,9 @@ void QwtText::setLayoutAttribute(LayoutAttribute attribute, bool on) \param attribute Layout attribute \return true, if attribute is enabled - \sa setLayoutAttribute + \sa setLayoutAttribute() */ -bool QwtText::testLayoutAttribute(LayoutAttribute attribute) const +bool QwtText::testLayoutAttribute( LayoutAttribute attribute ) const { return d_data->layoutAttributes | attribute; } @@ -445,38 +487,33 @@ bool QwtText::testLayoutAttribute(LayoutAttribute attribute) const \return Calculated height */ -int QwtText::heightForWidth(int width, const QFont &defaultFont) const +double QwtText::heightForWidth( double width, const QFont &defaultFont ) const { - const QwtMetricsMap map = QwtPainter::metricsMap(); - width = map.layoutToScreenX(width); - -#if QT_VERSION < 0x040000 - const QFont font = usedFont(defaultFont); -#else // We want to calculate in screen metrics. So // we need a font that uses screen metrics - const QFont font(usedFont(defaultFont), QApplication::desktop()); -#endif + const QFont font( usedFont( defaultFont ), QApplication::desktop() ); - int h = 0; + double h = 0; - if ( d_data->layoutAttributes & MinimumLayout ) { - int left, right, top, bottom; - d_data->textEngine->textMargins(font, d_data->text, - left, right, top, bottom); + if ( d_data->layoutAttributes & MinimumLayout ) + { + double left, right, top, bottom; + d_data->textEngine->textMargins( font, d_data->text, + left, right, top, bottom ); h = d_data->textEngine->heightForWidth( - font, d_data->renderFlags, d_data->text, - width + left + right); + font, d_data->renderFlags, d_data->text, + width + left + right ); h -= top + bottom; - } else { + } + else + { h = d_data->textEngine->heightForWidth( - font, d_data->renderFlags, d_data->text, width); + font, d_data->renderFlags, d_data->text, width ); } - h = map.screenToLayoutY(h); return h; } @@ -494,48 +531,31 @@ int QwtText::heightForWidth(int width, const QFont &defaultFont) const \param defaultFont Font of the text \return Caluclated size */ -QSize QwtText::textSize(const QFont &defaultFont) const +QSizeF QwtText::textSize( const QFont &defaultFont ) const { -#if QT_VERSION < 0x040000 - const QFont font(usedFont(defaultFont)); -#else // We want to calculate in screen metrics. So // we need a font that uses screen metrics - const QFont font(usedFont(defaultFont), QApplication::desktop()); -#endif + const QFont font( usedFont( defaultFont ), QApplication::desktop() ); if ( !d_layoutCache->textSize.isValid() - || d_layoutCache->font != font ) { + || d_layoutCache->font != font ) + { d_layoutCache->textSize = d_data->textEngine->textSize( - font, d_data->renderFlags, d_data->text); + font, d_data->renderFlags, d_data->text ); d_layoutCache->font = font; } - QSize sz = d_layoutCache->textSize; + QSizeF sz = d_layoutCache->textSize; - const QwtMetricsMap map = QwtPainter::metricsMap(); - - if ( d_data->layoutAttributes & MinimumLayout ) { - int left, right, top, bottom; - d_data->textEngine->textMargins(font, d_data->text, - left, right, top, bottom); - sz -= QSize(left + right, top + bottom); -#if QT_VERSION >= 0x040000 - if ( !map.isIdentity() ) { -#ifdef __GNUC__ -#endif - /* - When printing in high resolution, the tick labels - of are cut of. We need to find out why, but for - the moment we add a couple of pixels instead. - */ - sz += QSize(3, 0); - } -#endif + if ( d_data->layoutAttributes & MinimumLayout ) + { + double left, right, top, bottom; + d_data->textEngine->textMargins( font, d_data->text, + left, right, top, bottom ); + sz -= QSizeF( left + right, top + bottom ); } - sz = map.screenToLayout(sz); return sz; } @@ -545,66 +565,66 @@ QSize QwtText::textSize(const QFont &defaultFont) const \param painter Painter \param rect Rectangle */ -void QwtText::draw(QPainter *painter, const QRect &rect) const +void QwtText::draw( QPainter *painter, const QRectF &rect ) const { - if ( d_data->paintAttributes & PaintBackground ) { - if ( d_data->backgroundPen != Qt::NoPen || - d_data->backgroundBrush != Qt::NoBrush ) { + if ( d_data->paintAttributes & PaintBackground ) + { + if ( d_data->borderPen != Qt::NoPen || + d_data->backgroundBrush != Qt::NoBrush ) + { painter->save(); - painter->setPen(d_data->backgroundPen); - painter->setBrush(d_data->backgroundBrush); -#if QT_VERSION < 0x040000 - QwtPainter::drawRect(painter, rect); -#else - const QRect r(rect.x(), rect.y(), - rect.width() - 1, rect.height() - 1); - QwtPainter::drawRect(painter, r); -#endif + + painter->setPen( d_data->borderPen ); + painter->setBrush( d_data->backgroundBrush ); + + if ( d_data->borderRadius == 0 ) + { + QwtPainter::drawRect( painter, rect ); + } + else + { + painter->setRenderHint( QPainter::Antialiasing, true ); + painter->drawRoundedRect( rect, + d_data->borderRadius, d_data->borderRadius ); + } + painter->restore(); } } painter->save(); - if ( d_data->paintAttributes & PaintUsingTextFont ) { - painter->setFont(d_data->font); + if ( d_data->paintAttributes & PaintUsingTextFont ) + { + painter->setFont( d_data->font ); } - if ( d_data->paintAttributes & PaintUsingTextColor ) { + if ( d_data->paintAttributes & PaintUsingTextColor ) + { if ( d_data->color.isValid() ) - painter->setPen(d_data->color); + painter->setPen( d_data->color ); } - QRect expandedRect = rect; - if ( d_data->layoutAttributes & MinimumLayout ) { -#if QT_VERSION < 0x040000 - const QFont font(painter->font()); -#else + QRectF expandedRect = rect; + if ( d_data->layoutAttributes & MinimumLayout ) + { // We want to calculate in screen metrics. So // we need a font that uses screen metrics - const QFont font(painter->font(), QApplication::desktop()); -#endif + const QFont font( painter->font(), QApplication::desktop() ); - int left, right, top, bottom; + double left, right, top, bottom; d_data->textEngine->textMargins( - font, d_data->text, - left, right, top, bottom); - - const QwtMetricsMap map = QwtPainter::metricsMap(); - left = map.screenToLayoutX(left); - right = map.screenToLayoutX(right); - top = map.screenToLayoutY(top); - bottom = map.screenToLayoutY(bottom); - - expandedRect.setTop(rect.top() - top); - expandedRect.setBottom(rect.bottom() + bottom); - expandedRect.setLeft(rect.left() - left); - expandedRect.setRight(rect.right() + right); + font, d_data->text, left, right, top, bottom ); + + expandedRect.setTop( rect.top() - top ); + expandedRect.setBottom( rect.bottom() + bottom ); + expandedRect.setLeft( rect.left() - left ); + expandedRect.setRight( rect.right() + right ); } - d_data->textEngine->draw(painter, expandedRect, - d_data->renderFlags, d_data->text); + d_data->textEngine->draw( painter, expandedRect, + d_data->renderFlags, d_data->text ); painter->restore(); } @@ -614,28 +634,20 @@ void QwtText::draw(QPainter *painter, const QRect &rect) const In case of QwtText::AutoText the first text engine (beside QwtPlainTextEngine) is returned, where QwtTextEngine::mightRender - returns true. If there is none QwtPlainTextEngine is returnd. + returns true. If there is none QwtPlainTextEngine is returned. If no text engine is registered for the format QwtPlainTextEngine is returnd. \param text Text, needed in case of AutoText \param format Text format -*/ -const QwtTextEngine *QwtText::textEngine(const QString &text, - QwtText::TextFormat format) -{ - if ( engineDict == NULL ) { - /* - Note: engineDict is allocated, the first time it is used, - but never deleted, because there is no known last access time. - So don't be irritated, if it is reported as a memory leak - from your memory profiler. - */ - engineDict = new QwtTextEngineDict(); - } - return engineDict->textEngine(text, format); + \return Corresponding text engine +*/ +const QwtTextEngine *QwtText::textEngine( const QString &text, + QwtText::TextFormat format ) +{ + return QwtTextEngineDict::dict().textEngine( text, format ); } /*! @@ -644,10 +656,6 @@ const QwtTextEngine *QwtText::textEngine(const QString &text, With setTextEngine it is possible to extend Qwt with other types of text formats. - Owner of a commercial Qt license can build the qwtmathml library, - that is based on the MathML renderer, that is included in MML Widget - component of the Qt solutions package. - For QwtText::PlainText it is not allowed to assign a engine == NULL. \param format Text format @@ -656,30 +664,21 @@ const QwtTextEngine *QwtText::textEngine(const QString &text, \sa QwtMathMLTextEngine \warning Using QwtText::AutoText does nothing. */ -void QwtText::setTextEngine(QwtText::TextFormat format, - QwtTextEngine *engine) +void QwtText::setTextEngine( QwtText::TextFormat format, + QwtTextEngine *engine ) { - if ( engineDict == NULL ) - engineDict = new QwtTextEngineDict(); - - engineDict->setTextEngine(format, engine); + QwtTextEngineDict::dict().setTextEngine( format, engine ); } /*! \brief Find the text engine for a text format textEngine can be used to find out if a text format is supported. - F.e, if one wants to use MathML labels, the MathML renderer from the - commercial Qt solutions package might be required, that is not - available in Qt Open Source Edition environments. \param format Text format \return The text engine, or NULL if no engine is available. */ -const QwtTextEngine *QwtText::textEngine(QwtText::TextFormat format) +const QwtTextEngine *QwtText::textEngine( QwtText::TextFormat format ) { - if ( engineDict == NULL ) - engineDict = new QwtTextEngineDict(); - - return engineDict->textEngine(format); + return QwtTextEngineDict::dict().textEngine( format ); } diff --git a/libs/qwt/qwt_text.h b/libs/qwt/qwt_text.h index e353a3ef40..e78969083f 100644 --- a/libs/qwt/qwt_text.h +++ b/libs/qwt/qwt_text.h @@ -7,20 +7,19 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_TEXT_H #define QWT_TEXT_H +#include "qwt_global.h" #include <qstring.h> #include <qsize.h> #include <qfont.h> -#include "qwt_global.h" +#include <qmetatype.h> class QColor; class QPen; class QBrush; -class QRect; +class QRectF; class QPainter; class QwtTextEngine; @@ -33,17 +32,18 @@ class QwtTextEngine; A text might include control sequences (f.e tags) describing how to render it. Each format (f.e MathML, TeX, Qt Rich Text) has its own set of control sequences, that can be handles by - a QwtTextEngine for this format. + a special QwtTextEngine for this format. - Background\n A text might have a background, defined by a QPen and QBrush - to improve its visibility. + to improve its visibility. The corners of the background might + be rounded. - Font\n A text might have an individual font. - Color\n A text might have an individual color. - Render Flags\n Flags from Qt::AlignmentFlag and Qt::TextFlag used like in - QPainter::drawText. + QPainter::drawText(). \sa QwtTextEngine, QwtTextLabel */ @@ -58,39 +58,45 @@ public: The text format defines the QwtTextEngine, that is used to render the text. - - AutoText\n - The text format is determined using QwtTextEngine::mightRender for - all available text engines in increasing order > PlainText. - If none of the text engines can render the text is rendered - like PlainText. - - PlainText\n - Draw the text as it is, using a QwtPlainTextEngine. - - RichText\n - Use the Scribe framework (Qt Rich Text) to render the text. - - MathMLText\n - Use a MathML (http://en.wikipedia.org/wiki/MathML) render engine - to display the text. The Qwt MathML extension offers such an engine - based on the MathML renderer of the Qt solutions package. Unfortunately - it is only available for owners of a commercial Qt license. - - TeXText\n - Use a TeX (http://en.wikipedia.org/wiki/TeX) render engine - to display the text. - - OtherFormat\n - The number of text formats can be extended using setTextEngine. - Formats >= OtherFormat are not used by Qwt. - - \sa QwtTextEngine, setTextEngine + \sa QwtTextEngine, setTextEngine() */ - enum TextFormat { + enum TextFormat + { + /*! + The text format is determined using QwtTextEngine::mightRender() for + all available text engines in increasing order > PlainText. + If none of the text engines can render the text is rendered + like QwtText::PlainText. + */ AutoText = 0, + //! Draw the text as it is, using a QwtPlainTextEngine. PlainText, + + //! Use the Scribe framework (Qt Rich Text) to render the text. RichText, + /*! + Use a MathML (http://en.wikipedia.org/wiki/MathML) render engine + to display the text. The Qwt MathML extension offers such an engine + based on the MathML renderer of the Qt solutions package. + To enable MathML support the following code needs to be added to the + application: +\verbatim QwtText::setTextEngine(QwtText::MathMLText, new QwtMathMLTextEngine()); \endverbatim + */ MathMLText, + + /*! + Use a TeX (http://en.wikipedia.org/wiki/TeX) render engine + to display the text ( not implemented yet ). + */ TeXText, + /*! + The number of text formats can be extended using setTextEngine. + Formats >= QwtText::OtherFormat are not used by Qwt. + */ OtherFormat = 100 }; @@ -99,94 +105,95 @@ public: Font and color and background are optional attributes of a QwtText. The paint attributes hold the information, if they are set. - - - PaintUsingTextFont\n - The text has an individual font. - - PaintUsingTextColor\n - The text has an individual color. - - PaintBackground\n - The text has an individual background. */ - enum PaintAttribute { - PaintUsingTextFont = 1, - PaintUsingTextColor = 2, - PaintBackground = 4 + enum PaintAttribute + { + //! The text has an individual font. + PaintUsingTextFont = 0x01, + + //! The text has an individual color. + PaintUsingTextColor = 0x02, + + //! The text has an individual background. + PaintBackground = 0x04 }; + //! Paint attributes + typedef QFlags<PaintAttribute> PaintAttributes; + /*! \brief Layout Attributes - The layout attributes affects some aspects of the layout of the text. - - - MinimumLayout\n - Layout the text without its margins. This mode is useful if a - text needs to be aligned accurately, like the tick labels of a scale. - If QwtTextEngine::textMargins is not implemented for the format - of the text, MinimumLayout has no effect. */ - enum LayoutAttribute { - MinimumLayout = 1 + enum LayoutAttribute + { + /*! + Layout the text without its margins. This mode is useful if a + text needs to be aligned accurately, like the tick labels of a scale. + If QwtTextEngine::textMargins is not implemented for the format + of the text, MinimumLayout has no effect. + */ + MinimumLayout = 0x01 }; - QwtText(const QString & = QString::null, - TextFormat textFormat = AutoText); - QwtText(const QwtText &); + //! Layout attributes + typedef QFlags<LayoutAttribute> LayoutAttributes; + + QwtText( const QString & = QString::null, + TextFormat textFormat = AutoText ); + QwtText( const QwtText & ); ~QwtText(); - QwtText &operator=(const QwtText &); + QwtText &operator=( const QwtText & ); - int operator==(const QwtText &) const; - int operator!=(const QwtText &) const; + bool operator==( const QwtText & ) const; + bool operator!=( const QwtText & ) const; - void setText(const QString &, - QwtText::TextFormat textFormat = AutoText); + void setText( const QString &, + QwtText::TextFormat textFormat = AutoText ); QString text() const; - //! \return text().isNull() - inline bool isNull() const { - return text().isNull(); - } - - //! \return text().isEmpty() - inline bool isEmpty() const { - return text().isEmpty(); - } + bool isNull() const; + bool isEmpty() const; - void setFont(const QFont &); + void setFont( const QFont & ); QFont font() const; - QFont usedFont(const QFont &) const; + QFont usedFont( const QFont & ) const; - void setRenderFlags(int flags); + void setRenderFlags( int flags ); int renderFlags() const; - void setColor(const QColor &); + void setColor( const QColor & ); QColor color() const; - QColor usedColor(const QColor &) const; + QColor usedColor( const QColor & ) const; - void setBackgroundPen(const QPen &); - QPen backgroundPen() const; + void setBorderRadius( double ); + double borderRadius() const; - void setBackgroundBrush(const QBrush &); + void setBorderPen( const QPen & ); + QPen borderPen() const; + + void setBackgroundBrush( const QBrush & ); QBrush backgroundBrush() const; - void setPaintAttribute(PaintAttribute, bool on = true); - bool testPaintAttribute(PaintAttribute) const; + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; - void setLayoutAttribute(LayoutAttribute, bool on = true); - bool testLayoutAttribute(LayoutAttribute) const; + void setLayoutAttribute( LayoutAttribute, bool on = true ); + bool testLayoutAttribute( LayoutAttribute ) const; - int heightForWidth(int width, const QFont & = QFont()) const; - QSize textSize(const QFont & = QFont()) const; + double heightForWidth( double width, const QFont & = QFont() ) const; + QSizeF textSize( const QFont & = QFont() ) const; - void draw(QPainter *painter, const QRect &rect) const; + void draw( QPainter *painter, const QRectF &rect ) const; - static const QwtTextEngine *textEngine(const QString &text, - QwtText::TextFormat = AutoText); + static const QwtTextEngine *textEngine( + const QString &text, QwtText::TextFormat = AutoText ); - static const QwtTextEngine *textEngine(QwtText::TextFormat); - static void setTextEngine(QwtText::TextFormat, QwtTextEngine *); + static const QwtTextEngine *textEngine( QwtText::TextFormat ); + static void setTextEngine( QwtText::TextFormat, QwtTextEngine * ); private: class PrivateData; @@ -196,4 +203,21 @@ private: LayoutCache *d_layoutCache; }; +//! \return text().isNull() +inline bool QwtText::isNull() const +{ + return text().isNull(); +} + +//! \return text().isEmpty() +inline bool QwtText::isEmpty() const +{ + return text().isEmpty(); +} + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtText::PaintAttributes ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtText::LayoutAttributes ) + +Q_DECLARE_METATYPE( QwtText ) + #endif diff --git a/libs/qwt/qwt_text_engine.cpp b/libs/qwt/qwt_text_engine.cpp index 5c0cef2765..5991588a6a 100644 --- a/libs/qwt/qwt_text_engine.cpp +++ b/libs/qwt/qwt_text_engine.cpp @@ -7,142 +7,120 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - +#include "qwt_text_engine.h" +#include "qwt_math.h" +#include "qwt_painter.h" #include <qpainter.h> #include <qpixmap.h> #include <qimage.h> #include <qmap.h> #include <qwidget.h> -#include "qwt_math.h" -#include "qwt_painter.h" -#include "qwt_text_engine.h" +#include <qtextobject.h> +#include <qtextdocument.h> +#include <qabstracttextdocumentlayout.h> -static QString taggedRichText(const QString &text, int flags) +static QString taggedRichText( const QString &text, int flags ) { QString richText = text; // By default QSimpleRichText is Qt::AlignLeft - if (flags & Qt::AlignJustify) { - richText.prepend(QString::fromLatin1("<div align=\"justify\">")); - richText.append(QString::fromLatin1("</div>")); - } else if (flags & Qt::AlignRight) { - richText.prepend(QString::fromLatin1("<div align=\"right\">")); - richText.append(QString::fromLatin1("</div>")); - } else if (flags & Qt::AlignHCenter) { - richText.prepend(QString::fromLatin1("<div align=\"center\">")); - richText.append(QString::fromLatin1("</div>")); + if ( flags & Qt::AlignJustify ) + { + richText.prepend( QString::fromLatin1( "<div align=\"justify\">" ) ); + richText.append( QString::fromLatin1( "</div>" ) ); + } + else if ( flags & Qt::AlignRight ) + { + richText.prepend( QString::fromLatin1( "<div align=\"right\">" ) ); + richText.append( QString::fromLatin1( "</div>" ) ); + } + else if ( flags & Qt::AlignHCenter ) + { + richText.prepend( QString::fromLatin1( "<div align=\"center\">" ) ); + richText.append( QString::fromLatin1( "</div>" ) ); } return richText; } -#if QT_VERSION < 0x040000 - -#include <qsimplerichtext.h> -#include <qstylesheet.h> - -class QwtRichTextDocument: public QSimpleRichText -{ -public: - QwtRichTextDocument(const QString &text, int flags, const QFont &font): - QSimpleRichText(taggedRichText(text, flags), font) { - } -}; - -#else // QT_VERSION >= 0x040000 - -#include <qtextobject.h> -#include <qtextdocument.h> -#include <qabstracttextdocumentlayout.h> - -#if QT_VERSION < 0x040200 -#include <qlabel.h> -#endif - class QwtRichTextDocument: public QTextDocument { public: - QwtRichTextDocument(const QString &text, int flags, const QFont &font) { - setUndoRedoEnabled(false); - setDefaultFont(font); -#if QT_VERSION >= 0x040300 - setHtml(text); -#else -setHtml(taggedRichText(text, flags)); -#endif + QwtRichTextDocument( const QString &text, int flags, const QFont &font ) + { + setUndoRedoEnabled( false ); + setDefaultFont( font ); + setHtml( text ); // make sure we have a document layout - (void)documentLayout(); + ( void )documentLayout(); -#if QT_VERSION >= 0x040300 QTextOption option = defaultTextOption(); if ( flags & Qt::TextWordWrap ) - option.setWrapMode(QTextOption::WordWrap); + option.setWrapMode( QTextOption::WordWrap ); else - option.setWrapMode(QTextOption::NoWrap); + option.setWrapMode( QTextOption::NoWrap ); - option.setAlignment((Qt::Alignment) flags); - setDefaultTextOption(option); + option.setAlignment( static_cast<Qt::Alignment>( flags ) ); + setDefaultTextOption( option ); QTextFrame *root = rootFrame(); QTextFrameFormat fm = root->frameFormat(); - fm.setBorder(0); - fm.setMargin(0); - fm.setPadding(0); - fm.setBottomMargin(0); - fm.setLeftMargin(0); - root->setFrameFormat(fm); + fm.setBorder( 0 ); + fm.setMargin( 0 ); + fm.setPadding( 0 ); + fm.setBottomMargin( 0 ); + fm.setLeftMargin( 0 ); + root->setFrameFormat( fm ); adjustSize(); -#endif } }; -#endif - class QwtPlainTextEngine::PrivateData { public: - int effectiveAscent(const QFont &font) const { + int effectiveAscent( const QFont &font ) const + { const QString fontKey = font.key(); QMap<QString, int>::const_iterator it = - d_ascentCache.find(fontKey); - if ( it == d_ascentCache.end() ) { - int ascent = findAscent(font); - it = d_ascentCache.insert(fontKey, ascent); + d_ascentCache.find( fontKey ); + if ( it == d_ascentCache.end() ) + { + int ascent = findAscent( font ); + it = d_ascentCache.insert( fontKey, ascent ); } - return (*it); + return ( *it ); } private: - int findAscent(const QFont &font) const { - static const QString dummy("E"); - static const QColor white(Qt::white); - - const QFontMetrics fm(font); - QPixmap pm(fm.width(dummy), fm.height()); - pm.fill(white); - - QPainter p(&pm); - p.setFont(font); - p.drawText(0, 0, pm.width(), pm.height(), 0, dummy); + int findAscent( const QFont &font ) const + { + static const QString dummy( "E" ); + static const QColor white( Qt::white ); + + const QFontMetrics fm( font ); + QPixmap pm( fm.width( dummy ), fm.height() ); + pm.fill( white ); + + QPainter p( &pm ); + p.setFont( font ); + p.drawText( 0, 0, pm.width(), pm.height(), 0, dummy ); p.end(); -#if QT_VERSION < 0x040000 - const QImage img = pm.convertToImage(); -#else const QImage img = pm.toImage(); -#endif int row = 0; - for ( row = 0; row < img.height(); row++ ) { - const QRgb *line = (const QRgb *)img.scanLine(row); + for ( row = 0; row < img.height(); row++ ) + { + const QRgb *line = reinterpret_cast<const QRgb *>( + img.scanLine( row ) ); const int w = pm.width(); - for ( int col = 0; col < w; col++ ) { + for ( int col = 0; col < w; col++ ) + { if ( line[col] != white.rgb() ) return fm.ascent() - row + 1; } @@ -186,12 +164,12 @@ QwtPlainTextEngine::~QwtPlainTextEngine() \return Calculated height */ -int QwtPlainTextEngine::heightForWidth(const QFont& font, int flags, - const QString& text, int width) const +double QwtPlainTextEngine::heightForWidth( const QFont& font, int flags, + const QString& text, double width ) const { - const QFontMetrics fm(font); - const QRect rect = fm.boundingRect( - 0, 0, width, QWIDGETSIZE_MAX, flags, text); + const QFontMetricsF fm( font ); + const QRectF rect = fm.boundingRect( + QRectF( 0, 0, width, QWIDGETSIZE_MAX ), flags, text ); return rect.height(); } @@ -205,12 +183,12 @@ int QwtPlainTextEngine::heightForWidth(const QFont& font, int flags, \return Caluclated size */ -QSize QwtPlainTextEngine::textSize(const QFont &font, - int flags, const QString& text) const +QSizeF QwtPlainTextEngine::textSize( const QFont &font, + int flags, const QString& text ) const { - const QFontMetrics fm(font); - const QRect rect = fm.boundingRect( - 0, 0, QWIDGETSIZE_MAX, QWIDGETSIZE_MAX, flags, text); + const QFontMetricsF fm( font ); + const QRectF rect = fm.boundingRect( + QRectF( 0, 0, QWIDGETSIZE_MAX, QWIDGETSIZE_MAX ), flags, text ); return rect.size(); } @@ -224,14 +202,14 @@ QSize QwtPlainTextEngine::textSize(const QFont &font, \param top Return value for the top margin \param bottom Return value for the bottom margin */ -void QwtPlainTextEngine::textMargins(const QFont &font, const QString &, - int &left, int &right, int &top, int &bottom) const +void QwtPlainTextEngine::textMargins( const QFont &font, const QString &, + double &left, double &right, double &top, double &bottom ) const { left = right = top = 0; - const QFontMetrics fm(font); - top = fm.ascent() - d_data->effectiveAscent(font); - bottom = fm.descent() + 1; + const QFontMetricsF fm( font ); + top = fm.ascent() - d_data->effectiveAscent( font ); + bottom = fm.descent(); } /*! @@ -244,17 +222,17 @@ void QwtPlainTextEngine::textMargins(const QFont &font, const QString &, \param flags Bitwise OR of the flags used like in QPainter::drawText \param text Text to be rendered */ -void QwtPlainTextEngine::draw(QPainter *painter, const QRect &rect, - int flags, const QString& text) const +void QwtPlainTextEngine::draw( QPainter *painter, const QRectF &rect, + int flags, const QString& text ) const { - QwtPainter::drawText(painter, rect, flags, text); + QwtPainter::drawText( painter, rect, flags, text ); } /*! Test if a string can be rendered by this text engine. \return Always true. All texts can be rendered by QwtPlainTextEngine */ -bool QwtPlainTextEngine::mightRender(const QString &) const +bool QwtPlainTextEngine::mightRender( const QString & ) const { return true; } @@ -270,96 +248,45 @@ QwtRichTextEngine::QwtRichTextEngine() Find the height for a given width \param font Font of the text - \param flags Bitwise OR of the flags used like in QPainter::drawText + \param flags Bitwise OR of the flags used like in QPainter::drawText() \param text Text to be rendered \param width Width \return Calculated height */ -int QwtRichTextEngine::heightForWidth(const QFont& font, int flags, - const QString& text, int width) const +double QwtRichTextEngine::heightForWidth( const QFont& font, int flags, + const QString& text, double width ) const { - QwtRichTextDocument doc(text, flags, font); - -#if QT_VERSION < 0x040000 - doc.setWidth(width); - const int h = doc.height(); -#else - doc.setPageSize(QSize(width, QWIDGETSIZE_MAX)); - const int h = qRound(doc.documentLayout()->documentSize().height()); -#endif - return h; + QwtRichTextDocument doc( text, flags, font ); + + doc.setPageSize( QSizeF( width, QWIDGETSIZE_MAX ) ); + return doc.documentLayout()->documentSize().height(); } /*! Returns the size, that is needed to render text \param font Font of the text - \param flags Bitwise OR of the flags used like in QPainter::drawText + \param flags Bitwise OR of the flags used like in QPainter::drawText() \param text Text to be rendered \return Caluclated size */ -QSize QwtRichTextEngine::textSize(const QFont &font, - int flags, const QString& text) const +QSizeF QwtRichTextEngine::textSize( const QFont &font, + int flags, const QString& text ) const { - QwtRichTextDocument doc(text, flags, font); - -#if QT_VERSION < 0x040000 - doc.setWidth(QWIDGETSIZE_MAX); - - const int w = doc.widthUsed(); - const int h = doc.height(); - return QSize(w, h); - -#else // QT_VERSION >= 0x040000 - -#if QT_VERSION < 0x040200 - /* - Unfortunately offering the bounding rect calculation in the - API of QTextDocument has been forgotten in Qt <= 4.1.x. It - is planned to come with Qt 4.2.x. - In the meantime we need a hack with a temporary QLabel, - to reengineer the internal calculations. - */ - - static int off = 0; - static QLabel *label = NULL; - if ( label == NULL ) { - label = new QLabel; - label->hide(); - - const char *s = "XXXXX"; - label->setText(s); - int w1 = label->sizeHint().width(); - const QFontMetrics fm(label->font()); - int w2 = fm.width(s); - off = w1 - w2; - } - label->setFont(doc.defaultFont()); - label->setText(text); - - int w = qwtMax(label->sizeHint().width() - off, 0); - doc.setPageSize(QSize(w, QWIDGETSIZE_MAX)); - - int h = qRound(doc.documentLayout()->documentSize().height()); - return QSize(w, h); - -#else // QT_VERSION >= 0x040200 + QwtRichTextDocument doc( text, flags, font ); -#if QT_VERSION >= 0x040300 QTextOption option = doc.defaultTextOption(); - if ( option.wrapMode() != QTextOption::NoWrap ) { - option.setWrapMode(QTextOption::NoWrap); - doc.setDefaultTextOption(option); + if ( option.wrapMode() != QTextOption::NoWrap ) + { + option.setWrapMode( QTextOption::NoWrap ); + doc.setDefaultTextOption( option ); doc.adjustSize(); } -#endif - return doc.size().toSize(); -#endif -#endif + return doc.size(); } /*! @@ -367,42 +294,38 @@ QSize QwtRichTextEngine::textSize(const QFont &font, \param painter Painter \param rect Clipping rectangle - \param flags Bitwise OR of the flags like in for QPainter::drawText + \param flags Bitwise OR of the flags like in for QPainter::drawText() \param text Text to be rendered */ -void QwtRichTextEngine::draw(QPainter *painter, const QRect &rect, - int flags, const QString& text) const +void QwtRichTextEngine::draw( QPainter *painter, const QRectF &rect, + int flags, const QString& text ) const { - QwtRichTextDocument doc(text, flags, painter->font()); - QwtPainter::drawSimpleRichText(painter, rect, flags, doc); + QwtRichTextDocument doc( text, flags, painter->font() ); + QwtPainter::drawSimpleRichText( painter, rect, flags, doc ); } /*! Wrap text into <div align=...> </div> tags according flags \param text Text - \param flags Bitwise OR of the flags like in for QPainter::drawText + \param flags Bitwise OR of the flags like in for QPainter::drawText() \return Tagged text */ -QString QwtRichTextEngine::taggedText(const QString &text, int flags) const +QString QwtRichTextEngine::taggedText( const QString &text, int flags ) const { - return taggedRichText(text, flags); + return taggedRichText( text, flags ); } /*! Test if a string can be rendered by this text engine \param text Text to be tested - \return QStyleSheet::mightBeRichText(text); + \return Qt::mightBeRichText(text); */ -bool QwtRichTextEngine::mightRender(const QString &text) const +bool QwtRichTextEngine::mightRender( const QString &text ) const { -#if QT_VERSION < 0x040000 - return QStyleSheet::mightBeRichText(text); -#else - return Qt::mightBeRichText(text); -#endif + return Qt::mightBeRichText( text ); } /*! @@ -413,8 +336,8 @@ bool QwtRichTextEngine::mightRender(const QString &text) const \param top Return 0 \param bottom Return 0 */ -void QwtRichTextEngine::textMargins(const QFont &, const QString &, - int &left, int &right, int &top, int &bottom) const +void QwtRichTextEngine::textMargins( const QFont &, const QString &, + double &left, double &right, double &top, double &bottom ) const { left = right = top = bottom = 0; } diff --git a/libs/qwt/qwt_text_engine.h b/libs/qwt/qwt_text_engine.h index 0e8b8cbe88..927ec4e9f4 100644 --- a/libs/qwt/qwt_text_engine.h +++ b/libs/qwt/qwt_text_engine.h @@ -7,16 +7,14 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - #ifndef QWT_TEXT_ENGINE_H #define QWT_TEXT_ENGINE_H 1 -#include <qsize.h> #include "qwt_global.h" +#include <qsize.h> class QFont; -class QRect; +class QRectF; class QString; class QPainter; @@ -27,12 +25,11 @@ class QPainter; specific text format. They are used by QwtText to render a text. QwtPlainTextEngine and QwtRichTextEngine are part of the Qwt library. - - QwtMathMLTextEngine can be found in Qwt MathML extension, that - needs the MathML renderer of the Qt solutions package. Unfortunately - it is only available with a commercial Qt license. - - \sa QwtText::setTextEngine + The implementation of QwtMathMLTextEngine uses code from the + Qt solution package. Because of license implications it is built into + a separate library. + + \sa QwtText::setTextEngine() */ class QWT_EXPORT QwtTextEngine @@ -50,8 +47,8 @@ public: \return Calculated height */ - virtual int heightForWidth(const QFont &font, int flags, - const QString &text, int width) const = 0; + virtual double heightForWidth( const QFont &font, int flags, + const QString &text, double width ) const = 0; /*! Returns the size, that is needed to render text @@ -60,10 +57,10 @@ public: \param flags Bitwise OR of the flags like in for QPainter::drawText \param text Text to be rendered - \return Caluclated size + \return Calculated size */ - virtual QSize textSize(const QFont &font, int flags, - const QString &text) const = 0; + virtual QSizeF textSize( const QFont &font, int flags, + const QString &text ) const = 0; /*! Test if a string can be rendered by this text engine @@ -71,14 +68,14 @@ public: \param text Text to be tested \return true, if it can be rendered */ - virtual bool mightRender(const QString &text) const = 0; + virtual bool mightRender( const QString &text ) const = 0; /*! Return margins around the texts The textSize might include margins around the - text, like QFontMetrics::descent. In situations - where texts need to be aligend in detail, knowing + text, like QFontMetrics::descent(). In situations + where texts need to be aligned in detail, knowing these margins might improve the layout calculations. \param font Font of the text @@ -88,19 +85,19 @@ public: \param top Return value for the top margin \param bottom Return value for the bottom margin */ - virtual void textMargins(const QFont &font, const QString &text, - int &left, int &right, int &top, int &bottom) const = 0; + virtual void textMargins( const QFont &font, const QString &text, + double &left, double &right, double &top, double &bottom ) const = 0; /*! Draw the text in a clipping rectangle \param painter Painter \param rect Clipping rectangle - \param flags Bitwise OR of the flags like in for QPainter::drawText + \param flags Bitwise OR of the flags like in for QPainter::drawText() \param text Text to be rendered */ - virtual void draw(QPainter *painter, const QRect &rect, - int flags, const QString &text) const = 0; + virtual void draw( QPainter *painter, const QRectF &rect, + int flags, const QString &text ) const = 0; protected: QwtTextEngine(); @@ -119,19 +116,19 @@ public: QwtPlainTextEngine(); virtual ~QwtPlainTextEngine(); - virtual int heightForWidth(const QFont &font, int flags, - const QString &text, int width) const; + virtual double heightForWidth( const QFont &font, int flags, + const QString &text, double width ) const; - virtual QSize textSize(const QFont &font, int flags, - const QString &text) const; + virtual QSizeF textSize( const QFont &font, int flags, + const QString &text ) const; - virtual void draw(QPainter *painter, const QRect &rect, - int flags, const QString &text) const; + virtual void draw( QPainter *painter, const QRectF &rect, + int flags, const QString &text ) const; - virtual bool mightRender(const QString &) const; + virtual bool mightRender( const QString & ) const; - virtual void textMargins(const QFont &, const QString &, - int &left, int &right, int &top, int &bottom) const; + virtual void textMargins( const QFont &, const QString &, + double &left, double &right, double &top, double &bottom ) const; private: class PrivateData; @@ -152,21 +149,22 @@ class QWT_EXPORT QwtRichTextEngine: public QwtTextEngine public: QwtRichTextEngine(); - virtual int heightForWidth(const QFont &font, int flags, - const QString &text, int width) const; + virtual double heightForWidth( const QFont &font, int flags, + const QString &text, double width ) const; + + virtual QSizeF textSize( const QFont &font, int flags, + const QString &text ) const; - virtual QSize textSize(const QFont &font, int flags, - const QString &text) const; + virtual void draw( QPainter *painter, const QRectF &rect, + int flags, const QString &text ) const; - virtual void draw(QPainter *painter, const QRect &rect, - int flags, const QString &text) const; + virtual bool mightRender( const QString & ) const; - virtual bool mightRender(const QString &) const; + virtual void textMargins( const QFont &, const QString &, + double &left, double &right, double &top, double &bottom ) const; - virtual void textMargins(const QFont &, const QString &, - int &left, int &right, int &top, int &bottom) const; private: - QString taggedText(const QString &, int flags) const; + QString taggedText( const QString &, int flags ) const; }; #endif // !QT_NO_RICHTEXT diff --git a/libs/qwt/qwt_text_label.cpp b/libs/qwt/qwt_text_label.cpp index be175a334e..0b58baabf1 100644 --- a/libs/qwt/qwt_text_label.cpp +++ b/libs/qwt/qwt_text_label.cpp @@ -7,20 +7,20 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -// vim: expandtab - -#include <qpainter.h> -#include <qevent.h> +#include "qwt_text_label.h" #include "qwt_text.h" #include "qwt_painter.h" -#include "qwt_text_label.h" +#include <qpainter.h> +#include <qevent.h> +#include <qmath.h> class QwtTextLabel::PrivateData { public: PrivateData(): - indent(4), - margin(0) { + indent( 4 ), + margin( 0 ) + { } int indent; @@ -32,32 +32,19 @@ public: Constructs an empty label. \param parent Parent widget */ -QwtTextLabel::QwtTextLabel(QWidget *parent): - QFrame(parent) +QwtTextLabel::QwtTextLabel( QWidget *parent ): + QFrame( parent ) { init(); } -#if QT_VERSION < 0x040000 -/*! - Constructs an empty label. - \param parent Parent widget - \param name Object name -*/ -QwtTextLabel::QwtTextLabel(QWidget *parent, const char *name): - QFrame(parent, name) -{ - init(); -} -#endif - /*! Constructs a label that displays the text, text \param parent Parent widget \param text Text */ -QwtTextLabel::QwtTextLabel(const QwtText &text, QWidget *parent): - QFrame(parent) +QwtTextLabel::QwtTextLabel( const QwtText &text, QWidget *parent ): + QFrame( parent ) { init(); d_data->text = text; @@ -72,7 +59,27 @@ QwtTextLabel::~QwtTextLabel() void QwtTextLabel::init() { d_data = new PrivateData(); - setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); + setSizePolicy( QSizePolicy::Preferred, QSizePolicy::Preferred ); +} + +/*! + Interface for the designer plugin - does the same as setText() + \sa plainText() + */ +void QwtTextLabel::setPlainText( const QString &text ) +{ + setText( QwtText( text ) ); +} + +/*! + Interface for the designer plugin + + \return Text as plain text + \sa setPlainText(), text() + */ +QString QwtTextLabel::plainText() const +{ + return d_data->text.text(); } /*! @@ -82,9 +89,10 @@ void QwtTextLabel::init() \sa QwtText */ -void QwtTextLabel::setText(const QString &text, QwtText::TextFormat textFormat) +void QwtTextLabel::setText( const QString &text, + QwtText::TextFormat textFormat ) { - d_data->text.setText(text, textFormat); + d_data->text.setText( text, textFormat ); update(); updateGeometry(); @@ -94,7 +102,7 @@ void QwtTextLabel::setText(const QString &text, QwtText::TextFormat textFormat) Change the label's text \param text New text */ -void QwtTextLabel::setText(const QwtText &text) +void QwtTextLabel::setText( const QwtText &text ) { d_data->text = text; @@ -127,7 +135,7 @@ int QwtTextLabel::indent() const Set label's text indent in pixels \param indent Indentation in pixels */ -void QwtTextLabel::setIndent(int indent) +void QwtTextLabel::setIndent( int indent ) { if ( indent < 0 ) indent = 0; @@ -148,7 +156,7 @@ int QwtTextLabel::margin() const Set label's margin in pixels \param margin Margin in pixels */ -void QwtTextLabel::setMargin(int margin) +void QwtTextLabel::setMargin( int margin ) { d_data->margin = margin; @@ -165,16 +173,17 @@ QSize QwtTextLabel::sizeHint() const //! Return a minimum size hint QSize QwtTextLabel::minimumSizeHint() const { - QSize sz = d_data->text.textSize(font()); + QSizeF sz = d_data->text.textSize( font() ); - int mw = 2 * (frameWidth() + d_data->margin); + int mw = 2 * ( frameWidth() + d_data->margin ); int mh = mw; int indent = d_data->indent; if ( indent <= 0 ) indent = defaultIndent(); - if ( indent > 0 ) { + if ( indent > 0 ) + { const int align = d_data->text.renderFlags(); if ( align & Qt::AlignLeft || align & Qt::AlignRight ) mw += d_data->indent; @@ -182,16 +191,16 @@ QSize QwtTextLabel::minimumSizeHint() const mh += d_data->indent; } - sz += QSize(mw, mh); + sz += QSizeF( mw, mh ); - return sz; + return QSize( qCeil( sz.width() ), qCeil( sz.height() ) ); } /*! - Returns the preferred height for this widget, given the width. \param width Width + \return Preferred height for this widget, given the width. */ -int QwtTextLabel::heightForWidth(int width) const +int QwtTextLabel::heightForWidth( int width ) const { const int renderFlags = d_data->text.renderFlags(); @@ -203,8 +212,8 @@ int QwtTextLabel::heightForWidth(int width) const if ( renderFlags & Qt::AlignLeft || renderFlags & Qt::AlignRight ) width -= indent; - int height = d_data->text.heightForWidth(width, font()); - if ( renderFlags & Qt::AlignTop || renderFlags & Qt::AlignBottom ) + int height = qCeil( d_data->text.heightForWidth( width, font() ) ); + if ( ( renderFlags & Qt::AlignTop ) || ( renderFlags & Qt::AlignBottom ) ) height += indent; height += 2 * frameWidth(); @@ -212,91 +221,87 @@ int QwtTextLabel::heightForWidth(int width) const return height; } -//! Qt paint event -void QwtTextLabel::paintEvent(QPaintEvent *event) +/*! + Qt paint event + \param event Paint event +*/ +void QwtTextLabel::paintEvent( QPaintEvent *event ) { -#if QT_VERSION >= 0x040000 - QPainter painter(this); + QPainter painter( this ); - if ( !contentsRect().contains( event->rect() ) ) { + if ( !contentsRect().contains( event->rect() ) ) + { painter.save(); painter.setClipRegion( event->region() & frameRect() ); drawFrame( &painter ); painter.restore(); } - painter.setClipRegion(event->region() & contentsRect()); + painter.setClipRegion( event->region() & contentsRect() ); drawContents( &painter ); -#else // QT_VERSION < 0x040000 - QFrame::paintEvent(event); -#endif - } //! Redraw the text and focus indicator -void QwtTextLabel::drawContents(QPainter *painter) +void QwtTextLabel::drawContents( QPainter *painter ) { const QRect r = textRect(); if ( r.isEmpty() ) return; - painter->setFont(font()); -#if QT_VERSION < 0x040000 - painter->setPen(palette().color(QPalette::Active, QColorGroup::Text)); -#else - painter->setPen(palette().color(QPalette::Active, QPalette::Text)); -#endif + painter->setFont( font() ); + painter->setPen( palette().color( QPalette::Active, QPalette::Text ) ); - drawText(painter, r); + drawText( painter, QRectF( r ) ); - if ( hasFocus() ) { - const int margin = 2; + if ( hasFocus() ) + { + const int m = 2; - QRect focusRect = contentsRect(); - focusRect.setRect(focusRect.x() + margin, focusRect.y() + margin, - focusRect.width() - 2 * margin - 2, - focusRect.height() - 2 * margin - 2); + QRect focusRect = contentsRect().adjusted( m, m, -m + 1, -m + 1); - QwtPainter::drawFocusRect(painter, this, focusRect); + QwtPainter::drawFocusRect( painter, this, focusRect ); } } //! Redraw the text -void QwtTextLabel::drawText(QPainter *painter, const QRect &textRect) +void QwtTextLabel::drawText( QPainter *painter, const QRectF &textRect ) { - d_data->text.draw(painter, textRect); + d_data->text.draw( painter, textRect ); } /*! - Calculate the rect for the text in widget coordinates - \return Text rect + Calculate geometry for the text in widget coordinates + \return Geometry for the text */ QRect QwtTextLabel::textRect() const { QRect r = contentsRect(); - if ( !r.isEmpty() && d_data->margin > 0 ) { - r.setRect(r.x() + d_data->margin, r.y() + d_data->margin, - r.width() - 2 * d_data->margin, r.height() - 2 * d_data->margin ); + if ( !r.isEmpty() && d_data->margin > 0 ) + { + r.setRect( r.x() + d_data->margin, r.y() + d_data->margin, + r.width() - 2 * d_data->margin, r.height() - 2 * d_data->margin ); } - if ( !r.isEmpty() ) { + if ( !r.isEmpty() ) + { int indent = d_data->indent; if ( indent <= 0 ) indent = defaultIndent(); - if ( indent > 0 ) { + if ( indent > 0 ) + { const int renderFlags = d_data->text.renderFlags(); if ( renderFlags & Qt::AlignLeft ) - r.setX(r.x() + indent); + r.setX( r.x() + indent ); else if ( renderFlags & Qt::AlignRight ) - r.setWidth(r.width() - indent); + r.setWidth( r.width() - indent ); else if ( renderFlags & Qt::AlignTop ) - r.setY(r.y() + indent); + r.setY( r.y() + indent ); else if ( renderFlags & Qt::AlignBottom ) - r.setHeight(r.height() - indent); + r.setHeight( r.height() - indent ); } } @@ -309,11 +314,11 @@ int QwtTextLabel::defaultIndent() const return 0; QFont fnt; - if ( d_data->text.testPaintAttribute(QwtText::PaintUsingTextFont) ) + if ( d_data->text.testPaintAttribute( QwtText::PaintUsingTextFont ) ) fnt = d_data->text.font(); else fnt = font(); - return QFontMetrics(fnt).width('x') / 2; + return QFontMetrics( fnt ).width( 'x' ) / 2; } diff --git a/libs/qwt/qwt_text_label.h b/libs/qwt/qwt_text_label.h index ec75bb13c2..c481a24463 100644 --- a/libs/qwt/qwt_text_label.h +++ b/libs/qwt/qwt_text_label.h @@ -10,9 +10,9 @@ #ifndef QWT_TEXT_LABEL_H #define QWT_TEXT_LABEL_H -#include <qframe.h> #include "qwt_global.h" #include "qwt_text.h" +#include <qframe.h> class QString; class QPaintEvent; @@ -28,19 +28,20 @@ class QWT_EXPORT QwtTextLabel : public QFrame Q_PROPERTY( int indent READ indent WRITE setIndent ) Q_PROPERTY( int margin READ margin WRITE setMargin ) + Q_PROPERTY( QString plainText READ plainText WRITE setPlainText ) public: - explicit QwtTextLabel(QWidget *parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtTextLabel(QWidget *parent, const char *name); -#endif - explicit QwtTextLabel(const QwtText &, QWidget *parent = NULL); + explicit QwtTextLabel( QWidget *parent = NULL ); + explicit QwtTextLabel( const QwtText &, QWidget *parent = NULL ); virtual ~QwtTextLabel(); -public slots: - void setText(const QString &, - QwtText::TextFormat textFormat = QwtText::AutoText); - virtual void setText(const QwtText &); + void setPlainText( const QString & ); + QString plainText() const; + +public Q_SLOTS: + void setText( const QString &, + QwtText::TextFormat textFormat = QwtText::AutoText ); + virtual void setText( const QwtText & ); void clear(); @@ -48,21 +49,22 @@ public: const QwtText &text() const; int indent() const; - void setIndent(int); + void setIndent( int ); int margin() const; - void setMargin(int); + void setMargin( int ); virtual QSize sizeHint() const; virtual QSize minimumSizeHint() const; - virtual int heightForWidth(int) const; + virtual int heightForWidth( int ) const; QRect textRect() const; + virtual void drawText( QPainter *, const QRectF & ); + protected: - virtual void paintEvent(QPaintEvent *e); - virtual void drawContents(QPainter *); - virtual void drawText(QPainter *, const QRect &); + virtual void paintEvent( QPaintEvent *e ); + virtual void drawContents( QPainter * ); private: void init(); diff --git a/libs/qwt/qwt_thermo.cpp b/libs/qwt/qwt_thermo.cpp index 883ad411b4..ea641b2b2a 100644 --- a/libs/qwt/qwt_thermo.cpp +++ b/libs/qwt/qwt_thermo.cpp @@ -7,97 +7,126 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ -#include <qpainter.h> -#include <qevent.h> -#include <qstyle.h> -#include <qpixmap.h> -#include <qdrawutil.h> -#include "qwt_math.h" +#include "qwt_thermo.h" #include "qwt_scale_engine.h" #include "qwt_scale_draw.h" #include "qwt_scale_map.h" -#include "qwt_paint_buffer.h" -#include "qwt_thermo.h" +#include "qwt_color_map.h" +#include <qpainter.h> +#include <qevent.h> +#include <qdrawutil.h> +#include <qstyle.h> +#include <qstyleoption.h> +#include <qmath.h> + +static inline void qwtDrawLine( QPainter *painter, int pos, + const QColor &color, const QRect &pipeRect, const QRect &liquidRect, + Qt::Orientation orientation ) +{ + painter->setPen( color ); + if ( orientation == Qt::Horizontal ) + { + if ( pos >= liquidRect.left() && pos < liquidRect.right() ) + painter->drawLine( pos, pipeRect.top(), pos, pipeRect.bottom() ); + } + else + { + if ( pos >= liquidRect.top() && pos < liquidRect.bottom() ) + painter->drawLine( pipeRect.left(), pos, pipeRect.right(), pos ); + } +} + +QVector<double> qwtTickList( const QwtScaleDiv &scaleDiv ) +{ + QVector<double> values; + + double lowerLimit = scaleDiv.interval().minValue(); + double upperLimit = scaleDiv.interval().maxValue(); + + if ( upperLimit < lowerLimit ) + qSwap( lowerLimit, upperLimit ); + + values += lowerLimit; + + for ( int tickType = QwtScaleDiv::MinorTick; + tickType < QwtScaleDiv::NTickTypes; tickType++ ) + { + const QList<double> ticks = scaleDiv.ticks( tickType ); + + for ( int i = 0; i < ticks.count(); i++ ) + { + const double v = ticks[i]; + if ( v > lowerLimit && v < upperLimit ) + values += v; + } + } + + values += upperLimit; + + return values; +} class QwtThermo::PrivateData { public: PrivateData(): - fillBrush(Qt::black), - alarmBrush(Qt::white), - orientation(Qt::Vertical), - scalePos(QwtThermo::LeftScale), - borderWidth(2), - scaleDist(3), - thermoWidth(10), - minValue(0.0), - maxValue(1.0), - value(0.0), - alarmLevel(0.0), - alarmEnabled(false) { - map.setScaleInterval(minValue, maxValue); - } - - QwtScaleMap map; - QRect thermoRect; - QBrush fillBrush; - QBrush alarmBrush; + orientation( Qt::Vertical ), + scalePosition( QwtThermo::TrailingScale ), + spacing( 3 ), + borderWidth( 2 ), + pipeWidth( 10 ), + alarmLevel( 0.0 ), + alarmEnabled( false ), + autoFillPipe( true ), + originMode( QwtThermo::OriginMinimum ), + origin( 0.0 ), + colorMap( NULL ), + value( 0.0 ) + { + rangeFlags = QwtInterval::IncludeBorders; + } + + ~PrivateData() + { + delete colorMap; + } Qt::Orientation orientation; - ScalePos scalePos; + QwtThermo::ScalePosition scalePosition; + + int spacing; int borderWidth; - int scaleDist; - int thermoWidth; + int pipeWidth; - double minValue; - double maxValue; - double value; + QwtInterval::BorderFlags rangeFlags; double alarmLevel; bool alarmEnabled; -}; + bool autoFillPipe; + QwtThermo::OriginMode originMode; + double origin; -/*! - Constructor - \param parent Parent widget -*/ -QwtThermo::QwtThermo(QWidget *parent): - QWidget(parent) -{ - initThermo(); -} + QwtColorMap *colorMap; + + double value; +}; -#if QT_VERSION < 0x040000 /*! Constructor \param parent Parent widget - \param name Object name */ -QwtThermo::QwtThermo(QWidget *parent, const char *name): - QWidget(parent, name) +QwtThermo::QwtThermo( QWidget *parent ): + QwtAbstractScale( parent ) { - initThermo(); -} -#endif - -void QwtThermo::initThermo() -{ -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#endif d_data = new PrivateData; - setRange(d_data->minValue, d_data->maxValue, false); - QSizePolicy policy(QSizePolicy::MinimumExpanding, QSizePolicy::Fixed); - if (d_data->orientation == Qt::Vertical) + QSizePolicy policy( QSizePolicy::MinimumExpanding, QSizePolicy::Fixed ); + if ( d_data->orientation == Qt::Vertical ) policy.transpose(); - setSizePolicy(policy); + setSizePolicy( policy ); -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); + layoutThermo( true ); } //! Destructor @@ -106,35 +135,50 @@ QwtThermo::~QwtThermo() delete d_data; } -//! Set the maximum value. -void QwtThermo::setMaxValue(double v) -{ - setRange(d_data->minValue, v); -} +/*! + \brief Exclude/Include min/max values -//! Return the maximum value. -double QwtThermo::maxValue() const -{ - return d_data->maxValue; -} + According to the flags minValue() and maxValue() + are included/excluded from the pipe. In case of an + excluded value the corresponding tick is painted + 1 pixel off of the pipeRect(). -//! Set the minimum value. -void QwtThermo::setMinValue(double v) + F.e. when a minimum + of 0.0 has to be displayed as an empty pipe the minValue() + needs to be excluded. + + \param flags Range flags + \sa rangeFlags() +*/ +void QwtThermo::setRangeFlags( QwtInterval::BorderFlags flags ) { - setRange(v, d_data->maxValue); + if ( d_data->rangeFlags != flags ) + { + d_data->rangeFlags = flags; + update(); + } } -//! Return the minimum value. -double QwtThermo::minValue() const +/*! + \return Range flags + \sa setRangeFlags() +*/ +QwtInterval::BorderFlags QwtThermo::rangeFlags() const { - return d_data->minValue; + return d_data->rangeFlags; } -//! Set the current value. -void QwtThermo::setValue(double v) +/*! + Set the current value. + + \param value New Value + \sa value() +*/ +void QwtThermo::setValue( double value ) { - if (d_data->value != v) { - d_data->value = v; + if ( d_data->value != value ) + { + d_data->value = value; update(); } } @@ -153,12 +197,12 @@ double QwtThermo::value() const overload QwtScaleDraw::label(). \param scaleDraw ScaleDraw object, that has to be created with - new and will be deleted in ~QwtThermo or the next + new and will be deleted in ~QwtThermo() or the next call of setScaleDraw(). */ -void QwtThermo::setScaleDraw(QwtScaleDraw *scaleDraw) +void QwtThermo::setScaleDraw( QwtScaleDraw *scaleDraw ) { - setAbstractScaleDraw(scaleDraw); + setAbstractScaleDraw( scaleDraw ); } /*! @@ -167,7 +211,7 @@ void QwtThermo::setScaleDraw(QwtScaleDraw *scaleDraw) */ const QwtScaleDraw *QwtThermo::scaleDraw() const { - return (QwtScaleDraw *)abstractScaleDraw(); + return static_cast<const QwtScaleDraw *>( abstractScaleDraw() ); } /*! @@ -176,576 +220,615 @@ const QwtScaleDraw *QwtThermo::scaleDraw() const */ QwtScaleDraw *QwtThermo::scaleDraw() { - return (QwtScaleDraw *)abstractScaleDraw(); + return static_cast<QwtScaleDraw *>( abstractScaleDraw() ); } -//! Qt paint event. -void QwtThermo::paintEvent(QPaintEvent *e) +/*! + Paint event handler + \param event Paint event +*/ +void QwtThermo::paintEvent( QPaintEvent *event ) { - // Use double-buffering - const QRect &ur = e->rect(); - if ( ur.isValid() ) { -#if QT_VERSION < 0x040000 - QwtPaintBuffer paintBuffer(this, ur); - draw(paintBuffer.painter(), ur); -#else - QPainter painter(this); - draw(&painter, ur); -#endif - } -} + QPainter painter( this ); + painter.setClipRegion( event->region() ); -//! Draw the whole QwtThermo. -void QwtThermo::draw(QPainter *p, const QRect& ur) -{ - if ( !d_data->thermoRect.contains(ur) ) { - if (d_data->scalePos != NoScale) { -#if QT_VERSION < 0x040000 - scaleDraw()->draw(p, colorGroup()); -#else - scaleDraw()->draw(p, palette()); -#endif - } + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); - qDrawShadePanel(p, - d_data->thermoRect.x() - d_data->borderWidth, - d_data->thermoRect.y() - d_data->borderWidth, - d_data->thermoRect.width() + 2*d_data->borderWidth, - d_data->thermoRect.height() + 2*d_data->borderWidth, -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - true, d_data->borderWidth,0); + const QRect tRect = pipeRect(); + + if ( !tRect.contains( event->rect() ) ) + { + if ( d_data->scalePosition != QwtThermo::NoScale ) + scaleDraw()->draw( &painter, palette() ); } - drawThermo(p); + + const int bw = d_data->borderWidth; + + const QBrush brush = palette().brush( QPalette::Base ); + qDrawShadePanel( &painter, + tRect.adjusted( -bw, -bw, bw, bw ), + palette(), true, bw, + d_data->autoFillPipe ? &brush : NULL ); + + drawLiquid( &painter, tRect ); } -//! Qt resize event handler -void QwtThermo::resizeEvent(QResizeEvent *) +/*! + Resize event handler + \param event Resize event +*/ +void QwtThermo::resizeEvent( QResizeEvent *event ) { + Q_UNUSED( event ); layoutThermo( false ); } +/*! + Qt change event handler + \param event Event +*/ +void QwtThermo::changeEvent( QEvent *event ) +{ + switch( event->type() ) + { + case QEvent::StyleChange: + case QEvent::FontChange: + { + layoutThermo( true ); + break; + } + default: + break; + } +} + /*! Recalculate the QwtThermo geometry and layout based on - the QwtThermo::rect() and the fonts. + pipeRect() and the fonts. + \param update_geometry notify the layout system and call update to redraw the scale */ void QwtThermo::layoutThermo( bool update_geometry ) { - QRect r = rect(); - int mbd = 0; - if ( d_data->scalePos != NoScale ) { - int d1, d2; - scaleDraw()->getBorderDistHint(font(), d1, d2); - mbd = qwtMax(d1, d2); - } - - if ( d_data->orientation == Qt::Horizontal ) { - switch ( d_data->scalePos ) { - case TopScale: { - d_data->thermoRect.setRect( - r.x() + mbd + d_data->borderWidth, - r.y() + r.height() - - d_data->thermoWidth - 2*d_data->borderWidth, - r.width() - 2*(d_data->borderWidth + mbd), - d_data->thermoWidth); - scaleDraw()->setAlignment(QwtScaleDraw::TopScale); - scaleDraw()->move( d_data->thermoRect.x(), - d_data->thermoRect.y() - d_data->borderWidth - - d_data->scaleDist); - scaleDraw()->setLength(d_data->thermoRect.width()); - break; + const QRect tRect = pipeRect(); + const int bw = d_data->borderWidth + d_data->spacing; + const bool inverted = ( upperBound() < lowerBound() ); + + int from, to; + + if ( d_data->orientation == Qt::Horizontal ) + { + from = tRect.left(); + to = tRect.right(); + + if ( d_data->rangeFlags & QwtInterval::ExcludeMinimum ) + { + if ( inverted ) + to++; + else + from--; + } + if ( d_data->rangeFlags & QwtInterval::ExcludeMaximum ) + { + if ( inverted ) + from--; + else + to++; } - case BottomScale: - case NoScale: // like Bottom but without scale - default: // inconsistent orientation and scale position - // Mapping between values and pixels requires - // initialization of the scale geometry + if ( d_data->scalePosition == QwtThermo::TrailingScale ) { - d_data->thermoRect.setRect( - r.x() + mbd + d_data->borderWidth, - r.y() + d_data->borderWidth, - r.width() - 2*(d_data->borderWidth + mbd), - d_data->thermoWidth); - scaleDraw()->setAlignment(QwtScaleDraw::BottomScale); - scaleDraw()->move( - d_data->thermoRect.x(), - d_data->thermoRect.y() + d_data->thermoRect.height() - + d_data->borderWidth + d_data->scaleDist ); - scaleDraw()->setLength(d_data->thermoRect.width()); - break; + scaleDraw()->setAlignment( QwtScaleDraw::TopScale ); + scaleDraw()->move( from, tRect.top() - bw ); + } + else + { + scaleDraw()->setAlignment( QwtScaleDraw::BottomScale ); + scaleDraw()->move( from, tRect.bottom() + bw ); } + + scaleDraw()->setLength( to - from ); + } + else // Qt::Vertical + { + from = tRect.top(); + to = tRect.bottom(); + + if ( d_data->rangeFlags & QwtInterval::ExcludeMinimum ) + { + if ( inverted ) + from--; + else + to++; } - d_data->map.setPaintInterval(d_data->thermoRect.x(), - d_data->thermoRect.x() + d_data->thermoRect.width() - 1); - } else { // Qt::Vertical - switch ( d_data->scalePos ) { - case RightScale: { - d_data->thermoRect.setRect( - r.x() + d_data->borderWidth, - r.y() + mbd + d_data->borderWidth, - d_data->thermoWidth, - r.height() - 2*(d_data->borderWidth + mbd)); - scaleDraw()->setAlignment(QwtScaleDraw::RightScale); - scaleDraw()->move( - d_data->thermoRect.x() + d_data->thermoRect.width() - + d_data->borderWidth + d_data->scaleDist, - d_data->thermoRect.y()); - scaleDraw()->setLength(d_data->thermoRect.height()); - break; + if ( d_data->rangeFlags & QwtInterval::ExcludeMaximum ) + { + if ( inverted ) + to++; + else + from--; } - case LeftScale: - case NoScale: // like Left but without scale - default: // inconsistent orientation and scale position - // Mapping between values and pixels requires - // initialization of the scale geometry + if ( d_data->scalePosition == QwtThermo::LeadingScale ) { - d_data->thermoRect.setRect( - r.x() + r.width() - 2*d_data->borderWidth - d_data->thermoWidth, - r.y() + mbd + d_data->borderWidth, - d_data->thermoWidth, - r.height() - 2*(d_data->borderWidth + mbd)); - scaleDraw()->setAlignment(QwtScaleDraw::LeftScale); - scaleDraw()->move( - d_data->thermoRect.x() - d_data->scaleDist - - d_data->borderWidth, - d_data->thermoRect.y() ); - scaleDraw()->setLength(d_data->thermoRect.height()); - break; + scaleDraw()->setAlignment( QwtScaleDraw::RightScale ); + scaleDraw()->move( tRect.right() + bw, from ); } + else + { + scaleDraw()->setAlignment( QwtScaleDraw::LeftScale ); + scaleDraw()->move( tRect.left() - bw, from ); } - d_data->map.setPaintInterval( - d_data->thermoRect.y() + d_data->thermoRect.height() - 1, - d_data->thermoRect.y()); + + scaleDraw()->setLength( to - from ); } - if ( update_geometry ) { + + if ( update_geometry ) + { updateGeometry(); update(); } } /*! - \brief Set the thermometer orientation and the scale position. + \return Bounding rectangle of the pipe ( without borders ) + in widget coordinates +*/ +QRect QwtThermo::pipeRect() const +{ + int mbd = 0; + if ( d_data->scalePosition != QwtThermo::NoScale ) + { + int d1, d2; + scaleDraw()->getBorderDistHint( font(), d1, d2 ); + mbd = qMax( d1, d2 ); + } + const int bw = d_data->borderWidth; + const int scaleOff = bw + mbd; - The scale position NoScale disables the scale. - \param o orientation. Possible values are Qt::Horizontal and Qt::Vertical. - The default value is Qt::Vertical. - \param s Position of the scale. - The default value is NoScale. + const QRect cr = contentsRect(); - A valid combination of scale position and orientation is enforced: - - a horizontal thermometer can have the scale positions TopScale, - BottomScale or NoScale; - - a vertical thermometer can have the scale positions LeftScale, - RightScale or NoScale; - - an invalid scale position will default to NoScale. + QRect pipeRect = cr; + if ( d_data->orientation == Qt::Horizontal ) + { + pipeRect.adjust( scaleOff, 0, -scaleOff, 0 ); - \sa QwtThermo::setScalePosition() + if ( d_data->scalePosition == QwtThermo::TrailingScale ) + pipeRect.setTop( cr.top() + cr.height() - bw - d_data->pipeWidth ); + else + pipeRect.setTop( bw ); + + pipeRect.setHeight( d_data->pipeWidth ); + } + else // Qt::Vertical + { + pipeRect.adjust( 0, scaleOff, 0, -scaleOff ); + + if ( d_data->scalePosition == QwtThermo::LeadingScale ) + pipeRect.setLeft( bw ); + else + pipeRect.setLeft( cr.left() + cr.width() - bw - d_data->pipeWidth ); + + pipeRect.setWidth( d_data->pipeWidth ); + } + + return pipeRect; +} + +/*! + \brief Set the orientation. + \param orientation Allowed values are Qt::Horizontal and Qt::Vertical. + + \sa orientation(), scalePosition() */ -void QwtThermo::setOrientation(Qt::Orientation o, ScalePos s) +void QwtThermo::setOrientation( Qt::Orientation orientation ) { - if ( o == d_data->orientation && s == d_data->scalePos ) + if ( orientation == d_data->orientation ) return; - switch(o) { - case Qt::Horizontal: { - if ((s == NoScale) || (s == BottomScale) || (s == TopScale)) - d_data->scalePos = s; - else - d_data->scalePos = NoScale; - break; - } - case Qt::Vertical: { - if ((s == NoScale) || (s == LeftScale) || (s == RightScale)) - d_data->scalePos = s; - else - d_data->scalePos = NoScale; - break; - } - } + d_data->orientation = orientation; - if ( o != d_data->orientation ) { -#if QT_VERSION >= 0x040000 - if ( !testAttribute(Qt::WA_WState_OwnSizePolicy) ) -#else - if ( !testWState( WState_OwnSizePolicy ) ) -#endif - { - QSizePolicy sp = sizePolicy(); - sp.transpose(); - setSizePolicy(sp); - -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif - } + if ( !testAttribute( Qt::WA_WState_OwnSizePolicy ) ) + { + QSizePolicy sp = sizePolicy(); + sp.transpose(); + setSizePolicy( sp ); + + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); } - d_data->orientation = o; - layoutThermo(); + layoutThermo( true ); } /*! - \brief Change the scale position (and thermometer orientation). + \return Orientation + \sa setOrientation() +*/ +Qt::Orientation QwtThermo::orientation() const +{ + return d_data->orientation; +} - \param s Position of the scale. +/*! + \brief Change how the origin is determined. + \sa originMode(), serOrigin(), origin() + */ +void QwtThermo::setOriginMode( OriginMode m ) +{ + if ( m == d_data->originMode ) + return; - A valid combination of scale position and orientation is enforced: - - if the new scale position is LeftScale or RightScale, the - scale orientation will become Qt::Vertical; - - if the new scale position is BottomScale or TopScale, the scale - orientation will become Qt::Horizontal; - - if the new scale position is NoScale, the scale orientation will not change. + d_data->originMode = m; + update(); +} - \sa QwtThermo::setOrientation() -*/ -void QwtThermo::setScalePosition(ScalePos s) +/*! + \return Mode, how the origin is determined. + \sa setOriginMode(), serOrigin(), origin() + */ +QwtThermo::OriginMode QwtThermo::originMode() const { - if ((s == BottomScale) || (s == TopScale)) - setOrientation(Qt::Horizontal, s); - else if ((s == LeftScale) || (s == RightScale)) - setOrientation(Qt::Vertical, s); - else - setOrientation(d_data->orientation, NoScale); + return d_data->originMode; } -//! Return the scale position. -QwtThermo::ScalePos QwtThermo::scalePosition() const +/*! + \brief Specifies the custom origin. + + If originMode is set to OriginCustom this property controls where the + liquid starts. + + \param origin New origin level + \sa setOriginMode(), originMode(), origin() + */ +void QwtThermo::setOrigin( double origin ) { - return d_data->scalePos; + if ( origin == d_data->origin ) + return; + + d_data->origin = origin; + update(); +} + +/*! + \return Origin of the thermo, when OriginCustom is enabled + \sa setOrigin(), setOriginMode(), originMode() + */ +double QwtThermo::origin() const +{ + return d_data->origin; +} + +/*! + \brief Change the position of the scale + \param scalePosition Position of the scale. + + \sa ScalePosition, scalePosition() +*/ +void QwtThermo::setScalePosition( ScalePosition scalePosition ) +{ + if ( d_data->scalePosition == scalePosition ) + return; + + d_data->scalePosition = scalePosition; + + if ( testAttribute( Qt::WA_WState_Polished ) ) + layoutThermo( true ); } -//! Notify a font change. -void QwtThermo::fontChange(const QFont &f) +/*! + \return Scale position. + \sa setScalePosition() +*/ +QwtThermo::ScalePosition QwtThermo::scalePosition() const { - QWidget::fontChange( f ); - layoutThermo(); + return d_data->scalePosition; } //! Notify a scale change. void QwtThermo::scaleChange() { - update(); - layoutThermo(); + layoutThermo( true ); } -//! Redraw the liquid in thermometer pipe. -void QwtThermo::drawThermo(QPainter *p) +/*! + Redraw the liquid in thermometer pipe. + \param painter Painter + \param pipeRect Bounding rectangle of the pipe without borders +*/ +void QwtThermo::drawLiquid( + QPainter *painter, const QRect &pipeRect ) const { - int alarm = 0, taval = 0; + painter->save(); + painter->setClipRect( pipeRect, Qt::IntersectClip ); + painter->setPen( Qt::NoPen ); - QRect fRect; - QRect aRect; - QRect bRect; + const QwtScaleMap scaleMap = scaleDraw()->scaleMap(); - int inverted = ( d_data->maxValue < d_data->minValue ); + QRect liquidRect = fillRect( pipeRect ); - // - // Determine if value exceeds alarm threshold. - // Note: The alarm value is allowed to lie - // outside the interval (minValue, maxValue). - // - if (d_data->alarmEnabled) { - if (inverted) { - alarm = ((d_data->alarmLevel >= d_data->maxValue) - && (d_data->alarmLevel <= d_data->minValue) - && (d_data->value >= d_data->alarmLevel)); + if ( d_data->colorMap != NULL ) + { + const QwtInterval interval = scaleDiv().interval().normalized(); - } else { - alarm = (( d_data->alarmLevel >= d_data->minValue) - && (d_data->alarmLevel <= d_data->maxValue) - && (d_data->value >= d_data->alarmLevel)); - } - } + // Because the positions of the ticks are rounded + // we calculate the colors for the rounded tick values - // - // transform values - // - int tval = transform(d_data->value); - - if (alarm) - taval = transform(d_data->alarmLevel); - - // - // calculate recangles - // - if ( d_data->orientation == Qt::Horizontal ) { - if (inverted) { - bRect.setRect(d_data->thermoRect.x(), d_data->thermoRect.y(), - tval - d_data->thermoRect.x(), - d_data->thermoRect.height()); - - if (alarm) { - aRect.setRect(tval, d_data->thermoRect.y(), - taval - tval + 1, - d_data->thermoRect.height()); - fRect.setRect(taval + 1, d_data->thermoRect.y(), - d_data->thermoRect.x() + d_data->thermoRect.width() - (taval + 1), - d_data->thermoRect.height()); - } else { - fRect.setRect(tval, d_data->thermoRect.y(), - d_data->thermoRect.x() + d_data->thermoRect.width() - tval, - d_data->thermoRect.height()); - } - } else { - bRect.setRect(tval + 1, d_data->thermoRect.y(), - d_data->thermoRect.width() - (tval + 1 - d_data->thermoRect.x()), - d_data->thermoRect.height()); - - if (alarm) { - aRect.setRect(taval, d_data->thermoRect.y(), - tval - taval + 1, - d_data->thermoRect.height()); - fRect.setRect(d_data->thermoRect.x(), d_data->thermoRect.y(), - taval - d_data->thermoRect.x(), - d_data->thermoRect.height()); - } else { - fRect.setRect(d_data->thermoRect.x(), d_data->thermoRect.y(), - tval - d_data->thermoRect.x() + 1, - d_data->thermoRect.height()); - } + QVector<double> values = qwtTickList( scaleDraw()->scaleDiv() ); - } - } else { // Qt::Vertical - if (tval < d_data->thermoRect.y()) - tval = d_data->thermoRect.y(); - else { - if (tval > d_data->thermoRect.y() + d_data->thermoRect.height()) - tval = d_data->thermoRect.y() + d_data->thermoRect.height(); + if ( scaleMap.isInverting() ) + qSort( values.begin(), values.end(), qGreater<double>() ); + else + qSort( values.begin(), values.end(), qLess<double>() ); + + int from; + if ( !values.isEmpty() ) + { + from = qRound( scaleMap.transform( values[0] ) ); + qwtDrawLine( painter, from, + d_data->colorMap->color( interval, values[0] ), + pipeRect, liquidRect, d_data->orientation ); } - if (inverted) { - bRect.setRect(d_data->thermoRect.x(), tval + 1, - d_data->thermoRect.width(), - d_data->thermoRect.height() - (tval + 1 - d_data->thermoRect.y())); - - if (alarm) { - aRect.setRect(d_data->thermoRect.x(), taval, - d_data->thermoRect.width(), - tval - taval + 1); - fRect.setRect(d_data->thermoRect.x(), d_data->thermoRect.y(), - d_data->thermoRect.width(), - taval - d_data->thermoRect.y()); - } else { - fRect.setRect(d_data->thermoRect.x(), d_data->thermoRect.y(), - d_data->thermoRect.width(), - tval - d_data->thermoRect.y() + 1); + for ( int i = 1; i < values.size(); i++ ) + { + const int to = qRound( scaleMap.transform( values[i] ) ); + + for ( int pos = from + 1; pos < to; pos++ ) + { + const double v = scaleMap.invTransform( pos ); + + qwtDrawLine( painter, pos, + d_data->colorMap->color( interval, v ), + pipeRect, liquidRect, d_data->orientation ); } - } else { - bRect.setRect(d_data->thermoRect.x(), d_data->thermoRect.y(), - d_data->thermoRect.width(), - tval - d_data->thermoRect.y()); - if (alarm) { - aRect.setRect(d_data->thermoRect.x(),tval, - d_data->thermoRect.width(), - taval - tval + 1); - fRect.setRect(d_data->thermoRect.x(),taval + 1, - d_data->thermoRect.width(), - d_data->thermoRect.y() + d_data->thermoRect.height() - (taval + 1)); - } else { - fRect.setRect(d_data->thermoRect.x(),tval, - d_data->thermoRect.width(), - d_data->thermoRect.y() + d_data->thermoRect.height() - tval); + + qwtDrawLine( painter, to, + d_data->colorMap->color( interval, values[i] ), + pipeRect, liquidRect, d_data->orientation ); + + from = to; + } + } + else + { + if ( !liquidRect.isEmpty() && d_data->alarmEnabled ) + { + const QRect r = alarmRect( liquidRect ); + if ( !r.isEmpty() ) + { + painter->fillRect( r, palette().brush( QPalette::Highlight ) ); + liquidRect = QRegion( liquidRect ).subtracted( r ).boundingRect(); } } + + painter->fillRect( liquidRect, palette().brush( QPalette::ButtonText ) ); } - // - // paint thermometer - // - const QColor bgColor = -#if QT_VERSION < 0x040000 - colorGroup().color(QColorGroup::Background); -#else - palette().color(QPalette::Background); -#endif - p->fillRect(bRect, bgColor); + painter->restore(); +} - if (alarm) - p->fillRect(aRect, d_data->alarmBrush); +/*! + \brief Change the spacing between pipe and scale - p->fillRect(fRect, d_data->fillBrush); -} + A spacing of 0 means, that the backbone of the scale is below + the pipe. + + The default setting is 3 pixels. -//! Set the border width of the pipe. -void QwtThermo::setBorderWidth(int w) + \param spacing Number of pixels + \sa spacing(); +*/ +void QwtThermo::setSpacing( int spacing ) { - if ((w >= 0) && (w < (qwtMin(d_data->thermoRect.width(), - d_data->thermoRect.height()) + d_data->borderWidth) / 2 - 1)) { - d_data->borderWidth = w; - layoutThermo(); + if ( spacing <= 0 ) + spacing = 0; + + if ( spacing != d_data->spacing ) + { + d_data->spacing = spacing; + layoutThermo( true ); } } -//! Return the border width of the thermometer pipe. -int QwtThermo::borderWidth() const +/*! + \return Number of pixels between pipe and scale + \sa setSpacing() +*/ +int QwtThermo::spacing() const { - return d_data->borderWidth; + return d_data->spacing; } /*! - \brief Set the range - \param vmin value corresponding lower or left end of the thermometer - \param vmax value corresponding to the upper or right end of the thermometer - \param logarithmic logarithmic mapping, true or false + Set the border width of the pipe. + \param width Border width + \sa borderWidth() */ -void QwtThermo::setRange(double vmin, double vmax, bool logarithmic) +void QwtThermo::setBorderWidth( int width ) { - d_data->minValue = vmin; - d_data->maxValue = vmax; - - if ( logarithmic ) - setScaleEngine(new QwtLog10ScaleEngine); - else - setScaleEngine(new QwtLinearScaleEngine); - - /* - There are two different maps, one for the scale, the other - for the values. This is confusing and will be changed - in the future. TODO ... - */ + if ( width <= 0 ) + width = 0; - d_data->map.setTransformation(scaleEngine()->transformation()); - d_data->map.setScaleInterval(d_data->minValue, d_data->maxValue); - - if (autoScale()) - rescale(d_data->minValue, d_data->maxValue); - - layoutThermo(); + if ( width != d_data->borderWidth ) + { + d_data->borderWidth = width; + layoutThermo( true ); + } } /*! - \brief Change the brush of the liquid. - \param brush New brush. The default brush is solid black. + \return Border width of the thermometer pipe. + \sa setBorderWidth() */ -void QwtThermo::setFillBrush(const QBrush& brush) +int QwtThermo::borderWidth() const { - d_data->fillBrush = brush; - update(); + return d_data->borderWidth; } -//! Return the liquid brush. -const QBrush& QwtThermo::fillBrush() const +/*! + \brief Assign a color map for the fill color + + \param colorMap Color map + \warning The alarm threshold has no effect, when + a color map has been assigned +*/ +void QwtThermo::setColorMap( QwtColorMap *colorMap ) { - return d_data->fillBrush; + if ( colorMap != d_data->colorMap ) + { + delete d_data->colorMap; + d_data->colorMap = colorMap; + } } /*! - \brief Change the color of the liquid. - \param c New color. The default color is black. + \return Color map for the fill color + \warning The alarm threshold has no effect, when + a color map has been assigned */ -void QwtThermo::setFillColor(const QColor &c) +QwtColorMap *QwtThermo::colorMap() { - d_data->fillBrush.setColor(c); - update(); + return d_data->colorMap; } -//! Return the liquid color. -const QColor &QwtThermo::fillColor() const +/*! + \return Color map for the fill color + \warning The alarm threshold has no effect, when + a color map has been assigned +*/ +const QwtColorMap *QwtThermo::colorMap() const { - return d_data->fillBrush.color(); + return d_data->colorMap; } /*! - \brief Specify the liquid brush above the alarm threshold - \param brush New brush. The default is solid white. + \brief Change the brush of the liquid. + + Changes the QPalette::ButtonText brush of the palette. + + \param brush New brush. + \sa fillBrush(), QWidget::setPalette() */ -void QwtThermo::setAlarmBrush(const QBrush& brush) +void QwtThermo::setFillBrush( const QBrush& brush ) { - d_data->alarmBrush = brush; - update(); + QPalette pal = palette(); + pal.setBrush( QPalette::ButtonText, brush ); + setPalette( pal ); } -//! Return the liquid brush above the alarm threshold. -const QBrush& QwtThermo::alarmBrush() const +/*! + \return Liquid ( QPalette::ButtonText ) brush. + \sa setFillBrush(), QWidget::palette() +*/ +QBrush QwtThermo::fillBrush() const { - return d_data->alarmBrush; + return palette().brush( QPalette::ButtonText ); } /*! - \brief Specify the liquid color above the alarm threshold - \param c New color. The default is white. + \brief Specify the liquid brush above the alarm threshold + + Changes the QPalette::Highlight brush of the palette. + + \param brush New brush. + \sa alarmBrush(), QWidget::setPalette() + + \warning The alarm threshold has no effect, when + a color map has been assigned */ -void QwtThermo::setAlarmColor(const QColor &c) +void QwtThermo::setAlarmBrush( const QBrush& brush ) { - d_data->alarmBrush.setColor(c); - update(); + QPalette pal = palette(); + pal.setBrush( QPalette::Highlight, brush ); + setPalette( pal ); } -//! Return the liquid color above the alarm threshold. -const QColor &QwtThermo::alarmColor() const +/*! + \return Liquid brush ( QPalette::Highlight ) above the alarm threshold. + \sa setAlarmBrush(), QWidget::palette() + + \warning The alarm threshold has no effect, when + a color map has been assigned +*/ +QBrush QwtThermo::alarmBrush() const { - return d_data->alarmBrush.color(); + return palette().brush( QPalette::Highlight ); } -//! Specify the alarm threshold. -void QwtThermo::setAlarmLevel(double v) +/*! + Specify the alarm threshold. + + \param level Alarm threshold + \sa alarmLevel() + + \warning The alarm threshold has no effect, when + a color map has been assigned +*/ +void QwtThermo::setAlarmLevel( double level ) { - d_data->alarmLevel = v; + d_data->alarmLevel = level; d_data->alarmEnabled = 1; update(); } -//! Return the alarm threshold. +/*! + \return Alarm threshold. + \sa setAlarmLevel() + + \warning The alarm threshold has no effect, when + a color map has been assigned +*/ double QwtThermo::alarmLevel() const { return d_data->alarmLevel; } -//! Change the width of the pipe. -void QwtThermo::setPipeWidth(int w) -{ - if (w > 0) { - d_data->thermoWidth = w; - layoutThermo(); - } -} +/*! + Change the width of the pipe. -//! Return the width of the pipe. -int QwtThermo::pipeWidth() const + \param width Width of the pipe + \sa pipeWidth() +*/ +void QwtThermo::setPipeWidth( int width ) { - return d_data->thermoWidth; + if ( width > 0 ) + { + d_data->pipeWidth = width; + layoutThermo( true ); + } } - /*! - \brief Specify the distance between the pipe's endpoints - and the widget's border - - The margin is used to leave some space for the scale - labels. If a large font is used, it is advisable to - adjust the margins. - \param m New Margin. The default values are 10 for - horizontal orientation and 20 for vertical - orientation. - \warning The margin has no effect if the scale is disabled. - \warning This function is a NOOP because margins are determined - automatically. + \return Width of the pipe. + \sa setPipeWidth() */ -void QwtThermo::setMargin(int) +int QwtThermo::pipeWidth() const { + return d_data->pipeWidth; } - /*! \brief Enable or disable the alarm threshold - \param tf true (disabled) or false (enabled) + \param on true (disabled) or false (enabled) + + \warning The alarm threshold has no effect, when + a color map has been assigned */ -void QwtThermo::setAlarmEnabled(bool tf) +void QwtThermo::setAlarmEnabled( bool on ) { - d_data->alarmEnabled = tf; + d_data->alarmEnabled = on; update(); } -//! Return if the alarm threshold is enabled or disabled. +/*! + \return True, when the alarm threshold is enabled. + + \warning The alarm threshold has no effect, when + a color map has been assigned +*/ bool QwtThermo::alarmEnabled() const { return d_data->alarmEnabled; @@ -753,7 +836,7 @@ bool QwtThermo::alarmEnabled() const /*! \return the minimum size hint - \sa QwtThermo::minimumSizeHint + \sa minimumSizeHint() */ QSize QwtThermo::sizeHint() const { @@ -761,45 +844,161 @@ QSize QwtThermo::sizeHint() const } /*! - \brief Return a minimum size hint + \return Minimum size hint \warning The return value depends on the font and the scale. - \sa QwtThermo::sizeHint + \sa sizeHint() */ QSize QwtThermo::minimumSizeHint() const { int w = 0, h = 0; - if ( d_data->scalePos != NoScale ) { - const int sdExtent = scaleDraw()->extent( QPen(), font() ); - const int sdLength = scaleDraw()->minLength( QPen(), font() ); + if ( d_data->scalePosition != NoScale ) + { + const int sdExtent = qCeil( scaleDraw()->extent( font() ) ); + const int sdLength = scaleDraw()->minLength( font() ); w = sdLength; - h = d_data->thermoWidth + sdExtent + - d_data->borderWidth + d_data->scaleDist; + h = d_data->pipeWidth + sdExtent + d_data->spacing; - } else { // no scale + } + else // no scale + { w = 200; - h = d_data->thermoWidth; + h = d_data->pipeWidth; } if ( d_data->orientation == Qt::Vertical ) - qSwap(w, h); + qSwap( w, h ); w += 2 * d_data->borderWidth; h += 2 * d_data->borderWidth; + // finally add the margins + int left, right, top, bottom; + getContentsMargins( &left, &top, &right, &bottom ); + w += left + right; + h += top + bottom; + return QSize( w, h ); } -int QwtThermo::transform(double value) const +/*! + \brief Calculate the filled rectangle of the pipe + + \param pipeRect Rectangle of the pipe + \return Rectangle to be filled ( fill and alarm brush ) + + \sa pipeRect(), alarmRect() + */ +QRect QwtThermo::fillRect( const QRect &pipeRect ) const { - const double min = qwtMin(d_data->map.s1(), d_data->map.s2()); - const double max = qwtMax(d_data->map.s1(), d_data->map.s2()); + double origin; + if ( d_data->originMode == OriginMinimum ) + { + origin = qMin( lowerBound(), upperBound() ); + } + else if ( d_data->originMode == OriginMaximum ) + { + origin = qMax( lowerBound(), upperBound() ); + } + else // OriginCustom + { + origin = d_data->origin; + } + + const QwtScaleMap scaleMap = scaleDraw()->scaleMap(); + + int from = qRound( scaleMap.transform( d_data->value ) ); + int to = qRound( scaleMap.transform( origin ) ); - if ( value > max ) - value = max; - if ( value < min ) - value = min; + if ( to < from ) + qSwap( from, to ); + + QRect fillRect = pipeRect; + if ( d_data->orientation == Qt::Horizontal ) + { + fillRect.setLeft( from ); + fillRect.setRight( to ); + } + else // Qt::Vertical + { + fillRect.setTop( from ); + fillRect.setBottom( to ); + } - return d_data->map.transform(value); + return fillRect.normalized(); } + +/*! + \brief Calculate the alarm rectangle of the pipe + + \param fillRect Filled rectangle in the pipe + \return Rectangle to be filled with the alarm brush + + \sa pipeRect(), fillRect(), alarmLevel(), alarmBrush() + */ +QRect QwtThermo::alarmRect( const QRect &fillRect ) const +{ + QRect alarmRect( 0, 0, -1, -1); // something invalid + + if ( !d_data->alarmEnabled ) + return alarmRect; + + const bool inverted = ( upperBound() < lowerBound() ); + + bool increasing; + if ( d_data->originMode == OriginCustom ) + { + increasing = d_data->value > d_data->origin; + } + else + { + increasing = d_data->originMode == OriginMinimum; + } + + const QwtScaleMap map = scaleDraw()->scaleMap(); + const int alarmPos = qRound( map.transform( d_data->alarmLevel ) ); + const int valuePos = qRound( map.transform( d_data->value ) ); + + if ( d_data->orientation == Qt::Horizontal ) + { + int v1, v2; + if ( inverted ) + { + v1 = fillRect.left(); + + v2 = alarmPos - 1; + v2 = qMin( v2, increasing ? fillRect.right() : valuePos ); + } + else + { + v1 = alarmPos + 1; + v1 = qMax( v1, increasing ? fillRect.left() : valuePos ); + + v2 = fillRect.right(); + + } + alarmRect.setRect( v1, fillRect.top(), v2 - v1 + 1, fillRect.height() ); + } + else + { + int v1, v2; + if ( inverted ) + { + v1 = alarmPos + 1; + v1 = qMax( v1, increasing ? fillRect.top() : valuePos ); + + v2 = fillRect.bottom(); + } + else + { + v1 = fillRect.top(); + + v2 = alarmPos - 1; + v2 = qMin( v2, increasing ? fillRect.bottom() : valuePos ); + } + alarmRect.setRect( fillRect.left(), v1, fillRect.width(), v2 - v1 + 1 ); + } + + return alarmRect; +} diff --git a/libs/qwt/qwt_thermo.h b/libs/qwt/qwt_thermo.h index 8d02927a8a..b9aa67d795 100644 --- a/libs/qwt/qwt_thermo.h +++ b/libs/qwt/qwt_thermo.h @@ -10,14 +10,12 @@ #ifndef QWT_THERMO_H #define QWT_THERMO_H -#include <qwidget.h> -#include <qcolor.h> -#include <qfont.h> -#include <qrect.h> #include "qwt_global.h" #include "qwt_abstract_scale.h" +#include "qwt_interval.h" class QwtScaleDraw; +class QwtColorMap; /*! \brief The Thermometer Widget @@ -30,149 +28,148 @@ class QwtScaleDraw; \image html sysinfo.png - By default, the scale and range run over the same interval of values. - QwtAbstractScale::setScale() changes the interval of the scale and allows - easy conversion between physical units. - - The example shows how to make the scale indicate in degrees Fahrenheit and - to set the value in degrees Kelvin: -\code -#include <qapplication.h> -#include <qwt_thermo.h> - -double Kelvin2Fahrenheit(double kelvin) -{ - // see http://en.wikipedia.org/wiki/Kelvin - return 1.8*kelvin - 459.67; -} - -int main(int argc, char **argv) -{ - const double minKelvin = 0.0; - const double maxKelvin = 500.0; - - QApplication a(argc, argv); - QwtThermo t; - t.setRange(minKelvin, maxKelvin); - t.setScale(Kelvin2Fahrenheit(minKelvin), Kelvin2Fahrenheit(maxKelvin)); - // set the value in Kelvin but the scale displays in Fahrenheit - // 273.15 Kelvin = 0 Celsius = 32 Fahrenheit - t.setValue(273.15); - a.setMainWidget(&t); - t.show(); - return a.exec(); -} -\endcode - - \todo Improve the support for a logarithmic range and/or scale. + The fill colors might be calculated from an optional color map + If no color map has been assigned QwtThermo uses the + following colors/brushes from the widget palette: + + - QPalette::Base + Background of the pipe + - QPalette::ButtonText + Fill brush below the alarm level + - QPalette::Highlight + Fill brush for the values above the alarm level + - QPalette::WindowText + For the axis of the scale + - QPalette::Text + For the labels of the scale */ -class QWT_EXPORT QwtThermo: public QWidget, public QwtAbstractScale +class QWT_EXPORT QwtThermo: public QwtAbstractScale { Q_OBJECT - Q_ENUMS( ScalePos ) + Q_ENUMS( ScalePosition ) + Q_ENUMS( OriginMode ) + + Q_PROPERTY( Qt::Orientation orientation + READ orientation WRITE setOrientation ) + Q_PROPERTY( ScalePosition scalePosition + READ scalePosition WRITE setScalePosition ) + Q_PROPERTY( OriginMode originMode READ originMode WRITE setOriginMode ) - Q_PROPERTY( QBrush alarmBrush READ alarmBrush WRITE setAlarmBrush ) - Q_PROPERTY( QColor alarmColor READ alarmColor WRITE setAlarmColor ) Q_PROPERTY( bool alarmEnabled READ alarmEnabled WRITE setAlarmEnabled ) Q_PROPERTY( double alarmLevel READ alarmLevel WRITE setAlarmLevel ) - Q_PROPERTY( ScalePos scalePosition READ scalePosition - WRITE setScalePosition ) + Q_PROPERTY( double origin READ origin WRITE setOrigin ) + Q_PROPERTY( int spacing READ spacing WRITE setSpacing ) Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) - Q_PROPERTY( QBrush fillBrush READ fillBrush WRITE setFillBrush ) - Q_PROPERTY( QColor fillColor READ fillColor WRITE setFillColor ) - Q_PROPERTY( double maxValue READ maxValue WRITE setMaxValue ) - Q_PROPERTY( double minValue READ minValue WRITE setMinValue ) Q_PROPERTY( int pipeWidth READ pipeWidth WRITE setPipeWidth ) Q_PROPERTY( double value READ value WRITE setValue ) public: - /* - Scale position. QwtThermo tries to enforce valid combinations of its - orientation and scale position: - - Qt::Horizonal combines with NoScale, TopScale and BottomScale - - Qt::Vertical combines with NoScale, LeftScale and RightScale - \sa setOrientation, setScalePosition - */ - enum ScalePos { + /*! + Position of the scale + \sa setScalePosition(), setOrientation() + */ + enum ScalePosition + { + //! The slider has no scale NoScale, - LeftScale, - RightScale, - TopScale, - BottomScale + + //! The scale is right of a vertical or below of a horizontal slider + LeadingScale, + + //! The scale is left of a vertical or above of a horizontal slider + TrailingScale }; - explicit QwtThermo(QWidget *parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtThermo(QWidget *parent, const char *name); -#endif + /*! + Origin mode. This property specifies where the beginning of the liquid + is placed. + + \sa setOriginMode(), setOrigin() + */ + enum OriginMode + { + //! The origin is the minimum of the scale + OriginMinimum, + + //! The origin is the maximum of the scale + OriginMaximum, + + //! The origin is specified using the origin() property + OriginCustom + }; + + explicit QwtThermo( QWidget *parent = NULL ); virtual ~QwtThermo(); - void setOrientation(Qt::Orientation o, ScalePos s); + void setOrientation( Qt::Orientation ); + Qt::Orientation orientation() const; - void setScalePosition(ScalePos s); - ScalePos scalePosition() const; + void setScalePosition( ScalePosition ); + ScalePosition scalePosition() const; - void setBorderWidth(int w); + void setSpacing( int ); + int spacing() const; + + void setBorderWidth( int w ); int borderWidth() const; - void setFillBrush(const QBrush &b); - const QBrush &fillBrush() const; + void setOriginMode( OriginMode ); + OriginMode originMode() const; - void setFillColor(const QColor &c); - const QColor &fillColor() const; + void setOrigin( double ); + double origin() const; - void setAlarmBrush(const QBrush &b); - const QBrush &alarmBrush() const; + void setFillBrush( const QBrush &b ); + QBrush fillBrush() const; - void setAlarmColor(const QColor &c); - const QColor &alarmColor() const; + void setAlarmBrush( const QBrush &b ); + QBrush alarmBrush() const; - void setAlarmLevel(double v); + void setAlarmLevel( double v ); double alarmLevel() const; - void setAlarmEnabled(bool tf); + void setAlarmEnabled( bool tf ); bool alarmEnabled() const; - void setPipeWidth(int w); - int pipeWidth() const; + void setColorMap( QwtColorMap * ); + QwtColorMap *colorMap(); + const QwtColorMap *colorMap() const; - void setMaxValue(double v); - double maxValue() const; + void setPipeWidth( int w ); + int pipeWidth() const; - void setMinValue(double v); - double minValue() const; + void setRangeFlags( QwtInterval::BorderFlags ); + QwtInterval::BorderFlags rangeFlags() const; double value() const; - void setRange(double vmin, double vmax, bool lg = false); - void setMargin(int m); - virtual QSize sizeHint() const; virtual QSize minimumSizeHint() const; - void setScaleDraw(QwtScaleDraw *); + void setScaleDraw( QwtScaleDraw * ); const QwtScaleDraw *scaleDraw() const; -public slots: - void setValue(double val); +public Q_SLOTS: + virtual void setValue( double val ); protected: - void draw(QPainter *p, const QRect& update_rect); - void drawThermo(QPainter *p); - void layoutThermo( bool update = true ); + virtual void drawLiquid( QPainter *, const QRect & ) const; virtual void scaleChange(); - virtual void fontChange(const QFont &oldFont); - virtual void paintEvent(QPaintEvent *e); - virtual void resizeEvent(QResizeEvent *e); + virtual void paintEvent( QPaintEvent * ); + virtual void resizeEvent( QResizeEvent * ); + virtual void changeEvent( QEvent * ); QwtScaleDraw *scaleDraw(); + QRect pipeRect() const; + QRect fillRect( const QRect & ) const; + QRect alarmRect( const QRect & ) const; + private: - void initThermo(); - int transform(double v) const; + void layoutThermo( bool ); class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_transform.cpp b/libs/qwt/qwt_transform.cpp new file mode 100644 index 0000000000..359fc9f9b8 --- /dev/null +++ b/libs/qwt/qwt_transform.cpp @@ -0,0 +1,165 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_transform.h" +#include "qwt_math.h" + +#if QT_VERSION < 0x040601 +#define qExp(x) ::exp(x) +#endif + +//! Smallest allowed value for logarithmic scales: 1.0e-150 +QT_STATIC_CONST_IMPL double QwtLogTransform::LogMin = 1.0e-150; + +//! Largest allowed value for logarithmic scales: 1.0e150 +QT_STATIC_CONST_IMPL double QwtLogTransform::LogMax = 1.0e150; + +//! Constructor +QwtTransform::QwtTransform() +{ +} + +//! Destructor +QwtTransform::~QwtTransform() +{ +} + +/*! + \param value Value to be bounded + \return value unmodified + */ +double QwtTransform::bounded( double value ) const +{ + return value; +} + +//! Constructor +QwtNullTransform::QwtNullTransform(): + QwtTransform() +{ +} + +//! Destructor +QwtNullTransform::~QwtNullTransform() +{ +} + +/*! + \param value Value to be transformed + \return value unmodified + */ +double QwtNullTransform::transform( double value ) const +{ + return value; +} + +/*! + \param value Value to be transformed + \return value unmodified + */ +double QwtNullTransform::invTransform( double value ) const +{ + return value; +} + +//! \return Clone of the transformation +QwtTransform *QwtNullTransform::copy() const +{ + return new QwtNullTransform(); +} + +//! Constructor +QwtLogTransform::QwtLogTransform(): + QwtTransform() +{ +} + +//! Destructor +QwtLogTransform::~QwtLogTransform() +{ +} + +/*! + \param value Value to be transformed + \return log( value ) + */ +double QwtLogTransform::transform( double value ) const +{ + return ::log( value ); +} + +/*! + \param value Value to be transformed + \return exp( value ) + */ +double QwtLogTransform::invTransform( double value ) const +{ + return qExp( value ); +} + +/*! + \param value Value to be bounded + \return qBound( LogMin, value, LogMax ) + */ +double QwtLogTransform::bounded( double value ) const +{ + return qBound( LogMin, value, LogMax ); +} + +//! \return Clone of the transformation +QwtTransform *QwtLogTransform::copy() const +{ + return new QwtLogTransform(); +} + +/*! + Constructor + \param exponent Exponent +*/ +QwtPowerTransform::QwtPowerTransform( double exponent ): + QwtTransform(), + d_exponent( exponent ) +{ +} + +//! Destructor +QwtPowerTransform::~QwtPowerTransform() +{ +} + +/*! + \param value Value to be transformed + \return Exponentiation preserving the sign + */ +double QwtPowerTransform::transform( double value ) const +{ + if ( value < 0.0 ) + return -qPow( -value, 1.0 / d_exponent ); + else + return qPow( value, 1.0 / d_exponent ); + +} + +/*! + \param value Value to be transformed + \return Inverse exponentiation preserving the sign + */ +double QwtPowerTransform::invTransform( double value ) const +{ + if ( value < 0.0 ) + return -qPow( -value, d_exponent ); + else + return qPow( value, d_exponent ); +} + +//! \return Clone of the transformation +QwtTransform *QwtPowerTransform::copy() const +{ + return new QwtPowerTransform( d_exponent ); +} diff --git a/libs/qwt/qwt_transform.h b/libs/qwt/qwt_transform.h new file mode 100644 index 0000000000..ce13fa66fb --- /dev/null +++ b/libs/qwt/qwt_transform.h @@ -0,0 +1,137 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_TRANSFORM_H +#define QWT_TRANSFORM_H + +#include "qwt_global.h" + +/*! + \brief A transformation between coordinate systems + + QwtTransform manipulates values, when being mapped between + the scale and the paint device coordinate system. + + A transformation consists of 2 methods: + + - transform + - invTransform + + where one is is the inverse function of the other. + + When p1, p2 are the boundaries of the paint device coordinates + and s1, s2 the boundaries of the scale, QwtScaleMap uses the + following calculations: + + - p = p1 + ( p2 - p1 ) * ( T( s ) - T( s1 ) / ( T( s2 ) - T( s1 ) ); + - s = invT ( T( s1 ) + ( T( s2 ) - T( s1 ) ) * ( p - p1 ) / ( p2 - p1 ) ); +*/ +class QWT_EXPORT QwtTransform +{ +public: + QwtTransform(); + virtual ~QwtTransform(); + + /*! + Modify value to be a valid value for the transformation. + The default implementation does nothing. + */ + virtual double bounded( double value ) const; + + /*! + Transformation function + + \param value Value + \return Modified value + + \sa invTransform() + */ + virtual double transform( double value ) const = 0; + + /*! + Inverse transformation function + + \param value Value + \return Modified value + + \sa transform() + */ + virtual double invTransform( double value ) const = 0; + + //! Virtualized copy operation + virtual QwtTransform *copy() const = 0; +}; + +/*! + \brief Null transformation + + QwtNullTransform returns the values unmodified. + + */ +class QWT_EXPORT QwtNullTransform: public QwtTransform +{ +public: + QwtNullTransform(); + virtual ~QwtNullTransform(); + + virtual double transform( double value ) const; + virtual double invTransform( double value ) const; + + virtual QwtTransform *copy() const; +}; +/*! + \brief Logarithmic transformation + + QwtLogTransform modifies the values using log() and exp(). + + \note In the calculations of QwtScaleMap the base of the log function + has no effect on the mapping. So QwtLogTransform can be used + for log2(), log10() or any other logarithmic scale. + */ +class QWT_EXPORT QwtLogTransform: public QwtTransform +{ +public: + QwtLogTransform(); + virtual ~QwtLogTransform(); + + virtual double transform( double value ) const; + virtual double invTransform( double value ) const; + + virtual double bounded( double value ) const; + + virtual QwtTransform *copy() const; + + QT_STATIC_CONST double LogMin; + QT_STATIC_CONST double LogMax; +}; + +/*! + \brief A transformation using pow() + + QwtPowerTransform preserves the sign of a value. + F.e. a transformation with a factor of 2 + transforms a value of -3 to -9 and v.v. Thus QwtPowerTransform + can be used for scales including negative values. + */ +class QWT_EXPORT QwtPowerTransform: public QwtTransform +{ +public: + QwtPowerTransform( double exponent ); + virtual ~QwtPowerTransform(); + + virtual double transform( double value ) const; + virtual double invTransform( double value ) const; + + virtual QwtTransform *copy() const; + +private: + const double d_exponent; +}; + +#endif diff --git a/libs/qwt/qwt_wheel.cpp b/libs/qwt/qwt_wheel.cpp index aa9596cb64..5078184e08 100644 --- a/libs/qwt/qwt_wheel.cpp +++ b/libs/qwt/qwt_wheel.cpp @@ -7,280 +7,589 @@ * modify it under the terms of the Qwt License, Version 1.0 *****************************************************************************/ +#include "qwt_wheel.h" +#include "qwt_math.h" +#include "qwt_painter.h" #include <qevent.h> #include <qdrawutil.h> #include <qpainter.h> #include <qstyle.h> -#include "qwt_math.h" -#include "qwt_painter.h" -#include "qwt_paint_buffer.h" -#include "qwt_wheel.h" - -#define NUM_COLORS 30 +#include <qstyleoption.h> +#include <qapplication.h> +#include <qdatetime.h> + +#if QT_VERSION < 0x040601 +#define qFabs(x) ::fabs(x) +#define qFastSin(x) ::sin(x) +#define qExp(x) ::exp(x) +#endif class QwtWheel::PrivateData { public: - PrivateData() { - viewAngle = 175.0; - totalAngle = 360.0; - tickCnt = 10; - intBorder = 2; - borderWidth = 2; - wheelWidth = 20; -#if QT_VERSION < 0x040000 - allocContext = 0; -#endif + PrivateData(): + orientation( Qt::Horizontal ), + viewAngle( 175.0 ), + totalAngle( 360.0 ), + tickCount( 10 ), + wheelBorderWidth( 2 ), + borderWidth( 2 ), + wheelWidth( 20 ), + isScrolling( false ), + mouseOffset( 0.0 ), + tracking( true ), + pendingValueChanged( false ), + updateInterval( 50 ), + mass( 0.0 ), + timerId( 0 ), + speed( 0.0 ), + mouseValue( 0.0 ), + flyingValue( 0.0 ), + minimum( 0.0 ), + maximum( 100.0 ), + singleStep( 1.0 ), + pageStepCount( 1 ), + stepAlignment( true ), + value( 0.0 ), + inverted( false ), + wrapping( false ) + { }; - QRect sliderRect; + Qt::Orientation orientation; double viewAngle; double totalAngle; - int tickCnt; - int intBorder; + int tickCount; + int wheelBorderWidth; int borderWidth; int wheelWidth; -#if QT_VERSION < 0x040000 - int allocContext; -#endif - QColor colors[NUM_COLORS]; + + bool isScrolling; + double mouseOffset; + + bool tracking; + bool pendingValueChanged; // when not tracking + + int updateInterval; + double mass; + + // for the flying wheel effect + int timerId; + QTime time; + double speed; + double mouseValue; + double flyingValue; + + double minimum; + double maximum; + + double singleStep; + int pageStepCount; + bool stepAlignment; + + double value; + + bool inverted; + bool wrapping; }; //! Constructor -QwtWheel::QwtWheel(QWidget *parent): - QwtAbstractSlider(Qt::Horizontal, parent) +QwtWheel::QwtWheel( QWidget *parent ): + QWidget( parent ) { - initWheel(); + d_data = new PrivateData; + + setFocusPolicy( Qt::StrongFocus ); + setSizePolicy( QSizePolicy::Preferred, QSizePolicy::Fixed ); + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); } -#if QT_VERSION < 0x040000 -QwtWheel::QwtWheel(QWidget *parent, const char *name): - QwtAbstractSlider(Qt::Horizontal, parent) +//! Destructor +QwtWheel::~QwtWheel() { - setName(name); - initWheel(); + delete d_data; } -#endif -void QwtWheel::initWheel() +/*! + \brief En/Disable tracking + + If tracking is enabled (the default), the wheel emits the valueChanged() + signal while the wheel is moving. If tracking is disabled, the wheel + emits the valueChanged() signal only when the wheel movement is terminated. + + The wheelMoved() signal is emitted regardless id tracking is enabled or not. + + \param enable On/Off + \sa isTracking() + */ +void QwtWheel::setTracking( bool enable ) { - d_data = new PrivateData; + d_data->tracking = enable; +} -#if QT_VERSION < 0x040000 - setWFlags(Qt::WNoAutoErase); -#endif +/*! + \return True, when tracking is enabled + \sa setTracking(), valueChanged(), wheelMoved() +*/ +bool QwtWheel::isTracking() const +{ + return d_data->tracking; +} - setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); +/*! + \brief Specify the update interval when the wheel is flying -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif + Default and minimum value is 50 ms. - setUpdateTime(50); + \param interval Interval in milliseconds + \sa updateInterval(), setMass(), setTracking() +*/ +void QwtWheel::setUpdateInterval( int interval ) +{ + d_data->updateInterval = qMax( interval, 50 ); } -//! Destructor -QwtWheel::~QwtWheel() +/*! + \return Update interval when the wheel is flying + \sa setUpdateInterval(), mass(), isTracking() + */ +int QwtWheel::updateInterval() const { -#if QT_VERSION < 0x040000 - if ( d_data->allocContext ) - QColor::destroyAllocContext( d_data->allocContext ); -#endif - delete d_data; + return d_data->updateInterval; +} + +/*! + \brief Mouse press event handler + + Start movement of the wheel. + + \param event Mouse event +*/ +void QwtWheel::mousePressEvent( QMouseEvent *event ) +{ + stopFlying(); + + d_data->isScrolling = wheelRect().contains( event->pos() ); + + if ( d_data->isScrolling ) + { + d_data->time.start(); + d_data->speed = 0.0; + d_data->mouseValue = valueAt( event->pos() ); + d_data->mouseOffset = d_data->mouseValue - d_data->value; + d_data->pendingValueChanged = false; + + Q_EMIT wheelPressed(); + } } -//! Set up the color array for the background pixmap. -void QwtWheel::setColorArray() +/*! + \brief Mouse Move Event handler + + Turn the wheel according to the mouse position + + \param event Mouse event +*/ +void QwtWheel::mouseMoveEvent( QMouseEvent *event ) { - if ( !d_data->colors ) + if ( !d_data->isScrolling ) return; -#if QT_VERSION < 0x040000 - const QColor light = colorGroup().light(); - const QColor dark = colorGroup().dark(); -#else - const QColor light = palette().color(QPalette::Light); - const QColor dark = palette().color(QPalette::Dark); -#endif + double mouseValue = valueAt( event->pos() ); + + if ( d_data->mass > 0.0 ) + { + double ms = d_data->time.restart(); - if ( !d_data->colors[0].isValid() || - d_data->colors[0] != light || - d_data->colors[NUM_COLORS - 1] != dark ) { -#if QT_VERSION < 0x040000 - if ( d_data->allocContext ) - QColor::destroyAllocContext( d_data->allocContext ); + // the interval when mouse move events are posted are somehow + // random. To avoid unrealistic speed values we limit ms - d_data->allocContext = QColor::enterAllocContext(); -#endif + ms = qMax( ms, 5.0 ); - d_data->colors[0] = light; - d_data->colors[NUM_COLORS - 1] = dark; + d_data->speed = ( mouseValue - d_data->mouseValue ) / ms; + } + + d_data->mouseValue = mouseValue; + + double value = boundedValue( mouseValue - d_data->mouseOffset ); + if ( d_data->stepAlignment ) + value = alignedValue( value ); + + if ( value != d_data->value ) + { + d_data->value = value; - int dh, ds, dv, lh, ls, lv; -#if QT_VERSION < 0x040000 - d_data->colors[0].rgb(&lh, &ls, &lv); - d_data->colors[NUM_COLORS - 1].rgb(&dh, &ds, &dv); -#else - d_data->colors[0].getRgb(&lh, &ls, &lv); - d_data->colors[NUM_COLORS - 1].getRgb(&dh, &ds, &dv); -#endif + update(); + + Q_EMIT wheelMoved( d_data->value ); + + if ( d_data->tracking ) + Q_EMIT valueChanged( d_data->value ); + else + d_data->pendingValueChanged = true; + } +} + +/*! + \brief Mouse Release Event handler + + When the wheel has no mass the movement of the wheel stops, otherwise + it starts flying. + + \param event Mouse event +*/ + +void QwtWheel::mouseReleaseEvent( QMouseEvent *event ) +{ + Q_UNUSED( event ); + + if ( !d_data->isScrolling ) + return; + + d_data->isScrolling = false; + + bool startFlying = false; + + if ( d_data->mass > 0.0 ) + { + const int ms = d_data->time.elapsed(); + if ( ( qFabs( d_data->speed ) > 0.0 ) && ( ms < 50 ) ) + startFlying = true; + } + + if ( startFlying ) + { + d_data->flyingValue = + boundedValue( d_data->mouseValue - d_data->mouseOffset ); + + d_data->timerId = startTimer( d_data->updateInterval ); + } + else + { + if ( d_data->pendingValueChanged ) + Q_EMIT valueChanged( d_data->value ); + } + + d_data->pendingValueChanged = false; + d_data->mouseOffset = 0.0; + + Q_EMIT wheelReleased(); +} + +/*! + \brief Qt timer event - for ( int i = 1; i < NUM_COLORS - 1; ++i ) { - const double factor = double(i) / double(NUM_COLORS); + The flying wheel effect is implemented using a timer + + \param event Timer event + + \sa updateInterval() + */ +void QwtWheel::timerEvent( QTimerEvent *event ) +{ + if ( event->timerId() != d_data->timerId ) + { + QWidget::timerEvent( event ); + return; + } + + d_data->speed *= qExp( -d_data->updateInterval * 0.001 / d_data->mass ); + + d_data->flyingValue += d_data->speed * d_data->updateInterval; + d_data->flyingValue = boundedValue( d_data->flyingValue ); + + double value = d_data->flyingValue; + if ( d_data->stepAlignment ) + value = alignedValue( value ); + + if ( qFabs( d_data->speed ) < 0.001 * d_data->singleStep ) + { + // stop if d_data->speed < one step per second + stopFlying(); + } + + if ( value != d_data->value ) + { + d_data->value = value; + update(); - d_data->colors[i].setRgb( lh + int( double(dh - lh) * factor ), - ls + int( double(ds - ls) * factor ), - lv + int( double(dv - lv) * factor )); + if ( d_data->tracking || d_data->timerId == 0 ) + Q_EMIT valueChanged( d_data->value ); + } +} + + +/*! + \brief Handle wheel events + + In/Decrement the value + + \param event Wheel event +*/ +void QwtWheel::wheelEvent( QWheelEvent *event ) +{ + if ( !wheelRect().contains( event->pos() ) ) + { + event->ignore(); + return; + } + + if ( d_data->isScrolling ) + return; + + stopFlying(); + + double increment = 0.0; + + if ( ( event->modifiers() & Qt::ControlModifier) || + ( event->modifiers() & Qt::ShiftModifier ) ) + { + // one page regardless of delta + increment = d_data->singleStep * d_data->pageStepCount; + if ( event->delta() < 0 ) + increment = -increment; + } + else + { + const int numSteps = event->delta() / 120; + increment = d_data->singleStep * numSteps; + } + + if ( d_data->orientation == Qt::Vertical && d_data->inverted ) + increment = -increment; + + double value = boundedValue( d_data->value + increment ); + + if ( d_data->stepAlignment ) + value = alignedValue( value ); + + if ( value != d_data->value ) + { + d_data->value = value; + update(); + + Q_EMIT valueChanged( d_data->value ); + Q_EMIT wheelMoved( d_data->value ); + } +} + +/*! + Handle key events + + - Qt::Key_Home\n + Step to minimum() + + - Qt::Key_End\n + Step to maximum() + + - Qt::Key_Up\n + In case of a horizontal or not inverted vertical wheel the value + will be incremented by the step size. For an inverted vertical wheel + the value will be decremented by the step size. + + - Qt::Key_Down\n + In case of a horizontal or not inverted vertical wheel the value + will be decremented by the step size. For an inverted vertical wheel + the value will be incremented by the step size. + + - Qt::Key_PageUp\n + The value will be incremented by pageStepSize() * singleStepSize(). + + - Qt::Key_PageDown\n + The value will be decremented by pageStepSize() * singleStepSize(). + + \param event Key event +*/ +void QwtWheel::keyPressEvent( QKeyEvent *event ) +{ + if ( d_data->isScrolling ) + { + // don't interfere mouse scrolling + return; + } + + double value = d_data->value; + double increment = 0.0; + + switch ( event->key() ) + { + case Qt::Key_Down: + { + if ( d_data->orientation == Qt::Vertical && d_data->inverted ) + increment = d_data->singleStep; + else + increment = -d_data->singleStep; + + break; } -#if QT_VERSION < 0x040000 - QColor::leaveAllocContext(); -#endif + case Qt::Key_Up: + { + if ( d_data->orientation == Qt::Vertical && d_data->inverted ) + increment = -d_data->singleStep; + else + increment = d_data->singleStep; + + break; + } + case Qt::Key_Left: + { + if ( d_data->orientation == Qt::Horizontal ) + { + if ( d_data->inverted ) + increment = d_data->singleStep; + else + increment = -d_data->singleStep; + } + break; + } + case Qt::Key_Right: + { + if ( d_data->orientation == Qt::Horizontal ) + { + if ( d_data->inverted ) + increment = -d_data->singleStep; + else + increment = d_data->singleStep; + } + break; + } + case Qt::Key_PageUp: + { + increment = d_data->pageStepCount * d_data->singleStep; + break; + } + case Qt::Key_PageDown: + { + increment = -d_data->pageStepCount * d_data->singleStep; + break; + } + case Qt::Key_Home: + { + value = d_data->minimum; + break; + } + case Qt::Key_End: + { + value = d_data->maximum; + break; + } + default:; + { + event->ignore(); + } + } + + if ( event->isAccepted() ) + stopFlying(); + + if ( increment != 0.0 ) + { + value = boundedValue( d_data->value + increment ); + + if ( d_data->stepAlignment ) + value = alignedValue( value ); + } + + if ( value != d_data->value ) + { + d_data->value = value; + update(); + + Q_EMIT valueChanged( d_data->value ); + Q_EMIT wheelMoved( d_data->value ); } } /*! \brief Adjust the number of grooves in the wheel's surface. - The number of grooves is limited to 6 <= cnt <= 50. + The number of grooves is limited to 6 <= count <= 50. Values outside this range will be clipped. The default value is 10. - \param cnt Number of grooves per 360 degrees + + \param count Number of grooves per 360 degrees + \sa tickCount() */ -void QwtWheel::setTickCnt(int cnt) +void QwtWheel::setTickCount( int count ) { - d_data->tickCnt = qwtLim( cnt, 6, 50 ); - update(); -} + count = qBound( 6, count, 50 ); -int QwtWheel::tickCnt() const -{ - return d_data->tickCnt; + if ( count != d_data->tickCount ) + { + d_data->tickCount = qBound( 6, count, 50 ); + update(); + } } /*! - \return mass + \return Number of grooves in the wheel's surface. + \sa setTickCnt() */ -double QwtWheel::mass() const +int QwtWheel::tickCount() const { - return QwtAbstractSlider::mass(); + return d_data->tickCount; } /*! - \brief Set the internal border width of the wheel. + \brief Set the wheel border width of the wheel. - The internal border must not be smaller than 1 + The wheel border must not be smaller than 1 and is limited in dependence on the wheel's size. Values outside the allowed range will be clipped. - The internal border defaults to 2. - \param w border width + The wheel border defaults to 2. + + \param borderWidth Border width + \sa internalBorder() */ -void QwtWheel::setInternalBorder( int w ) +void QwtWheel::setWheelBorderWidth( int borderWidth ) { - const int d = qwtMin( width(), height() ) / 3; - w = qwtMin( w, d ); - d_data->intBorder = qwtMax( w, 1 ); - layoutWheel(); + const int d = qMin( width(), height() ) / 3; + borderWidth = qMin( borderWidth, d ); + d_data->wheelBorderWidth = qMax( borderWidth, 1 ); + update(); } -int QwtWheel::internalBorder() const +/*! + \return Wheel border width + \sa setWheelBorderWidth() +*/ +int QwtWheel::wheelBorderWidth() const { - return d_data->intBorder; + return d_data->wheelBorderWidth; } -//! Draw the Wheel's background gradient -void QwtWheel::drawWheelBackground( QPainter *p, const QRect &r ) -{ - p->save(); - - // - // initialize pens - // -#if QT_VERSION < 0x040000 - const QColor light = colorGroup().light(); - const QColor dark = colorGroup().dark(); -#else - const QColor light = palette().color(QPalette::Light); - const QColor dark = palette().color(QPalette::Dark); -#endif - - QPen lightPen; - lightPen.setColor(light); - lightPen.setWidth(d_data->intBorder); - - QPen darkPen; - darkPen.setColor(dark); - darkPen.setWidth(d_data->intBorder); - - setColorArray(); - - // - // initialize auxiliary variables - // - - const int nFields = NUM_COLORS * 13 / 10; - const int hiPos = nFields - NUM_COLORS + 1; - - if ( orientation() == Qt::Horizontal ) { - const int rx = r.x(); - int ry = r.y() + d_data->intBorder; - const int rh = r.height() - 2* d_data->intBorder; - const int rw = r.width(); - // - // draw shaded background - // - int x1 = rx; - for (int i = 1; i < nFields; i++ ) { - const int x2 = rx + (rw * i) / nFields; - p->fillRect(x1, ry, x2-x1 + 1 ,rh, d_data->colors[qwtAbs(i-hiPos)]); - x1 = x2 + 1; - } - p->fillRect(x1, ry, rw - (x1 - rx), rh, d_data->colors[NUM_COLORS - 1]); - - // - // draw internal border - // - p->setPen(lightPen); - ry = r.y() + d_data->intBorder / 2; - p->drawLine(r.x(), ry, r.x() + r.width() , ry); - - p->setPen(darkPen); - ry = r.y() + r.height() - (d_data->intBorder - d_data->intBorder / 2); - p->drawLine(r.x(), ry , r.x() + r.width(), ry); - } else { // Qt::Vertical - int rx = r.x() + d_data->intBorder; - const int ry = r.y(); - const int rh = r.height(); - const int rw = r.width() - 2 * d_data->intBorder; - - // - // draw shaded background - // - int y1 = ry; - for ( int i = 1; i < nFields; i++ ) { - const int y2 = ry + (rh * i) / nFields; - p->fillRect(rx, y1, rw, y2-y1 + 1, d_data->colors[qwtAbs(i-hiPos)]); - y1 = y2 + 1; - } - p->fillRect(rx, y1, rw, rh - (y1 - ry), d_data->colors[NUM_COLORS - 1]); +/*! + \brief Set the border width - // - // draw internal borders - // - p->setPen(lightPen); - rx = r.x() + d_data->intBorder / 2; - p->drawLine(rx, r.y(), rx, r.y() + r.height()); + The border defaults to 2. - p->setPen(darkPen); - rx = r.x() + r.width() - (d_data->intBorder - d_data->intBorder / 2); - p->drawLine(rx, r.y(), rx , r.y() + r.height()); - } + \param width Border width + \sa borderWidth() +*/ +void QwtWheel::setBorderWidth( int width ) +{ + d_data->borderWidth = qMax( width, 0 ); + update(); +} - p->restore(); +/*! + \return Border width + \sa setBorderWidth() +*/ +int QwtWheel::borderWidth() const +{ + return d_data->borderWidth; } +/*! + \return Rectangle of the wheel without the outer border +*/ +QRect QwtWheel::wheelRect() const +{ + const int bw = d_data->borderWidth; + return contentsRect().adjusted( bw, bw, -bw, -bw ); +} /*! \brief Set the total angle which the wheel can be turned. @@ -291,9 +600,11 @@ void QwtWheel::drawWheelBackground( QPainter *p, const QRect &r ) to get from the minimum value to the maximum value. The default setting of the total angle is 360 degrees. + \param angle total angle in degrees + \sa totalAngle() */ -void QwtWheel::setTotalAngle(double angle) +void QwtWheel::setTotalAngle( double angle ) { if ( angle < 0.0 ) angle = 0.0; @@ -302,6 +613,10 @@ void QwtWheel::setTotalAngle(double angle) update(); } +/*! + \return Total angle which the wheel can be turned. + \sa setTotalAngle() +*/ double QwtWheel::totalAngle() const { return d_data->totalAngle; @@ -309,35 +624,37 @@ double QwtWheel::totalAngle() const /*! \brief Set the wheel's orientation. - \param o Orientation. Allowed values are - Qt::Horizontal and Qt::Vertical. - Defaults to Qt::Horizontal. - \sa QwtAbstractSlider::orientation() + + The default orientation is Qt::Horizontal. + + \param orientation Qt::Horizontal or Qt::Vertical. + \sa orientation() */ -void QwtWheel::setOrientation(Qt::Orientation o) +void QwtWheel::setOrientation( Qt::Orientation orientation ) { - if ( orientation() == o ) + if ( d_data->orientation == orientation ) return; -#if QT_VERSION >= 0x040000 - if ( !testAttribute(Qt::WA_WState_OwnSizePolicy) ) -#else - if ( !testWState( WState_OwnSizePolicy ) ) -#endif + if ( !testAttribute( Qt::WA_WState_OwnSizePolicy ) ) { QSizePolicy sp = sizePolicy(); sp.transpose(); - setSizePolicy(sp); + setSizePolicy( sp ); -#if QT_VERSION >= 0x040000 - setAttribute(Qt::WA_WState_OwnSizePolicy, false); -#else - clearWState( WState_OwnSizePolicy ); -#endif + setAttribute( Qt::WA_WState_OwnSizePolicy, false ); } - QwtAbstractSlider::setOrientation(o); - layoutWheel(); + d_data->orientation = orientation; + update(); +} + +/*! + \return Orientation + \sa setOrientation() +*/ +Qt::Orientation QwtWheel::orientation() const +{ + return d_data->orientation; } /*! @@ -346,291 +663,637 @@ void QwtWheel::setOrientation(Qt::Orientation o) You may use this function for fine-tuning the appearance of the wheel. The default value is 175 degrees. The value is limited from 10 to 175 degrees. + \param angle Visible angle in degrees + \sa viewAngle(), setTotalAngle() */ -void QwtWheel::setViewAngle(double angle) +void QwtWheel::setViewAngle( double angle ) { - d_data->viewAngle = qwtLim( angle, 10.0, 175.0 ); + d_data->viewAngle = qBound( 10.0, angle, 175.0 ); update(); } +/*! + \return Visible portion of the wheel + \sa setViewAngle(), totalAngle() +*/ double QwtWheel::viewAngle() const { return d_data->viewAngle; } +/*! + Determine the value corresponding to a specified point + + \param pos Position + \return Value corresponding to pos +*/ +double QwtWheel::valueAt( const QPoint &pos ) const +{ + const QRectF rect = wheelRect(); + + double w, dx; + if ( d_data->orientation == Qt::Vertical ) + { + w = rect.height(); + dx = rect.top() - pos.y(); + } + else + { + w = rect.width(); + dx = pos.x() - rect.left(); + } + + if ( w == 0.0 ) + return 0.0; + + if ( d_data->inverted ) + { + dx = w - dx; + } + + // w pixels is an arc of viewAngle degrees, + // so we convert change in pixels to change in angle + const double ang = dx * d_data->viewAngle / w; + + // value range maps to totalAngle degrees, + // so convert the change in angle to a change in value + const double val = ang * ( maximum() - minimum() ) / d_data->totalAngle; + + return val; +} + +/*! + \brief Qt Paint Event + \param event Paint event +*/ +void QwtWheel::paintEvent( QPaintEvent *event ) +{ + QPainter painter( this ); + painter.setClipRegion( event->region() ); + + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); + + qDrawShadePanel( &painter, + contentsRect(), palette(), true, d_data->borderWidth ); + + drawWheelBackground( &painter, wheelRect() ); + drawTicks( &painter, wheelRect() ); + + if ( hasFocus() ) + QwtPainter::drawFocusRect( &painter, this ); +} + +/*! + Draw the Wheel's background gradient + + \param painter Painter + \param rect Geometry for the wheel +*/ +void QwtWheel::drawWheelBackground( + QPainter *painter, const QRectF &rect ) +{ + painter->save(); + + QPalette pal = palette(); + + // draw shaded background + QLinearGradient gradient( rect.topLeft(), + ( d_data->orientation == Qt::Horizontal ) ? rect.topRight() : rect.bottomLeft() ); + gradient.setColorAt( 0.0, pal.color( QPalette::Button ) ); + gradient.setColorAt( 0.2, pal.color( QPalette::Midlight ) ); + gradient.setColorAt( 0.7, pal.color( QPalette::Mid ) ); + gradient.setColorAt( 1.0, pal.color( QPalette::Dark ) ); + + painter->fillRect( rect, gradient ); + + // draw internal border + + const QPen lightPen( palette().color( QPalette::Light ), + d_data->wheelBorderWidth, Qt::SolidLine, Qt::FlatCap ); + const QPen darkPen( pal.color( QPalette::Dark ), + d_data->wheelBorderWidth, Qt::SolidLine, Qt::FlatCap ); + + const double bw2 = 0.5 * d_data->wheelBorderWidth; + + if ( d_data->orientation == Qt::Horizontal ) + { + painter->setPen( lightPen ); + painter->drawLine( QPointF( rect.left(), rect.top() + bw2 ), + QPointF( rect.right(), rect.top() + bw2 ) ); + + painter->setPen( darkPen ); + painter->drawLine( QPointF( rect.left(), rect.bottom() - bw2 ), + QPointF( rect.right(), rect.bottom() - bw2 ) ); + } + else // Qt::Vertical + { + painter->setPen( lightPen ); + painter->drawLine( QPointF( rect.left() + bw2, rect.top() ), + QPointF( rect.left() + bw2, rect.bottom() ) ); + + painter->setPen( darkPen ); + painter->drawLine( QPointF( rect.right() - bw2, rect.top() ), + QPointF( rect.right() - bw2, rect.bottom() ) ); + } + + painter->restore(); +} + /*! - \brief Redraw the wheel - \param p painter - \param r contents rectangle + Draw the Wheel's ticks + + \param painter Painter + \param rect Geometry for the wheel */ -void QwtWheel::drawWheel( QPainter *p, const QRect &r ) +void QwtWheel::drawTicks( QPainter *painter, const QRectF &rect ) { - // - // draw background gradient - // - drawWheelBackground( p, r ); + const double range = d_data->maximum - d_data->minimum; - if ( maxValue() == minValue() || d_data->totalAngle == 0.0 ) + if ( range == 0.0 || d_data->totalAngle == 0.0 ) + { return; + } -#if QT_VERSION < 0x040000 - const QColor light = colorGroup().light(); - const QColor dark = colorGroup().dark(); -#else - const QColor light = palette().color(QPalette::Light); - const QColor dark = palette().color(QPalette::Dark); -#endif + const QPen lightPen( palette().color( QPalette::Light ), + 0, Qt::SolidLine, Qt::FlatCap ); + const QPen darkPen( palette().color( QPalette::Dark ), + 0, Qt::SolidLine, Qt::FlatCap ); - const double sign = (minValue() < maxValue()) ? 1.0 : -1.0; - double cnvFactor = qwtAbs(d_data->totalAngle / (maxValue() - minValue())); + const double cnvFactor = qAbs( d_data->totalAngle / range ); const double halfIntv = 0.5 * d_data->viewAngle / cnvFactor; const double loValue = value() - halfIntv; const double hiValue = value() + halfIntv; - const double tickWidth = 360.0 / double(d_data->tickCnt) / cnvFactor; - const double sinArc = sin(d_data->viewAngle * M_PI / 360.0); - cnvFactor *= M_PI / 180.0; - + const double tickWidth = 360.0 / double( d_data->tickCount ) / cnvFactor; + const double sinArc = qFastSin( d_data->viewAngle * M_PI / 360.0 ); - // - // draw grooves - // - if ( orientation() == Qt::Horizontal ) { - const double halfSize = double(r.width()) * 0.5; + if ( d_data->orientation == Qt::Horizontal ) + { + const double radius = rect.width() * 0.5; - int l1 = r.y() + d_data->intBorder; - int l2 = r.y() + r.height() - d_data->intBorder - 1; + double l1 = rect.top() + d_data->wheelBorderWidth; + double l2 = rect.bottom() - d_data->wheelBorderWidth - 1; // draw one point over the border if border > 1 - if ( d_data->intBorder > 1 ) { - l1 --; - l2 ++; + if ( d_data->wheelBorderWidth > 1 ) + { + l1--; + l2++; } - const int maxpos = r.x() + r.width() - 2; - const int minpos = r.x() + 2; + const double maxpos = rect.right() - 2; + const double minpos = rect.left() + 2; - // // draw tick marks - // - for ( double tickValue = ceil(loValue / tickWidth) * tickWidth; - tickValue < hiValue; tickValue += tickWidth ) { - // - // calculate position - // - const int tickPos = r.x() + r.width() - - int( halfSize - * (sinArc + sign * sin((tickValue - value()) * cnvFactor)) - / sinArc); - // - // draw vertical line - // - if ( (tickPos <= maxpos) && (tickPos > minpos) ) { - p->setPen(dark); - p->drawLine(tickPos -1 , l1, tickPos - 1, l2 ); - p->setPen(light); - p->drawLine(tickPos, l1, tickPos, l2); + for ( double tickValue = ::ceil( loValue / tickWidth ) * tickWidth; + tickValue < hiValue; tickValue += tickWidth ) + { + const double angle = qwtRadians( tickValue - value() ); + const double s = qFastSin( angle * cnvFactor ); + + const double off = radius * ( sinArc + s ) / sinArc; + + double tickPos; + if ( d_data->inverted ) + tickPos = rect.left() + off; + else + tickPos = rect.right() - off; + + if ( ( tickPos <= maxpos ) && ( tickPos > minpos ) ) + { + painter->setPen( darkPen ); + painter->drawLine( QPointF( tickPos - 1 , l1 ), + QPointF( tickPos - 1, l2 ) ); + painter->setPen( lightPen ); + painter->drawLine( QPointF( tickPos, l1 ), + QPointF( tickPos, l2 ) ); } } - } else if ( orientation() == Qt::Vertical ) { - const double halfSize = double(r.height()) * 0.5; + } + else // Qt::Vertical + { + const double radius = rect.height() * 0.5; - int l1 = r.x() + d_data->intBorder; - int l2 = r.x() + r.width() - d_data->intBorder - 1; + double l1 = rect.left() + d_data->wheelBorderWidth; + double l2 = rect.right() - d_data->wheelBorderWidth - 1; - if ( d_data->intBorder > 1 ) { + if ( d_data->wheelBorderWidth > 1 ) + { l1--; l2++; } - const int maxpos = r.y() + r.height() - 2; - const int minpos = r.y() + 2; + const double maxpos = rect.bottom() - 2; + const double minpos = rect.top() + 2; - // - // draw tick marks - // - for ( double tickValue = ceil(loValue / tickWidth) * tickWidth; - tickValue < hiValue; tickValue += tickWidth ) { - - // - // calculate position - // - const int tickPos = r.y() + int( halfSize * - (sinArc + sign * sin((tickValue - value()) * cnvFactor)) - / sinArc); - - // - // draw horizontal line - // - if ( (tickPos <= maxpos) && (tickPos > minpos) ) { - p->setPen(dark); - p->drawLine(l1, tickPos - 1 ,l2, tickPos - 1); - p->setPen(light); - p->drawLine(l1, tickPos, l2, tickPos); + for ( double tickValue = ::ceil( loValue / tickWidth ) * tickWidth; + tickValue < hiValue; tickValue += tickWidth ) + { + const double angle = qwtRadians( tickValue - value() ); + const double s = qFastSin( angle * cnvFactor ); + + const double off = radius * ( sinArc + s ) / sinArc; + + double tickPos; + + if ( d_data->inverted ) + tickPos = rect.bottom() - off; + else + tickPos = rect.top() + off; + + if ( ( tickPos <= maxpos ) && ( tickPos > minpos ) ) + { + painter->setPen( darkPen ); + painter->drawLine( QPointF( l1, tickPos - 1 ), + QPointF( l2, tickPos - 1 ) ); + painter->setPen( lightPen ); + painter->drawLine( QPointF( l1, tickPos ), + QPointF( l2, tickPos ) ); } } } } +/*! + \brief Set the width of the wheel + + Corresponds to the wheel height for horizontal orientation, + and the wheel width for vertical orientation. -//! Determine the value corresponding to a specified point -double QwtWheel::getValue( const QPoint &p ) + \param width the wheel's width + \sa wheelWidth() +*/ +void QwtWheel::setWheelWidth( int width ) { - // The reference position is arbitrary, but the - // sign of the offset is important - int w, dx; - if ( orientation() == Qt::Vertical ) { - w = d_data->sliderRect.height(); - dx = d_data->sliderRect.y() - p.y(); - } else { - w = d_data->sliderRect.width(); - dx = p.x() - d_data->sliderRect.x(); - } + d_data->wheelWidth = width; + update(); +} - // w pixels is an arc of viewAngle degrees, - // so we convert change in pixels to change in angle - const double ang = dx * d_data->viewAngle / w; +/*! + \return Width of the wheel + \sa setWheelWidth() +*/ +int QwtWheel::wheelWidth() const +{ + return d_data->wheelWidth; +} - // value range maps to totalAngle degrees, - // so convert the change in angle to a change in value - const double val = ang * ( maxValue() - minValue() ) / d_data->totalAngle; +/*! + \return a size hint +*/ +QSize QwtWheel::sizeHint() const +{ + const QSize hint = minimumSizeHint(); + return hint.expandedTo( QApplication::globalStrut() ); +} - // Note, range clamping and rasterizing to step is automatically - // handled by QwtAbstractSlider, so we simply return the change in value - return val; +/*! + \return Minimum size hint + \warning The return value is based on the wheel width. +*/ +QSize QwtWheel::minimumSizeHint() const +{ + QSize sz( 3 * d_data->wheelWidth + 2 * d_data->borderWidth, + d_data->wheelWidth + 2 * d_data->borderWidth ); + if ( d_data->orientation != Qt::Horizontal ) + sz.transpose(); + + return sz; } -//! Qt Resize Event -void QwtWheel::resizeEvent(QResizeEvent *) +/*! + \brief Set the step size of the counter + + A value <= 0.0 disables stepping + + \param stepSize Single step size + \sa singleStep(), setPageStepCount() +*/ +void QwtWheel::setSingleStep( double stepSize ) { - layoutWheel( false ); + d_data->singleStep = qMax( stepSize, 0.0 ); } -//! Recalculate the slider's geometry and layout based on -// the current rect and fonts. -// \param update_geometry notify the layout system and call update -// to redraw the scale -void QwtWheel::layoutWheel( bool update_geometry ) +/*! + \return Single step size + \sa setSingleStep() + */ +double QwtWheel::singleStep() const { - const QRect r = this->rect(); - d_data->sliderRect.setRect(r.x() + d_data->borderWidth, r.y() + d_data->borderWidth, - r.width() - 2*d_data->borderWidth, r.height() - 2*d_data->borderWidth); + return d_data->singleStep; +} - if ( update_geometry ) { - updateGeometry(); - update(); +/*! + \brief En/Disable step alignment + + When step alignment is enabled value changes initiated by + user input ( mouse, keyboard, wheel ) are aligned to + the multiples of the single step. + + \param on On/Off + \sa stepAlignment(), setSingleStep() + */ +void QwtWheel::setStepAlignment( bool on ) +{ + if ( on != d_data->stepAlignment ) + { + d_data->stepAlignment = on; } } -//! Qt Paint Event -void QwtWheel::paintEvent(QPaintEvent *e) +/*! + \return True, when the step alignment is enabled + \sa setStepAlignment(), singleStep() + */ +bool QwtWheel::stepAlignment() const { - // Use double-buffering - const QRect &ur = e->rect(); - if ( ur.isValid() ) { -#if QT_VERSION < 0x040000 - QwtPaintBuffer paintBuffer(this, ur); - draw(paintBuffer.painter(), ur); -#else - QPainter painter(this); - draw(&painter, ur); -#endif - } + return d_data->stepAlignment; } -//! Redraw panel and wheel -void QwtWheel::draw(QPainter *painter, const QRect&) +/*! + \brief Set the page step count + + pageStepCount is a multiplicator for the single step size + that typically corresponds to the user pressing PageUp or PageDown. + + A value of 0 disables page stepping. + + The default value is 1. + + \param count Multiplicator for the single step size + \sa pageStepCount(), setSingleStep() + */ +void QwtWheel::setPageStepCount( int count ) { - qDrawShadePanel( painter, rect().x(), rect().y(), - rect().width(), rect().height(), -#if QT_VERSION < 0x040000 - colorGroup(), -#else - palette(), -#endif - true, d_data->borderWidth ); + d_data->pageStepCount = qMax( 0, count ); +} - drawWheel( painter, d_data->sliderRect ); +/*! + \return Page step count + \sa setPageStepCount(), singleStep() + */ +int QwtWheel::pageStepCount() const +{ + return d_data->pageStepCount; +} - if ( hasFocus() ) - QwtPainter::drawFocusRect(painter, this); +/*! + \brief Set the minimum and maximum values + + The maximum is adjusted if necessary to ensure that the range remains valid. + The value might be modified to be inside of the range. + + \param min Minimum value + \param max Maximum value + + \sa minimum(), maximum() + */ +void QwtWheel::setRange( double min, double max ) +{ + max = qMax( min, max ); + + if ( d_data->minimum == min && d_data->maximum == max ) + return; + + d_data->minimum = min; + d_data->maximum = max; + + if ( d_data->value < min || d_data->value > max ) + { + d_data->value = qBound( min, d_data->value, max ); + + update(); + Q_EMIT valueChanged( d_data->value ); + } } +/*! + Set the minimum value of the range -//! Notify value change -void QwtWheel::valueChange() + \param value Minimum value + \sa setRange(), setMaximum(), minimum() + + \note The maximum is adjusted if necessary to ensure that the range remains valid. +*/ +void QwtWheel::setMinimum( double value ) { - QwtAbstractSlider::valueChange(); - update(); + setRange( value, maximum() ); } +/*! + \return The minimum of the range + \sa setRange(), setMinimum(), maximum() +*/ +double QwtWheel::minimum() const +{ + return d_data->minimum; +} /*! - \brief Determine the scrolling mode and direction corresponding - to a specified point - \param p point - \param scrollMode scrolling mode - \param direction direction + Set the maximum value of the range + + \param value Maximum value + \sa setRange(), setMinimum(), maximum() */ -void QwtWheel::getScrollMode( const QPoint &p, int &scrollMode, int &direction) +void QwtWheel::setMaximum( double value ) { - if ( d_data->sliderRect.contains(p) ) - scrollMode = ScrMouse; - else - scrollMode = ScrNone; + setRange( minimum(), value ); +} - direction = 0; +/*! + \return The maximum of the range + \sa setRange(), setMaximum(), minimum() +*/ +double QwtWheel::maximum() const +{ + return d_data->maximum; } /*! - \brief Set the mass of the wheel + \brief Set a new value without adjusting to the step raster + + \param value New value - Assigning a mass turns the wheel into a flywheel. - \param val the wheel's mass + \sa value(), valueChanged() + \warning The value is clipped when it lies outside the range. */ -void QwtWheel::setMass(double val) +void QwtWheel::setValue( double value ) { - QwtAbstractSlider::setMass(val); + stopFlying(); + d_data->isScrolling = false; + + value = qBound( d_data->minimum, value, d_data->maximum ); + + if ( d_data->value != value ) + { + d_data->value = value; + + update(); + Q_EMIT valueChanged( d_data->value ); + } } /*! - \brief Set the width of the wheel + \return Current value of the wheel + \sa setValue(), valueChanged() + */ +double QwtWheel::value() const +{ + return d_data->value; +} - Corresponds to the wheel height for horizontal orientation, - and the wheel width for vertical orientation. - \param w the wheel's width -*/ -void QwtWheel::setWheelWidth(int w) +/*! + \brief En/Disable inverted appearance + + An inverted wheel increases its values in the opposite direction. + The direction of an inverted horizontal wheel will be from right to left + an inverted vertical wheel will increase from bottom to top. + + \param on En/Disable inverted appearance + \sa isInverted() + + */ +void QwtWheel::setInverted( bool on ) { - d_data->wheelWidth = w; - layoutWheel(); + if ( d_data->inverted != on ) + { + d_data->inverted = on; + update(); + } } /*! - \return a size hint -*/ -QSize QwtWheel::sizeHint() const + \return True, when the wheel is inverted + \sa setInverted() + */ +bool QwtWheel::isInverted() const { - return minimumSizeHint(); + return d_data->inverted; } /*! - \brief Return a minimum size hint - \warning The return value is based on the wheel width. + \brief En/Disable wrapping + + If wrapping is true stepping up from maximum() value will take + you to the minimum() value and vice versa. + + \param on En/Disable wrapping + \sa wrapping() + */ +void QwtWheel::setWrapping( bool on ) +{ + d_data->wrapping = on; +} + +/*! + \return True, when wrapping is set + \sa setWrapping() + */ +bool QwtWheel::wrapping() const +{ + return d_data->wrapping; +} + +/*! + \brief Set the slider's mass for flywheel effect. + + If the slider's mass is greater then 0, it will continue + to move after the mouse button has been released. Its speed + decreases with time at a rate depending on the slider's mass. + A large mass means that it will continue to move for a + long time. + + Derived widgets may overload this function to make it public. + + \param mass New mass in kg + + \bug If the mass is smaller than 1g, it is set to zero. + The maximal mass is limited to 100kg. + \sa mass() */ -QSize QwtWheel::minimumSizeHint() const +void QwtWheel::setMass( double mass ) { - QSize sz( 3*d_data->wheelWidth + 2*d_data->borderWidth, - d_data->wheelWidth + 2*d_data->borderWidth ); - if ( orientation() != Qt::Horizontal ) - sz.transpose(); - return sz; + if ( mass < 0.001 ) + { + d_data->mass = 0.0; + } + else + { + d_data->mass = qMin( 100.0, mass ); + } + + if ( d_data->mass <= 0.0 ) + stopFlying(); } /*! - \brief Call update() when the palette changes + \return mass + \sa setMass() */ -void QwtWheel::paletteChange( const QPalette& ) +double QwtWheel::mass() const { - update(); + return d_data->mass; +} + +//! Stop the flying movement of the wheel +void QwtWheel::stopFlying() +{ + if ( d_data->timerId != 0 ) + { + killTimer( d_data->timerId ); + d_data->timerId = 0; + d_data->speed = 0.0; + } +} + +double QwtWheel::boundedValue( double value ) const +{ + const double range = d_data->maximum - d_data->minimum; + + if ( d_data->wrapping && range >= 0.0 ) + { + if ( value < d_data->minimum ) + { + value += ::ceil( ( d_data->minimum - value ) / range ) * range; + } + else if ( value > d_data->maximum ) + { + value -= ::ceil( ( value - d_data->maximum ) / range ) * range; + } + } + else + { + value = qBound( d_data->minimum, value, d_data->maximum ); + } + + return value; +} + +double QwtWheel::alignedValue( double value ) const +{ + const double stepSize = d_data->singleStep; + + if ( stepSize > 0.0 ) + { + value = d_data->minimum + + qRound( ( value - d_data->minimum ) / stepSize ) * stepSize; + + if ( stepSize > 1e-12 ) + { + if ( qFuzzyCompare( value + 1.0, 1.0 ) ) + { + // correct rounding error if value = 0 + value = 0.0; + } + else if ( qFuzzyCompare( value, d_data->maximum ) ) + { + // correct rounding error at the border + value = d_data->maximum; + } + } + } + + return value; } diff --git a/libs/qwt/qwt_wheel.h b/libs/qwt/qwt_wheel.h index a9649ddffe..846543b843 100644 --- a/libs/qwt/qwt_wheel.h +++ b/libs/qwt/qwt_wheel.h @@ -11,71 +11,165 @@ #define QWT_WHEEL_H #include "qwt_global.h" -#include "qwt_abstract_slider.h" +#include <qwidget.h> /*! \brief The Wheel Widget The wheel widget can be used to change values over a very large range - in very small steps. Using the setMass member, it can be configured - as a flywheel. + in very small steps. Using the setMass() member, it can be configured + as a flying wheel. + + The default range of the wheel is [0.0, 100.0] \sa The radio example. */ -class QWT_EXPORT QwtWheel : public QwtAbstractSlider +class QWT_EXPORT QwtWheel: public QWidget { Q_OBJECT + + Q_PROPERTY( Qt::Orientation orientation + READ orientation WRITE setOrientation ) + + Q_PROPERTY( double value READ value WRITE setValue ) + Q_PROPERTY( double minimum READ minimum WRITE setMinimum ) + Q_PROPERTY( double maximum READ maximum WRITE setMaximum ) + + Q_PROPERTY( double singleStep READ singleStep WRITE setSingleStep ) + Q_PROPERTY( int pageStepCount READ pageStepCount WRITE setPageStepCount ) + Q_PROPERTY( bool stepAlignment READ stepAlignment WRITE setStepAlignment ) + + Q_PROPERTY( bool tracking READ isTracking WRITE setTracking ) + Q_PROPERTY( bool wrapping READ wrapping WRITE setWrapping ) + Q_PROPERTY( bool inverted READ isInverted WRITE setInverted ) + + Q_PROPERTY( double mass READ mass WRITE setMass ) + Q_PROPERTY( int updateInterval READ updateInterval WRITE setUpdateInterval ) + Q_PROPERTY( double totalAngle READ totalAngle WRITE setTotalAngle ) Q_PROPERTY( double viewAngle READ viewAngle WRITE setViewAngle ) - Q_PROPERTY( int tickCnt READ tickCnt WRITE setTickCnt ) - Q_PROPERTY( int internalBorder READ internalBorder WRITE setInternalBorder ) - Q_PROPERTY( double mass READ mass WRITE setMass ) + Q_PROPERTY( int tickCount READ tickCount WRITE setTickCount ) + Q_PROPERTY( int wheelWidth READ wheelWidth WRITE setWheelWidth ) + Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) + Q_PROPERTY( int wheelBorderWidth READ wheelBorderWidth WRITE setWheelBorderWidth ) public: - explicit QwtWheel(QWidget *parent = NULL); -#if QT_VERSION < 0x040000 - explicit QwtWheel(QWidget *parent, const char *name); -#endif + explicit QwtWheel( QWidget *parent = NULL ); virtual ~QwtWheel(); - virtual void setOrientation(Qt::Orientation); + double value() const; + + void setOrientation( Qt::Orientation ); + Qt::Orientation orientation() const; double totalAngle() const; double viewAngle() const; - int tickCnt() const; - int internalBorder() const; + + void setTickCount( int ); + int tickCount() const; + + void setWheelWidth( int ); + int wheelWidth() const; + + void setWheelBorderWidth( int ); + int wheelBorderWidth() const; + + void setBorderWidth( int ); + int borderWidth() const; + + void setInverted( bool tf ); + bool isInverted() const; + + void setWrapping( bool tf ); + bool wrapping() const; + + void setSingleStep( double ); + double singleStep() const; + + void setPageStepCount( int ); + int pageStepCount() const; + + void setStepAlignment( bool on ); + bool stepAlignment() const; + + void setRange( double vmin, double vmax ); + + void setMinimum( double min ); + double minimum() const; + + void setMaximum( double max ); + double maximum() const; + + void setUpdateInterval( int ); + int updateInterval() const; + + void setTracking( bool enable ); + bool isTracking() const; double mass() const; - void setTotalAngle (double angle); - void setTickCnt(int cnt); - void setViewAngle(double angle); - void setInternalBorder(int width); - void setMass(double val); - void setWheelWidth( int w ); +public Q_SLOTS: + void setValue( double ); + void setTotalAngle ( double ); + void setViewAngle( double ); + void setMass( double ); - virtual QSize sizeHint() const; - virtual QSize minimumSizeHint() const; +Q_SIGNALS: + + /*! + \brief Notify a change of value. + + When tracking is enabled this signal will be emitted every + time the value changes. + + \param value new value + \sa setTracking() + */ + void valueChanged( double value ); + + /*! + This signal is emitted when the user presses the + the wheel with the mouse + */ + void wheelPressed(); + + /*! + This signal is emitted when the user releases the mouse + */ + void wheelReleased(); + + /*! + This signal is emitted when the user moves the + wheel with the mouse. + + \param value new value + */ + void wheelMoved( double value ); protected: - virtual void resizeEvent(QResizeEvent *e); - virtual void paintEvent(QPaintEvent *e); + virtual void paintEvent( QPaintEvent * ); + virtual void mousePressEvent( QMouseEvent * ); + virtual void mouseReleaseEvent( QMouseEvent * ); + virtual void mouseMoveEvent( QMouseEvent * ); + virtual void keyPressEvent( QKeyEvent * ); + virtual void wheelEvent( QWheelEvent * ); + virtual void timerEvent( QTimerEvent * ); - void layoutWheel( bool update = true ); - void draw(QPainter *p, const QRect& update_rect); - void drawWheel(QPainter *p, const QRect &r); - void drawWheelBackground(QPainter *p, const QRect &r); - void setColorArray(); + void stopFlying(); + + QRect wheelRect() const; + + virtual QSize sizeHint() const; + virtual QSize minimumSizeHint() const; - virtual void valueChange(); - virtual void paletteChange( const QPalette &); + virtual void drawTicks( QPainter *, const QRectF & ); + virtual void drawWheelBackground( QPainter *, const QRectF & ); - virtual double getValue(const QPoint &p); - virtual void getScrollMode(const QPoint &p, - int &scrollMode, int &direction); + virtual double valueAt( const QPoint & ) const; private: - void initWheel(); + double alignedValue( double ) const; + double boundedValue( double ) const; class PrivateData; PrivateData *d_data; diff --git a/libs/qwt/qwt_widget_overlay.cpp b/libs/qwt/qwt_widget_overlay.cpp new file mode 100644 index 0000000000..07c6272e1e --- /dev/null +++ b/libs/qwt/qwt_widget_overlay.cpp @@ -0,0 +1,373 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_widget_overlay.h" +#include "qwt_painter.h" +#include <qpainter.h> +#include <qpaintengine.h> +#include <qimage.h> +#include <qevent.h> + +static QImage::Format qwtMaskImageFormat() +{ + if ( QwtPainter::isX11GraphicsSystem() ) + return QImage::Format_ARGB32; + + return QImage::Format_ARGB32_Premultiplied; +} + +static QRegion qwtAlphaMask( + const QImage& image, const QVector<QRect> rects ) +{ + const int w = image.width(); + const int h = image.height(); + + QRegion region; + QRect rect; + + for ( int i = 0; i < rects.size(); i++ ) + { + int x1, x2, y1, y2; + rects[i].getCoords( &x1, &y1, &x2, &y2 ); + + x1 = qMax( x1, 0 ); + x2 = qMin( x2, w - 1 ); + y1 = qMax( y1, 0 ); + y2 = qMin( y2, h - 1 ); + + for ( int y = y1; y <= y2; ++y ) + { + bool inRect = false; + int rx0 = -1; + + const uint *line = + reinterpret_cast<const uint *> ( image.scanLine( y ) ) + x1; + for ( int x = x1; x <= x2; x++ ) + { + const bool on = ( ( *line++ >> 24 ) != 0 ); + if ( on != inRect ) + { + if ( inRect ) + { + rect.setCoords( rx0, y, x - 1, y ); + region += rect; + } + else + { + rx0 = x; + } + + inRect = on; + } + } + + if ( inRect ) + { + rect.setCoords( rx0, y, x2, y ); + region = region.united( rect ); + } + } + } + + return region; +} + +class QwtWidgetOverlay::PrivateData +{ +public: + PrivateData(): + maskMode( QwtWidgetOverlay::MaskHint ), + renderMode( QwtWidgetOverlay::AutoRenderMode ), + rgbaBuffer( NULL ) + { + } + + ~PrivateData() + { + resetRgbaBuffer(); + } + + void resetRgbaBuffer() + { + if ( rgbaBuffer ) + { + ::free( rgbaBuffer ); + rgbaBuffer = NULL; + } + } + + MaskMode maskMode; + RenderMode renderMode; + uchar *rgbaBuffer; +}; + +/*! + \brief Constructor + \param widget Parent widget, where the overlay is aligned to +*/ +QwtWidgetOverlay::QwtWidgetOverlay( QWidget* widget ): + QWidget( widget ) +{ + d_data = new PrivateData; + + setAttribute( Qt::WA_TransparentForMouseEvents ); + setAttribute( Qt::WA_NoSystemBackground ); + setFocusPolicy( Qt::NoFocus ); + + if ( widget ) + { + resize( widget->size() ); + widget->installEventFilter( this ); + } +} + +//! Destructor +QwtWidgetOverlay::~QwtWidgetOverlay() +{ + delete d_data; +} + +/*! + \brief Specify how to find the mask for the overlay + + \param mode New mode + \sa maskMode() + */ +void QwtWidgetOverlay::setMaskMode( MaskMode mode ) +{ + if ( mode != d_data->maskMode ) + { + d_data->maskMode = mode; + d_data->resetRgbaBuffer(); + } +} + +/*! + \return Mode how to find the mask for the overlay + \sa setMaskMode() + */ +QwtWidgetOverlay::MaskMode QwtWidgetOverlay::maskMode() const +{ + return d_data->maskMode; +} + +/*! + Set the render mode + \param mode Render mode + + \sa RenderMode, renderMode() +*/ +void QwtWidgetOverlay::setRenderMode( RenderMode mode ) +{ + d_data->renderMode = mode; +} + +/*! + \return Render mode + \sa RenderMode, setRenderMode() + */ +QwtWidgetOverlay::RenderMode QwtWidgetOverlay::renderMode() const +{ + return d_data->renderMode; +} + +/*! + Recalculate the mask and repaint the overlay + */ +void QwtWidgetOverlay::updateOverlay() +{ + updateMask(); + update(); +} + +void QwtWidgetOverlay::updateMask() +{ + d_data->resetRgbaBuffer(); + + QRegion mask; + + if ( d_data->maskMode == QwtWidgetOverlay::MaskHint ) + { + mask = maskHint(); + } + else if ( d_data->maskMode == QwtWidgetOverlay::AlphaMask ) + { + // TODO: the image doesn't need to be larger than + // the bounding rectangle of the hint !! + + QRegion hint = maskHint(); + if ( hint.isEmpty() ) + hint += QRect( 0, 0, width(), height() ); + + // A fresh buffer from calloc() is usually faster + // than reinitializing an existing one with + // QImage::fill( 0 ) or memset() + + d_data->rgbaBuffer = ( uchar* )::calloc( width() * height(), 4 ); + + QImage image( d_data->rgbaBuffer, + width(), height(), qwtMaskImageFormat() ); + + QPainter painter( &image ); + draw( &painter ); + painter.end(); + + mask = qwtAlphaMask( image, hint.rects() ); + + if ( d_data->renderMode == QwtWidgetOverlay::DrawOverlay ) + { + // we don't need the buffer later + d_data->resetRgbaBuffer(); + } + } + + // A bug in Qt initiates a full repaint of the widget + // when we change the mask, while we are visible ! + + setVisible( false ); + + if ( mask.isEmpty() ) + clearMask(); + else + setMask( mask ); + + setVisible( true ); +} + +/*! + Paint event + \param event Paint event + + \sa drawOverlay() +*/ +void QwtWidgetOverlay::paintEvent( QPaintEvent* event ) +{ + const QRegion clipRegion = event->region(); + + QPainter painter( this ); + + bool useRgbaBuffer = false; + if ( d_data->renderMode == QwtWidgetOverlay::CopyAlphaMask ) + { + useRgbaBuffer = true; + } + else if ( d_data->renderMode == QwtWidgetOverlay::AutoRenderMode ) + { + if ( painter.paintEngine()->type() == QPaintEngine::Raster ) + useRgbaBuffer = true; + } + + if ( d_data->rgbaBuffer && useRgbaBuffer ) + { + const QImage image( d_data->rgbaBuffer, + width(), height(), qwtMaskImageFormat() ); + + QVector<QRect> rects; + if ( clipRegion.rects().size() > 2000 ) + { + // the region is to complex + painter.setClipRegion( clipRegion ); + rects += clipRegion.boundingRect(); + } + else + { + rects = clipRegion.rects(); + } + + for ( int i = 0; i < rects.size(); i++ ) + { + const QRect r = rects[i]; + painter.drawImage( r.topLeft(), image, r ); + } + } + else + { + painter.setClipRegion( clipRegion ); + draw( &painter ); + } +} + +/*! + Resize event + \param event Resize event +*/ +void QwtWidgetOverlay::resizeEvent( QResizeEvent* event ) +{ + Q_UNUSED( event ); + + d_data->resetRgbaBuffer(); +} + +void QwtWidgetOverlay::draw( QPainter *painter ) const +{ + QWidget *widget = const_cast< QWidget *>( parentWidget() ); + if ( widget ) + { + painter->setClipRect( parentWidget()->contentsRect() ); + + // something special for the plot canvas + QPainterPath clipPath; + + ( void )QMetaObject::invokeMethod( + widget, "borderPath", Qt::DirectConnection, + Q_RETURN_ARG( QPainterPath, clipPath ), Q_ARG( QRect, rect() ) ); + + if (!clipPath.isEmpty()) + { + painter->setClipPath( clipPath, Qt::IntersectClip ); + } + } + + drawOverlay( painter ); +} + +/*! + \brief Calculate an approximation for the mask + + - MaskHint + The hint is used as mask. + + - AlphaMask + The hint is used to speed up the algorithm + for calculating a mask from non transparent pixels + + - NoMask + The hint is unused. + + The default implementation returns an invalid region + indicating no hint. + + \return Hint for the mask + */ +QRegion QwtWidgetOverlay::maskHint() const +{ + return QRegion(); +} + +/*! + \brief Event filter + + Resize the overlay according to the size of the parent widget. + + \param object Object to be filtered + \param event Event + + \return See QObject::eventFilter() +*/ + +bool QwtWidgetOverlay::eventFilter( QObject* object, QEvent* event ) +{ + if ( object == parent() && event->type() == QEvent::Resize ) + { + QResizeEvent *resizeEvent = static_cast<QResizeEvent *>( event ); + resize( resizeEvent->size() ); + } + + return QObject::eventFilter( object, event ); +} diff --git a/libs/qwt/qwt_widget_overlay.h b/libs/qwt/qwt_widget_overlay.h new file mode 100644 index 0000000000..40d45510b1 --- /dev/null +++ b/libs/qwt/qwt_widget_overlay.h @@ -0,0 +1,148 @@ +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_WIDGET_OVERLAY_H +#define QWT_WIDGET_OVERLAY_H + +#include "qwt_global.h" +#include <qwidget.h> +#include <qregion.h> + +class QPainter; + +/*! + \brief An overlay for a widget + + The main use case of an widget overlay is to avoid + heavy repaint operation of the widget below. + + F.e. in combination with the plot canvas an overlay + avoid replots as the content of the canvas can be restored from + its backing store. + + QwtWidgetOverlay is an abstract base class. Deriving classes are + supposed to reimplement the following methods: + + - drawOverlay() + - maskHint() + + Internally QwtPlotPicker uses overlays for displaying + the rubber band and the tracker text. + + \sa QwtPlotCanvas::BackingStore + */ +class QWT_EXPORT QwtWidgetOverlay: public QWidget +{ +public: + /*! + \brief Mask mode + + When using masks the widget below gets paint events for + the masked regions of the overlay only. Otherwise + Qt triggers full repaints. On less powerful hardware + ( f.e embedded systems ) - or when using the raster paint + engine on a remote desktop - bit blitting is a noticeable + operation, that needs to be avoided. + + If and how to mask depends on how expensive the calculation + of the mask is and how many pixels can be excluded by the mask. + + The default setting is MaskHint. + + \sa setMaskMode(), maskMode() + */ + enum MaskMode + { + //! Don't use a mask. + NoMask, + + /*! + \brief Use maskHint() as mask + + For many situations a fast approximation is good enough + and it is not necessary to build a more detailed mask + ( f.e the bounding rectangle of a text ). + */ + MaskHint, + + /*! + \brief Calculate a mask by checking the alpha values + + Sometimes it is not possible to give a fast approximation + and the mask needs to be calculated by drawing the overlay + and testing the result. + + When a valid maskHint() is available + only pixels inside this approximation are checked. + */ + AlphaMask + }; + + /*! + \brief Render mode + + For calculating the alpha mask the overlay has already + been painted to a temporary QImage. Instead of rendering + the overlay twice this buffer can be copied for drawing + the overlay. + + On graphic systems using the raster paint engine ( QWS, Windows ) + it means usually copying some memory only. On X11 it results in an + expensive operation building a pixmap and for simple overlays + it might not be recommended. + + \note The render mode has no effect, when maskMode() != AlphaMask. + */ + enum RenderMode + { + //! Copy the buffer, when using the raster paint engine. + AutoRenderMode, + + //! Always copy the buffer + CopyAlphaMask, + + //! Never copy the buffer + DrawOverlay + }; + + QwtWidgetOverlay( QWidget* ); + virtual ~QwtWidgetOverlay(); + + void setMaskMode( MaskMode ); + MaskMode maskMode() const; + + void setRenderMode( RenderMode ); + RenderMode renderMode() const; + + void updateOverlay(); + + virtual bool eventFilter( QObject *, QEvent *); + +protected: + virtual void paintEvent( QPaintEvent* event ); + virtual void resizeEvent( QResizeEvent* event ); + + virtual QRegion maskHint() const; + + /*! + Draw the widget overlay + \param painter Painter + */ + virtual void drawOverlay( QPainter *painter ) const = 0; + +private: + void updateMask(); + void draw( QPainter * ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif -- GitLab From ff6ecfe63f0a6f85fcb60e7a2a8f9062a896e245 Mon Sep 17 00:00:00 2001 From: Bryant <bwmairs@ucsc.edu> Date: Wed, 25 Jun 2014 18:57:04 -0700 Subject: [PATCH 47/53] Now update QGC to use the new Qwt 6.1 code. I was unsure how to update the QwtPlotPrintFilter code, so I just commented it out with a FIXME. --- QGCExternalLibs.pri | 4 +- src/ui/QGCDataPlot2D.cc | 45 +++++++------- src/ui/RadioCalibration/CurveCalibrator.cc | 6 +- src/ui/RadioCalibration/CurveCalibrator.h | 1 - src/ui/designer/QGCXYPlot.cc | 7 +-- src/ui/linechart/ChartPlot.cc | 11 ++-- src/ui/linechart/IncrementalPlot.cc | 70 +++++++++++----------- src/ui/linechart/IncrementalPlot.h | 5 +- src/ui/linechart/LinechartPlot.cc | 42 +++++-------- src/ui/linechart/LinechartPlot.h | 2 +- src/ui/linechart/ScrollZoomer.h | 1 + 11 files changed, 91 insertions(+), 103 deletions(-) diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index ce80c1a782..cbd86a9c52 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -320,7 +320,9 @@ INCLUDEPATH += \ # # [REQUIRED] QWT plotting library dependency. Provides plotting capabilities. # -include(libs/qwt/qwt.pri) +include(libs/qwt.pri) +DEPENDPATH += libs/qwt +INCLUDEPATH += libs/qwt # # [REQUIRED] QSerialPort library. Provides serial port wrapper library. diff --git a/src/ui/QGCDataPlot2D.cc b/src/ui/QGCDataPlot2D.cc index 4a24151a14..b8c15d1750 100644 --- a/src/ui/QGCDataPlot2D.cc +++ b/src/ui/QGCDataPlot2D.cc @@ -172,19 +172,20 @@ void QGCDataPlot2D::print() if ( dialog.exec() ) { plot->setStyleSheet("QWidget { background-color: #FFFFFF; color: #000000; background-clip: border; font-size: 10pt;}"); plot->setCanvasBackground(Qt::white); - QwtPlotPrintFilter filter; - filter.color(Qt::white, QwtPlotPrintFilter::CanvasBackground); - filter.color(Qt::black, QwtPlotPrintFilter::AxisScale); - filter.color(Qt::black, QwtPlotPrintFilter::AxisTitle); - filter.color(Qt::black, QwtPlotPrintFilter::MajorGrid); - filter.color(Qt::black, QwtPlotPrintFilter::MinorGrid); - if ( printer.colorMode() == QPrinter::GrayScale ) { - int options = QwtPlotPrintFilter::PrintAll; - options &= ~QwtPlotPrintFilter::PrintBackground; - options |= QwtPlotPrintFilter::PrintFrameWithScales; - filter.setOptions(options); - } - plot->print(printer, filter); + // FIXME: QwtPlotPrintFilter no longer exists in Qwt 6.1 + //QwtPlotPrintFilter filter; + //filter.color(Qt::white, QwtPlotPrintFilter::CanvasBackground); + //filter.color(Qt::black, QwtPlotPrintFilter::AxisScale); + //filter.color(Qt::black, QwtPlotPrintFilter::AxisTitle); + //filter.color(Qt::black, QwtPlotPrintFilter::MajorGrid); + //filter.color(Qt::black, QwtPlotPrintFilter::MinorGrid); + //if ( printer.colorMode() == QPrinter::GrayScale ) { + // int options = QwtPlotPrintFilter::PrintAll; + // options &= ~QwtPlotPrintFilter::PrintBackground; + // options |= QwtPlotPrintFilter::PrintFrameWithScales; + // filter.setOptions(options); + //} + //plot->print(printer); plot->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; font-size: 11pt;}"); //plot->setCanvasBackground(QColor(5, 5, 8)); } @@ -210,6 +211,7 @@ void QGCDataPlot2D::exportPDF(QString fileName) plot->setStyleSheet("QWidget { background-color: #FFFFFF; color: #000000; background-clip: border; font-size: 10pt;}"); // plot->setCanvasBackground(Qt::white); + // FIXME: QwtPlotPrintFilter no longer exists in Qwt 6.1 // QwtPlotPrintFilter filter; // filter.color(Qt::white, QwtPlotPrintFilter::CanvasBackground); // filter.color(Qt::black, QwtPlotPrintFilter::AxisScale); @@ -223,7 +225,7 @@ void QGCDataPlot2D::exportPDF(QString fileName) // options |= QwtPlotPrintFilter::PrintFrameWithScales; // filter.setOptions(options); // } - plot->print(printer);//, filter); + //plot->print(printer); plot->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; font-size: 11pt;}"); //plot->setCanvasBackground(QColor(5, 5, 8)); } @@ -237,14 +239,15 @@ void QGCDataPlot2D::exportSVG(QString fileName) generator.setFileName(fileName); generator.setSize(QSize(800, 600)); - QwtPlotPrintFilter filter; - filter.color(Qt::white, QwtPlotPrintFilter::CanvasBackground); - filter.color(Qt::black, QwtPlotPrintFilter::AxisScale); - filter.color(Qt::black, QwtPlotPrintFilter::AxisTitle); - filter.color(Qt::black, QwtPlotPrintFilter::MajorGrid); - filter.color(Qt::black, QwtPlotPrintFilter::MinorGrid); + // FIXME: QwtPlotPrintFilter no longer exists in Qwt 6.1 + //QwtPlotPrintFilter filter; + //filter.color(Qt::white, QwtPlotPrintFilter::CanvasBackground); + //filter.color(Qt::black, QwtPlotPrintFilter::AxisScale); + //filter.color(Qt::black, QwtPlotPrintFilter::AxisTitle); + //filter.color(Qt::black, QwtPlotPrintFilter::MajorGrid); + //filter.color(Qt::black, QwtPlotPrintFilter::MinorGrid); - plot->print(generator, filter); + //plot->print(generator); plot->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; font-size: 11pt;}"); } } diff --git a/src/ui/RadioCalibration/CurveCalibrator.cc b/src/ui/RadioCalibration/CurveCalibrator.cc index 9ef8ec58b4..5fb3d2456b 100644 --- a/src/ui/RadioCalibration/CurveCalibrator.cc +++ b/src/ui/RadioCalibration/CurveCalibrator.cc @@ -42,7 +42,7 @@ CurveCalibrator::CurveCalibrator(QString titleString, QWidget *parent) : set[i] = static_cast<double>((*setpoints)[i]); } - curve->setData(pos, set); + curve->setSamples(pos, set); curve->attach(plot); plot->replot(); @@ -99,7 +99,7 @@ void CurveCalibrator::setSetpoint(int setpoint) set[i] = static_cast<double>((*setpoints)[i]); } - curve->setData(pos, set); + curve->setSamples(pos, set); plot->replot(); emit setpointChanged(setpoint, setpoints->value(setpoint)); @@ -118,7 +118,7 @@ void CurveCalibrator::set(const QVector<uint16_t> &data) pos[i] = static_cast<double>((*positions)[i]); set[i] = static_cast<double>((*setpoints)[i]); } - curve->setData(pos, set); + curve->setSamples(pos, set); plot->replot(); } else { qDebug() << __FILE__ << __LINE__ << ": wrong data vector size"; diff --git a/src/ui/RadioCalibration/CurveCalibrator.h b/src/ui/RadioCalibration/CurveCalibrator.h index 1f4c0b1e9d..9a4dec9220 100644 --- a/src/ui/RadioCalibration/CurveCalibrator.h +++ b/src/ui/RadioCalibration/CurveCalibrator.h @@ -34,7 +34,6 @@ This file is part of the QGROUNDCONTROL project #include <QVector> #include <qwt_plot.h> #include <qwt_plot_curve.h> -//#include <qwt_array.h> #include <QGridLayout> #include <QHBoxLayout> #include <QLabel> diff --git a/src/ui/designer/QGCXYPlot.cc b/src/ui/designer/QGCXYPlot.cc index a258feedf2..5df799a35a 100644 --- a/src/ui/designer/QGCXYPlot.cc +++ b/src/ui/designer/QGCXYPlot.cc @@ -116,9 +116,8 @@ public: return QwtDoubleRect(xmin,ymin,xmax-xmin,ymax-ymin); } -protected: /* From QwtPlotItem. Draw the complete series */ - virtual void draw (QPainter *p, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QRect &canvasRect) const + virtual void draw (QPainter *p, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QRectF &canvasRect) const { Q_UNUSED(canvasRect); QPointF lastPoint; @@ -151,7 +150,7 @@ protected: ++smoothCount; point = smoothTotal/smoothCount; } - QPointF paintCoord = QPointF(xMap.xTransform(point.x()), yMap.xTransform(point.y())); + QPointF paintCoord = QPointF(xMap.transform(point.x()), yMap.transform(point.y())); m_color.setAlpha((m_maxShowPoints - count + i)*255/m_maxShowPoints); p->setPen(m_color); if(i != 0) @@ -246,7 +245,7 @@ QGCXYPlot::~QGCXYPlot() void QGCXYPlot::clearPlot() { xycurve->clear(); - plot->clear(); + plot->detachItems(); ui->timeScrollBar->setMaximum(xycurve->dataSize()); ui->timeScrollBar->setValue(ui->timeScrollBar->maximum()); } diff --git a/src/ui/linechart/ChartPlot.cc b/src/ui/linechart/ChartPlot.cc index a1741f85cf..e6d5b6db0b 100644 --- a/src/ui/linechart/ChartPlot.cc +++ b/src/ui/linechart/ChartPlot.cc @@ -41,7 +41,8 @@ ChartPlot::ChartPlot(QWidget *parent): grid->attach(this); // Enable zooming - zoomer = new ScrollZoomer(canvas()); + QwtPlotCanvas *c = static_cast<QwtPlotCanvas*>(canvas()); + zoomer = new ScrollZoomer(c); colors = QList<QColor>(); @@ -113,8 +114,8 @@ void ChartPlot::styleChanged(MainWindow::QGC_MAINWINDOW_STYLE style) setCanvasBackground(QColor(0xFF, 0xFF, 0xFF)); // Configure the plot grid. - grid->setMinPen(QPen(QColor(0x55, 0x55, 0x55), gridWidth, Qt::DotLine)); - grid->setMajPen(QPen(QColor(0x22, 0x22, 0x22), gridWidth, Qt::DotLine)); + grid->setMinorPen(QPen(QColor(0x55, 0x55, 0x55), gridWidth, Qt::DotLine)); + grid->setMajorPen(QPen(QColor(0x22, 0x22, 0x22), gridWidth, Qt::DotLine)); } else { @@ -126,8 +127,8 @@ void ChartPlot::styleChanged(MainWindow::QGC_MAINWINDOW_STYLE style) setCanvasBackground(QColor(0, 0, 0)); // Configure the plot grid. - grid->setMinPen(QPen(QColor(0xAA, 0xAA, 0xAA), gridWidth, Qt::DotLine)); - grid->setMajPen(QPen(QColor(0xDD, 0xDD, 0xDD), gridWidth, Qt::DotLine)); + grid->setMinorPen(QPen(QColor(0xAA, 0xAA, 0xAA), gridWidth, Qt::DotLine)); + grid->setMajorPen(QPen(QColor(0xDD, 0xDD, 0xDD), gridWidth, Qt::DotLine)); } // And finally refresh the widget to make sure all color changes are redrawn. diff --git a/src/ui/linechart/IncrementalPlot.cc b/src/ui/linechart/IncrementalPlot.cc index 5826d09d39..a06077dab3 100644 --- a/src/ui/linechart/IncrementalPlot.cc +++ b/src/ui/linechart/IncrementalPlot.cc @@ -132,7 +132,7 @@ void IncrementalPlot::showLegend(bool show) if (legend == NULL) { legend = new QwtLegend; legend->setFrameStyle(QFrame::Box); - legend->setItemMode(QwtLegend::CheckableItem); + legend->setDefaultItemMode(QwtLegendData::Checkable); } insertLegend(legend, QwtPlot::RightLegend); } else { @@ -168,30 +168,32 @@ void IncrementalPlot::updateStyle(QwtPlotCurve *curve) { if(styleText.isNull()) return; - // Style of datapoints + + // Since the symbols always use the same color as the curve line, we just use that color. + // This saves us from having to deal with cases where the symbol is NULL. + QColor oldColor = curve->pen().color(); + + // Update the symbol style + QwtSymbol *newSymbol = NULL; if (styleText.contains("circles")) { - curve->setSymbol(QwtSymbol(QwtSymbol::Ellipse, - Qt::NoBrush, QPen(QBrush(curve->symbol().pen().color()), symbolWidth), QSize(6, 6)) ); + newSymbol = new QwtSymbol(QwtSymbol::Ellipse, Qt::NoBrush, QPen(oldColor, symbolWidth), QSize(6, 6)); } else if (styleText.contains("crosses")) { - curve->setSymbol(QwtSymbol(QwtSymbol::XCross, - Qt::NoBrush, QPen(QBrush(curve->symbol().pen().color()), symbolWidth), QSize(5, 5)) ); + newSymbol = new QwtSymbol(QwtSymbol::XCross, Qt::NoBrush, QPen(oldColor, symbolWidth), QSize(5, 5)); } else if (styleText.contains("rect")) { - curve->setSymbol(QwtSymbol(QwtSymbol::Rect, - Qt::NoBrush, QPen(QBrush(curve->symbol().pen().color()), symbolWidth), QSize(6, 6)) ); - } else if (styleText.contains("line")) { // Show no symbol - curve->setSymbol(QwtSymbol(QwtSymbol::NoSymbol, - Qt::NoBrush, QPen(QBrush(curve->symbol().pen().color()), symbolWidth), QSize(6, 6)) ); + newSymbol = new QwtSymbol(QwtSymbol::Rect, Qt::NoBrush, QPen(oldColor, symbolWidth), QSize(6, 6)); } + // Else-case already handled by NULL value, which indicates no symbol + curve->setSymbol(newSymbol); - // Style of lines + // Update the line style if (styleText.contains("dotted")) { - curve->setPen(QPen(QBrush(curve->symbol().pen().color()), curveWidth, Qt::DotLine)); + curve->setPen(QPen(oldColor, curveWidth, Qt::DotLine)); } else if (styleText.contains("dashed")) { - curve->setPen(QPen(QBrush(curve->symbol().pen().color()), curveWidth, Qt::DashLine)); + curve->setPen(QPen(oldColor, curveWidth, Qt::DashLine)); } else if (styleText.contains("line") || styleText.contains("solid")) { - curve->setPen(QPen(QBrush(curve->symbol().pen().color()), curveWidth, Qt::SolidLine)); + curve->setPen(QPen(oldColor, curveWidth, Qt::SolidLine)); } else { - curve->setPen(QPen(QBrush(curve->symbol().pen().color()), curveWidth, Qt::NoPen)); + curve->setPen(QPen(oldColor, curveWidth, Qt::NoPen)); } curve->setStyle(QwtPlotCurve::Lines); } @@ -273,23 +275,27 @@ void IncrementalPlot::appendData(const QString &key, double *x, double *y, int s data = d_data.value(key); } + // If this is a new curve, create it. if (!curves.contains(key)) { curve = new QwtPlotCurve(key); curves.insert(key, curve); curve->setStyle(QwtPlotCurve::NoCurve); - curve->setPaintAttribute(QwtPlotCurve::PaintFiltered); + curve->setPaintAttribute(QwtPlotCurve::FilterPoints); + // Set the color. Only the pen needs to be set const QColor &c = getNextColor(); - curve->setSymbol(QwtSymbol(QwtSymbol::XCross, - QBrush(c), QPen(c, symbolWidth), QSize(5, 5)) ); - updateStyle(curve); //Apply any user-set style + curve->setPen(c, symbolWidth); + + qDebug() << "Creating curve" << key << "with color" << c; + + updateStyle(curve); curve->attach(this); } else { curve = curves.value(key); } data->append(x, y, size); - curve->setRawData(data->x(), data->y(), data->count()); + curve->setRawSamples(data->x(), data->y(), data->count()); bool scaleChanged = false; @@ -326,17 +332,10 @@ void IncrementalPlot::appendData(const QString &key, double *x, double *y, int s updateScale(); } else { - const bool cacheMode = - canvas()->testPaintAttribute(QwtPlotCanvas::PaintCached); - -#if QT_VERSION >= 0x040000 && defined(Q_WS_X11) - // Even if not recommended by TrollTech, Qt::WA_PaintOutsidePaintEvent - // works on X11. This has an tremendous effect on the performance.. - - canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, true); -#endif + QwtPlotCanvas *c = static_cast<QwtPlotCanvas*>(canvas()); + const bool cacheMode = c->testPaintAttribute(QwtPlotCanvas::BackingStore); - canvas()->setPaintAttribute(QwtPlotCanvas::PaintCached, false); + c->setPaintAttribute(QwtPlotCanvas::BackingStore, false); // FIXME Check if here all curves should be drawn // QwtPlotCurve* plotCurve; // foreach(plotCurve, curves) @@ -344,12 +343,11 @@ void IncrementalPlot::appendData(const QString &key, double *x, double *y, int s // plotCurve->draw(0, curve->dataSize()-1); // } - curve->draw(curve->dataSize() - size, curve->dataSize() - 1); - canvas()->setPaintAttribute(QwtPlotCanvas::PaintCached, cacheMode); + // FIXME: Unsure what this call should be now. + //curve->draw(curve->dataSize() - size, curve->dataSize() - 1); + replot(); + c->setPaintAttribute(QwtPlotCanvas::BackingStore, cacheMode); -#if QT_VERSION >= 0x040000 && defined(Q_WS_X11) - canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, false); -#endif } } diff --git a/src/ui/linechart/IncrementalPlot.h b/src/ui/linechart/IncrementalPlot.h index 66f2b07347..3988556c54 100644 --- a/src/ui/linechart/IncrementalPlot.h +++ b/src/ui/linechart/IncrementalPlot.h @@ -32,7 +32,6 @@ This file is part of the QGROUNDCONTROL project #define INCREMENTALPLOT_H #include <QTimer> -#include <qwt_array.h> #include <qwt_plot.h> #include <qwt_legend.h> #include <QMap> @@ -59,8 +58,8 @@ public: private: int d_count; - QwtArray<double> d_x; - QwtArray<double> d_y; + QVector<double> d_x; + QVector<double> d_y; }; /** diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc index f65134499d..3916338a6c 100644 --- a/src/ui/linechart/LinechartPlot.cc +++ b/src/ui/linechart/LinechartPlot.cc @@ -277,7 +277,7 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value) // Assign dataset to curve QwtPlotCurve* curve = curves.value(dataname); - curve->setRawData(dataset->getPlotX(), dataset->getPlotY(), dataset->getPlotCount()); + curve->setRawSamples(dataset->getPlotX(), dataset->getPlotY(), dataset->getPlotCount()); // qDebug() << "mintime" << minTime << "maxtime" << maxTime << "last max time" << "window position" << getWindowPosition(); @@ -324,7 +324,7 @@ void LinechartPlot::addCurve(QString id) curves.insert(id, curve); curve->setStyle(QwtPlotCurve::Lines); - curve->setPaintAttribute(QwtPlotCurve::PaintFiltered); + curve->setPaintAttribute(QwtPlotCurve::FilterPoints, true); setCurveColor(id, currentColor); //curve->setBrush(currentColor); Leads to a filled curve // curve->setRenderHint(QwtPlotItem::RenderAntialiased); @@ -468,10 +468,18 @@ void LinechartPlot::showCurve(QString id) void LinechartPlot::setCurveColor(QString id, QColor color) { QwtPlotCurve* curve = curves.value(id); + // Change the color of the curve. curve->setPen(QPen(QBrush(color), curveWidth)); - QwtSymbol x = curve->symbol(); - x.setPen(QPen(QBrush(color), symbolWidth)); - curve->setSymbol(x); + + qDebug() << "Setting curve" << id << "to" << color; + + // And change the color of the symbol, making sure to preserve the symbol style + const QwtSymbol *oldSymbol = curve->symbol(); + QwtSymbol *newSymbol = NULL; + if (oldSymbol) { + newSymbol = new QwtSymbol(oldSymbol->style(), QBrush(color), QPen(color, symbolWidth), QSize(symbolWidth, symbolWidth)); + } + curve->setSymbol(newSymbol); } /** @@ -609,7 +617,7 @@ quint64 LinechartPlot::getDataInterval() **/ void LinechartPlot::setLogarithmicScaling() { - yScaleEngine = new QwtLog10ScaleEngine(); + yScaleEngine = new QwtLogScaleEngine(); setAxisScaleEngine(QwtPlot::yLeft, yScaleEngine); } @@ -671,24 +679,6 @@ void LinechartPlot::paintRealtime() windowLock.unlock(); - // Defined both on windows 32- and 64 bit -#if !(defined Q_OS_WIN) - - // const bool cacheMode = - // canvas()->testPaintAttribute(QwtPlotCanvas::PaintCached); - const bool oldDirectPaint = - canvas()->testAttribute(Qt::WA_PaintOutsidePaintEvent); - - const QPaintEngine *pe = canvas()->paintEngine(); - bool directPaint = pe->hasFeature(QPaintEngine::PaintOutsidePaintEvent); - //if ( pe->type() == QPaintEngine::X11 ) { - // Even if not recommended by TrollTech, Qt::WA_PaintOutsidePaintEvent - // works on X11. This has an tremendous effect on the performance.. - directPaint = true; - //} - canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, directPaint); -#endif - // Only set current view as zoombase if zoomer is not active // else we could not zoom out any more @@ -698,10 +688,6 @@ void LinechartPlot::paintRealtime() replot(); } -#if !(defined Q_OS_WIN) - canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, oldDirectPaint); -#endif - /* QMap<QString, QwtPlotCurve*>::iterator i; diff --git a/src/ui/linechart/LinechartPlot.h b/src/ui/linechart/LinechartPlot.h index 5d19f5c53c..be5c29bf9f 100644 --- a/src/ui/linechart/LinechartPlot.h +++ b/src/ui/linechart/LinechartPlot.h @@ -45,7 +45,7 @@ This file is part of the PIXHAWK project #include <qwt_scale_draw.h> #include <qwt_scale_widget.h> #include <qwt_scale_engine.h> -#include <qwt_array.h> +#include <qwt_compat.h> #include <qwt_plot.h> #include "ChartPlot.h" #include "MG.h" diff --git a/src/ui/linechart/ScrollZoomer.h b/src/ui/linechart/ScrollZoomer.h index b4e12b52dd..fbbbe18f26 100644 --- a/src/ui/linechart/ScrollZoomer.h +++ b/src/ui/linechart/ScrollZoomer.h @@ -6,6 +6,7 @@ #include <qscrollview.h> #endif #include <qwt_plot_zoomer.h> +#include <qwt_plot_canvas.h> class ScrollData; class ScrollBar; -- GitLab From 61be9117163c17f85c71b13553c2f0b929983283 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Thu, 26 Jun 2014 11:52:47 +0200 Subject: [PATCH 48/53] Fixed unused param warnings --- src/uas/QGXPX4UAS.cc | 3 +++ src/uas/UAS.h | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/uas/QGXPX4UAS.cc b/src/uas/QGXPX4UAS.cc index 723c7d4836..a64c53ee82 100644 --- a/src/uas/QGXPX4UAS.cc +++ b/src/uas/QGXPX4UAS.cc @@ -20,6 +20,9 @@ void QGXPX4UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) void QGXPX4UAS::processParamValueMsgHook(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue) { + Q_UNUSED(rawValue); + Q_UNUSED(paramValue); + int compId = msg.compid; if (paramName == "SYS_AUTOSTART") { diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 82777bc332..ca048d4c2b 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -974,7 +974,7 @@ protected: quint64 getUnixReferenceTime(quint64 time); virtual void processParamValueMsg(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue); - virtual void processParamValueMsgHook(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue) {}; + virtual void processParamValueMsgHook(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue) { Q_UNUSED(msg); Q_UNUSED(paramName); Q_UNUSED(rawValue); Q_UNUSED(paramValue); }; int componentID[256]; bool componentMulti[256]; -- GitLab From 7e9c2bef8c5703723f1011522ea92a3893dc484c Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lm@inf.ethz.ch> Date: Thu, 26 Jun 2014 14:05:09 +0200 Subject: [PATCH 49/53] Fix warning in waypoint class --- src/Waypoint.cc | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/Waypoint.cc b/src/Waypoint.cc index 33e0bf62a8..4a96042c9f 100644 --- a/src/Waypoint.cc +++ b/src/Waypoint.cc @@ -194,11 +194,9 @@ void Waypoint::setAction(MAV_CMD action) // Flick defaults according to WP type - switch (this->action) { - case MAV_CMD_NAV_TAKEOFF: + if (this->action == MAV_CMD_NAV_TAKEOFF) { // We default to 15 degrees minimum takeoff pitch this->param1 = 15.0; - break; } emit changed(this); -- GitLab From 92af88b41d25e39443a524ebf515d6aaa3ace014 Mon Sep 17 00:00:00 2001 From: Don Gagne <don@thegagnes.com> Date: Thu, 26 Jun 2014 10:17:20 -0700 Subject: [PATCH 50/53] Fix linux release build --- src/ui/QGCHilFlightGearConfiguration.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc index 0488fbbd08..f1f7f584c5 100644 --- a/src/ui/QGCHilFlightGearConfiguration.cc +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -77,6 +77,7 @@ QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav, QWidget * Q_ASSERT(success); success = connect(_ui.optionsPlainTextEdit, SIGNAL(customContextMenuRequested(const QPoint&)), this, SLOT(_showContextMenu(const QPoint &))); Q_ASSERT(success); + Q_UNUSED(success); // Silence release build unused variable warning } QGCHilFlightGearConfiguration::~QGCHilFlightGearConfiguration() -- GitLab From af8ad534c2b074df2c9d3d7953a0f4d9f2b40e44 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Thu, 26 Jun 2014 19:39:25 -0700 Subject: [PATCH 51/53] Remove use of Qwt5.x types as they're now deprecated. --- src/ui/linechart/LinechartPlot.h | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/src/ui/linechart/LinechartPlot.h b/src/ui/linechart/LinechartPlot.h index be5c29bf9f..f47363dce1 100644 --- a/src/ui/linechart/LinechartPlot.h +++ b/src/ui/linechart/LinechartPlot.h @@ -45,7 +45,6 @@ This file is part of the PIXHAWK project #include <qwt_scale_draw.h> #include <qwt_scale_widget.h> #include <qwt_scale_engine.h> -#include <qwt_compat.h> #include <qwt_plot.h> #include "ChartPlot.h" #include "MG.h" @@ -134,14 +133,14 @@ protected: private: quint64 count; - QwtArray<double> ms; - QwtArray<double> value; + QVector<double> ms; + QVector<double> value; double mean; double median; double variance; unsigned int averageWindow; - QwtArray<double> outputMs; - QwtArray<double> outputValue; + QVector<double> outputMs; + QVector<double> outputValue; }; -- GitLab From 514ef5ca2ca97735ce88a7782841843ac4cb8ec7 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Thu, 26 Jun 2014 19:40:56 -0700 Subject: [PATCH 52/53] Fix for ScrollZoomer being updated for Qwt6.x. --- src/ui/linechart/ScrollZoomer.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/ui/linechart/ScrollZoomer.cc b/src/ui/linechart/ScrollZoomer.cc index e497cfc3e0..3bf2ab5546 100644 --- a/src/ui/linechart/ScrollZoomer.cc +++ b/src/ui/linechart/ScrollZoomer.cc @@ -439,9 +439,9 @@ void ScrollZoomer::layoutScrollBars(const QRect &rect) void ScrollZoomer::scrollBarMoved(Qt::Orientation o, double min, double) { if ( o == Qt::Horizontal ) - move(min, zoomRect().top()); + move(QPoint(min, zoomRect().top())); else - move(zoomRect().left(), min); + move(QPoint(zoomRect().left(), min)); emit zoomed(zoomRect()); } -- GitLab From c50336321da822366a737b5b17ea05313fde7988 Mon Sep 17 00:00:00 2001 From: Bryant Mairs <bwmairs@gmail.com> Date: Thu, 26 Jun 2014 19:43:19 -0700 Subject: [PATCH 53/53] Update Qwt6.x update for QGCXYPlot.cc as QwtDoubleRectno longer exists --- src/ui/designer/QGCXYPlot.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/ui/designer/QGCXYPlot.cc b/src/ui/designer/QGCXYPlot.cc index 5df799a35a..7a83b5e4d3 100644 --- a/src/ui/designer/QGCXYPlot.cc +++ b/src/ui/designer/QGCXYPlot.cc @@ -110,10 +110,10 @@ public: double yMin() const { return ymin; } double yMax() const { return ymax; } - virtual QwtDoubleRect boundingRect() const { + virtual QRectF boundingRect() const { if(!minMaxSet) - return QwtDoubleRect(1,1,-2,-2); - return QwtDoubleRect(xmin,ymin,xmax-xmin,ymax-ymin); + return QRectF(1,1,-2,-2); + return QRectF(xmin,ymin,xmax-xmin,ymax-ymin); } /* From QwtPlotItem. Draw the complete series */ -- GitLab