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

#include <QDebug>

49

50
HSIDisplay::HSIDisplay(QWidget *parent) :
51 52 53 54 55 56 57 58 59 60
    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),
61 62
    attXSaturation(0.2f),
    attYSaturation(0.2f),
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
    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),
88
    uiZSetCoordinate(-0.51f),
89 90 91 92 93 94 95 96 97 98 99 100 101
    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),
102
    dragStarted(false),
103
    topMargin(12.0f),
104
    leftDragStarted(false),
pixhawk's avatar
pixhawk committed
105
    mouseHasMoved(false),
106 107 108
    actionPending(false),
    userSetPointSet(false),
    userXYSetPointSet(false)
109
{
110
    refreshTimer->setInterval(updateInterval);
111

pixhawk's avatar
pixhawk committed
112
    columns = 1;
113
    this->setAutoFillBackground(true);
114 115 116
    QPalette pal = palette();
    pal.setColor(backgroundRole(), QGC::colorBlack);
    setPalette(pal);
117

118 119
    vwidth = 80.0f;
    vheight = 80.0f;
pixhawk's avatar
pixhawk committed
120

121
    xCenterPos = vwidth/2.0f;
pixhawk's avatar
pixhawk committed
122
    yCenterPos = vheight/2.0f + topMargin - bottomMargin;
123

124 125 126
    uas = NULL;
    resetMAVState();

127 128
    // Do first update
    setMetricWidth(metricWidth);
129 130 131
    // Set tooltip
    setToolTip(tr("View from top in body frame. Scroll with mouse wheel to change the horizontal field of view of the widget."));
    setStatusTip(tr("View from top in body frame. Scroll with mouse wheel to change the horizontal field of view of the widget."));
132 133

    connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage()));
134 135 136
    statusClearTimer.start(3000);

    setFocusPolicy(Qt::StrongFocus);
137 138
}

139 140 141 142 143
HSIDisplay::~HSIDisplay()
{

}

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
    if (!isVisible()) return;
189 190 191
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
192 193
    // Center location of the HSI gauge items

194
    //float bottomMargin = 3.0f;
195 196

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

200 201 202 203 204 205 206 207
    // 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;

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

212 213
    // Draw base instrument
    // ----------------------
lm's avatar
lm committed
214
    painter.setBrush(Qt::NoBrush);
215
    const QColor ringColor = QColor(200, 250, 200);
lm's avatar
lm committed
216 217 218 219
    QPen pen;
    pen.setColor(ringColor);
    pen.setWidth(refLineWidthToPen(0.1f));
    painter.setPen(pen);
lm's avatar
lm committed
220
    const int ringCount = 2;
221
    for (int i = 0; i < ringCount; i++) {
222
        float radius = (vwidth - (topMargin + bottomMargin)*0.3f) / (1.35f * i+1) / 2.0f - bottomMargin / 2.0f;
223
        drawCircle(xCenterPos, yCenterPos, radius, 0.1f, ringColor, &painter);
224
        paintText(tr("%1 m").arg(refToMetric(radius), 5, 'f', 1, ' '), QGC::colorCyan, 1.6f, vwidth/2-4, vheight/2+radius+2.2, &painter);
lm's avatar
lm committed
225 226
    }

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

240 241 242 243 244 245 246 247 248
    // Draw trail
//    QPointF m(bodyXSetCoordinate, bodyYSetCoordinate);
//    // Transform from body to world coordinates
//    m = metricWorldToBody(m);
//    // Scale from metric body to screen reference units
//    QPointF s = metricBodyToRef(m);
//    drawLine(s.x(), s.y(), xCenterPos, yCenterPos, 1.5f, uas->getColor(), &painter);


lm's avatar
lm committed
249
    // Draw center indicator
250 251 252 253 254 255
//    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);

256
    if (uas) {
257 258 259
        // Translate to center
        painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
        QColor uasColor = uas->getColor();
260
        MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
lm's avatar
lm committed
261
        //MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
262 263 264
        // Translate back
        painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);
    }
265 266

    // ----------------------
267

268 269 270
    // Draw satellites
    drawGPS(painter);

271 272 273
    // Draw state indicator

    // Draw position
