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

3
QGroundControl Open Source Ground Control Station
4

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

7
This file is part of the QGROUNDCONTROL project
8

9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
10 11 12 13
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
15 16 17 18 19
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
21 22 23 24 25 26 27 28 29 30 31 32 33

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

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

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

#include <QDebug>

49

50
HSIDisplay::HSIDisplay(QWidget *parent) :
51
    HDDisplay(NULL, "HSI", parent),
52 53 54 55 56 57 58
    dragStarted(false),
    leftDragStarted(false),
    mouseHasMoved(false),
    startX(0.0f),
    startY(0.0f),
    actionPending(false),
    directSending(false),
59 60 61 62 63 64 65 66 67
    gpsSatellites(),
    satellitesUsed(0),
    attXSet(0.0f),
    attYSet(0.0f),
    attYawSet(0.0f),
    altitudeSet(1.0f),
    posXSet(0.0f),
    posYSet(0.0f),
    posZSet(0.0f),
68 69
    attXSaturation(0.2f),
    attYSaturation(0.2f),
70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94
    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),
LM's avatar
LM committed
95
    uiZSetCoordinate(0.0f),
96 97
    uiYawSet(0.0f),
    metricWidth(4.0),
98 99
    xCenterPos(0),
    yCenterPos(0),
100 101 102 103 104 105 106 107 108
    positionLock(false),
    attControlEnabled(false),
    xyControlEnabled(false),
    zControlEnabled(false),
    yawControlEnabled(false),
    positionFix(0),
    gpsFix(0),
    visionFix(0),
    laserFix(0),
109
    iruFix(0),
110
    mavInitialized(false),
111 112
    topMargin(20.0f),
    bottomMargin(14.0f),
113 114 115 116 117 118 119 120
    attControlKnown(false),
    xyControlKnown(false),
    zControlKnown(false),
    yawControlKnown(false),
    positionFixKnown(false),
    visionFixKnown(false),
    gpsFixKnown(false),
    iruFixKnown(false),
121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146
    gyroKnown(false),
    gyroON(false),
    gyroOK(false),
    accelKnown(false),
    accelON(false),
    accelOK(false),
    magKnown(false),
    magON(false),
    magOK(false),
    pressureKnown(false),
    pressureON(false),
    pressureOK(false),
    diffPressureKnown(false),
    diffPressureON(false),
    diffPressureOK(false),
    flowKnown(false),
    flowON(false),
    flowOK(false),
    laserKnown(false),
    laserON(false),
    laserOK(false),
    viconKnown(false),
    viconON(false),
    viconOK(false),
    actuatorsKnown(false),
    actuatorsON(false),
147 148 149 150 151 152 153
    actuatorsOK(false),
    setPointKnown(false),
    positionSetPointKnown(false),
    userSetPointSet(false),
    userXYSetPointSet(false),
    userZSetPointSet(false),
    userYawSetPointSet(false)
154
{
155
    refreshTimer->setInterval(updateInterval);
156

pixhawk's avatar
pixhawk committed
157
    columns = 1;
158
    this->setAutoFillBackground(true);
159 160 161
    QPalette pal = palette();
    pal.setColor(backgroundRole(), QGC::colorBlack);
    setPalette(pal);
162

163
    vwidth = 80.0f;
164
    vheight = 100.0f;
pixhawk's avatar
pixhawk committed
165

166
    xCenterPos = vwidth/2.0f;
pixhawk's avatar
pixhawk committed
167
    yCenterPos = vheight/2.0f + topMargin - bottomMargin;
168

169 170 171
    uas = NULL;
    resetMAVState();

172 173
    // Do first update
    setMetricWidth(metricWidth);
174 175 176
    // 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."));
177 178

    connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage()));
179 180
    statusClearTimer.start(3000);

181 182 183 184
    if (UASManager::instance()->getActiveUAS())
    {
        setActiveUAS(UASManager::instance()->getActiveUAS());
    }
185

186
    setFocusPolicy(Qt::StrongFocus);
187 188
}

189 190 191 192 193
HSIDisplay::~HSIDisplay()
{

}

194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219
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;
220 221 222 223

    // Setpoints
    positionSetPointKnown = false;
    setPointKnown = false;
224 225
}

lm's avatar
lm committed
226 227 228 229
void HSIDisplay::paintEvent(QPaintEvent * event)
{
    Q_UNUSED(event);
    //paintGL();
230 231 232
    //    static quint64 interval = 0;
    //    //qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
    //    interval = MG::TIME::getGroundTimeNow();
233
    renderOverlay();
lm's avatar
lm committed
234 235
}

