HSIDisplay.cc 37.9 KB
Newer Older
1 2
/*=====================================================================

3
QGroundControl Open Source Ground Control Station
4

5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
6

7
This file is part of the QGROUNDCONTROL project
8

9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
10 11 12 13
    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.

14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
15 16 17 18 19
    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
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
21 22 23 24 25 26 27 28 29 30 31 32 33

======================================================================*/

/**
 * @file
 *   @brief Implementation of Horizontal Situation Indicator class
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QFile>
#include <QStringList>
34
#include <QPainter>
35 36 37
#include <QGraphicsScene>
#include <QHBoxLayout>
#include <QDoubleSpinBox>
38 39
#include "UASManager.h"
#include "HSIDisplay.h"
40
#include "QGC.h"
pixhawk's avatar
pixhawk committed
41
#include "Waypoint.h"
42
#include "UASWaypointManager.h"
43
#include <qmath.h>
lm's avatar
lm committed
44 45
//#include "Waypoint2DIcon.h"
//#include "MAV2DIcon.h"
46 47 48

#include <QDebug>

49

50
HSIDisplay::HSIDisplay(QWidget *parent) :
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 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
    HDDisplay(NULL, "HSI", parent),
    gpsSatellites(),
    satellitesUsed(0),
    attXSet(0.0f),
    attYSet(0.0f),
    attYawSet(0.0f),
    altitudeSet(1.0f),
    posXSet(0.0f),
    posYSet(0.0f),
    posZSet(0.0f),
    attXSaturation(0.5f),
    attYSaturation(0.5f),
    attYawSaturation(0.5f),
    posXSaturation(0.05f),
    posYSaturation(0.05f),
    altitudeSaturation(1.0f),
    lat(0.0f),
    lon(0.0f),
    alt(0.0f),
    globalAvailable(0),
    x(0.0f),
    y(0.0f),
    z(0.0f),
    vx(0.0f),
    vy(0.0f),
    vz(0.0f),
    speed(0.0f),
    localAvailable(0),
    roll(0.0f),
    pitch(0.0f),
    yaw(0.0f),
    bodyXSetCoordinate(0.0f),
    bodyYSetCoordinate(0.0f),
    bodyZSetCoordinate(0.0f),
    bodyYawSet(0.0f),
    uiXSetCoordinate(0.0f),
    uiYSetCoordinate(0.0f),
    uiZSetCoordinate(0.0f),
    uiYawSet(0.0f),
    metricWidth(4.0),
    positionLock(false),
    attControlEnabled(false),
    xyControlEnabled(false),
    zControlEnabled(false),
    yawControlEnabled(false),
    positionFix(0),
    gpsFix(0),
    visionFix(0),
    laserFix(0),
    mavInitialized(false),
    bottomMargin(10.0f),
    topMargin(12.0f),
    userSetPointSet(false)
104
{
105
    refreshTimer->setInterval(updateInterval);
106

pixhawk's avatar
pixhawk committed
107
    columns = 1;
108
    this->setAutoFillBackground(true);
109 110 111
    QPalette pal = palette();
    pal.setColor(backgroundRole(), QGC::colorBlack);
    setPalette(pal);
112

113 114
    vwidth = 80.0f;
    vheight = 80.0f;
pixhawk's avatar
pixhawk committed
115

116
    xCenterPos = vwidth/2.0f;
pixhawk's avatar
pixhawk committed
117
    yCenterPos = vheight/2.0f + topMargin - bottomMargin;
118
    //qDebug() << "CENTER" << xCenterPos << yCenterPos;
119 120 121

    // Add interaction elements
    QHBoxLayout* layout = new QHBoxLayout(this);
122 123
    layout->setMargin(0);
    layout->setSpacing(12);
124 125 126
    QDoubleSpinBox* spinBox = new QDoubleSpinBox(this);
    spinBox->setMinimum(0.1);
    spinBox->setMaximum(9999);
127
    spinBox->setMaximumWidth(50);
128 129 130
    spinBox->setValue(metricWidth);
    spinBox->setToolTip(tr("Ground width in meters shown on instrument"));
    spinBox->setStatusTip(tr("Ground width in meters shown on instrument"));
131 132 133
    connect(spinBox, SIGNAL(valueChanged(double)), this, SLOT(setMetricWidth(double)));
    connect(this, SIGNAL(metricWidthChanged(double)), spinBox, SLOT(setValue(double)));
    layout->addWidget(spinBox);
134
    layout->setAlignment(spinBox, Qt::AlignBottom | Qt::AlignRight);
135 136
    this->setLayout(layout);

137 138 139
    uas = NULL;
    resetMAVState();

140 141
    // Do first update
    setMetricWidth(metricWidth);
142 143
}

144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169
void HSIDisplay::resetMAVState()
{
    mavInitialized = false;
    attControlKnown = false;
    attControlEnabled = false;
    xyControlKnown = false;
    xyControlEnabled = false;
    zControlKnown = false;
    zControlEnabled = false;
    yawControlKnown = false;
    yawControlEnabled = false;

    // Draw position lock indicators
    positionFixKnown = false;
    positionFix = 0;
    visionFixKnown = false;
    visionFix = 0;
    gpsFixKnown = false;
    gpsFix = 0;
    iruFixKnown = false;
    iruFix = 0;

    // Data
    setPointKnown = false;
    localAvailable = 0;
    globalAvailable = 0;
170 171 172 173

    // Setpoints
    positionSetPointKnown = false;
    setPointKnown = false;
174 175
}

lm's avatar
lm committed
176 177 178 179
void HSIDisplay::paintEvent(QPaintEvent * event)
{
    Q_UNUSED(event);
    //paintGL();
180 181 182
//    static quint64 interval = 0;
//    //qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
//    interval = MG::TIME::getGroundTimeNow();
183
    renderOverlay();
lm's avatar
lm committed
184 185
}

186
void HSIDisplay::renderOverlay()
187
{
188 189 190
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
191 192
    // Center location of the HSI gauge items

193
    //float bottomMargin = 3.0f;
194 195

    // Size of the ring instrument
196
    //const float margin = 0.1f;  // 10% margin of total width on each side
pixhawk's avatar
pixhawk committed
197
    float baseRadius = (vheight - topMargin - bottomMargin) / 2.0f - bottomMargin / 2.0f;
198

199 200 201 202 203 204 205 206
    // 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;
    double scalingFactorH = this->height()/vheight;
    if (scalingFactorH < scalingFactor) scalingFactor = scalingFactorH;

207
    QPainter painter(viewport());
208 209
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
210

211 212
    // Draw base instrument
    // ----------------------
lm's avatar
lm committed
213
    painter.setBrush(Qt::NoBrush);
214
    const QColor ringColor = QColor(200, 250, 200);
lm's avatar
lm committed
215 216 217 218
    QPen pen;
    pen.setColor(ringColor);
    pen.setWidth(refLineWidthToPen(0.1f));
    painter.setPen(pen);
lm's avatar
lm committed
219
    const int ringCount = 2;
220
    for (int i = 0; i < ringCount; i++) {
221
        float radius = (vwidth - (topMargin + bottomMargin)*0.3f) / (1.3f * i+1) / 2.0f - bottomMargin / 2.0f;
222
        drawCircle(xCenterPos, yCenterPos, radius, 0.1f, ringColor, &painter);
lm's avatar
lm committed
223 224
    }

225 226 227
    // Draw orientation labels
    // Translate and rotate coordinate frame
    painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
228 229 230
    const float yawDeg = ((yaw/M_PI)*180.0f);
    int yawRotate = static_cast<int>(yawDeg) % 360;
    painter.rotate(-yawRotate);
231 232
    paintText(tr("N"), ringColor, 3.5f, - 1.0f, - baseRadius - 5.5f, &painter);
    paintText(tr("S"), ringColor, 3.5f, - 1.0f, + baseRadius + 1.5f, &painter);
233
    paintText(tr("E"), ringColor, 3.5f, + baseRadius + 3.0f, - 1.25f, &painter);
234
    paintText(tr("W"), ringColor, 3.5f, - baseRadius - 5.5f, - 1.75f, &painter);
235
    painter.rotate(+yawRotate);
236 237
    painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);

lm's avatar
lm committed
238
    // Draw center indicator
239 240 241 242 243 244
//    QPolygonF p(3);
//    p.replace(0, QPointF(xCenterPos, yCenterPos-4.0f));
//    p.replace(1, QPointF(xCenterPos-4.0f, yCenterPos+3.5f));
//    p.replace(2, QPointF(xCenterPos+4.0f, yCenterPos+3.5f));
//    drawPolygon(p, &painter);

245
    if (uas) {
246 247 248
        // Translate to center
        painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
        QColor uasColor = uas->getColor();
lm's avatar
lm committed
249
        //MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
250 251 252
        // Translate back
        painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);
    }
253 254

    // ----------------------
255

256 257 258
    // Draw satellites
    drawGPS(painter);

259 260 261
    // Draw state indicator

    // Draw position
262
    QColor positionColor(20, 20, 200);
263
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
264 265 266

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
267
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
268 269


270
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
271

272
    if (userSetPointSet) {
273 274 275 276
        QColor spColor(150, 150, 150);
        drawSetpointXY(uiXSetCoordinate, uiYSetCoordinate, uiYawSet, spColor, painter);
    }

277
    if (positionSetPointKnown) {
278
        // Draw setpoint
279
        drawSetpointXY(bodyXSetCoordinate, bodyYSetCoordinate, bodyYawSet, QGC::colorCyan, painter);
280 281
        // Draw travel direction line
        QPointF m(bodyXSetCoordinate, bodyYSetCoordinate);
lm's avatar
lm committed
282 283 284
        // Transform from body to world coordinates
        m = metricWorldToBody(m);
        // Scale from metric body to screen reference units
285
        QPointF s = metricBodyToRef(m);
286
        drawLine(s.x(), s.y(), xCenterPos, yCenterPos, 1.5f, QGC::colorCyan, &painter);
287 288 289
    }

    // Labels on outer part and bottom
290

291 292 293 294
    // Draw waypoints
    drawWaypoints(painter);

    // Draw status flags
295 296 297 298
    drawStatusFlag(2,  1, tr("ATT"), attControlEnabled, attControlKnown, painter);
    drawStatusFlag(22, 1, tr("PXY"), xyControlEnabled,  xyControlKnown,  painter);
    drawStatusFlag(44, 1, tr("PZ"),  zControlEnabled,   zControlKnown,   painter);
    drawStatusFlag(66, 1, tr("YAW"), yawControlEnabled, yawControlKnown, painter);
299

300
    // Draw position lock indicators
301 302 303 304
    drawPositionLock(2,  5, tr("POS"), positionFix, positionFixKnown, painter);
    drawPositionLock(22, 5, tr("VIS"), visionFix,   visionFixKnown,   painter);
    drawPositionLock(44, 5, tr("GPS"), gpsFix,      gpsFixKnown,      painter);
    drawPositionLock(66, 5, tr("IRU"), iruFix,      iruFixKnown,      painter);
305 306 307

    // Draw speed to top left
    paintText(tr("SPEED"), QGC::colorCyan, 2.2f, 2, 11, &painter);
308
    paintText(tr("%1 m/s").arg(speed, 5, 'f', 2, '0'), Qt::white, 2.2f, 12, 11, &painter);
309 310 311

    // Draw crosstrack error to top right
    float crossTrackError = 0;
312 313
    paintText(tr("XTRACK"), QGC::colorCyan, 2.2f, 57, 11, &painter);
    paintText(tr("%1 m").arg(crossTrackError, 5, 'f', 2, '0'), Qt::white, 2.2f, 70, 11, &painter);
314 315

    // Draw position to bottom left
316
    if (localAvailable > 0 && globalAvailable == 0) {
317 318 319 320 321 322 323
        // Position
        QString str;
        str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
        paintText(tr("POS"), QGC::colorCyan, 2.6f, 2, vheight- 5.0f, &painter);
        paintText(str, Qt::white, 2.6f, 10, vheight - 5.0f, &painter);
    }

324
    if (globalAvailable > 0) {
325 326
        // Position
        QString str;
327
        str.sprintf("lat: %05.2f lon: %06.2f alt: %06.2f", lat, lon, alt);
328 329 330 331 332 333
        paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 5.0f, &painter);
        paintText(str, Qt::white, 2.6f, 10, vheight - 5.0f, &painter);
    }

    // Draw Field of view to bottom right
    paintText(tr("FOV"), QGC::colorCyan, 2.6f, 62, vheight- 5.0f, &painter);
334
}
335

336
void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, QPainter& painter)
337
{
338
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
339
    QColor statusColor(250, 250, 250);
340
    if(status) {
pixhawk's avatar
pixhawk committed
341
        painter.setBrush(QGC::colorGreen);
342
    } else {
343
        painter.setBrush(QGC::colorDarkYellow);
344 345
    }
    painter.setPen(Qt::NoPen);
346 347 348 349 350

    float indicatorWidth = refToScreenX(7.0f);
    float indicatorHeight = refToScreenY(4.0f);

    painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), indicatorWidth, indicatorHeight));
351
    paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
352
    // Cross out instrument if state unknown
353
    if (!known) {
354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370
        QPen pen(Qt::yellow);
        pen.setWidth(2);
        painter.setPen(pen);
        // Top left to bottom right
        QPointF p1, p2, p3, p4;
        p1.setX(refToScreenX(x));
        p1.setY(refToScreenX(y));
        p2.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
        p2.setY(p1.y()+indicatorHeight);
        painter.drawLine(p1, p2);
        // Bottom left to top right
        p3.setX(refToScreenX(x));
        p3.setY(refToScreenX(y)+indicatorHeight);
        p4.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
        p4.setY(p1.y());
        painter.drawLine(p3, p4);
    }
371 372
}

373
void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, bool known, QPainter& painter)
374
{
375 376 377 378 379 380 381 382 383 384 385 386
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
    QColor negStatusColor(200, 20, 20);
    QColor intermediateStatusColor (Qt::yellow);
    QColor posStatusColor(20, 200, 20);
    QColor statusColor(250, 250, 250);
    if (status == 3) {
        painter.setBrush(posStatusColor);
    } else if (status == 2) {
        painter.setBrush(intermediateStatusColor.dark(150));
    } else {
        painter.setBrush(negStatusColor);
    }
387

388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403
    // Lock text
    QString lockText;
    switch (status) {
    case 1:
        lockText = tr("LOC");
        break;
    case 2:
        lockText = tr("2D");
        break;
    case 3:
        lockText = tr("3D");
        break;
    default:
        lockText = tr("NO");
        break;
    }
404

405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429
    float indicatorWidth = refToScreenX(7.0f);
    float indicatorHeight = refToScreenY(4.0f);

    painter.setPen(Qt::NoPen);
    painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), refToScreenX(7.0f), refToScreenY(4.0f)));
    paintText(lockText, statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
    // Cross out instrument if state unknown
    if (!known) {
        QPen pen(Qt::yellow);
        pen.setWidth(2);
        painter.setPen(pen);
        // Top left to bottom right
        QPointF p1, p2, p3, p4;
        p1.setX(refToScreenX(x));
        p1.setY(refToScreenX(y));
        p2.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
        p2.setY(p1.y()+indicatorHeight);
        painter.drawLine(p1, p2);
        // Bottom left to top right
        p3.setX(refToScreenX(x));
        p3.setY(refToScreenX(y)+indicatorHeight);
        p4.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
        p4.setY(p1.y());
        painter.drawLine(p3, p4);
    }
430 431
}

lm's avatar
lm committed
432 433
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
434
    Q_UNUSED(uas);
lm's avatar
lm committed
435 436 437
    positionLock = lock;
}

pixhawk's avatar
pixhawk committed
438
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
439 440
{
    attControlEnabled = enabled;
441
    attControlKnown = true;
lm's avatar
lm committed
442 443
}

pixhawk's avatar
pixhawk committed
444
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
445 446
{
    xyControlEnabled = enabled;
447
    xyControlKnown = true;
lm's avatar
lm committed
448 449
}

pixhawk's avatar
pixhawk committed
450
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
451 452
{
    zControlEnabled = enabled;
453
    zControlKnown = true;
lm's avatar
lm committed
454 455
}

LM's avatar
LM committed
456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472
void HSIDisplay::updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance)
{
    // FIXME add multi-object support
    QPainter painter(this);
    QColor color(Qt::yellow);
    float radius = vwidth / 20.0f;
    QPen pen(color);
    pen.setWidthF(refLineWidthToPen(0.4f));
    pen.setColor(color);
    painter.setPen(pen);
    painter.setBrush(Qt::NoBrush);
    QPointF in(cos(bearing)-sin(bearing)*distance, sin(bearing)+cos(bearing)*distance);
    // Scale from metric to screen reference coordinates
    QPointF p = metricBodyToRef(in);
    drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter);
}

pixhawk's avatar
pixhawk committed
473 474 475 476
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
    // First translate to body-centered coordinates
    // Rotate around -yaw
477 478
    float angle = yaw + M_PI;
    QPointF result(cos(angle) * (x - world.x()) - sin(angle) * (y - world.y()), sin(angle) * (x - world.x()) + cos(angle) * (y - world.y()));
pixhawk's avatar
pixhawk committed
479 480 481 482 483 484 485
    return result;
}

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
486
    QPointF result((cos(yaw) * body.x()) + (sin(yaw) * body.y()) + x, (-sin(yaw) * body.x()) + (cos(yaw) * body.y()) + y);
pixhawk's avatar
pixhawk committed
487
    return result;
488
}
489

490 491
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
lm's avatar
lm committed
492
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth - x, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth - y);
493 494 495 496
}

QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
lm's avatar
lm committed
497
    return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
498 499 500 501 502
}

/**
 * @see refToScreenX()
 */
