HDDisplay.cc 40.5 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2 3 4 5 6 7 8 9 10 11 12 13
/*=====================================================================
======================================================================*/

/**
 * @file
 *   @brief Implementation of Head Down Display (HDD)
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QFile>
#include <QGLWidget>
pixhawk's avatar
pixhawk committed
14
#include <QStringList>
15
#include <QGraphicsTextItem>
16 17
#include <QDockWidget>
#include <QInputDialog>
18
#include <QMouseEvent>
19 20
#include <QMenu>
#include <QSettings>
21
#include <qmath.h>
pixhawk's avatar
pixhawk committed
22 23 24
#include "UASManager.h"
#include "HDDisplay.h"
#include "ui_HDDisplay.h"
25
#include "MG.h"
26
#include "QGC.h"
27
#include "MainWindow.h"
pixhawk's avatar
pixhawk committed
28 29
#include <QDebug>

30
HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53
    QGraphicsView(parent),
    uas(NULL),
    xCenterOffset(0.0f),
    yCenterOffset(0.0f),
    vwidth(80.0f),
    vheight(80.0f),
    backgroundColor(QColor(0, 0, 0)),
    defaultColor(QColor(70, 200, 70)),
    setPointColor(QColor(200, 20, 200)),
    warningColor(Qt::yellow),
    criticalColor(Qt::red),
    infoColor(QColor(20, 200, 20)),
    fuelColor(criticalColor),
    warningBlinkRate(5),
    refreshTimer(new QTimer(this)),
    hardwareAcceleration(true),
    strongStrokeWidth(1.5f),
    normalStrokeWidth(1.0f),
    fineStrokeWidth(0.5f),
    acceptList(new QStringList()),
    acceptUnitList(new QStringList()),
    lastPaintTime(0),
    columns(3),
54 55
    valuesChanged(true),
    m_ui(NULL)
pixhawk's avatar
pixhawk committed
56
{
57
    setWindowTitle(title);
pixhawk's avatar
pixhawk committed
58 59
    //m_ui->setupUi(this);

60 61
    setAutoFillBackground(true);

62
    // Add all items in accept list to gauge
63 64
    if (plotList) {
        for(int i = 0; i < plotList->length(); ++i) {
65 66
            addGauge(plotList->at(i));
        }
67 68
    }

69
    restoreState();
70 71 72
    // Set preferred size
    setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);

73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108
    createActions();

    //    setBackgroundBrush(QBrush(backgroundColor));
    //    setDragMode(QGraphicsView::ScrollHandDrag);
    //    setCacheMode(QGraphicsView::CacheBackground);
    //    // FIXME Handle full update with care - ressource intensive
    //    setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
    //
    //    setRenderHints(QPainter::Antialiasing | QPainter::SmoothPixmapTransform);
    //
    //    //Set-up the scene
    //    QGraphicsScene* Scene = new QGraphicsScene(this);
    //    setScene(Scene);
    //
    //    //Populate the scene
    //    for(int x = 0; x < 1000; x = x + 25) {
    //        for(int y = 0; y < 1000; y = y + 25) {
    //
    //            if(x % 100 == 0 && y % 100 == 0) {
    //                Scene->addRect(x, y, 2, 2);
    //
    //                QString pointString;
    //                QTextStream stream(&pointString);
    //                stream << "(" << x << "," << y << ")";
    //                QGraphicsTextItem* item = Scene->addText(pointString);
    //                item->setPos(x, y);
    //            } else {
    //                Scene->addRect(x, y, 1, 1);
    //            }
    //        }
    //    }
    //
    //    //Set-up the view
    //    setSceneRect(0, 0, 1000, 1000);
    //    setCenter(QPointF(500.0, 500.0)); //A modified version of centerOn(), handles special cases
    //    setCursor(Qt::OpenHandCursor);
109 110


111
    // Set minimum size
112 113
    this->setMinimumHeight(125);
    this->setMinimumWidth(100);
pixhawk's avatar
pixhawk committed
114

LM's avatar
LM committed
115 116
    scalingFactor = this->width()/vwidth;

pixhawk's avatar
pixhawk committed
117
    // Refresh timer
118
    refreshTimer->setInterval(180); //
119
    connect(refreshTimer, SIGNAL(timeout()), this, SLOT(triggerUpdate()));
pixhawk's avatar
pixhawk committed
120 121 122 123 124 125 126 127
    //connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintGL()));

    fontDatabase = QFontDatabase();
    const QString fontFileName = ":/general/vera.ttf"; ///< Font file is part of the QRC file and compiled into the app
    const QString fontFamilyName = "Bitstream Vera Sans";
    if(!QFile::exists(fontFileName)) qDebug() << "ERROR! font file: " << fontFileName << " DOES NOT EXIST!";

    fontDatabase.addApplicationFont(fontFileName);
128
    font = fontDatabase.font(fontFamilyName, "Roman", qMax(5, (int)(10*scalingFactor*1.2f+0.5f)));
pixhawk's avatar
pixhawk committed
129 130 131
    if (font.family() != fontFamilyName) qDebug() << "ERROR! Font not loaded: " << fontFamilyName;

    // Connect with UAS
Lorenz Meier's avatar
Lorenz Meier committed
132 133
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection);
    setActiveUAS(UASManager::instance()->getActiveUAS());
pixhawk's avatar
pixhawk committed
134 135 136 137
}

HDDisplay::~HDDisplay()
{
138
    saveState();
139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154
	if(this->refreshTimer)
	{
		delete this->refreshTimer;
	}
	if(this->acceptList)
	{
		delete this->acceptList;
	}
	if(this->acceptUnitList)
	{
		delete this->acceptUnitList;
	}
	if(this->m_ui)
	{
		delete m_ui;
	}
pixhawk's avatar
pixhawk committed
155 156
}

157 158
QSize HDDisplay::sizeHint() const
{
159
    return QSize(400, 400.0f*(vwidth/vheight)*1.2f);
160 161
}

162 163
void HDDisplay::enableGLRendering(bool enable)
{
164
    Q_UNUSED(enable);
165 166
}

167 168 169
void HDDisplay::triggerUpdate()
{
    // Only repaint the regions necessary
170
    update(this->geometry());
171 172
}

173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201
//void HDDisplay::updateValue(UASInterface* uas, const QString& name, const QString& unit, double value, quint64 msec)
//{
//    // UAS is not needed
//    Q_UNUSED(uas);

//    if (!isnan(value) && !isinf(value))
//    {
//        // Update mean
//        const float oldMean = valuesMean.value(name, 0.0f);
//        const int meanCount = valuesCount.value(name, 0);
//        double mean = (oldMean * meanCount +  value) / (meanCount + 1);
//        if (isnan(mean) || isinf(mean)) mean = 0.0;
//        valuesMean.insert(name, mean);
//        valuesCount.insert(name, meanCount + 1);
//        // Two-value sliding average
//        double dot = (valuesDot.value(name) + (value - values.value(name, 0.0f)) / ((msec - lastUpdate.value(name, 0))/1000.0f))/2.0f;
//        if (isnan(dot) || isinf(dot))
//        {
//            dot = 0.0;
//        }
//        valuesDot.insert(name, dot);
//        values.insert(name, value);
//        lastUpdate.insert(name, msec);
//        //}

//        //qDebug() << __FILE__ << __LINE__ << "VALUE:" << value << "MEAN:" << mean << "DOT:" << dot << "COUNT:" << meanCount;
//    }
//}

pixhawk's avatar
pixhawk committed
202 203
void HDDisplay::paintEvent(QPaintEvent * event)
{
204
    Q_UNUSED(event);
lm's avatar
lm committed
205
    //qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
206
    renderOverlay();
207 208
}

209 210 211 212 213 214 215
void HDDisplay::contextMenuEvent (QContextMenuEvent* event)
{
    QMenu menu(this);
    menu.addAction(addGaugeAction);
    menu.addActions(getItemRemoveActions());
    menu.addSeparator();
    menu.addAction(setColumnsAction);
216 217 218 219 220 221
    // Title change would ruin settings
    // this can only be allowed once
    // HDDisplays are instantiated
    // by a factory method based on
    // QSettings
    //menu.addAction(setTitleAction);
222 223 224 225 226 227 228 229 230
    menu.exec(event->globalPos());
}

void HDDisplay::saveState()
{
    QSettings settings;

    QString instruments;
    // Restore instrument settings
231
    for (int i = 0; i < acceptList->count(); i++) {
232
        QString key = acceptList->at(i);
233
        instruments += "|" + QString::number(minValues.value(key, -1.0))+","+key+","+acceptUnitList->at(i)+","+QString::number(maxValues.value(key, +1.0))+","+customNames.value(key, "")+","+((symmetric.value(key, false)) ? "s" : "");
234 235
    }

236
    // qDebug() << "Saving" << instruments;
237 238 239 240 241 242 243 244 245 246

    settings.setValue(windowTitle()+"_gauges", instruments);
    settings.sync();
}

void HDDisplay::restoreState()
{
    QSettings settings;
    settings.sync();

247 248
    acceptList->clear();

249
    QStringList instruments = settings.value(windowTitle()+"_gauges").toString().split('|');
250
    for (int i = 0; i < instruments.count(); i++) {
251 252 253 254 255 256 257
        addGauge(instruments.at(i));
    }
}

QList<QAction*> HDDisplay::getItemRemoveActions()
{
    QList<QAction*> actions;
258
    for(int i = 0; i < acceptList->length(); ++i) {
259 260 261 262 263 264 265 266 267 268 269 270 271
        QString gauge = acceptList->at(i);
        QAction* remove = new QAction(tr("Remove %1 gauge").arg(gauge), this);
        remove->setStatusTip(tr("Removes the %1 gauge from the view.").arg(gauge));
        remove->setData(gauge);
        connect(remove, SIGNAL(triggered()), this, SLOT(removeItemByAction()));
        actions.append(remove);
    }
    return actions;
}

void HDDisplay::removeItemByAction()
{
    QAction* trigger = qobject_cast<QAction*>(QObject::sender());
272
    if (trigger) {
273 274 275 276 277
        QString item = trigger->data().toString();
        int index = acceptList->indexOf(item);
        acceptList->removeAt(index);
        minValues.remove(item);
        maxValues.remove(item);
278 279
        symmetric.remove(item);
        adjustGaugeAspectRatio();
280 281 282 283 284 285
    }
}

void HDDisplay::addGauge()
{
    QStringList items;
286
    for (int i = 0; i < values.count(); ++i) {
287
        QString key = values.keys().at(i);
288 289 290 291 292 293 294
        QString label = key;
        QStringList keySplit = key.split(".");
        if (keySplit.size() > 1)
        {
            keySplit.removeFirst();
            label = keySplit.join(".");
        }
295
        QString unit = units.value(key);
296
        if (unit.contains("deg") || unit.contains("rad")) {
297
            items.append(QString("%1,%2,%3,%4,%5,s").arg("-180").arg(key).arg(unit).arg("+180").arg(label));
298
        } else {
299
            items.append(QString("%1,%2,%3,%4,%5").arg("0").arg(key).arg(unit).arg("+100").arg(label));
300
        }
301 302 303
    }
    bool ok;
    QString item = QInputDialog::getItem(this, tr("Add Gauge Instrument"),
304
                                         tr("Format: min, data name, unit, max, label [,s]"), items, 0, true, &ok);
305
    if (ok && !item.isEmpty()) {
306 307 308 309 310 311
        addGauge(item);
    }
}

void HDDisplay::addGauge(const QString& gauge)
{
312
    if (gauge.length() > 0) {
313
        QStringList parts = gauge.split(',');
314
        if (parts.count() > 2) {
315 316
            double val;
            bool ok;
lm's avatar
lm committed
317
            bool success = true;
318 319

            QString key = parts.at(1);
lm's avatar
lm committed
320
            QString unit = parts.at(2);
321

322
            if (!acceptList->contains(key)) {
323 324
                // Convert min to double number
                val = parts.first().toDouble(&ok);
lm's avatar
lm committed
325
                success &= ok;
326 327
                if (ok) minValues.insert(key, val);
                // Convert max to double number
lm's avatar
lm committed
328 329
                val = parts.at(3).toDouble(&ok);
                success &= ok;
330
                if (ok) maxValues.insert(key, val);
331 332 333 334 335 336 337 338
                // Convert name
                if (parts.length() >= 5)
                {
                    if (parts.at(4).length() > 0)
                    {
                        customNames.insert(key, parts.at(4));
                    }
                }
339
                // Convert symmetric flag
340 341 342 343
                if (parts.length() >= 6)
                {
                    if (parts.at(5).contains("s"))
                    {
344 345 346
                        symmetric.insert(key, true);
                    }
                }
347
                if (success) {
lm's avatar
lm committed
348 349 350 351
                    // Add value to acceptlist
                    acceptList->append(key);
                    acceptUnitList->append(unit);
                }
352
            }
353 354
        } else if (parts.count() > 1) {
            if (!acceptList->contains(gauge)) {
lm's avatar
lm committed
355 356
                acceptList->append(parts.at(0));
                acceptUnitList->append(parts.at(1));
357 358 359
            }
        }
    }
360
    adjustGaugeAspectRatio();
361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383
}

void HDDisplay::createActions()
{
    addGaugeAction = new QAction(tr("New &Gauge"), this);
    addGaugeAction->setStatusTip(tr("Add a new gauge to the view by adding its name from the linechart"));
    connect(addGaugeAction, SIGNAL(triggered()), this, SLOT(addGauge()));

    setTitleAction = new QAction(tr("Set Widget Title"), this);
    setTitleAction->setStatusTip(tr("Set the title caption of this tool widget"));
    connect(setTitleAction, SIGNAL(triggered()), this, SLOT(setTitle()));

    setColumnsAction = new QAction(tr("Set Number of Instrument Columns"), this);
    setColumnsAction->setStatusTip(tr("Set number of columns to draw"));
    connect(setColumnsAction, SIGNAL(triggered()), this, SLOT(setColumns()));
}


void HDDisplay::setColumns()
{
    bool ok;
    int i = QInputDialog::getInt(this, tr("Number of Instrument Columns"),
                                 tr("Columns:"), columns, 1, 15, 1, &ok);
384
    if (ok) {
385 386 387 388 389 390 391
        columns = i;
    }
}

void HDDisplay::setColumns(int cols)
{
    columns = cols;
392 393 394 395 396 397 398 399 400 401
    adjustGaugeAspectRatio();
}

void HDDisplay::adjustGaugeAspectRatio()
{
    // Adjust vheight dynamically according to the number of rows
    float vColWidth = vwidth / columns;
    int vRows = ceil(acceptList->length()/(float)columns);
    // Assuming square instruments, vheight is column width*row count
    vheight = vColWidth * vRows;
402 403 404 405 406
}

void HDDisplay::setTitle()
{
    QDockWidget* parent = dynamic_cast<QDockWidget*>(this->parentWidget());
407
    if (parent) {
408 409 410 411 412 413 414 415 416 417
        bool ok;
        QString text = QInputDialog::getText(this, tr("New title"),
                                             tr("Widget title:"), QLineEdit::Normal,
                                             parent->windowTitle(), &ok);
        if (ok && !text.isEmpty())
            parent->setWindowTitle(text);
        this->setWindowTitle(text);
    }
}

418
void HDDisplay::renderOverlay()
419
{
420 421
    if (!valuesChanged || !isVisible()) return;

422 423 424
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
425
    quint64 refreshInterval = 100;
426
    quint64 currTime = MG::TIME::getGroundTimeNow();
427
    if (currTime - lastPaintTime < refreshInterval) {
428 429 430 431
        // FIXME Need to find the source of the spurious paint events
        //return;
    }
    lastPaintTime = currTime;
pixhawk's avatar
pixhawk committed
432 433 434 435 436
    // Draw instruments
    // TESTING THIS SHOULD BE MOVED INTO A QGRAPHICSVIEW
    // Update scaling factor
    // adjust scaling to fit both horizontally and vertically
    scalingFactor = this->width()/vwidth;
437

pixhawk's avatar
pixhawk committed
438 439 440
    double scalingFactorH = this->height()/vheight;
    if (scalingFactorH < scalingFactor) scalingFactor = scalingFactorH;

441
    QPainter painter(viewport());
pixhawk's avatar
pixhawk committed
442 443
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
444
    //painter.fillRect(QRect(0, 0, width(), height()), backgroundColor);
pixhawk's avatar
pixhawk committed
445
    const float spacing = 0.4f; // 40% of width
446
    const float gaugeWidth = vwidth / (((float)columns) + (((float)columns+1) * spacing + spacing * 0.5f));
447 448 449 450 451 452 453 454 455
    QColor gaugeColor;
    if (MainWindow::instance()->getStyle() == MainWindow::QGC_MAINWINDOW_STYLE_LIGHT)
    {
        gaugeColor = QColor(0, 0, 0);
    }
    else
    {
        gaugeColor = QColor(255, 255, 255);
    }
pixhawk's avatar
pixhawk committed
456 457 458 459 460 461 462 463 464 465 466
    //drawSystemIndicator(10.0f-gaugeWidth/2.0f, 20.0f, 10.0f, 40.0f, 15.0f, &painter);
    //drawGauge(15.0f, 15.0f, gaugeWidth/2.0f, 0, 1.0f, "thrust", values.value("thrust", 0.0f), gaugeColor, &painter, qMakePair(0.45f, 0.8f), qMakePair(0.8f, 1.0f), true);
    //drawGauge(15.0f+gaugeWidth*1.7f, 15.0f, gaugeWidth/2.0f, 0, 10.0f, "altitude", values.value("altitude", 0.0f), gaugeColor, &painter, qMakePair(1.0f, 2.5f), qMakePair(0.0f, 0.5f), true);

    // Left spacing from border / other gauges, measured from left edge to center
    float leftSpacing = gaugeWidth * spacing;
    float xCoord = leftSpacing + gaugeWidth/2.0f;

    float topSpacing = leftSpacing;
    float yCoord = topSpacing + gaugeWidth/2.0f;

467 468
    for (int i = 0; i < acceptList->size(); ++i)
    {
pixhawk's avatar
pixhawk committed
469
        QString value = acceptList->at(i);
470 471
        QString label = customNames.value(value);
        drawGauge(xCoord, yCoord, gaugeWidth/2.0f, minValues.value(value, -1.0f), maxValues.value(value, 1.0f), label, values.value(value, minValues.value(value, 0.0f)), gaugeColor, &painter, symmetric.value(value, false), goodRanges.value(value, qMakePair(0.0f, 0.5f)), critRanges.value(value, qMakePair(0.7f, 1.0f)), true);
pixhawk's avatar
pixhawk committed
472 473
        xCoord += gaugeWidth + leftSpacing;
        // Move one row down if necessary
474 475
        if (xCoord + gaugeWidth*0.9f > vwidth)
        {
pixhawk's avatar
pixhawk committed
476 477 478 479
            yCoord += topSpacing + gaugeWidth;
            xCoord = leftSpacing + gaugeWidth/2.0f;
        }
    }
pixhawk's avatar
pixhawk committed
480 481 482 483 484 485 486 487
}

/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HDDisplay::setActiveUAS(UASInterface* uas)
{
Lorenz Meier's avatar
Lorenz Meier committed
488 489
    if (!uas)
        return;
490
    // Disconnect any previously connected active UAS
491
    if (this->uas != NULL) {
492
        removeSource(this->uas);
pixhawk's avatar
pixhawk committed
493 494 495
    }

    // Now connect the new UAS
496
	addSource(uas);
pixhawk's avatar
pixhawk committed
497
    this->uas = uas;
pixhawk's avatar
pixhawk committed
498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514
}

/**
 * Rotate a polygon around a point
 *
 * @param p polygon to rotate
 * @param origin the rotation center
 * @param angle rotation angle, in radians
 * @return p Polygon p rotated by angle around the origin point
 */