236
void HSIDisplay::renderOverlay()
237
{
238
    if (!isVisible()) return;
239 240 241
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
242 243
    // Center location of the HSI gauge items

244
    //float bottomMargin = 3.0f;
245 246

    // Size of the ring instrument
247
    //const float margin = 0.1f;  // 10% margin of total width on each side
248
    float baseRadius = (vheight - topMargin - bottomMargin) / 2.0f - (topMargin + bottomMargin) / 2.8f;
249

250 251 252 253 254 255 256 257
    // 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;

258
    QPainter painter(viewport());
259 260
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
261

262 263
    // Draw base instrument
    // ----------------------
lm's avatar
lm committed
264
    painter.setBrush(Qt::NoBrush);
265
    const QColor ringColor = QColor(200, 200, 200);
lm's avatar
lm committed
266 267
    QPen pen;
    pen.setColor(ringColor);
268
    pen.setWidth(refLineWidthToPen(1.0f));
lm's avatar
lm committed
269
    painter.setPen(pen);
lm's avatar
lm committed
270
    const int ringCount = 2;
271 272
    for (int i = 0; i < ringCount; i++)
    {
273
        float radius = (vwidth - (topMargin + bottomMargin)*0.3f) / (1.35f * i+1) / 2.0f - bottomMargin / 2.0f;
274
        drawCircle(xCenterPos, yCenterPos, radius, 1.0f, ringColor, &painter);
275
        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
276 277
    }

278 279 280
    // Draw orientation labels
    // Translate and rotate coordinate frame
    painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
281 282 283
    const float yawDeg = ((yaw/M_PI)*180.0f);
    int yawRotate = static_cast<int>(yawDeg) % 360;
    painter.rotate(-yawRotate);
284 285
    paintText(tr("N"), ringColor, 3.5f, - 1.0f, - baseRadius - 5.5f, &painter);
    paintText(tr("S"), ringColor, 3.5f, - 1.0f, + baseRadius + 1.5f, &painter);
286
    paintText(tr("E"), ringColor, 3.5f, + baseRadius + 3.0f, - 1.25f, &painter);
287
    paintText(tr("W"), ringColor, 3.5f, - baseRadius - 5.5f, - 1.75f, &painter);
288
    painter.rotate(+yawRotate);
289 290
    painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);

291
    // Draw trail
292 293 294 295 296 297
    //    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);
298 299


lm's avatar
lm committed
300
    // Draw center indicator
301 302 303 304 305
    //    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);
306

307 308
    if (uas)
    {
309 310 311
        // Translate to center
        painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
        QColor uasColor = uas->getColor();
312
        MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
lm's avatar
lm committed
313
        //MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
314 315 316
        // Translate back
        painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);
    }
317 318

    // ----------------------
319

320 321 322
    // Draw satellites
    drawGPS(painter);

323 324 325
    // Draw state indicator

    // Draw position
326
    QColor positionColor(20, 20, 200);
327
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
328 329 330

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
331
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
332 333


334
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
335

336 337 338 339 340 341
    float xSpDiff = uiXSetCoordinate - bodyXSetCoordinate;
    float ySpDiff = uiYSetCoordinate - bodyYSetCoordinate;
    float zSpDiff = uiZSetCoordinate - bodyZSetCoordinate;

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

342 343 344 345
    float angleDiff = uiYawSet - bodyYawSet;

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

346 347
    //if (((userSetPointSet) || (normAngleDiff > 0.05f) || dragStarted) && !(setPointDist < 0.08f && mavInitialized))

348

349 350 351 352 353
    // Labels on outer part and bottom

    // Draw waypoints
    drawWaypoints(painter);

354
    // Draw status flags
355 356 357 358 359
    drawStatusFlag(1,  1, tr("RAT"), rateControlEnabled, rateControlKnown, painter);
    drawStatusFlag(17, 1, tr("ATT"), attControlEnabled, attControlKnown, painter);
    drawStatusFlag(33, 1, tr("PXY"), xyControlEnabled,  xyControlKnown,  painter);
    drawStatusFlag(49, 1, tr("PZ"),  zControlEnabled,   zControlKnown,   painter);
    drawStatusFlag(65, 1, tr("YAW"), yawControlEnabled, yawControlKnown, painter);
360

361
    // Draw position lock indicators
362 363 364 365 366 367 368 369 370 371 372 373 374 375 376
    drawPositionLock(1,  6, tr("POS"), positionFix, positionFixKnown, painter);
    drawPositionLock(17, 6, tr("GPS"), gpsFix,      gpsFixKnown,      painter);
    drawStatusFlag(33,   6, tr("FLO"), flowON, flowKnown, flowOK, painter);
    drawPositionLock(49, 6, tr("VIS"), visionFix,   visionFixKnown,   painter);
    drawPositionLock(65, 6, tr("IRU"), iruFix,      iruFixKnown,      painter);

    drawStatusFlag(1,   11, tr("GYR"), gyroON, gyroKnown, gyroOK, painter);
    drawStatusFlag(17,  11, tr("ACC"), accelON, accelKnown, accelOK, painter);
    drawStatusFlag(33,  11, tr("MAG"), magON, magKnown, magOK, painter);
    drawStatusFlag(49,  11, tr("BAR"), pressureON, pressureKnown, pressureOK, painter);
    drawStatusFlag(65,  11, tr("PIT"), diffPressureON, diffPressureKnown, diffPressureOK, painter);

    drawStatusFlag(1, 16, tr("ACT"), actuatorsON, actuatorsKnown, actuatorsOK, painter);
    drawStatusFlag(17, 16, tr("LAS"), laserON, laserKnown, laserOK, painter);
    drawStatusFlag(33, 16, tr("VCN"), viconON, viconKnown, viconOK, painter);
377 378

    // Draw speed to top left
379 380
    paintText(tr("SPEED"), QGC::colorCyan, 2.2f, 2, topMargin+2, &painter);
    paintText(tr("%1 m/s").arg(speed, 5, 'f', 2, '0'), Qt::white, 2.2f, 12, topMargin+2, &painter);
381 382 383

    // Draw crosstrack error to top right
    float crossTrackError = 0;
384 385
    paintText(tr("XTRACK"), QGC::colorCyan, 2.2f, 54, topMargin+2, &painter);
    paintText(tr("%1 m").arg(crossTrackError, 5, 'f', 2, '0'), Qt::white, 2.2f, 67, topMargin+2, &painter);