503
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
504 505 506 507
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

508 509 510 511 512 513 514 515
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

516 517 518 519 520
void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
    static bool dragStarted;
    static float startX;

521
    if (event->MouseButtonDblClick) {
522 523 524 525 526
        //setBodySetpointCoordinateXY(-refToMetric(screenToRefY(event->y()) - yCenterPos), refToMetric(screenToRefX(event->x()) - xCenterPos));

        QPointF p = screenToMetricBody(event->posF());
        setBodySetpointCoordinateXY(p.x(), p.y());
        qDebug() << "Double click at x: " << screenToRefX(event->x()) - xCenterPos << "y:" << screenToRefY(event->y()) - yCenterPos;
527
    } else if (event->MouseButtonPress) {
528
        startX = event->globalX();
529
        if (event->button() == Qt::RightButton) {
530 531
            // Start tracking mouse move
            dragStarted = true;
532
        } else if (event->button() == Qt::LeftButton) {
533 534

        }
535
    } else if (event->MouseButtonRelease) {
536
        dragStarted = false;
537
    } else if (event->MouseMove) {
538
        if (dragStarted) uiYawSet += (startX - event->globalX()) / this->frameSize().width();
pixhawk's avatar
pixhawk committed
539
    }
540 541
}

542 543
void HSIDisplay::setMetricWidth(double width)
{
544
    if (width != metricWidth) {
545 546 547 548 549
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

550 551 552 553 554 555
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573
    if (this->uas != NULL) {
        disconnect(this->uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
        disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
        disconnect(this->uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
        disconnect(this->uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
        disconnect(this->uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
        disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
        disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));

        disconnect(this->uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
        disconnect(this->uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
        disconnect(this->uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
        disconnect(this->uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));

        disconnect(this->uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
        disconnect(this->uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
        disconnect(this->uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
        disconnect(this->uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
LM's avatar
LM committed
574
        disconnect(this->uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
575
    }
576

577 578 579 580 581 582 583
    connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
    connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
    connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
    connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
    connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
    connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
    connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
584

585 586 587 588
    connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
    connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
    connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
    connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
589

590 591 592 593
    connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
    connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
    connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
    connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
LM's avatar
LM committed
594
    connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
595

596
    this->uas = uas;
597

598
    resetMAVState();
599 600
}

601 602 603 604 605 606 607
void HSIDisplay::updateSpeed(UASInterface* uas, double vx, double vy, double vz, quint64 time)
{
    Q_UNUSED(uas);
    Q_UNUSED(time);
    this->vx = vx;
    this->vy = vy;
    this->vz = vz;
608
    this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
609 610 611 612 613 614
}

void HSIDisplay::setBodySetpointCoordinateXY(double x, double y)
{
    // Set coordinates and send them out to MAV

lm's avatar
lm committed
615 616 617 618 619
    QPointF sp(x, y);
    sp = metricBodyToWorld(sp);
    uiXSetCoordinate = sp.x();
    uiYSetCoordinate = sp.y();

pixhawk's avatar
pixhawk committed
620 621
    qDebug() << "Attempting to set new setpoint at x: " << x << "metric y:" << y;

622
    if (uas && mavInitialized) {
pixhawk's avatar
pixhawk committed
623 624 625
        uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
        qDebug() << "Setting new setpoint at x: " << x << "metric y:" << y;
    }
626 627 628 629 630 631 632 633 634 635 636 637 638
}

void HSIDisplay::setBodySetpointCoordinateZ(double z)
{
    // Set coordinates and send them out to MAV
    uiZSetCoordinate = z;
}

void HSIDisplay::sendBodySetPointCoordinates()
{
    // Send the coordinates to the MAV
}

639
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
640
{
641 642 643 644 645 646
    Q_UNUSED(uas);
    Q_UNUSED(usec);
    attXSet = pitchDesired;
    attYSet = rollDesired;
    attYawSet = yawDesired;
    altitudeSet = thrustDesired;
647 648
}

lm's avatar
lm committed
649 650 651 652 653 654 655 656 657
void HSIDisplay::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 time)
{
    Q_UNUSED(uas);
    Q_UNUSED(time);
    this->roll = roll;
    this->pitch = pitch;
    this->yaw = yaw;
}

lm's avatar
lm committed
658
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
659
{
660 661
    Q_UNUSED(usec);
    Q_UNUSED(uasid);
662 663 664 665
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
666
    mavInitialized = true;
667
    setPointKnown = true;
668
    positionSetPointKnown = true;
pixhawk's avatar
pixhawk committed
669

670 671 672 673 674
    //    qDebug() << "Received setpoint at x: " << x << "metric y:" << y;
    //    posXSet = xDesired;
    //    posYSet = yDesired;
    //    posZSet = zDesired;
    //    posYawSet = yawDesired;
675 676 677 678
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
679 680 681 682
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
683 684 685 686
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
687 688 689 690
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
691 692
}

lm's avatar
lm committed
693
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
lm's avatar
lm committed
694 695
{
    Q_UNUSED(uasid);
lm's avatar
lm committed
696
    //qDebug() << "UPDATED SATELLITE";
lm's avatar
lm committed
697
    // If slot is empty, insert object
698
    if (gpsSatellites.contains(satid)) {
lm's avatar
lm committed
699
        gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
700
    } else {
lm's avatar
lm committed
701
        gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
lm's avatar
lm committed
702 703 704
    }
}

705 706 707
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
    yawControlEnabled = enabled;
708
    yawControlKnown = true;
709 710 711 712 713 714 715 716 717
}

/**
 * @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
 */
void HSIDisplay::updateLocalization(UASInterface* uas, int fix)
{
    Q_UNUSED(uas);
    positionFix = fix;
718
    positionFixKnown = true;
719
    //qDebug() << "LOCALIZATION FIX CALLED";
720 721 722 723 724 725 726 727
}
/**
 * @param fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D localization, 3: 3D localization
 */
void HSIDisplay::updateGpsLocalization(UASInterface* uas, int fix)
{
    Q_UNUSED(uas);
    gpsFix = fix;
728
    gpsFixKnown = true;
729 730 731 732 733 734 735 736
}
/**
 * @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
 */
void HSIDisplay::updateVisionLocalization(UASInterface* uas, int fix)
{
    Q_UNUSED(uas);
    visionFix = fix;
737
    visionFixKnown = true;
738
    //qDebug() << "VISION FIX GOT CALLED";
739 740
}

741 742 743 744 745 746 747
/**
 * @param fix 0: lost, 1-N: Localized with N ultrasound or infrared sensors
 */
void HSIDisplay::updateInfraredUltrasoundLocalization(UASInterface* uas, int fix)
{
    Q_UNUSED(uas);
    iruFix = fix;
748
    iruFixKnown = true;
749 750
}

lm's avatar
lm committed
751 752
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
753
    QColor color;
754
    if (snr > 0 && snr < 30) {
lm's avatar
lm committed
755
        color = QColor(250, 10, 10);
756
    } else if (snr >= 30 && snr < 35) {
lm's avatar
lm committed
757
        color = QColor(230, 230, 10);
758
    } else if (snr >= 35 && snr < 40) {
lm's avatar
lm committed
759
        color = QColor(90, 200, 90);
760
    } else if (snr >= 40) {
lm's avatar
lm committed
761
        color = QColor(20, 200, 20);
762
    } else {
lm's avatar
lm committed
763 764 765
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
766 767
}

768
void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color, QPainter &painter)
769
{
770
    if (setPointKnown) {
771 772 773 774 775 776 777 778 779 780 781 782
        float radius = vwidth / 20.0f;
        QPen pen(color);
        pen.setWidthF(refLineWidthToPen(0.4f));
        pen.setColor(color);
        painter.setPen(pen);
        painter.setBrush(Qt::NoBrush);
        QPointF in(x, y);
        // Transform from body to world coordinates
        in = metricWorldToBody(in);
        // Scale from metric to screen reference coordinates
        QPointF p = metricBodyToRef(in);
        drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter);
783
        radius *= 0.8f;
784 785 786 787
        drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * radius, refLineWidthToPen(0.4f), color, &painter);
        painter.setBrush(color);
        drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter);
    }
788 789
}

790 791
void HSIDisplay::drawWaypoints(QPainter& painter)
{
792 793
    if (uas) {
        const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointList();
794 795 796 797 798 799 800 801 802 803 804 805
        //        for (int i = 0; i < list.size(); i++)
        //        {
        //            QPointF in(list.at(i)->getX(), list.at(i)->getY());
        //            // Transform from world to body coordinates
        //            in = metricWorldToBody(in);
        //            // Scale from metric to screen reference coordinates
        //            QPointF p = metricBodyToRef(in);
        //            Waypoint2DIcon* wp = new Waypoint2DIcon();
        //            wp->setLocalPosition(list.at(i)->getX(), list.at(i)->getY());
        //            wp->setPos(0, 0);
        //            scene()->addItem(wp);
        //        }
806 807 808

        QColor color;
        painter.setBrush(Qt::NoBrush);
pixhawk's avatar
pixhawk committed
809

810
        QPointF lastWaypoint;
pixhawk's avatar
pixhawk committed
811

812
        for (int i = 0; i < list.size(); i++) {
813
            QPointF in;
814
            if (list.at(i)->getFrame() == MAV_FRAME_LOCAL) {
815 816
                // Do not transform
                in = QPointF(list.at(i)->getX(), list.at(i)->getY());
817
            } else {
818 819 820 821 822
                // Transform to local coordinates first
                double x = list.at(i)->getX();
                double y = list.at(i)->getY();
                in = QPointF(x, y);
            }
823 824 825 826 827
            // Transform from world to body coordinates
            in = metricWorldToBody(in);
            // Scale from metric to screen reference coordinates
            QPointF p = metricBodyToRef(in);

828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843
            // Setup pen
            QPen pen(color);
            painter.setBrush(Qt::NoBrush);

            // DRAW WAYPOINT
            //drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter);
            float waypointSize = vwidth / 20.0f * 2.0f;
            QPolygonF poly(4);
            // Top point
            poly.replace(0, QPointF(p.x(), p.y()-waypointSize/2.0f));
            // Right point
            poly.replace(1, QPointF(p.x()+waypointSize/2.0f, p.y()));
            // Bottom point
            poly.replace(2, QPointF(p.x(), p.y() + waypointSize/2.0f));
            poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y()));

844
            // Select color based on if this is the current waypoint
845
            if (list.at(i)->getCurrent()) {
846 847
                color = QGC::colorCyan;//uas->getColor();
                pen.setWidthF(refLineWidthToPen(0.8f));
848
            } else {
849
                color = uas->getColor();
850
                pen.setWidthF(refLineWidthToPen(0.4f));
851 852
            }

853
            pen.setColor(color);
854
            painter.setPen(pen);
855
            float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
856
            drawLine(p.x(), p.y(), p.x()+sin(list.at(i)->getYaw()+yaw) * radius, p.y()-cos(list.at(i)->getYaw()+yaw) * radius, refLineWidthToPen(0.4f), color, &painter);
857
            drawPolygon(poly, &painter);
858

859
            // DRAW CONNECTING LINE
860
            // Draw line from last waypoint to this one
861
            if (!lastWaypoint.isNull()) {
862 863 864
                pen.setWidthF(refLineWidthToPen(0.4f));
                painter.setPen(pen);
                color = uas->getColor();
865 866 867
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f), color, &painter);
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
868 869
        }
    }
870 871
}

872 873 874 875 876 877
void HSIDisplay::drawSafetyArea(const QPointF &topLeft, const QPointF &bottomRight, const QColor &color, QPainter &painter)
{
    QPen pen(color);
    pen.setWidthF(refLineWidthToPen(0.1f));
    pen.setColor(color);
    painter.setPen(pen);
878
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
879
}
lm's avatar
lm committed
880

881 882 883 884
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
    float yCenter = xCenterPos;
lm's avatar
lm committed
885 886
    // Max satellite circle radius

lm's avatar
lm committed
887 888 889
    const float margin = 0.15f;  // 20% margin of total width on each side
    float radius = (vwidth - vwidth * 2.0f * margin) / 2.0f;
    quint64 currTime = MG::TIME::getGroundTimeNowUsecs();
lm's avatar
lm committed
890

pixhawk's avatar
pixhawk committed
891 892 893 894 895
    // Draw satellite labels
    //    QString label;
    //    label.sprintf("%05.1f", value);
    //    paintText(label, color, 4.5f, xRef-7.5f, yRef-2.0f, painter);

lm's avatar
lm committed
896
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
897
    while (i.hasNext()) {
lm's avatar
lm committed
898 899 900 901
        i.next();
        GPSSatellite* sat = i.value();

        // Check if update is not older than 5 seconds, else delete satellite
902
        if (sat->lastUpdate + 1000000 < currTime) {
lm's avatar
lm committed
903 904
            // Delete and go to next satellite
            gpsSatellites.remove(i.key());
905
            if (i.hasNext()) {
lm's avatar
lm committed
906 907
                i.next();
                sat = i.value();
908
            } else {
lm's avatar
lm committed
909 910 911 912
                continue;
            }
        }

913
        if (sat) {
lm's avatar
lm committed
914 915 916 917
            // Draw satellite
            QBrush brush;
            QColor color = getColorForSNR(sat->snr);
            brush.setColor(color);
918
            if (sat->used) {
lm's avatar
lm committed
919
                brush.setStyle(Qt::SolidPattern);
920
            } else {
lm's avatar
lm committed
921 922 923 924 925 926
                brush.setStyle(Qt::NoBrush);
            }
            painter.setPen(Qt::SolidLine);
            painter.setPen(color);
            painter.setBrush(brush);

lm's avatar
lm committed
927 928
            float xPos = xCenter + (sin(((sat->azimuth/255.0f)*360.0f)/180.0f * M_PI) * cos(sat->elevation/180.0f * M_PI)) * radius;
            float yPos = yCenter - (cos(((sat->azimuth/255.0f)*360.0f)/180.0f * M_PI) * cos(sat->elevation/180.0f * M_PI)) * radius;
lm's avatar
lm committed
929

930
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
931
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
932
            // Draw satellite PRN
lm's avatar
lm committed
933
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
934 935
        }
    }
936 937
}