void HDDisplay::rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin)
{
    // Standard 2x2 rotation matrix, counter-clockwise
    //
    //   |  cos(phi)   sin(phi) |
    //   | -sin(phi)   cos(phi) |
    //
515
    for (int i = 0; i < p.size(); i++) {
pixhawk's avatar
pixhawk committed
516 517 518 519 520 521 522 523 524 525 526 527 528 529 530
        QPointF curr = p.at(i);

        const float x = curr.x();
        const float y = curr.y();

        curr.setX(((cos(angle) * (x-origin.x())) + (-sin(angle) * (y-origin.y()))) + origin.x());
        curr.setY(((sin(angle) * (x-origin.x())) + (cos(angle) * (y-origin.y()))) + origin.y());
        p.replace(i, curr);
    }
}

void HDDisplay::drawPolygon(QPolygonF refPolygon, QPainter* painter)
{
    // Scale coordinates
    QPolygonF draw(refPolygon.size());
531
    for (int i = 0; i < refPolygon.size(); i++) {
pixhawk's avatar
pixhawk committed
532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584
        QPointF curr;
        curr.setX(refToScreenX(refPolygon.at(i).x()));
        curr.setY(refToScreenY(refPolygon.at(i).y()));
        draw.replace(i, curr);
    }
    painter->drawPolygon(draw);
}