386 387

    // Draw position to bottom left
388 389
    if (localAvailable > 0)
    {
390 391
        // Position
        QString str;
392
        float offset = (globalAvailable > 0) ? -3.0f : 0.0f;
393
        str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
394 395
        paintText(tr("POS"), QGC::colorCyan, 2.6f, 2, vheight - offset - 2.0f, &painter);
        paintText(str, Qt::white, 2.6f, 10, vheight - offset - 2.0f, &painter);
396 397
    }

398 399
    if (globalAvailable > 0)
    {
400 401
        // Position
        QString str;
402
        str.sprintf("lat: %05.2f lon: %06.2f alt: %06.2f", lat, lon, alt);
403 404
        paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 2.0f, &painter);
        paintText(str, Qt::white, 2.6f, 10, vheight - 2.0f, &painter);
405 406
    }

407 408 409
    // Draw Safety
    double x1, y1, z1, x2, y2, z2;
    UASManager::instance()->getLocalNEDSafetyLimits(&x1, &y1, &z1, &x2, &y2, &z2);
410
    //    drawSafetyArea(QPointF(x1, y1), QPointF(x2, y2), QGC::colorYellow, painter);
411 412

    // Draw status message
413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433
    paintText(statusMessage, QGC::colorOrange, 2.8f, 8, 15, &painter);

    // Draw setpoint over waypoints
    if (positionSetPointKnown || setPointKnown)
    {
        // Draw setpoint
        drawSetpointXYZYaw(bodyXSetCoordinate, bodyYSetCoordinate, bodyZSetCoordinate, bodyYawSet, QGC::colorYellow, painter);
        // Draw travel direction line
        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, QGC::colorYellow, &painter);
    }

    if ((userSetPointSet || dragStarted) && ((normAngleDiff > 0.05f) || !(setPointDist < 0.08f && mavInitialized)))
    {
        QColor spColor(150, 250, 150);
        drawSetpointXYZYaw(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet, spColor, painter);
    }
434
}
435

436
void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, QPainter& painter)
437 438 439 440 441
{
    drawStatusFlag(x, y, label, status, known, true, painter);
}

void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, bool ok, QPainter& painter)
442
{
443
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
444
    QColor statusColor(250, 250, 250);
445 446

    if (!ok) {
447
        painter.setBrush(QGC::colorDarkYellow);
448 449 450 451 452 453
    } else {
        if(status) {
            painter.setBrush(QGC::colorGreen);
        } else {
            painter.setBrush(Qt::darkGray);
        }
454 455
    }
    painter.setPen(Qt::NoPen);
456 457 458 459 460

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

    painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), indicatorWidth, indicatorHeight));
461
    paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
462
    // Cross out instrument if state unknown
463 464
    if (!known)
    {
465
        QPen pen(Qt::yellow);
466
        pen.setWidth(3);
467 468 469 470 471 472 473 474 475 476 477 478 479 480 481
        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);
    }
482 483
}

484
void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, bool known, QPainter& painter)
485
{
486 487 488 489 490 491 492 493 494 495 496 497
    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);
    }
498

499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514
    // 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;
    }
515

516 517 518 519 520 521 522 523 524
    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);
525
        pen.setWidth(3);
526 527 528 529 530 531 532 533 534 535 536 537 538 539 540
        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);
    }
541 542
}

lm's avatar
lm committed
543 544
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
545
    Q_UNUSED(uas);
546
    bool changed = positionLock != lock;
lm's avatar
lm committed
547
    positionLock = lock;
548 549 550 551
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
552 553
}

pixhawk's avatar
pixhawk committed
554
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
555
{
556
    bool changed = attControlEnabled != enabled;
lm's avatar
lm committed
557
    attControlEnabled = enabled;
558
    attControlKnown = true;
559 560 561 562
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
563 564
}

pixhawk's avatar
pixhawk committed
565
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
566
{
567
    bool changed = xyControlEnabled != enabled;
lm's avatar
lm committed
568
    xyControlEnabled = enabled;
569
    xyControlKnown = true;
570 571 572 573
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
574 575
}

pixhawk's avatar
pixhawk committed
576
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
577
{
578
    bool changed = zControlEnabled != enabled;
lm's avatar
lm committed
579
    zControlEnabled = enabled;
580
    zControlKnown = true;
581 582 583 584
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
585 586
}

LM's avatar
LM committed
587 588
void HSIDisplay::updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance)
{
589 590 591 592 593
    Q_UNUSED(quality);
    Q_UNUSED(name);
    Q_UNUSED(type);
    Q_UNUSED(id);
    Q_UNUSED(time);
LM's avatar
LM committed
594 595 596 597 598 599 600 601 602 603 604 605 606 607 608
    // 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
609 610 611 612
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
    // First translate to body-centered coordinates
    // Rotate around -yaw
613
    float angle = -yaw - M_PI;
614
    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
615 616 617 618 619 620 621
    return result;
}

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
622
    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
623
    return result;
624
}
625

626 627
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
628
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth);
629 630 631 632
}

QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
lm's avatar
lm committed
633
    return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
634 635 636 637 638
}

/**
 * @see refToScreenX()
 */
639
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
640 641 642 643
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

644 645 646 647 648 649 650 651 652 653
double HSIDisplay::metricToRef(double metric)
{
    return (metric / metricWidth) * vwidth;
}

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

654 655 656 657 658 659 660 661
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