938
void HSIDisplay::drawObjects(QPainter &painter)
939
{
940
    Q_UNUSED(painter);
941 942
}

943
void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
944
{
945
    if (xyControlKnown && xyControlEnabled) {
946 947 948
        // Draw the needle
        const float maxWidth = radius / 10.0f;
        const float minWidth = maxWidth * 0.3f;
949

950
        float angle = atan2(posXSet, -posYSet);
951
        angle -= (float)M_PI/2.0f;
952

953
        QPolygonF p(6);
954

955
        //radius *= ((posXSaturation + posYSaturation) - sqrt(pow(posXSet, 2), pow(posYSet, 2))) / (2*posXSaturation);
lm's avatar
lm committed
956

957
        radius *= sqrt(pow(posXSet, 2) + pow(posYSet, 2)) / sqrt(posXSaturation + posYSaturation);
lm's avatar
lm committed
958

959 960 961 962 963 964
        p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f));
        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.4f));
        p.replace(4, QPointF(xRef,               yRef-radius * 0.36f));
        p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f));
965

966
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
967

968 969 970 971 972 973 974
        QBrush indexBrush;
        indexBrush.setColor(color);
        indexBrush.setStyle(Qt::SolidPattern);
        painter->setPen(Qt::SolidLine);
        painter->setPen(color);
        painter->setBrush(indexBrush);
        drawPolygon(p, painter);