void HDDisplay::drawChangeRateStrip(float xRef, float yRef, float height, float minRate, float maxRate, float value, QPainter* painter)
{
    QBrush brush(defaultColor, Qt::NoBrush);
    painter->setBrush(brush);
    QPen rectPen(Qt::SolidLine);
    rectPen.setWidth(0);
    rectPen.setColor(defaultColor);
    painter->setPen(rectPen);

    float scaledValue = value;

    // Saturate value
    if (value > maxRate) scaledValue = maxRate;
    if (value < minRate) scaledValue = minRate;

    //           x (Origin: xRef, yRef)
    //           -
    //           |
    //           |
    //           |
    //           =
    //           |
    //   -0.005 >|
    //           |
    //           -

    const float width = height / 8.0f;
    const float lineWidth = 0.5f;

    // Indicator lines
    // Top horizontal line
    drawLine(xRef, yRef, xRef+width, yRef, lineWidth, defaultColor, painter);
    // Vertical main line
    drawLine(xRef+width/2.0f, yRef, xRef+width/2.0f, yRef+height, lineWidth, defaultColor, painter);
    // Zero mark
    drawLine(xRef, yRef+height/2.0f, xRef+width, yRef+height/2.0f, lineWidth, defaultColor, painter);
    // Horizontal bottom line
    drawLine(xRef, yRef+height, xRef+width, yRef+height, lineWidth, defaultColor, painter);

    // Text
    QString label;
    label.sprintf("< %06.2f", value);
    paintText(label, defaultColor, 3.0f, xRef+width/2.0f, yRef+height-((scaledValue - minRate)/(maxRate-minRate))*height - 1.6f, painter);
}