274
    QColor positionColor(20, 20, 200);
275
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
276 277 278

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
279
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
280 281


282
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
283

284 285 286 287 288 289
    float xSpDiff = uiXSetCoordinate - bodyXSetCoordinate;
    float ySpDiff = uiYSetCoordinate - bodyYSetCoordinate;
    float zSpDiff = uiZSetCoordinate - bodyZSetCoordinate;

    float setPointDist = sqrt(xSpDiff*xSpDiff + ySpDiff*ySpDiff + zSpDiff*zSpDiff);

290 291 292 293
    float angleDiff = uiYawSet - bodyYawSet;

    float normAngleDiff = fabs(atan2(sin(angleDiff), cos(angleDiff)));

294
    if (userSetPointSet && setPointDist > 0.08f || normAngleDiff > 0.05f || dragStarted)
295
    {
296
        QColor spColor(150, 150, 150);
297
        drawSetpointXYZYaw(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet, spColor, painter);
298 299
    }

300 301 302 303 304 305 306 307
    // Labels on outer part and bottom

    // Draw waypoints
    drawWaypoints(painter);

    // Draw setpoint over waypoints
    if (positionSetPointKnown)
    {
308
        // Draw setpoint
309
        drawSetpointXYZYaw(bodyXSetCoordinate, bodyYSetCoordinate, bodyZSetCoordinate, bodyYawSet, uas->getColor(), painter);
310 311
        // Draw travel direction line
        QPointF m(bodyXSetCoordinate, bodyYSetCoordinate);
lm's avatar
lm committed
312 313 314
        // Transform from body to world coordinates
        m = metricWorldToBody(m);
        // Scale from metric body to screen reference units
315
        QPointF s = metricBodyToRef(m);
316
        drawLine(s.x(), s.y(), xCenterPos, yCenterPos, 1.5f, uas->getColor(), &painter);
317 318
    }

319
    // Draw status flags
320 321 322 323
    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);
324

325
    // Draw position lock indicators
326 327 328 329
    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);
330 331 332

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

    // Draw crosstrack error to top right
    float crossTrackError = 0;
337 338
    paintText(tr("XTRACK"), QGC::colorCyan, 2.2f, 54, 11, &painter);
    paintText(tr("%1 m").arg(crossTrackError, 5, 'f', 2, '0'), Qt::white, 2.2f, 67, 11, &painter);
339 340

    // Draw position to bottom left
341
    if (localAvailable > 0 && globalAvailable == 0) {
342 343 344
        // Position
        QString str;
        str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
345 346
        paintText(tr("POS"), QGC::colorCyan, 2.6f, 2, vheight- 4.0f, &painter);
        paintText(str, Qt::white, 2.6f, 10, vheight - 4.0f, &painter);
347 348
    }

349
    if (globalAvailable > 0) {
350 351
        // Position
        QString str;
352
        str.sprintf("lat: %05.2f lon: %06.2f alt: %06.2f", lat, lon, alt);
353 354
        paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 4.0f, &painter);
        paintText(str, Qt::white, 2.6f, 10, vheight - 4.0f, &painter);
355 356
    }

357 358 359 360 361 362 363
    // Draw Safety
    double x1, y1, z1, x2, y2, z2;
    UASManager::instance()->getLocalNEDSafetyLimits(&x1, &y1, &z1, &x2, &y2, &z2);
//    drawSafetyArea(QPointF(x1, y1), QPointF(x2, y2), QGC::colorYellow, painter);

    // Draw status message
    paintText(statusMessage, QGC::colorOrange, 2.4f, 8, 15, &painter);
364
}
365

366
void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, QPainter& painter)
367
{
368
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
369
    QColor statusColor(250, 250, 250);
370
    if(status) {
pixhawk's avatar
pixhawk committed
371
        painter.setBrush(QGC::colorGreen);
372
    } else {
373
        painter.setBrush(QGC::colorDarkYellow);
374 375
    }
    painter.setPen(Qt::NoPen);
376 377 378 379 380

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

    painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), indicatorWidth, indicatorHeight));
381
    paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
382
    // Cross out instrument if state unknown
383 384
    if (!known)
    {
385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401
        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);
    }