lm's avatar
lm committed
975

976 977
        //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
    }
978 979
}

980
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
981
{
982
    if (attControlKnown && attControlEnabled) {
983 984 985
        // Draw the needle
        const float maxWidth = radius / 10.0f;
        const float minWidth = maxWidth * 0.3f;
986

987
        float angle = atan2(attXSet, attYSet);
988
        angle -= (float)M_PI/2.0f;
lm's avatar
lm committed
989

990
        radius *= sqrt(pow(attXSet, 2) + pow(attYSet, 2)) / sqrt(attXSaturation + attYSaturation);
991

992
        QPolygonF p(6);
993

994 995 996 997 998 999
        p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f));
        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.4f));
        p.replace(4, QPointF(xRef,               yRef-radius * 0.36f));
        p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f));
1000

1001
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1002

1003 1004 1005 1006 1007 1008 1009
        QBrush indexBrush;
        indexBrush.setColor(color);
        indexBrush.setStyle(Qt::SolidPattern);
        painter->setPen(Qt::SolidLine);
        painter->setPen(color);
        painter->setBrush(indexBrush);
        drawPolygon(p, painter);
1010

1011
        // TODO Draw Yaw indicator
lm's avatar
lm committed
1012

1013 1014
        //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
    }
1015 1016 1017 1018
}