585
void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float max, QString name, float value, const QColor& color, QPainter* painter, bool symmetric, QPair<float, float> goodRange, QPair<float, float> criticalRange, bool solid)
pixhawk's avatar
pixhawk committed
586
{
587 588 589 590 591 592 593 594 595 596 597 598 599 600
    // Select color scheme based on light or dark theme.
    QColor valueColor;
    QColor backgroundColor;
    if (MainWindow::instance()->getStyle() == MainWindow::QGC_MAINWINDOW_STYLE_LIGHT)
    {
        valueColor = QColor(26, 75, 95);
        backgroundColor = QColor(246, 246, 246);
    }
    else
    {
        valueColor = QGC::colorCyan;
        backgroundColor = QColor(34, 34, 34);
    }

pixhawk's avatar
pixhawk committed
601 602 603 604
    // Draw the circle
    QPen circlePen(Qt::SolidLine);

    // Rotate the whole gauge with this angle (in radians) for the zero position
605
    float zeroRotation;
606
    if (symmetric) {
607
        zeroRotation = 1.35f;
608
    } else {
609 610
        zeroRotation = 0.49f;
    }
pixhawk's avatar
pixhawk committed
611 612 613

    // Scale the rotation so that the gauge does one revolution
    // per max. change
614
    float rangeScale;
615
    if (symmetric) {
616
        rangeScale = ((2.0f * M_PI) / (max - min)) * 0.57f;
617
    } else {
618 619
        rangeScale = ((2.0f * M_PI) / (max - min)) * 0.72f;
    }
pixhawk's avatar
pixhawk committed
620

621 622 623
    const float scaledValue = (value-min)*rangeScale;

    float nameHeight = radius / 2.6f;
pixhawk's avatar
pixhawk committed
624 625
    paintText(name.toUpper(), color, nameHeight*0.7f, xRef-radius, yRef-radius, painter);

626 627 628
    // Ensure some space
    nameHeight *= 1.2f;

629
    if (!solid) {
pixhawk's avatar
pixhawk committed
630 631 632 633
        circlePen.setStyle(Qt::DotLine);
    }
    circlePen.setWidth(refLineWidthToPen(radius/12.0f));
    circlePen.setColor(color);
634

635
    if (symmetric) {
636 637
        circlePen.setStyle(Qt::DashLine);
    }
pixhawk's avatar
pixhawk committed
638 639
    painter->setBrush(Qt::NoBrush);
    painter->setPen(circlePen);
640 641
    drawCircle(xRef, yRef+nameHeight, radius, 0.0f, color, painter);
    //drawCircle(xRef, yRef+nameHeight, radius, 0.0f, 170.0f, 1.0f, color, painter);
pixhawk's avatar
pixhawk committed
642 643

    QString label;
644 645

    // Show integer values without decimal places
646
    if (intValues.contains(name)) {
647
        label.sprintf("% 05d", (int)value);
648
    } else {
649 650
        label.sprintf("% 06.1f", value);
    }
pixhawk's avatar
pixhawk committed
651 652 653 654


    // Text
    // height
655 656
    const float textHeight = radius/2.1f;
    const float textX = xRef-radius/3.0f;
pixhawk's avatar
pixhawk committed
657 658 659
    const float textY = yRef+radius/2.0f;

    // Draw background rectangle
660
    QBrush brush(backgroundColor, Qt::SolidPattern);
pixhawk's avatar
pixhawk committed
661 662
    painter->setBrush(brush);
    painter->setPen(Qt::NoPen);
663

664
    if (symmetric) {
665
        painter->drawRect(refToScreenX(xRef-radius), refToScreenY(yRef+nameHeight+radius/4.0f), refToScreenX(radius+radius), refToScreenY((radius - radius/4.0f)*1.2f));
666
    } else {
667 668
        painter->drawRect(refToScreenX(xRef-radius/2.5f), refToScreenY(yRef+nameHeight+radius/4.0f), refToScreenX(radius+radius/2.0f), refToScreenY((radius - radius/4.0f)*1.2f));
    }
pixhawk's avatar
pixhawk committed
669 670

    // Draw good value and crit. value markers
671
    if (goodRange.first != goodRange.second) {
pixhawk's avatar
pixhawk committed
672 673 674 675 676 677 678
        QRectF rectangle(refToScreenX(xRef-radius/2.0f), refToScreenY(yRef+nameHeight-radius/2.0f), refToScreenX(radius*2.0f), refToScreenX(radius*2.0f));
        painter->setPen(Qt::green);
        //int start = ((goodRange.first*rangeScale+zeroRotation)/M_PI)*180.0f * 16.0f;// + 16.0f * 60.0f;
        //int span  = start - ((goodRange.second*rangeScale+zeroRotation)/M_PI)*180.0f * 16.0f;
        //painter->drawArc(rectangle, start, span);
    }

679
    if (criticalRange.first != criticalRange.second) {
pixhawk's avatar
pixhawk committed
680 681 682 683 684 685 686 687 688
        QRectF rectangle(refToScreenX(xRef-radius/2.0f-3.0f), refToScreenY(yRef+nameHeight-radius/2.0f-3.0f), refToScreenX(radius*2.0f), refToScreenX(radius*2.0f));
        painter->setPen(Qt::yellow);
        //int start = ((criticalRange.first*rangeScale+zeroRotation)/M_PI)*180.0f * 16.0f - 180.0f*16.0f;// + 16.0f * 60.0f;
        //int span  = start - ((criticalRange.second*rangeScale+zeroRotation)/M_PI)*180.0f * 16.0f + 180.0f*16.0f;
        //painter->drawArc(rectangle, start, span);
    }

    // Draw the value
    //painter->setPen(textColor);
689
    paintText(label, valueColor, textHeight, textX, textY+nameHeight, painter);
pixhawk's avatar
pixhawk committed
690 691 692 693 694 695 696 697 698 699
    //paintText(label, color, ((radius - radius/3.0f)*1.1f), xRef-radius/2.5f, yRef+radius/3.0f, painter);

    // Draw the needle

    const float maxWidth = radius / 6.0f;
    const float minWidth = maxWidth * 0.3f;

    QPolygonF p(6);

    p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef+nameHeight+radius * 0.05f));