662 663
void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
664 665
    if (event->type() == QMouseEvent::MouseButtonDblClick)
    {
666
        QPointF p = screenToMetricBody(event->posF());
pixhawk's avatar
pixhawk committed
667 668 669 670 671
        if (!directSending)
        {
            setBodySetpointCoordinateXY(p.x(), p.y());
            if (!userZSetPointSet) setBodySetpointCoordinateZ(0.0);
        }
672
        //        qDebug() << "Double click at x: " << screenToRefX(event->x()) - xCenterPos << "y:" << screenToRefY(event->y()) - yCenterPos;
673 674 675 676 677
    }
}

void HSIDisplay::mouseReleaseEvent(QMouseEvent * event)
{
LM's avatar
LM committed
678
    // FIXME hardcode yaw to current value
679
    //setBodySetpointCoordinateYaw(0);
680
    if (mouseHasMoved)
681
    {
682 683 684 685
        if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::RightButton)
        {
            if (dragStarted)
            {
LM's avatar
LM committed
686
                if (!directSending) setBodySetpointCoordinateYaw(uiYawSet);
687 688 689 690 691 692 693
                dragStarted = false;
            }
        }
        if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::LeftButton)
        {
            if (leftDragStarted)
            {
LM's avatar
LM committed
694
                if (!directSending) setBodySetpointCoordinateZ(uiZSetCoordinate);
695
                leftDragStarted = false;
696 697
            }
        }
698
    }
699
    mouseHasMoved = false;
700 701 702 703 704 705 706 707 708
}

void HSIDisplay::mousePressEvent(QMouseEvent * event)
{
    if (event->type() == QMouseEvent::MouseButtonPress)
    {
        if (event->button() == Qt::RightButton)
        {
            startX = event->x();
709 710
            // Start tracking mouse move
            dragStarted = true;
711 712 713
        }
        else if (event->button() == Qt::LeftButton)
        {
714 715
            startY = event->y();
            leftDragStarted = true;
716
        }
pixhawk's avatar
pixhawk committed
717
    }
718
    mouseHasMoved = false;
719
}
720

721 722 723 724
void HSIDisplay::mouseMoveEvent(QMouseEvent * event)
{
    if (event->type() == QMouseEvent::MouseMove)
    {
725
        if (dragStarted) uiYawSet -= 0.06f*(startX - event->x()) / this->frameSize().width();
726 727 728

        if (leftDragStarted)
        {
729 730
            //            uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height();
            //            setBodySetpointCoordinateZ(uiZSetCoordinate);
731
        }
732 733

        if (leftDragStarted || dragStarted) mouseHasMoved = true;
pixhawk's avatar
pixhawk committed
734
    }
735 736
}

pixhawk's avatar
pixhawk committed
737 738
void HSIDisplay::keyPressEvent(QKeyEvent* event)
{
739 740
    QPointF bodySP = metricWorldToBody(QPointF(uiXSetCoordinate, uiYSetCoordinate));

741
    if ((event->key() == Qt::Key_Enter || event->key() == Qt::Key_Return) && actionPending)
pixhawk's avatar
pixhawk committed
742 743 744 745 746 747
    {
        actionPending = false;
        statusMessage = "SETPOINT SENT";
        statusClearTimer.start();
        sendBodySetPointCoordinates();
    }
LM's avatar
LM committed
748
    else
749
    {
LM's avatar
LM committed
750 751 752 753 754 755 756
        // FIXME hardcode yaw to current value
        setBodySetpointCoordinateYaw(0);


        // Reset setpoints to current position / orientation
        // if not initialized
        if (!userYawSetPointSet)
757
        {
LM's avatar
LM committed
758
            setBodySetpointCoordinateYaw(0);
759
        }
LM's avatar
LM committed
760 761

        if (!userZSetPointSet)
762
        {
LM's avatar
LM committed
763
            setBodySetpointCoordinateZ(0);
764 765
        }

LM's avatar
LM committed
766
        if (!userXYSetPointSet)
767
        {
LM's avatar
LM committed
768
            setBodySetpointCoordinateXY(0, 0);
769
        }
LM's avatar
LM committed
770 771

        if ((event->key() ==  Qt::Key_W))
772
        {
LM's avatar
LM committed
773
            setBodySetpointCoordinateXY(qBound(-1.5, bodySP.x()+0.2, +1.5), bodySP.y());
774 775
        }

LM's avatar
LM committed
776
        if ((event->key() ==  Qt::Key_S))
777
        {
LM's avatar
LM committed
778
            setBodySetpointCoordinateXY(qBound(-1.5, bodySP.x()-0.2, +1.5), bodySP.y());
779
        }
LM's avatar
LM committed
780 781

        if ((event->key() ==  Qt::Key_A))
782 783 784 785
        {
            setBodySetpointCoordinateXY(bodySP.x(), qBound(-1.5, bodySP.y()-0.2, +1.5));
        }

LM's avatar
LM committed
786
        if ((event->key() ==  Qt::Key_D))
787 788 789 790
        {
            setBodySetpointCoordinateXY(bodySP.x(), qBound(-1.5, bodySP.y()+0.2, +1.5));
        }

LM's avatar
LM committed
791
        if ((event->key() ==  Qt::Key_Up))
792
        {
pixhawk's avatar
pixhawk committed
793
            setBodySetpointCoordinateZ(-0.2);
794 795
        }

LM's avatar
LM committed
796
        if ((event->key() ==  Qt::Key_Down))
797
        {
pixhawk's avatar
pixhawk committed
798
            setBodySetpointCoordinateZ(+0.2);
799 800
        }

LM's avatar
LM committed
801
        if ((event->key() ==  Qt::Key_Left))
802
        {
LM's avatar
LM committed
803
            setBodySetpointCoordinateYaw(-0.2);
804 805
        }

LM's avatar
LM committed
806
        if ((event->key() ==  Qt::Key_Right))
807
        {
LM's avatar
LM committed
808
            setBodySetpointCoordinateYaw(0.2);
809
        }
PIXHAWK Team's avatar
PIXHAWK Team committed
810
    }
811 812


LM's avatar
LM committed
813 814 815
    // Overwrite any existing non-zero body setpoints
    // for escape
    if ((event->key() == Qt::Key_Escape) || (event->key() == Qt::Key_R))
PIXHAWK Team's avatar
PIXHAWK Team committed
816
    {
LM's avatar
LM committed
817
        setBodySetpointCoordinateXY(0, 0);
818 819 820
        setBodySetpointCoordinateZ(0);
        setBodySetpointCoordinateYaw(0);
        statusMessage = "CANCELLED, PRESS <ENTER> TO SEND";
PIXHAWK Team's avatar
PIXHAWK Team committed
821
    }
822 823

    if ((event->key() == Qt::Key_T))
PIXHAWK Team's avatar
PIXHAWK Team committed
824
    {
825 826 827
        directSending = !directSending;
        statusMessage = (directSending) ? "DIRECT SEND ON" : "DIRECT SEND OFF";
        statusClearTimer.start();
PIXHAWK Team's avatar
PIXHAWK Team committed
828
    }
829 830

    if (actionPending && (directSending || (event->key() == Qt::Key_Escape)))
PIXHAWK Team's avatar
PIXHAWK Team committed
831
    {
832 833 834 835
        actionPending = false;
        statusMessage = "SETPOINT SENT";
        statusClearTimer.start();
        sendBodySetPointCoordinates();
PIXHAWK Team's avatar
PIXHAWK Team committed
836
    }
837 838

    HDDisplay::keyPressEvent(event);
pixhawk's avatar
pixhawk committed
839 840
}