402 403
}

404
void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, bool known, QPainter& painter)
405
{
406 407 408 409 410 411 412 413 414 415 416 417
    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);
    }
418

419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434
    // 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;
    }
435

436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460
    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);
    }
461 462
}

lm's avatar
lm committed
463 464
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
465
    Q_UNUSED(uas);
lm's avatar
lm committed
466 467 468
    positionLock = lock;
}

pixhawk's avatar
pixhawk committed
469
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
470 471
{
    attControlEnabled = enabled;
472
    attControlKnown = true;
lm's avatar
lm committed
473 474
}

pixhawk's avatar
pixhawk committed
475
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
476 477
{
    xyControlEnabled = enabled;
478
    xyControlKnown = true;
lm's avatar
lm committed
479 480
}

pixhawk's avatar
pixhawk committed
481
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
482 483
{
    zControlEnabled = enabled;
484
    zControlKnown = true;
lm's avatar
lm committed
485 486
}

LM's avatar
LM committed
487 488
void HSIDisplay::updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance)
{
489 490 491 492 493
	Q_UNUSED(quality);
	Q_UNUSED(name);
	Q_UNUSED(type);
	Q_UNUSED(id);
	Q_UNUSED(time);
LM's avatar
LM committed
494 495 496 497 498 499 500 501 502 503 504 505 506 507 508
    // 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
509 510 511 512
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
    // First translate to body-centered coordinates
    // Rotate around -yaw
513
    float angle = -yaw - M_PI;
514
    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
515 516 517 518 519 520 521
    return result;
}

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
522
    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
523
    return result;
524
}
525

526 527
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
528
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth);
529 530 531 532
}

QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
lm's avatar
lm committed
533
    return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
534 535 536 537 538
}

/**
 * @see refToScreenX()
 */
539
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
540 541 542 543
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

544 545 546 547 548 549 550 551 552 553
double HSIDisplay::metricToRef(double metric)
{
    return (metric / metricWidth) * vwidth;
}

double HSIDisplay::refToMetric(double ref)
{
    return (ref/vwidth) * metricWidth;
}

554 555 556 557 558 559 560 561
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

562 563
void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
564 565
    if (event->type() == QMouseEvent::MouseButtonDblClick)
    {
566 567
        QPointF p = screenToMetricBody(event->posF());
        setBodySetpointCoordinateXY(p.x(), p.y());
568
//        qDebug() << "Double click at x: " << screenToRefX(event->x()) - xCenterPos << "y:" << screenToRefY(event->y()) - yCenterPos;
569 570 571 572 573
    }
}

void HSIDisplay::mouseReleaseEvent(QMouseEvent * event)
{
574
    if (mouseHasMoved)
575
    {
576 577 578 579 580 581 582 583 584 585 586 587
        if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::RightButton)
        {
            if (dragStarted)
            {
                setBodySetpointCoordinateYaw(uiYawSet);
                dragStarted = false;
            }
        }
        if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::LeftButton)
        {
            if (leftDragStarted)
            {
588 589
                setBodySetpointCoordinateZ(uiZSetCoordinate);
                leftDragStarted = false;
590 591
            }
        }
592
    }
593
    mouseHasMoved = false;
594 595 596 597 598 599 600 601 602
}

void HSIDisplay::mousePressEvent(QMouseEvent * event)
{
    if (event->type() == QMouseEvent::MouseButtonPress)
    {
        if (event->button() == Qt::RightButton)
        {
            startX = event->x();
603 604
            // Start tracking mouse move
            dragStarted = true;
605 606 607
        }
        else if (event->button() == Qt::LeftButton)
        {
608 609
            startY = event->y();
            leftDragStarted = true;
610
        }
pixhawk's avatar
pixhawk committed
611
    }
612
    mouseHasMoved = false;
613
}
614

615 616 617 618
void HSIDisplay::mouseMoveEvent(QMouseEvent * event)
{
    if (event->type() == QMouseEvent::MouseMove)
    {
619
        if (dragStarted) uiYawSet -= 0.06f*(startX - event->x()) / this->frameSize().width();
620 621 622

        if (leftDragStarted)
        {
pixhawk's avatar
pixhawk committed
623
//            uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height();
624
//            setBodySetpointCoordinateZ(uiZSetCoordinate);
625
        }
626 627

        if (leftDragStarted || dragStarted) mouseHasMoved = true;
pixhawk's avatar
pixhawk committed
628
    }
629 630
}