700 701
    p.replace(1, QPointF(xRef-minWidth/2.0f, yRef+nameHeight+radius * 0.89f));
    p.replace(2, QPointF(xRef+minWidth/2.0f, yRef+nameHeight+radius * 0.89f));
pixhawk's avatar
pixhawk committed
702 703 704 705 706
    p.replace(3, QPointF(xRef+maxWidth/2.0f, yRef+nameHeight+radius * 0.05f));
    p.replace(4, QPointF(xRef,               yRef+nameHeight+radius * 0.0f));
    p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef+nameHeight+radius * 0.05f));


707
    rotatePolygonClockWiseRad(p, scaledValue+zeroRotation, QPointF(xRef, yRef+nameHeight));
pixhawk's avatar
pixhawk committed
708 709 710 711 712 713 714 715 716 717 718 719

    QBrush indexBrush;
    indexBrush.setColor(color);
    indexBrush.setStyle(Qt::SolidPattern);
    painter->setPen(Qt::NoPen);
    painter->setBrush(indexBrush);
    drawPolygon(p, painter);
}


void HDDisplay::drawSystemIndicator(float xRef, float yRef, int maxNum, float maxWidth, float maxHeight, QPainter* painter)
{
720
    if (values.size() > 0) {
pixhawk's avatar
pixhawk committed
721 722 723 724 725 726
        QString selectedKey = values.begin().key();
        //   | | | | | |
        //   | | | | | |
        //   x speed: 2.54

        // One column per value
727
        QMapIterator<QString, double> value(values);
pixhawk's avatar
pixhawk committed
728 729 730 731 732 733 734 735 736 737

        float x = xRef;
        float y = yRef;

        const float vspacing = 1.0f;
        float width = 1.5f;
        float height = 1.5f;
        const float hspacing = 0.6f;

        int i = 0;
738
        while (value.hasNext() && i < maxNum && x < maxWidth && y < maxHeight) {
pixhawk's avatar
pixhawk committed
739 740 741 742
            value.next();
            QBrush brush(Qt::SolidPattern);


743
            if (value.value() < 0.01f && value.value() > -0.01f) {
pixhawk's avatar
pixhawk committed
744
                brush.setColor(Qt::gray);
745
            } else if (value.value() > 0.01f) {
pixhawk's avatar
pixhawk committed
746
                brush.setColor(Qt::blue);
747
            } else {
pixhawk's avatar
pixhawk committed
748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772
                brush.setColor(Qt::yellow);
            }

            painter->setBrush(brush);
            painter->setPen(Qt::NoPen);

            // Draw current value colormap
            painter->drawRect(refToScreenX(x), refToScreenY(y), refToScreenX(width), refToScreenY(height));

            // Draw change rate colormap
            painter->drawRect(refToScreenX(x), refToScreenY(y+height+hspacing), refToScreenX(width), refToScreenY(height));

            // Draw mean value colormap
            painter->drawRect(refToScreenX(x), refToScreenY(y+2.0f*(height+hspacing)), refToScreenX(width), refToScreenY(height));

            // Add spacing
            x += width+vspacing;

            // Iterate
            i++;
        }

        // Draw detail label
        QString detail = "NO DATA AVAILABLE";

773
        if (values.contains(selectedKey)) {
pixhawk's avatar
pixhawk committed
774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790
            detail = values.find(selectedKey).key();
            detail.append(": ");
            detail.append(QString::number(values.find(selectedKey).value()));
        }
        paintText(detail, QColor(255, 255, 255), 3.0f, xRef, yRef+3.0f*(height+hspacing)+1.0f, painter);
    }
}