841 842 843 844 845
void HSIDisplay::contextMenuEvent (QContextMenuEvent* event)
{
    event->ignore();
}

846 847
void HSIDisplay::setMetricWidth(double width)
{
848
    if (width != metricWidth) {
849 850 851 852 853
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

854 855 856 857 858 859
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
860 861 862
    if (!uas)
        return;

863 864 865 866 867 868
    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)));
869
        disconnect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
870
        disconnect(this->uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
871 872 873 874 875 876 877 878 879 880 881
        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
882
        disconnect(this->uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
883 884 885 886 887 888 889 890 891 892

        disconnect(this->uas, SIGNAL(gyroStatusChanged(bool,bool,bool)), this, SLOT(updateGyroStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(accelStatusChanged(bool,bool,bool)), this, SLOT(updateAccelStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)), this, SLOT(updateMagSensorStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(baroStatusChanged(bool,bool,bool)), this, SLOT(updateBaroStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)), this, SLOT(updateAirspeedStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)), this, SLOT(updateOpticalFlowStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(laserStatusChanged(bool,bool,bool)), this, SLOT(updateLaserStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)), this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool)));
        disconnect(this->uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)), this, SLOT(updateActuatorStatus(bool,bool,bool)));
893
    }
894

895 896 897 898 899
    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)));
900
    connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
901
    connect(uas, SIGNAL(velocityChanged_NED(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
902
    connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
903

904 905 906 907
    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)));
908

909 910 911 912
    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
913
    connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
914

915 916 917 918 919 920 921 922 923 924
    connect(uas, SIGNAL(gyroStatusChanged(bool,bool,bool)), this, SLOT(updateGyroStatus(bool,bool,bool)));
    connect(uas, SIGNAL(accelStatusChanged(bool,bool,bool)), this, SLOT(updateAccelStatus(bool,bool,bool)));
    connect(uas, SIGNAL(magSensorStatusChanged(bool,bool,bool)), this, SLOT(updateMagSensorStatus(bool,bool,bool)));
    connect(uas, SIGNAL(baroStatusChanged(bool,bool,bool)), this, SLOT(updateBaroStatus(bool,bool,bool)));
    connect(uas, SIGNAL(airspeedStatusChanged(bool,bool,bool)), this, SLOT(updateAirspeedStatus(bool,bool,bool)));
    connect(uas, SIGNAL(opticalFlowStatusChanged(bool,bool,bool)), this, SLOT(updateOpticalFlowStatus(bool,bool,bool)));
    connect(uas, SIGNAL(laserStatusChanged(bool,bool,bool)), this, SLOT(updateLaserStatus(bool,bool,bool)));
    connect(uas, SIGNAL(groundTruthSensorStatusChanged(bool,bool,bool)), this, SLOT(updateGroundTruthSensorStatus(bool,bool,bool)));
    connect(uas, SIGNAL(actuatorStatusChanged(bool,bool,bool)), this, SLOT(updateActuatorStatus(bool,bool,bool)));

925
    this->uas = uas;
926

927
    resetMAVState();
928 929
}

930 931 932 933 934 935 936
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;
937
    this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
938 939 940 941
}