pixhawk's avatar
pixhawk committed
631 632
void HSIDisplay::keyPressEvent(QKeyEvent* event)
{
633
    if ((event->key() == Qt::Key_Enter || event->key() == Qt::Key_Return) && actionPending)
pixhawk's avatar
pixhawk committed
634 635 636 637 638 639 640 641 642 643 644 645
    {
        actionPending = false;
        statusMessage = "SETPOINT SENT";
        statusClearTimer.start();
        sendBodySetPointCoordinates();
    }
    else
    {
        HDDisplay::keyPressEvent(event);
    }
}

646 647 648 649 650
void HSIDisplay::contextMenuEvent (QContextMenuEvent* event)
{
    event->ignore();
}

651 652
void HSIDisplay::setMetricWidth(double width)
{
653
    if (width != metricWidth) {
654 655 656 657 658
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

659 660 661 662 663 664
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682
    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
683
        disconnect(this->uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
684
    }
685

686 687 688 689 690 691 692
    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)));
693

694 695 696 697
    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)));
698

699 700 701 702
    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
703
    connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
704

705
    this->uas = uas;
706

707
    resetMAVState();
708 709
}

710 711 712 713 714 715 716
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;
717
    this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
718 719 720 721
}

void HSIDisplay::setBodySetpointCoordinateXY(double x, double y)
{
722
    userSetPointSet = true;
723
    userXYSetPointSet = true;
724 725
    // Set coordinates and send them out to MAV

lm's avatar
lm committed
726 727 728 729 730
    QPointF sp(x, y);
    sp = metricBodyToWorld(sp);
    uiXSetCoordinate = sp.x();
    uiYSetCoordinate = sp.y();

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

733 734
    if (uas && mavInitialized)
    {
pixhawk's avatar
pixhawk committed
735 736 737 738
        //sendBodySetPointCoordinates();
        statusMessage = "POSITION SET, PRESS <ENTER> TO SEND";
        actionPending = true;
        statusClearTimer.start();
pixhawk's avatar
pixhawk committed
739
    }
740 741 742 743
}

void HSIDisplay::setBodySetpointCoordinateZ(double z)
{
744
    userSetPointSet = true;
745 746
    // Set coordinates and send them out to MAV
    uiZSetCoordinate = z;
pixhawk's avatar
pixhawk committed
747 748 749 750
    statusMessage = "Z SET, PRESS <ENTER> TO SEND";
    actionPending = true;
    statusClearTimer.start();
    //sendBodySetPointCoordinates();
751 752 753 754
}

void HSIDisplay::setBodySetpointCoordinateYaw(double yaw)
{
755 756 757 758 759 760 761 762 763 764 765
    if (!userXYSetPointSet && setPointKnown)
    {
        uiXSetCoordinate = bodyXSetCoordinate;
        uiYSetCoordinate = bodyYSetCoordinate;
    }
    else if (!userXYSetPointSet && mavInitialized)
    {
        QPointF coord = metricBodyToWorld(QPointF(0.0, 0.0));
        uiXSetCoordinate = coord.x();
        uiYSetCoordinate = coord.y();
    }
766 767 768
    userSetPointSet = true;
    // Set coordinates and send them out to MAV
    uiYawSet = atan2(sin(yaw), cos(yaw));
pixhawk's avatar
pixhawk committed
769 770 771 772
    statusMessage = "YAW SET, PRESS <ENTER> TO SEND";
    statusClearTimer.start();
    actionPending = true;
    //sendBodySetPointCoordinates();
773 774 775 776 777
}

void HSIDisplay::sendBodySetPointCoordinates()
{
    // Send the coordinates to the MAV
778 779 780 781 782 783 784 785 786 787 788 789 790 791 792
    if (uas && mavInitialized)
    {
        double dx = uiXSetCoordinate - uas->getLocalX();
        double dy = uiYSetCoordinate - uas->getLocalY();
        double dz = uiZSetCoordinate - uas->getLocalZ();
        bool valid = (sqrt(dx*dx + dy*dy + dz*dz) < 1.0);//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
        if (valid)
        {
            uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
        }
        else
        {
            setStatusMessage("REJECTED NEW SETPOINT: OUT OF BOUNDS");
        }
    }
793 794
}