void HDDisplay::drawChangeIndicatorGauge(float xRef, float yRef, float radius, float expectedMaxChange, float value, const QColor& color, QPainter* painter, bool solid)
{
    // Draw the circle
    QPen circlePen(Qt::SolidLine);
    if (!solid) circlePen.setStyle(Qt::DotLine);
    circlePen.setWidth(refLineWidthToPen(0.5f));
    circlePen.setColor(defaultColor);
    painter->setBrush(Qt::NoBrush);
    painter->setPen(circlePen);
791 792
    drawCircle(xRef, yRef, radius, 200.0f, color, painter);
    //drawCircle(xRef, yRef, radius, 200.0f, 170.0f, 1.0f, color, painter);
pixhawk's avatar
pixhawk committed
793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841

    QString label;
    label.sprintf("%05.1f", value);

    // Draw the value
    paintText(label, color, 4.5f, xRef-7.5f, yRef-2.0f, painter);

    // Draw the needle
    // Scale the rotation so that the gauge does one revolution
    // per max. change
    const float rangeScale = (2.0f * M_PI) / expectedMaxChange;
    const float maxWidth = radius / 10.0f;
    const float minWidth = maxWidth * 0.3f;

    QPolygonF p(6);

    p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.5f));
    p.replace(1, QPointF(xRef-minWidth/2.0f, yRef-radius * 0.9f));
    p.replace(2, QPointF(xRef+minWidth/2.0f, yRef-radius * 0.9f));
    p.replace(3, QPointF(xRef+maxWidth/2.0f, yRef-radius * 0.5f));
    p.replace(4, QPointF(xRef,               yRef-radius * 0.46f));
    p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.5f));

    rotatePolygonClockWiseRad(p, value*rangeScale, QPointF(xRef, yRef));

    QBrush indexBrush;
    indexBrush.setColor(defaultColor);
    indexBrush.setStyle(Qt::SolidPattern);
    painter->setPen(Qt::SolidLine);
    painter->setPen(defaultColor);
    painter->setBrush(indexBrush);
    drawPolygon(p, painter);
}

/**
 * Paint text on top of the image and OpenGL drawings
 *
 * @param text chars to write
 * @param color text color
 * @param fontSize text size in mm
 * @param refX position in reference units (mm of the real instrument). This is relative to the measurement unit position, NOT in pixels.
 * @param refY position in reference units (mm of the real instrument). This is relative to the measurement unit position, NOT in pixels.
 */