void HSIDisplay::setBodySetpointCoordinateXY(double x, double y)
{
942 943 944 945 946
    if (uas)
    {
        userSetPointSet = true;
        userXYSetPointSet = true;
        // Set coordinates and send them out to MAV
947

948 949 950 951 952 953
        QPointF sp(x, y);
        sp = metricBodyToWorld(sp);
        uiXSetCoordinate = sp.x();
        uiYSetCoordinate = sp.y();

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

pixhawk's avatar
pixhawk committed
955

pixhawk's avatar
pixhawk committed
956 957 958 959
        //sendBodySetPointCoordinates();
        statusMessage = "POSITION SET, PRESS <ENTER> TO SEND";
        actionPending = true;
        statusClearTimer.start();
pixhawk's avatar
pixhawk committed
960
    }
961 962 963 964
}

void HSIDisplay::setBodySetpointCoordinateZ(double z)
{
965 966 967
    if (uas)
    {
        userSetPointSet = true;
LM's avatar
LM committed
968
        userZSetPointSet = true;
969 970 971 972 973 974
        // Set coordinates and send them out to MAV
        uiZSetCoordinate = z+uas->getLocalZ();
        statusMessage = "Z SET, PRESS <ENTER> TO SEND";
        actionPending = true;
        statusClearTimer.start();
    }
pixhawk's avatar
pixhawk committed
975
    //sendBodySetPointCoordinates();
976 977 978 979
}

void HSIDisplay::setBodySetpointCoordinateYaw(double yaw)
{
980
    if (uas)
981
    {
982 983 984 985 986 987 988 989 990 991 992 993
        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();
        }
        userSetPointSet = true;
LM's avatar
LM committed
994
        userYawSetPointSet = true;
995 996 997 998 999
        // Set coordinates and send them out to MAV
        uiYawSet = atan2(sin(yaw+uas->getYaw()), cos(yaw+uas->getYaw()));
        statusMessage = "YAW SET, PRESS <ENTER> TO SEND";
        statusClearTimer.start();
        actionPending = true;
1000
    }
pixhawk's avatar
pixhawk committed
1001
    //sendBodySetPointCoordinates();
1002 1003 1004 1005 1006
}

void HSIDisplay::sendBodySetPointCoordinates()
{
    // Send the coordinates to the MAV
1007
    if (uas)
1008
    {
1009
        uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
1010
    }
1011 1012
}

1013
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
1014
{
1015 1016 1017 1018 1019 1020
    Q_UNUSED(uas);
    Q_UNUSED(usec);
    attXSet = pitchDesired;
    attYSet = rollDesired;
    attYawSet = yawDesired;
    altitudeSet = thrustDesired;
1021 1022
}

lm's avatar
lm committed
1023 1024 1025 1026 1027 1028 1029 1030 1031
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;
}

1032 1033
void HSIDisplay::updateUserPositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired)
{
1034
	Q_UNUSED(uasid);
1035 1036 1037 1038 1039
    uiXSetCoordinate = xDesired;
    uiYSetCoordinate = yDesired;
    uiZSetCoordinate = zDesired;
    uiYawSet = yawDesired;
    userXYSetPointSet = true;
LM's avatar
LM committed
1040 1041
    userZSetPointSet = true;
    userYawSetPointSet = true;
1042 1043 1044
    userSetPointSet = true;
}

lm's avatar
lm committed
1045
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
1046
{
1047
    Q_UNUSED(uasid);
1048
    Q_UNUSED(usec);
1049 1050 1051 1052
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
1053
    mavInitialized = true;
1054
    setPointKnown = true;
1055
    positionSetPointKnown = true;
pixhawk's avatar
pixhawk committed
1056

1057 1058 1059 1060
    if (!userSetPointSet && !dragStarted)
    {
        uiXSetCoordinate = bodyXSetCoordinate;
        uiYSetCoordinate = bodyYSetCoordinate;
1061
        //        uiZSetCoordinate = bodyZSetCoordinate;
1062 1063
        uiYawSet= bodyYawSet;
    }
1064 1065 1066 1067
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
1068 1069 1070 1071
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
1072 1073 1074 1075
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
1076 1077 1078 1079
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
1080 1081
}

lm's avatar
lm committed
1082
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
lm's avatar
lm committed
1083 1084 1085
{
    Q_UNUSED(uasid);
    // If slot is empty, insert object
1086 1087 1088 1089 1090 1091
    if (satid != 0) { // Satellite PRNs currently range from 1-32, but are never zero
        if (gpsSatellites.contains(satid)) {
            gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
        } else {
            gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
        }
lm's avatar
lm committed
1092 1093 1094
    }
}

1095 1096 1097
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
    yawControlEnabled = enabled;
1098
    yawControlKnown = true;
1099 1100 1101 1102 1103 1104 1105 1106 1107
}