795
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
796
{
797 798 799 800 801 802
    Q_UNUSED(uas);
    Q_UNUSED(usec);
    attXSet = pitchDesired;
    attYSet = rollDesired;
    attYawSet = yawDesired;
    altitudeSet = thrustDesired;
803 804
}

lm's avatar
lm committed
805 806 807 808 809 810 811 812 813
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
814
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
815
{
816 817
    Q_UNUSED(usec);
    Q_UNUSED(uasid);
818 819 820 821
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
822
    mavInitialized = true;
823
    setPointKnown = true;
824
    positionSetPointKnown = true;
pixhawk's avatar
pixhawk committed
825

826 827 828 829
    if (!userSetPointSet && !dragStarted)
    {
        uiXSetCoordinate = bodyXSetCoordinate;
        uiYSetCoordinate = bodyYSetCoordinate;
pixhawk's avatar
pixhawk committed
830
//        uiZSetCoordinate = bodyZSetCoordinate;
831 832
        uiYawSet= bodyYawSet;
    }
833 834 835 836
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
837 838 839 840
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
841 842 843 844
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
845 846 847 848
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
849 850
}

lm's avatar
lm committed
851
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
lm's avatar
lm committed
852 853
{
    Q_UNUSED(uasid);
lm's avatar
lm committed
854
    //qDebug() << "UPDATED SATELLITE";
lm's avatar
lm committed
855
    // If slot is empty, insert object
856
    if (gpsSatellites.contains(satid)) {
lm's avatar
lm committed
857
        gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
858
    } else {
lm's avatar
lm committed
859
        gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
lm's avatar
lm committed
860 861 862
    }
}

863 864 865
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
    yawControlEnabled = enabled;
866
    yawControlKnown = true;
867 868 869 870 871 872 873 874 875
}