void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
{
1019
    if (zControlKnown && zControlEnabled) {
1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033
        // Draw the circle
        QPen circlePen(Qt::SolidLine);
        circlePen.setWidth(refLineWidthToPen(0.5f));
        circlePen.setColor(color);
        painter->setBrush(Qt::NoBrush);
        painter->setPen(circlePen);
        drawCircle(xRef, yRef, radius, 200.0f, color, painter);
        //drawCircle(xRef, yRef, radius, 200.0f, 170.0f, 1.0f, color, painter);

        //    // Draw the value
        //    QString label;
        //    label.sprintf("%05.1f", value);
        //    paintText(label, color, 4.5f, xRef-7.5f, yRef-2.0f, painter);
    }
1034
}
1035

1036 1037 1038
void HSIDisplay::wheelEvent(QWheelEvent* event)
{
    double zoomScale = 0.005; // Scaling of zoom value
1039
    if(event->delta() > 0) {
1040 1041
        // Reduce width -> Zoom in
        metricWidth -= event->delta() * zoomScale;
1042
    } else {
1043 1044 1045 1046 1047 1048
        // Increase width -> Zoom out
        metricWidth -= event->delta() * zoomScale;
    }
    metricWidth = qBound(0.1, metricWidth, 9999.0);
    emit metricWidthChanged(metricWidth);
}
pixhawk's avatar
pixhawk committed
1049

1050 1051 1052 1053
void HSIDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
1054
    Q_UNUSED(event) {
1055 1056 1057 1058 1059 1060 1061 1062
        refreshTimer->start(updateInterval);
    }
}

void HSIDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (post-display)
    // events
1063
    Q_UNUSED(event) {
1064
        refreshTimer->stop();
1065 1066 1067
    }
}

1068 1069
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
1070 1071 1072 1073 1074 1075
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
1076 1077 1078 1079
}

void HSIDisplay::pressKey(int key)
{
1080
    Q_UNUSED(key);
1081
}
pixhawk's avatar
pixhawk committed
1082 1083