HSIDisplay.cc 37.7 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 "Waypoint2DIcon.h"
44
#include "MAV2DIcon.h"
45 46 47

#include <QDebug>

48
HSIDisplay::HSIDisplay(QWidget *parent) :
pixhawk's avatar
pixhawk committed
49
        HDDisplay(NULL, "HSI", parent),
pixhawk's avatar
pixhawk committed
50
        gpsSatellites(),
51
        satellitesUsed(0),
52 53 54 55 56 57 58
        attXSet(0.0f),
        attYSet(0.0f),
        attYawSet(0.0f),
        altitudeSet(1.0f),
        posXSet(0.0f),
        posYSet(0.0f),
        posZSet(0.0f),
lm's avatar
lm committed
59 60 61
        attXSaturation(0.5f),
        attYSaturation(0.5f),
        attYawSaturation(0.5f),
62 63 64 65 66 67
        posXSaturation(0.05f),
        posYSaturation(0.05f),
        altitudeSaturation(1.0f),
        lat(0.0f),
        lon(0.0f),
        alt(0.0f),
68
        globalAvailable(0),
69 70 71 72 73 74 75
        x(0.0f),
        y(0.0f),
        z(0.0f),
        vx(0.0f),
        vy(0.0f),
        vz(0.0f),
        speed(0.0f),
76
        localAvailable(0),
77 78 79
        roll(0.0f),
        pitch(0.0f),
        yaw(0.0f),
80 81 82 83 84 85 86 87
        bodyXSetCoordinate(0.0f),
        bodyYSetCoordinate(0.0f),
        bodyZSetCoordinate(0.0f),
        bodyYawSet(0.0f),
        uiXSetCoordinate(0.0f),
        uiYSetCoordinate(0.0f),
        uiZSetCoordinate(0.0f),
        uiYawSet(0.0f),
88
        metricWidth(4.0),
lm's avatar
lm committed
89 90 91
        positionLock(false),
        attControlEnabled(false),
        xyControlEnabled(false),
pixhawk's avatar
pixhawk committed
92
        zControlEnabled(false),
93 94 95 96 97
        yawControlEnabled(false),
        positionFix(0),
        gpsFix(0),
        visionFix(0),
        laserFix(0),
pixhawk's avatar
pixhawk committed
98
        mavInitialized(false),
99
        bottomMargin(10.0f),
100 101
        topMargin(12.0f),
        userSetPointSet(false)
102
{
103
    refreshTimer->setInterval(updateInterval);
104

pixhawk's avatar
pixhawk committed
105
    columns = 1;
106
    this->setAutoFillBackground(true);
107

108 109
    vwidth = 80.0f;
    vheight = 80.0f;
pixhawk's avatar
pixhawk committed
110

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

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

132 133 134
    uas = NULL;
    resetMAVState();

135 136
    // Do first update
    setMetricWidth(metricWidth);
137 138
}

139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164
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;
165 166 167 168

    // Setpoints
    positionSetPointKnown = false;
    setPointKnown = false;
169 170
}

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

181
void HSIDisplay::renderOverlay()
182
{
183 184 185
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
186 187
    // Center location of the HSI gauge items

188
    //float bottomMargin = 3.0f;
189 190

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

194 195 196 197 198 199 200 201
    // 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;

202
    QPainter painter(viewport());
203 204
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
205

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

221 222 223
    // Draw orientation labels
    // Translate and rotate coordinate frame
    painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
224
    painter.rotate((yaw/(M_PI))*180.0f);
225 226
    paintText(tr("N"), ringColor, 3.5f, - 1.0f, - baseRadius - 5.5f, &painter);
    paintText(tr("S"), ringColor, 3.5f, - 1.0f, + baseRadius + 1.5f, &painter);
227
    paintText(tr("E"), ringColor, 3.5f, + baseRadius + 2.0f, - 1.25f, &painter);
228
    paintText(tr("W"), ringColor, 3.5f, - baseRadius - 5.5f, - 1.75f, &painter);
229
    painter.rotate((-yaw/(M_PI))*180.0f);
230 231
    painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);

lm's avatar
lm committed
232
    // Draw center indicator
233 234 235 236 237 238 239 240 241 242 243 244 245 246 247
//    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);

    if (uas)
    {
        // Translate to center
        painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
        QColor uasColor = uas->getColor();
        MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
        // Translate back
        painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);
    }