/**
 * @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;
876
    positionFixKnown = true;
877
    //qDebug() << "LOCALIZATION FIX CALLED";
878 879 880 881 882 883 884 885
}
/**
 * @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;
886
    gpsFixKnown = true;
887 888 889 890 891 892 893 894
}
/**
 * @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;
895
    visionFixKnown = true;
896
    //qDebug() << "VISION FIX GOT CALLED";
897 898
}

899 900 901 902 903 904 905
/**
 * @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;
906
    iruFixKnown = true;
907 908
}

lm's avatar
lm committed
909 910
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
911
    QColor color;
912
    if (snr > 0 && snr < 30) {
lm's avatar
lm committed
913
        color = QColor(250, 10, 10);
914
    } else if (snr >= 30 && snr < 35) {
lm's avatar
lm committed
915
        color = QColor(230, 230, 10);
916
    } else if (snr >= 35 && snr < 40) {
lm's avatar
lm committed
917
        color = QColor(90, 200, 90);
918
    } else if (snr >= 40) {
lm's avatar
lm committed
919
        color = QColor(20, 200, 20);
920
    } else {
lm's avatar
lm committed
921 922 923
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
924 925
}

926
void HSIDisplay::drawSetpointXYZYaw(float x, float y, float z, float yaw, const QColor &color, QPainter &painter)
927
{
928
    if (setPointKnown && uas) {
929
        float radius = vwidth / 18.0f;
930 931 932 933 934 935 936 937 938 939
        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);
940 941 942 943 944 945 946 947 948 949

        QPolygonF poly(4);
        // Top point
        poly.replace(0, QPointF(p.x()-radius, p.y()-radius));
        // Right point
        poly.replace(1, QPointF(p.x()+radius, p.y()-radius));
        // Bottom point
        poly.replace(2, QPointF(p.x()+radius, p.y()+radius));
        poly.replace(3, QPointF(p.x()-radius, p.y()+radius));

950 951 952
        // Label
        paintText(QString("z: %1 m").arg(z), color, 1.2f, p.x()-radius, p.y()-radius-2.0f, &painter);

953 954
        drawPolygon(poly, &painter);

955
        radius *= 0.8f;
956
        drawLine(p.x(), p.y(), p.x()+sin(-yaw + uas->getYaw() + M_PI) * radius, p.y()+cos(-yaw + uas->getYaw() + M_PI) * radius, refLineWidthToPen(0.4f), color, &painter);
957 958

        // Draw center dot
959 960 961
        painter.setBrush(color);
        drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter);
    }
962 963
}

964 965
void HSIDisplay::drawWaypoints(QPainter& painter)
{
966 967
    if (uas)
    {
pixhawk's avatar
pixhawk committed
968
        const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
969 970 971

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

973
        QPointF lastWaypoint;
pixhawk's avatar
pixhawk committed
974

975
        for (int i = 0; i < list.size(); i++) {
976
            QPointF in;
977 978
            if (list.at(i)->getFrame() == MAV_FRAME_LOCAL_NED)
            {
979 980
                // Do not transform
                in = QPointF(list.at(i)->getX(), list.at(i)->getY());
981
            } else {
982 983 984 985 986
                // Transform to local coordinates first
                double x = list.at(i)->getX();
                double y = list.at(i)->getY();
                in = QPointF(x, y);
            }
987 988 989 990 991
            // Transform from world to body coordinates
            in = metricWorldToBody(in);
            // Scale from metric to screen reference coordinates
            QPointF p = metricBodyToRef(in);

992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006
            // Setup pen
            QPen pen(color);
            painter.setBrush(Qt::NoBrush);

            // DRAW WAYPOINT
            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()));

1007
            // Select color based on if this is the current waypoint
1008
            if (list.at(i)->getCurrent()) {
1009
                color = QGC::colorYellow;//uas->getColor();
1010
                pen.setWidthF(refLineWidthToPen(0.8f));
1011
            } else {
1012
                color = QGC::colorCyan;
1013
                pen.setWidthF(refLineWidthToPen(0.4f));
1014 1015
            }

1016
            pen.setColor(color);
1017
            painter.setPen(pen);
1018
            float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
1019
            drawLine(p.x(), p.y(), p.x()+sin(list.at(i)->getYaw()/180.0*M_PI-yaw) * radius, p.y()-cos(list.at(i)->getYaw()/180.0*M_PI-yaw) * radius, refLineWidthToPen(0.4f), color, &painter);
1020
            drawPolygon(poly, &painter);
1021 1022
            float acceptRadius = list.at(i)->getAcceptanceRadius();
            drawCircle(p.x(), p.y(), metricToRef(acceptRadius), 1.0, Qt::green, &painter);
1023

1024
            // DRAW CONNECTING LINE
1025
            // Draw line from last waypoint to this one
1026 1027
            if (!lastWaypoint.isNull())
            {
1028 1029
                pen.setWidthF(refLineWidthToPen(0.4f));
                painter.setPen(pen);
1030
                color = QGC::colorCyan;
1031 1032 1033
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f), color, &painter);
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
1034 1035
        }
    }
1036 1037
}

1038 1039 1040 1041 1042
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);
1043
    pen.setBrush(Qt::NoBrush);
1044
    painter.setPen(pen);
1045
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
1046
}
lm's avatar
lm committed
1047

1048 1049 1050 1051
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
    float yCenter = xCenterPos;
lm's avatar
lm committed
1052 1053
    // Max satellite circle radius

lm's avatar
lm committed
1054 1055 1056
    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
1057

pixhawk's avatar
pixhawk committed
1058 1059 1060 1061 1062
    // 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
1063
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
1064
    while (i.hasNext()) {
lm's avatar
lm committed
1065 1066 1067 1068
        i.next();
        GPSSatellite* sat = i.value();

        // Check if update is not older than 5 seconds, else delete satellite
1069
        if (sat->lastUpdate + 1000000 < currTime) {
lm's avatar
lm committed
1070 1071
            // Delete and go to next satellite
            gpsSatellites.remove(i.key());
1072
            if (i.hasNext()) {
lm's avatar
lm committed
1073 1074
                i.next();
                sat = i.value();
1075
            } else {
lm's avatar
lm committed
1076 1077 1078 1079
                continue;
            }
        }

1080
        if (sat) {
lm's avatar
lm committed
1081 1082 1083 1084
            // Draw satellite
            QBrush brush;
            QColor color = getColorForSNR(sat->snr);
            brush.setColor(color);
1085
            if (sat->used) {
lm's avatar
lm committed
1086
                brush.setStyle(Qt::SolidPattern);
1087
            } else {
lm's avatar
lm committed
1088 1089 1090 1091 1092 1093
                brush.setStyle(Qt::NoBrush);
            }
            painter.setPen(Qt::SolidLine);
            painter.setPen(color);
            painter.setBrush(brush);

lm's avatar
lm committed
1094 1095
            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
1096

1097
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
1098
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
1099
            // Draw satellite PRN
lm's avatar
lm committed
1100
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
1101 1102
        }
    }
1103 1104
}

1105
void HSIDisplay::drawObjects(QPainter &painter)
1106
{
1107
    Q_UNUSED(painter);
1108 1109
}

1110
void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1111
{
1112
    if (xyControlKnown && xyControlEnabled) {
1113
        // Draw the needle
1114
        const float maxWidth = radius / 5.0f;
1115
        const float minWidth = maxWidth * 0.3f;
1116

1117
        float angle = atan2(posXSet, -posYSet);
1118
        angle -= (float)M_PI/2.0f;
1119

1120
        QPolygonF p(6);
1121

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

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

1126 1127 1128 1129 1130 1131
        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));
1132

1133
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1134

1135 1136 1137 1138 1139 1140 1141
        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
1142

1143 1144
        //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
    }
1145 1146
}

1147
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1148
{
1149
    if (attControlKnown && attControlEnabled) {
1150 1151 1152
        // Draw the needle
        const float maxWidth = radius / 10.0f;
        const float minWidth = maxWidth * 0.3f;
1153

1154
        float angle = atan2(attYSet, -attXSet);
lm's avatar
lm committed
1155

1156
        radius *= sqrt(attXSet*attXSet + attYSet*attYSet) / sqrt(attXSaturation*attXSaturation + attYSaturation*attYSaturation);
1157

1158
        QPolygonF p(6);
1159

1160 1161 1162 1163 1164 1165
        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));
1166

1167
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1168

1169 1170 1171 1172 1173 1174 1175
        QBrush indexBrush;
        indexBrush.setColor(color);
        indexBrush.setStyle(Qt::SolidPattern);
        painter->setPen(Qt::SolidLine);
        painter->setPen(color);
        painter->setBrush(indexBrush);
        drawPolygon(p, painter);
1176

1177
        // TODO Draw Yaw indicator
lm's avatar
lm committed
1178

1179 1180
        //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
    }
1181 1182 1183 1184
}

void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
{
1185
    if (zControlKnown && zControlEnabled) {
1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199
        // 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);
    }
1200
}
1201

1202 1203 1204
void HSIDisplay::wheelEvent(QWheelEvent* event)
{
    double zoomScale = 0.005; // Scaling of zoom value
1205
    if(event->delta() > 0) {
1206 1207
        // Reduce width -> Zoom in
        metricWidth -= event->delta() * zoomScale;
1208
    } else {
1209 1210 1211
        // Increase width -> Zoom out
        metricWidth -= event->delta() * zoomScale;
    }
1212
    metricWidth = qBound(0.5, metricWidth, 9999.0);
1213 1214
    emit metricWidthChanged(metricWidth);
}
pixhawk's avatar
pixhawk committed
1215

1216 1217 1218 1219
void HSIDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
1220
    Q_UNUSED(event) {
1221 1222 1223 1224 1225 1226 1227 1228
        refreshTimer->start(updateInterval);
    }
}

void HSIDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (post-display)
    // events
1229
    Q_UNUSED(event) {
1230
        refreshTimer->stop();
1231 1232 1233
    }
}

1234 1235
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
1236 1237 1238 1239 1240 1241
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
1242 1243 1244 1245
}

void HSIDisplay::pressKey(int key)
{
1246
    Q_UNUSED(key);
1247
}
pixhawk's avatar
pixhawk committed
1248 1249