/**
 * @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;
1108
    positionFixKnown = true;
1109
    //qDebug() << "LOCALIZATION FIX CALLED";
1110 1111 1112 1113 1114 1115 1116 1117
}
/**
 * @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;
1118
    gpsFixKnown = true;
1119 1120 1121 1122 1123 1124 1125 1126
}
/**
 * @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;
1127
    visionFixKnown = true;
1128
    //qDebug() << "VISION FIX GOT CALLED";
1129 1130
}

1131 1132 1133 1134 1135 1136 1137
/**
 * @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;
1138
    iruFixKnown = true;
1139 1140
}

lm's avatar
lm committed
1141 1142
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
1143
    QColor color;
1144
    if (snr > 0 && snr < 30) {
lm's avatar
lm committed
1145
        color = QColor(250, 10, 10);
1146
    } else if (snr >= 30 && snr < 35) {
lm's avatar
lm committed
1147
        color = QColor(230, 230, 10);
1148
    } else if (snr >= 35 && snr < 40) {
lm's avatar
lm committed
1149
        color = QColor(90, 200, 90);
1150
    } else if (snr >= 40) {
lm's avatar
lm committed
1151
        color = QColor(20, 200, 20);
1152
    } else {
lm's avatar
lm committed
1153 1154 1155
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
1156 1157
}

1158
void HSIDisplay::drawSetpointXYZYaw(float x, float y, float z, float yaw, const QColor &color, QPainter &painter)
1159
{
1160 1161
    if (uas)
    {
1162
        float radius = vwidth / 18.0f;
1163
        QPen pen(color);
1164
        pen.setWidthF(refLineWidthToPen(1.6f));
1165 1166 1167 1168 1169 1170 1171 1172
        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);
1173 1174 1175 1176 1177 1178 1179 1180 1181 1182

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

1183
        // Label
pixhawk's avatar
pixhawk committed
1184
        paintText(QString("z: %1").arg(z, 3, 'f', 1, QChar(' ')), color, 2.1f, p.x()-radius, p.y()-radius-3.5f, &painter);
1185

1186 1187
        drawPolygon(poly, &painter);

1188
        radius *= 0.8f;
1189
        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.6f), color, &painter);
1190 1191

        // Draw center dot
1192 1193 1194
        painter.setBrush(color);
        drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter);
    }
1195 1196
}

1197
void HSIDisplay::drawWaypoint(QPainter& painter, const QColor& color, float width, const Waypoint *w, const QPointF& p)
1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216
{
    painter.setBrush(Qt::NoBrush);

    // Setup pen for foreground
    QPen pen(color);
    pen.setWidthF(width);

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

    float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
1217 1218
    float acceptRadius = w->getAcceptanceRadius();
    double yawDiff = w->getYaw()/180.0*M_PI-yaw;
1219 1220 1221

    // Draw background
    pen.setColor(Qt::black);
1222
    painter.setPen(pen);
1223
    drawLine(p.x(), p.y(), p.x()+sin(yawDiff) * radius, p.y()-cos(yawDiff) * radius, refLineWidthToPen(0.4f*3.0f), Qt::black, &painter);
1224
    drawPolygon(poly, &painter);
1225
    drawCircle(p.x(), p.y(), metricToRef(acceptRadius), 3.0, Qt::black, &painter);
1226 1227 1228 1229

    // Draw foreground
    pen.setColor(color);
    painter.setPen(pen);
1230
    drawLine(p.x(), p.y(), p.x()+sin(yawDiff) * radius, p.y()-cos(yawDiff) * radius, refLineWidthToPen(0.4f), color, &painter);
1231 1232 1233 1234
    drawPolygon(poly, &painter);
    drawCircle(p.x(), p.y(), metricToRef(acceptRadius), 1.0, Qt::green, &painter);
}

1235 1236
void HSIDisplay::drawWaypoints(QPainter& painter)
{
1237 1238
    if (uas)
    {
1239
        // Grab all waypoints.
Lorenz Meier's avatar
Lorenz Meier committed
1240
        const QList<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
1241
        const int numWaypoints = list.size();
1242

1243
        // Do not work on empty lists
1244 1245 1246 1247
        if (list.size() == 0)
        {
            return;
        }
1248

1249
        // Make sure any drawn shapes are not filled-in.
1250
        painter.setBrush(Qt::NoBrush);
pixhawk's avatar
pixhawk committed
1251

1252
        QPointF lastWaypoint;
1253
        for (int i = 0; i < numWaypoints; i++)
1254
        {
1255
            const Waypoint *w = list.at(i);
1256
            QPointF in;
1257 1258 1259 1260 1261 1262 1263
            // Use local coordinates as-is.
            int frameRef = w->getFrame();
            if (frameRef == MAV_FRAME_LOCAL_NED)
            {
                in = QPointF(w->getX(), w->getY());
            }
            else if (frameRef == MAV_FRAME_LOCAL_ENU)
1264
            {
1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279
                in = QPointF(w->getY(), w->getX());
            }
            // Convert global coordinates into the local ENU frame, then display them.
            else if (frameRef == MAV_FRAME_GLOBAL || frameRef == MAV_FRAME_GLOBAL_RELATIVE_ALT) {
                // Get the position of the GPS origin for the MAV.

                // Transform the lat/lon for this waypoint into the local frame
                double e, n, u;
                UASManager::instance()->wgs84ToEnu(w->getX(), w->getY(),w->getZ(), &e, &n, &u);
                in = QPointF(n, e);
            }
            // Otherwise we don't process this waypoint.
            // FIXME: This code will probably fail if the last waypoint found is not a valid one.
            else {
                continue;
1280
            }
1281

1282 1283 1284 1285 1286
            // Transform from world to body coordinates
            in = metricWorldToBody(in);
            // Scale from metric to screen reference coordinates
            QPointF p = metricBodyToRef(in);

1287 1288
            // Select color based on if this is the current waypoint.
            if (w->getCurrent())
1289
            {
1290
                drawWaypoint(painter, QGC::colorYellow, refLineWidthToPen(0.8f), w, p);
1291 1292 1293
            }
            else
            {
1294
                drawWaypoint(painter, QGC::colorCyan, refLineWidthToPen(0.4f), w, p);
1295 1296
            }

1297
            // Draw connecting line from last waypoint to this one.
1298 1299
            if (!lastWaypoint.isNull())
            {
1300 1301
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f*2.0f), Qt::black, &painter);
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f), QGC::colorCyan, &painter);
1302 1303
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
1304 1305
        }
    }
1306 1307
}

1308 1309 1310 1311 1312
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);
1313
    pen.setBrush(Qt::NoBrush);
1314
    painter.setPen(pen);
1315
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
1316
}
lm's avatar
lm committed
1317

1318 1319 1320
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
1321
    float yCenter = yCenterPos;
lm's avatar
lm committed
1322

1323 1324 1325 1326 1327
    const float yawDeg = ((yaw/M_PI)*180.0f);
    int yawRotate = static_cast<int>(yawDeg) % 360;
    // XXX check rotation direction

    // Max satellite circle radius
lm's avatar
lm committed
1328 1329 1330
    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
1331

pixhawk's avatar
pixhawk committed
1332 1333 1334 1335 1336
    // 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
1337
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
1338
    while (i.hasNext()) {
lm's avatar
lm committed
1339 1340 1341
        i.next();
        GPSSatellite* sat = i.value();

1342 1343
        // Check if update is not older than 10 seconds, else delete satellite
        if (sat->lastUpdate + 10000000 < currTime) {
lm's avatar
lm committed
1344 1345
            // Delete and go to next satellite
            gpsSatellites.remove(i.key());
1346
            if (i.hasNext()) {
lm's avatar
lm committed
1347 1348
                i.next();
                sat = i.value();
1349
            } else {
lm's avatar
lm committed
1350 1351 1352 1353
                continue;
            }
        }

1354
        if (sat) {
lm's avatar
lm committed
1355 1356 1357 1358
            // Draw satellite
            QBrush brush;
            QColor color = getColorForSNR(sat->snr);
            brush.setColor(color);
1359
            if (sat->used) {
lm's avatar
lm committed
1360
                brush.setStyle(Qt::SolidPattern);
1361
            } else {
lm's avatar
lm committed
1362 1363 1364 1365 1366 1367
                brush.setStyle(Qt::NoBrush);
            }
            painter.setPen(Qt::SolidLine);
            painter.setPen(color);
            painter.setBrush(brush);

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

1371
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
1372
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
1373
            // Draw satellite PRN
lm's avatar
lm committed
1374
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
1375 1376
        }
    }
1377 1378
}

1379
void HSIDisplay::drawObjects(QPainter &painter)
1380
{
1381
    Q_UNUSED(painter);
1382 1383
}

1384
void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1385
{
1386
    if (xyControlKnown && xyControlEnabled) {
1387
        // Draw the needle
1388
        const float maxWidth = radius / 5.0f;
1389
        const float minWidth = maxWidth * 0.3f;
1390

1391
        float angle = atan2(posXSet, -posYSet);
1392
        angle -= (float)M_PI/2.0f;
1393

1394
        QPolygonF p(6);
1395

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

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

1400 1401 1402 1403 1404 1405
        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));
1406

1407
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1408

1409 1410 1411 1412 1413 1414 1415
        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
1416

1417 1418
        //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
    }
1419 1420
}

1421
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1422
{
1423
    if (attControlKnown && attControlEnabled) {
1424 1425 1426
        // Draw the needle
        const float maxWidth = radius / 10.0f;
        const float minWidth = maxWidth * 0.3f;
1427

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

1430
        radius *= sqrt(attXSet*attXSet + attYSet*attYSet) / sqrt(attXSaturation*attXSaturation + attYSaturation*attYSaturation);
1431

1432
        QPolygonF p(6);
1433

1434 1435 1436 1437 1438 1439
        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));
1440

1441
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1442

1443 1444 1445 1446 1447 1448 1449
        QBrush indexBrush;
        indexBrush.setColor(color);
        indexBrush.setStyle(Qt::SolidPattern);
        painter->setPen(Qt::SolidLine);
        painter->setPen(color);
        painter->setBrush(indexBrush);
        drawPolygon(p, painter);
1450

1451
        // TODO Draw Yaw indicator
lm's avatar
lm committed
1452

1453 1454
        //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
    }
1455 1456 1457 1458
}

void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
{
1459
    if (zControlKnown && zControlEnabled) {
1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473
        // 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);
    }
1474
}
1475

1476 1477 1478
void HSIDisplay::wheelEvent(QWheelEvent* event)
{
    double zoomScale = 0.005; // Scaling of zoom value
1479
    if(event->delta() > 0) {
1480 1481
        // Reduce width -> Zoom in
        metricWidth -= event->delta() * zoomScale;
1482
    } else {
1483 1484 1485
        // Increase width -> Zoom out
        metricWidth -= event->delta() * zoomScale;
    }
1486
    metricWidth = qBound(0.5, metricWidth, 9999.0);
1487 1488
    emit metricWidthChanged(metricWidth);
}
pixhawk's avatar
pixhawk committed
1489

1490 1491 1492 1493
void HSIDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
1494
    Q_UNUSED(event) {
1495 1496 1497 1498 1499 1500 1501 1502
        refreshTimer->start(updateInterval);
    }
}

void HSIDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (post-display)
    // events
1503
    Q_UNUSED(event) {
1504
        refreshTimer->stop();
1505 1506 1507
    }
}

1508 1509
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
1510 1511 1512 1513 1514 1515
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
1516 1517 1518 1519
}

void HSIDisplay::pressKey(int key)
{
1520
    Q_UNUSED(key);
1521
}
pixhawk's avatar
pixhawk committed
1522 1523