248 249

    // ----------------------
250

251 252 253
    // Draw satellites
    drawGPS(painter);

254 255 256
    // Draw state indicator

    // Draw position
257
    QColor positionColor(20, 20, 200);
258
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
259 260 261

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
262
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
263 264


265
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
266

267
    if (userSetPointSet)
268 269 270 271 272
    {
        QColor spColor(150, 150, 150);
        drawSetpointXY(uiXSetCoordinate, uiYSetCoordinate, uiYawSet, spColor, painter);
    }

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

    // Labels on outer part and bottom
287

288 289 290 291
    // Draw waypoints
    drawWaypoints(painter);

    // Draw status flags
292 293 294 295
    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);
296

297
    // Draw position lock indicators
298 299 300 301
    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);
302 303 304

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

    // Draw crosstrack error to top right
    float crossTrackError = 0;
309 310
    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);
311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332

    // Draw position to bottom left
    if (localAvailable > 0 && globalAvailable == 0)
    {
        // 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);
    }

    if (globalAvailable > 0)
    {
        // Position
        QString str;
        str.sprintf("%05.2f lat %06.2f lon %06.2f alt", lat, lon, alt);
        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);
333
}
334

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

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

    painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), indicatorWidth, indicatorHeight));
353
    paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373
    // 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);
    }
374 375
}

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

396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412
        // 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;
        }
413

414 415 416 417 418
        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)));
419
        paintText(lockText, statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439
        // 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);
        }
440 441
}

lm's avatar
lm committed
442 443
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
444
    Q_UNUSED(uas);
lm's avatar
lm committed
445 446 447
    positionLock = lock;
}

pixhawk's avatar
pixhawk committed
448
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
449 450
{
    attControlEnabled = enabled;
451
    attControlKnown = true;
lm's avatar
lm committed
452 453
}

pixhawk's avatar
pixhawk committed
454
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
455 456
{
    xyControlEnabled = enabled;
457
    xyControlKnown = true;
lm's avatar
lm committed
458 459
}

pixhawk's avatar
pixhawk committed
460
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
461 462
{
    zControlEnabled = enabled;
463
    zControlKnown = true;
lm's avatar
lm committed
464 465
}

pixhawk's avatar
pixhawk committed
466 467 468 469
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
    // First translate to body-centered coordinates
    // Rotate around -yaw
470 471
    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
472 473 474 475 476 477 478
    return result;
}

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
479
    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
480
    return result;
481
}
482

483 484
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
lm's avatar
lm committed
485
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth - x, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth - y);
486 487 488 489
}

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

/**
 * @see refToScreenX()
 */
496
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
497 498 499 500
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

501 502 503 504 505 506 507 508
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

509 510 511 512 513 514 515 516 517 518 519 520 521 522 523
void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
    static bool dragStarted;
    static float startX;

    if (event->MouseButtonDblClick)
    {
        //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;
    }
    else if (event->MouseButtonPress)
    {
524
        startX = event->globalX();
525 526
        if (event->button() == Qt::RightButton)
        {
527 528
            // Start tracking mouse move
            dragStarted = true;
529 530 531 532 533 534
        }
        else if (event->button() == Qt::LeftButton)
        {

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

545 546 547 548 549 550 551 552 553
void HSIDisplay::setMetricWidth(double width)
{
    if (width != metricWidth)
    {
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

554 555 556 557 558 559
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579
        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)));
        }
580

581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599
        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)));

        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)));

        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)));

        this->uas = uas;
600 601

        resetMAVState();
602 603
}

604 605 606 607 608 609 610
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;
611
    this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
612 613 614 615 616 617
}

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

lm's avatar
lm committed
618 619 620 621 622
    QPointF sp(x, y);
    sp = metricBodyToWorld(sp);
    uiXSetCoordinate = sp.x();
    uiYSetCoordinate = sp.y();

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

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

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

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

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

lm's avatar
lm committed
653 654 655 656 657 658 659 660 661
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
662
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
663
{
664 665
    Q_UNUSED(usec);
    Q_UNUSED(uasid);
666 667 668 669
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
670
    mavInitialized = true;
671
    setPointKnown = true;
672
    positionSetPointKnown = true;
pixhawk's avatar
pixhawk committed
673

674 675 676 677 678
    //    qDebug() << "Received setpoint at x: " << x << "metric y:" << y;
    //    posXSet = xDesired;
    //    posYSet = yDesired;
    //    posZSet = zDesired;
    //    posYawSet = yawDesired;
679 680 681 682
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
683 684 685 686
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
687 688 689 690
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
691 692 693 694
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
695 696
}

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