void HDDisplay::paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter)
{
    QPen prevPen = painter->pen();
    float pPositionX = refToScreenX(refX) - (fontSize*scalingFactor*0.072f);
    float pPositionY = refToScreenY(refY) - (fontSize*scalingFactor*0.212f);

842 843 844 845
    QFont font("Bitstream Vera Sans");
    // Enforce minimum font size of 5 pixels
    int fSize = qMax(5, (int)(fontSize*scalingFactor*1.26f));
    font.setPixelSize(fSize);
pixhawk's avatar
pixhawk committed
846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864

    QFontMetrics metrics = QFontMetrics(font);
    int border = qMax(4, metrics.leading());
    QRect rect = metrics.boundingRect(0, 0, width() - 2*border, int(height()*0.125),
                                      Qt::AlignLeft | Qt::TextWordWrap, text);
    painter->setPen(color);
    painter->setFont(font);
    painter->setRenderHint(QPainter::TextAntialiasing);
    painter->drawText(pPositionX, pPositionY,
                      rect.width(), rect.height(),
                      Qt::AlignCenter | Qt::TextWordWrap, text);
    painter->setPen(prevPen);
}

float HDDisplay::refLineWidthToPen(float line)
{
    return line * 2.50f;
}

865
// Connect a generic source
866 867 868 869 870 871
void HDDisplay::addSource(QObject* obj)
{
    //genericSources.append(obj);
    // FIXME XXX HACK
//    if (plots.size() > 0)
//    {
872 873 874 875 876 877
        connect(obj, SIGNAL(valueChanged(int,QString,QString,qint8,quint64)), this, SLOT(updateValue(int,QString,QString,qint8,quint64)));
        connect(obj, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), this, SLOT(updateValue(int,QString,QString,quint8,quint64)));
        connect(obj, SIGNAL(valueChanged(int,QString,QString,qint16,quint64)), this, SLOT(updateValue(int,QString,QString,qint16,quint64)));
        connect(obj, SIGNAL(valueChanged(int,QString,QString,quint16,quint64)), this, SLOT(updateValue(int,QString,QString,quint16,quint64)));
        connect(obj, SIGNAL(valueChanged(int,QString,QString,qint32,quint64)), this, SLOT(updateValue(int,QString,QString,qint32,quint64)));
        connect(obj, SIGNAL(valueChanged(int,QString,QString,quint32,quint64)), this, SLOT(updateValue(int,QString,QString,quint32,quint64)));
878 879 880 881 882 883
        connect(obj, SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), this, SLOT(updateValue(int,QString,QString,quint64,quint64)));
        connect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), this, SLOT(updateValue(int,QString,QString,qint64,quint64)));
        connect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), this, SLOT(updateValue(int,QString,QString,double,quint64)));
//    }
}

884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927
// Disconnect a generic source
void HDDisplay::removeSource(QObject* obj)
{
    //genericSources.append(obj);
    // FIXME XXX HACK
//    if (plots.size() > 0)
//    {
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint8,quint64)), this, SLOT(updateValue(int,QString,QString,qint8,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), this, SLOT(updateValue(int,QString,QString,quint8,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint16,quint64)), this, SLOT(updateValue(int,QString,QString,qint16,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint16,quint64)), this, SLOT(updateValue(int,QString,QString,quint16,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint32,quint64)), this, SLOT(updateValue(int,QString,QString,qint32,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint32,quint64)), this, SLOT(updateValue(int,QString,QString,quint32,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), this, SLOT(updateValue(int,QString,QString,quint64,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), this, SLOT(updateValue(int,QString,QString,qint64,quint64)));
        disconnect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), this, SLOT(updateValue(int,QString,QString,double,quint64)));
//    }
}

void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec)
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec)
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec)
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec)
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec)
928 929 930 931 932
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

933
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec)
934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec)
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec)
{
    if (!intValues.contains(name)) intValues.insert(name, true);
    updateValue(uasId, name, unit, (double)value, msec);
}

lm's avatar
lm committed
951
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec)
pixhawk's avatar
pixhawk committed
952
{
953
    Q_UNUSED(uasId);
954
    Q_UNUSED(unit);
955 956 957 958 959 960
    // Update mean
    const float oldMean = valuesMean.value(name, 0.0f);
    const int meanCount = valuesCount.value(name, 0);
    valuesMean.insert(name, (oldMean * meanCount +  value) / (meanCount + 1));
    valuesCount.insert(name, meanCount + 1);
    valuesDot.insert(name, (value - values.value(name, 0.0f)) / ((msec - lastUpdate.value(name, 0))/1000.0f));
961
    if (values.value(name, 0.0) != value) valuesChanged = true;
962
    values.insert(name, value);
963
    units.insert(name, unit);
964
    lastUpdate.insert(name, msec);
pixhawk's avatar
pixhawk committed
965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984
}

/**
 * @param y coordinate in pixels to be converted to reference mm units
 * @return the screen coordinate relative to the QGLWindow origin
 */
float HDDisplay::refToScreenX(float x)
{
    return (scalingFactor * x);
}

/**
 * @param x coordinate in pixels to be converted to reference mm units
 * @return the screen coordinate relative to the QGLWindow origin
 */
float HDDisplay::refToScreenY(float y)
{
    return (scalingFactor * y);
}

985 986 987 988 989 990 991 992 993 994
float HDDisplay::screenToRefX(float x)
{
    return x/scalingFactor;
}

float HDDisplay::screenToRefY(float y)
{
    return y/scalingFactor;
}

pixhawk's avatar
pixhawk committed
995 996 997 998 999 1000 1001 1002 1003
void HDDisplay::drawLine(float refX1, float refY1, float refX2, float refY2, float width, const QColor& color, QPainter* painter)
{
    QPen pen(Qt::SolidLine);
    pen.setWidth(refLineWidthToPen(width));
    pen.setColor(color);
    painter->setPen(pen);
    painter->drawLine(QPoint(refToScreenX(refX1), refToScreenY(refY1)), QPoint(refToScreenX(refX2), refToScreenY(refY2)));
}