712 713 714
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
    yawControlEnabled = enabled;
715
    yawControlKnown = true;
716 717 718 719 720 721 722 723 724
}

/**
 * @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;
725
    positionFixKnown = true;
726
    //qDebug() << "LOCALIZATION FIX CALLED";
727 728 729 730 731 732 733 734
}
/**
 * @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;
735
    gpsFixKnown = true;
736 737 738 739 740 741 742 743
}
/**
 * @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;
744
    visionFixKnown = true;
745
    //qDebug() << "VISION FIX GOT CALLED";
746 747
}

748 749 750 751 752 753 754
/**
 * @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;
755
    iruFixKnown = true;
756 757
}

lm's avatar
lm committed
758 759
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
760
    QColor color;
lm's avatar
lm committed
761 762 763 764 765
    if (snr > 0 && snr < 30)
    {
        color = QColor(250, 10, 10);
    }
    else if (snr >= 30 && snr < 35)
lm's avatar
lm committed
766
    {
lm's avatar
lm committed
767
        color = QColor(230, 230, 10);
lm's avatar
lm committed
768
    }
lm's avatar
lm committed
769
    else if (snr >= 35 && snr < 40)
lm's avatar
lm committed
770
    {
lm's avatar
lm committed
771
        color = QColor(90, 200, 90);
lm's avatar
lm committed
772
    }
lm's avatar
lm committed
773
    else if (snr >= 40)
lm's avatar
lm committed
774
    {
lm's avatar
lm committed
775
        color = QColor(20, 200, 20);
lm's avatar
lm committed
776 777 778 779 780 781
    }
    else
    {
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
782 783
}

784
void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color, QPainter &painter)
785
{
786 787 788 789 790 791 792 793 794 795 796 797 798 799
    if (setPointKnown)
    {
        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);
800
        radius *= 0.8f;
801 802 803 804
        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);
    }
805 806
}

807 808
void HSIDisplay::drawWaypoints(QPainter& painter)
{
809
    if (uas)
pixhawk's avatar
pixhawk committed
810
    {
pixhawk's avatar
pixhawk committed
811
		const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointList();
812 813 814 815 816 817 818 819 820 821 822 823
        //        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);
        //        }
824 825 826

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

828
        QPointF lastWaypoint;
pixhawk's avatar
pixhawk committed
829

830
        for (int i = 0; i < list.size(); i++)
pixhawk's avatar
pixhawk committed
831
        {
832 833 834 835 836 837 838 839 840 841 842 843 844
            QPointF in;
            if (list.at(i)->getFrame() == MAV_FRAME_LOCAL)
            {
                // Do not transform
                in = QPointF(list.at(i)->getX(), list.at(i)->getY());
            }
            else
            {
                // Transform to local coordinates first
                double x = list.at(i)->getX();
                double y = list.at(i)->getY();
                in = QPointF(x, y);
            }
845 846 847 848 849
            // Transform from world to body coordinates
            in = metricWorldToBody(in);
            // Scale from metric to screen reference coordinates
            QPointF p = metricBodyToRef(in);

850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865
            // 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()));

866 867 868
            // Select color based on if this is the current waypoint
            if (list.at(i)->getCurrent())
            {
869 870
                color = QGC::colorCyan;//uas->getColor();
                pen.setWidthF(refLineWidthToPen(0.8f));
871 872 873 874
            }
            else
            {
                color = uas->getColor();
875
                pen.setWidthF(refLineWidthToPen(0.4f));
876 877
            }

878
            pen.setColor(color);
879
            painter.setPen(pen);
880
            float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
881
            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);
882
            drawPolygon(poly, &painter);
883

884
            // DRAW CONNECTING LINE
885 886 887
            // Draw line from last waypoint to this one
            if (!lastWaypoint.isNull())
            {
888 889 890
                pen.setWidthF(refLineWidthToPen(0.4f));
                painter.setPen(pen);
                color = uas->getColor();
891 892 893
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f), color, &painter);
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
894 895
        }
    }
896 897
}

898 899 900 901 902 903
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);
904
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
905
}
lm's avatar
lm committed
906

907 908 909 910
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
    float yCenter = xCenterPos;
lm's avatar
lm committed
911 912
    // Max satellite circle radius

lm's avatar
lm committed
913 914 915
    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
916

pixhawk's avatar
pixhawk committed
917 918 919 920 921
    // 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
922 923
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
    while (i.hasNext())
lm's avatar
lm committed
924
    {
lm's avatar
lm committed
925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943
        i.next();
        GPSSatellite* sat = i.value();

        // Check if update is not older than 5 seconds, else delete satellite
        if (sat->lastUpdate + 1000000 < currTime)
        {
            // Delete and go to next satellite
            gpsSatellites.remove(i.key());
            if (i.hasNext())
            {
                i.next();
                sat = i.value();
            }
            else
            {
                continue;
            }
        }

lm's avatar
lm committed
944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961
        if (sat)
        {
            // Draw satellite
            QBrush brush;
            QColor color = getColorForSNR(sat->snr);
            brush.setColor(color);
            if (sat->used)
            {
                brush.setStyle(Qt::SolidPattern);
            }
            else
            {
                brush.setStyle(Qt::NoBrush);
            }
            painter.setPen(Qt::SolidLine);
            painter.setPen(color);
            painter.setBrush(brush);

lm's avatar
lm committed
962 963
            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
964

965
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
966
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
967
            // Draw satellite PRN
lm's avatar
lm committed
968
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
969 970
        }
    }
971 972
}

973
void HSIDisplay::drawObjects(QPainter &painter)
974
{
975
    Q_UNUSED(painter);
976 977
}

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

986
        float angle = atan2(posXSet, -posYSet);
987
        angle -= (float)M_PI/2.0f;
988

989
        QPolygonF p(6);
990

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

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

995 996 997 998 999 1000
        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));
1001

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

1004 1005 1006 1007 1008 1009 1010
        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
1011

1012 1013
        //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
    }
1014 1015
}

1016
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1017
{
1018 1019 1020 1021 1022
    if (attControlKnown && attControlEnabled)
    {
        // Draw the needle
        const float maxWidth = radius / 10.0f;
        const float minWidth = maxWidth * 0.3f;
1023

1024
        float angle = atan2(attXSet, attYSet);
1025
        angle -= (float)M_PI/2.0f;
lm's avatar
lm committed
1026

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

1029
        QPolygonF p(6);
1030

1031 1032 1033 1034 1035 1036
        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));
1037

1038
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1039

1040 1041 1042 1043 1044 1045 1046
        QBrush indexBrush;
        indexBrush.setColor(color);
        indexBrush.setStyle(Qt::SolidPattern);
        painter->setPen(Qt::SolidLine);
        painter->setPen(color);
        painter->setBrush(indexBrush);
        drawPolygon(p, painter);
1047

1048
        // TODO Draw Yaw indicator
lm's avatar
lm committed
1049

1050 1051
        //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
    }
1052 1053 1054 1055
}

void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
{
1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071
    if (zControlKnown && zControlEnabled)
    {
        // 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);
    }
1072
}
1073

1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089
void HSIDisplay::wheelEvent(QWheelEvent* event)
{
    double zoomScale = 0.005; // Scaling of zoom value
    if(event->delta() > 0)
    {
        // Reduce width -> Zoom in
        metricWidth -= event->delta() * zoomScale;
    }
    else
    {
        // Increase width -> Zoom out
        metricWidth -= event->delta() * zoomScale;
    }
    metricWidth = qBound(0.1, metricWidth, 9999.0);
    emit metricWidthChanged(metricWidth);
}
pixhawk's avatar
pixhawk committed
1090

1091 1092 1093 1094
void HSIDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
1095
    Q_UNUSED(event)
1096
    {
1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107
        refreshTimer->start(updateInterval);
    }
}

void HSIDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (post-display)
    // events
    Q_UNUSED(event)
    {
        refreshTimer->stop();
1108 1109 1110
    }
}

1111 1112
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
1113 1114 1115 1116 1117 1118
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
1119 1120 1121 1122
}

void HSIDisplay::pressKey(int key)
{
1123
    Q_UNUSED(key);
1124
}
pixhawk's avatar
pixhawk committed
1125 1126