1004
void HDDisplay::drawEllipse(float refX, float refY, float radiusX, float radiusY, float lineWidth, const QColor& color, QPainter* painter)
pixhawk's avatar
pixhawk committed
1005 1006 1007 1008 1009 1010 1011 1012
{
    QPen pen(painter->pen().style());
    pen.setWidth(refLineWidthToPen(lineWidth));
    pen.setColor(color);
    painter->setPen(pen);
    painter->drawEllipse(QPointF(refToScreenX(refX), refToScreenY(refY)), refToScreenX(radiusX), refToScreenY(radiusY));
}

1013
void HDDisplay::drawCircle(float refX, float refY, float radius, float lineWidth, const QColor& color, QPainter* painter)
pixhawk's avatar
pixhawk committed
1014
{
1015
    drawEllipse(refX, refY, radius, radius, lineWidth, color, painter);
pixhawk's avatar
pixhawk committed
1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028
}

void HDDisplay::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
    switch (e->type()) {
    case QEvent::LanguageChange:
        m_ui->retranslateUi(this);
        break;
    default:
        break;
    }
}
1029 1030


1031 1032 1033 1034
void HDDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
1035 1036
    Q_UNUSED(event);
    refreshTimer->start(updateInterval);
1037 1038 1039 1040 1041 1042
}

void HDDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (pre-display)
    // events
1043 1044 1045
    Q_UNUSED(event);
    refreshTimer->stop();
    saveState();
1046
}
1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178


///**
//  * Sets the current centerpoint.  Also updates the scene's center point.
//  * Unlike centerOn, which has no way of getting the floating point center
//  * back, SetCenter() stores the center point.  It also handles the special
//  * sidebar case.  This function will claim the centerPoint to sceneRec ie.
//  * the centerPoint must be within the sceneRec.
//  */
////Set the current centerpoint in the
//void HDDisplay::setCenter(const QPointF& centerPoint) {
//    //Get the rectangle of the visible area in scene coords
//    QRectF visibleArea = mapToScene(rect()).boundingRect();
//
//    //Get the scene area
//    QRectF sceneBounds = sceneRect();
//
//    double boundX = visibleArea.width() / 2.0;
//    double boundY = visibleArea.height() / 2.0;
//    double boundWidth = sceneBounds.width() - 2.0 * boundX;
//    double boundHeight = sceneBounds.height() - 2.0 * boundY;
//
//    //The max boundary that the centerPoint can be to
//    QRectF bounds(boundX, boundY, boundWidth, boundHeight);
//
//    if(bounds.contains(centerPoint)) {
//        //We are within the bounds
//        currentCenterPoint = centerPoint;
//    } else {
//        //We need to clamp or use the center of the screen
//        if(visibleArea.contains(sceneBounds)) {
//            //Use the center of scene ie. we can see the whole scene
//            currentCenterPoint = sceneBounds.center();
//        } else {
//
//            currentCenterPoint = centerPoint;
//
//            //We need to clamp the center. The centerPoint is too large
//            if(centerPoint.x() > bounds.x() + bounds.width()) {
//                currentCenterPoint.setX(bounds.x() + bounds.width());
//            } else if(centerPoint.x() < bounds.x()) {
//                currentCenterPoint.setX(bounds.x());
//            }
//
//            if(centerPoint.y() > bounds.y() + bounds.height()) {
//                currentCenterPoint.setY(bounds.y() + bounds.height());
//            } else if(centerPoint.y() < bounds.y()) {
//                currentCenterPoint.setY(bounds.y());
//            }
//
//        }
//    }
//
//    //Update the scrollbars
//    centerOn(currentCenterPoint);
//}
//
///**
//  * Handles when the mouse button is pressed
//  */
//void HDDisplay::mousePressEvent(QMouseEvent* event) {
//    //For panning the view
//    lastPanPoint = event->pos();
//    setCursor(Qt::ClosedHandCursor);
//}
//
///**
//  * Handles when the mouse button is released
//  */
//void HDDisplay::mouseReleaseEvent(QMouseEvent* event) {
//    setCursor(Qt::OpenHandCursor);
//    lastPanPoint = QPoint();
//}
//
///**
//*Handles the mouse move event
//*/
//void HDDisplay::mouseMoveEvent(QMouseEvent* event) {
//    if(!lastPanPoint.isNull()) {
//        //Get how much we panned
//        QPointF delta = mapToScene(lastPanPoint) - mapToScene(event->pos());
//        lastPanPoint = event->pos();
//
//        //Update the center ie. do the pan
//        setCenter(getCenter() + delta);
//    }
//}
//
///**
//  * Zoom the view in and out.
//  */
//void HDDisplay::wheelEvent(QWheelEvent* event) {
//
//    //Get the position of the mouse before scaling, in scene coords
//    QPointF pointBeforeScale(mapToScene(event->pos()));
//
//    //Get the original screen centerpoint
//    QPointF screenCenter = getCenter(); //CurrentCenterPoint; //(visRect.center());
//
//    //Scale the view ie. do the zoom
//    double scaleFactor = 1.15; //How fast we zoom
//    if(event->delta() > 0) {
//        //Zoom in
//        scale(scaleFactor, scaleFactor);
//    } else {
//        //Zooming out
//        scale(1.0 / scaleFactor, 1.0 / scaleFactor);
//    }
//
//    //Get the position after scaling, in scene coords
//    QPointF pointAfterScale(mapToScene(event->pos()));
//
//    //Get the offset of how the screen moved
//    QPointF offset = pointBeforeScale - pointAfterScale;
//
//    //Adjust to the new center for correct zooming
//    QPointF newCenter = screenCenter + offset;
//    setCenter(newCenter);
//}
//
///**
//  * Need to update the center so there is no jolt in the
//  * interaction after resizing the widget.
//  */
//void HDDisplay::resizeEvent(QResizeEvent* event) {
//    //Get the rectangle of the visible area in scene coords
//    QRectF visibleArea = mapToScene(rect()).boundingRect();
//    setCenter(visibleArea.center());
//
//    //Call the subclass resize so the scrollbars are updated correctly
//    QGraphicsView::resizeEvent(event);
//}