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

3
QGroundControl Open Source Ground Control Station
4

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

7
This file is part of the QGROUNDCONTROL project
8

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

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

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

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

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

#include <QFile>
#include <QStringList>
34
#include <QPainter>
35 36 37
#include <QGraphicsScene>
#include <QHBoxLayout>
#include <QDoubleSpinBox>
38 39
#include "UASManager.h"
#include "HSIDisplay.h"
40
#include "QGC.h"
pixhawk's avatar
pixhawk committed
41
#include "Waypoint.h"
42
#include "UASWaypointManager.h"
43
#include <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 181
    statusClearTimer.start(3000);

    setFocusPolicy(Qt::StrongFocus);
182 183
}

184 185 186 187 188
HSIDisplay::~HSIDisplay()
{

}

189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214
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;
215 216 217 218

    // Setpoints
    positionSetPointKnown = false;
    setPointKnown = false;
219 220
}

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

231
void HSIDisplay::renderOverlay()
232
{
233
    if (!isVisible()) return;
234 235 236
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
237 238
    // Center location of the HSI gauge items

239
    //float bottomMargin = 3.0f;
240 241

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

245 246 247 248 249 250 251 252
    // 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;

253
    QPainter painter(viewport());
254 255
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
256

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

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

286
    // Draw trail
287 288 289 290 291 292
    //    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);
293 294


lm's avatar
lm committed
295
    // Draw center indicator
296 297 298 299 300
    //    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);
301

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

    // ----------------------
314

315 316 317
    // Draw satellites
    drawGPS(painter);

318 319 320
    // Draw state indicator

    // Draw position
321
    QColor positionColor(20, 20, 200);
322
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
323 324 325

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
326
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
327 328


329
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
330

331 332 333 334 335 336
    float xSpDiff = uiXSetCoordinate - bodyXSetCoordinate;
    float ySpDiff = uiYSetCoordinate - bodyYSetCoordinate;
    float zSpDiff = uiZSetCoordinate - bodyZSetCoordinate;

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

337 338 339 340
    float angleDiff = uiYawSet - bodyYawSet;

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

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

343

344 345 346 347 348
    // Labels on outer part and bottom

    // Draw waypoints
    drawWaypoints(painter);

349
    // Draw status flags
350 351 352 353 354
    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);
355

356
    // Draw position lock indicators
357 358 359 360 361 362 363 364 365 366 367 368 369 370 371
    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);
372 373

    // Draw speed to top left
374 375
    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);
376 377 378

    // Draw crosstrack error to top right
    float crossTrackError = 0;
379 380
    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);
381 382

    // Draw position to bottom left
383 384
    if (localAvailable > 0)
    {
385 386
        // Position
        QString str;
387
        float offset = (globalAvailable > 0) ? -3.0f : 0.0f;
388
        str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
389 390
        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);
391 392
    }

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

402 403 404
    // Draw Safety
    double x1, y1, z1, x2, y2, z2;
    UASManager::instance()->getLocalNEDSafetyLimits(&x1, &y1, &z1, &x2, &y2, &z2);
405
    //    drawSafetyArea(QPointF(x1, y1), QPointF(x2, y2), QGC::colorYellow, painter);
406 407

    // Draw status message
408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428
    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);
    }
429
}
430

431
void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, QPainter& painter)
432 433 434 435 436
{
    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)
437
{
438
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
439
    QColor statusColor(250, 250, 250);
440 441

    if (!ok) {
442
        painter.setBrush(QGC::colorDarkYellow);
443 444 445 446 447 448
    } else {
        if(status) {
            painter.setBrush(QGC::colorGreen);
        } else {
            painter.setBrush(Qt::darkGray);
        }
449 450
    }
    painter.setPen(Qt::NoPen);
451 452 453 454 455

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

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

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

494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509
    // 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;
    }
510

511 512 513 514 515 516 517 518 519
    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);
520
        pen.setWidth(3);
521 522 523 524 525 526 527 528 529 530 531 532 533 534 535
        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);
    }
536 537
}

lm's avatar
lm committed
538 539
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
540
    Q_UNUSED(uas);
541
    bool changed = positionLock != lock;
lm's avatar
lm committed
542
    positionLock = lock;
543 544 545 546
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
547 548
}

pixhawk's avatar
pixhawk committed
549
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
550
{
551
    bool changed = attControlEnabled != enabled;
lm's avatar
lm committed
552
    attControlEnabled = enabled;
553
    attControlKnown = true;
554 555 556 557
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
558 559
}

pixhawk's avatar
pixhawk committed
560
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
561
{
562
    bool changed = xyControlEnabled != enabled;
lm's avatar
lm committed
563
    xyControlEnabled = enabled;
564
    xyControlKnown = true;
565 566 567 568
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
569 570
}

pixhawk's avatar
pixhawk committed
571
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
572
{
573
    bool changed = zControlEnabled != enabled;
lm's avatar
lm committed
574
    zControlEnabled = enabled;
575
    zControlKnown = true;
576 577 578 579
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
580 581
}

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

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
617
    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
618
    return result;
619
}
620

621 622
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
623
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth);
624 625 626 627
}

QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
lm's avatar
lm committed
628
    return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
629 630 631 632 633
}

/**
 * @see refToScreenX()
 */
634
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
635 636 637 638
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

639 640 641 642 643 644 645 646 647 648
double HSIDisplay::metricToRef(double metric)
{
    return (metric / metricWidth) * vwidth;
}

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

649 650 651 652 653 654 655 656
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

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

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

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

716 717 718 719
void HSIDisplay::mouseMoveEvent(QMouseEvent * event)
{
    if (event->type() == QMouseEvent::MouseMove)
    {
720
        if (dragStarted) uiYawSet -= 0.06f*(startX - event->x()) / this->frameSize().width();
721 722 723

        if (leftDragStarted)
        {
724 725
            //            uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height();
            //            setBodySetpointCoordinateZ(uiZSetCoordinate);
726
        }
727 728

        if (leftDragStarted || dragStarted) mouseHasMoved = true;
pixhawk's avatar
pixhawk committed
729
    }
730 731
}

pixhawk's avatar
pixhawk committed
732 733
void HSIDisplay::keyPressEvent(QKeyEvent* event)
{
734 735
    QPointF bodySP = metricWorldToBody(QPointF(uiXSetCoordinate, uiYSetCoordinate));

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


        // Reset setpoints to current position / orientation
        // if not initialized
        if (!userYawSetPointSet)
752
        {
LM's avatar
LM committed
753
            setBodySetpointCoordinateYaw(0);
754
        }
LM's avatar
LM committed
755 756

        if (!userZSetPointSet)
757
        {
LM's avatar
LM committed
758
            setBodySetpointCoordinateZ(0);
759 760
        }

LM's avatar
LM committed
761
        if (!userXYSetPointSet)
762
        {
LM's avatar
LM committed
763
            setBodySetpointCoordinateXY(0, 0);
764
        }
LM's avatar
LM committed
765 766

        if ((event->key() ==  Qt::Key_W))
767
        {
LM's avatar
LM committed
768
            setBodySetpointCoordinateXY(qBound(-1.5, bodySP.x()+0.2, +1.5), bodySP.y());
769 770
        }

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

        if ((event->key() ==  Qt::Key_A))
777 778 779 780
        {
            setBodySetpointCoordinateXY(bodySP.x(), qBound(-1.5, bodySP.y()-0.2, +1.5));
        }

LM's avatar
LM committed
781
        if ((event->key() ==  Qt::Key_D))
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_Up))
787
        {
pixhawk's avatar
pixhawk committed
788
            setBodySetpointCoordinateZ(-0.2);
789 790
        }

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

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

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


LM's avatar
LM committed
808 809 810
    // 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
811
    {
LM's avatar
LM committed
812
        setBodySetpointCoordinateXY(0, 0);
813 814 815
        setBodySetpointCoordinateZ(0);
        setBodySetpointCoordinateYaw(0);
        statusMessage = "CANCELLED, PRESS <ENTER> TO SEND";
PIXHAWK Team's avatar
PIXHAWK Team committed
816
    }
817 818

    if ((event->key() == Qt::Key_T))
PIXHAWK Team's avatar
PIXHAWK Team committed
819
    {
820 821 822
        directSending = !directSending;
        statusMessage = (directSending) ? "DIRECT SEND ON" : "DIRECT SEND OFF";
        statusClearTimer.start();
PIXHAWK Team's avatar
PIXHAWK Team committed
823
    }
824 825

    if (actionPending && (directSending || (event->key() == Qt::Key_Escape)))
PIXHAWK Team's avatar
PIXHAWK Team committed
826
    {
827 828 829 830
        actionPending = false;
        statusMessage = "SETPOINT SENT";
        statusClearTimer.start();
        sendBodySetPointCoordinates();
PIXHAWK Team's avatar
PIXHAWK Team committed
831
    }
832 833

    HDDisplay::keyPressEvent(event);
pixhawk's avatar
pixhawk committed
834 835
}

836 837 838 839 840
void HSIDisplay::contextMenuEvent (QContextMenuEvent* event)
{
    event->ignore();
}

841 842
void HSIDisplay::setMetricWidth(double width)
{
843
    if (width != metricWidth) {
844 845 846 847 848
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

849 850 851 852 853 854
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
855 856 857 858 859 860
    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)));
861
        disconnect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
862 863 864 865 866 867 868 869 870 871 872 873
        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
874
        disconnect(this->uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
875 876 877 878 879 880 881 882 883 884

        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)));
885
    }
886

887 888 889 890 891
    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)));
892
    connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
893 894
    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)));
895

896 897 898 899
    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)));
900

901 902 903 904
    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
905
    connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
906

907 908 909 910 911 912 913 914 915 916
    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)));

917
    this->uas = uas;
918

919
    resetMAVState();
920 921
}

922 923 924 925 926 927 928
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;
929
    this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
930 931 932 933
}

void HSIDisplay::setBodySetpointCoordinateXY(double x, double y)
{
934 935 936 937 938
    if (uas)
    {
        userSetPointSet = true;
        userXYSetPointSet = true;
        // Set coordinates and send them out to MAV
939

940 941 942 943 944 945
        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
946

pixhawk's avatar
pixhawk committed
947

pixhawk's avatar
pixhawk committed
948 949 950 951
        //sendBodySetPointCoordinates();
        statusMessage = "POSITION SET, PRESS <ENTER> TO SEND";
        actionPending = true;
        statusClearTimer.start();
pixhawk's avatar
pixhawk committed
952
    }
953 954 955 956
}

void HSIDisplay::setBodySetpointCoordinateZ(double z)
{
957 958 959
    if (uas)
    {
        userSetPointSet = true;
LM's avatar
LM committed
960
        userZSetPointSet = true;
961 962 963 964 965 966
        // 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
967
    //sendBodySetPointCoordinates();
968 969 970 971
}

void HSIDisplay::setBodySetpointCoordinateYaw(double yaw)
{
972
    if (uas)
973
    {
974 975 976 977 978 979 980 981 982 983 984 985
        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
986
        userYawSetPointSet = true;
987 988 989 990 991
        // 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;
992
    }
pixhawk's avatar
pixhawk committed
993
    //sendBodySetPointCoordinates();
994 995 996 997 998
}

void HSIDisplay::sendBodySetPointCoordinates()
{
    // Send the coordinates to the MAV
999
    if (uas)
1000
    {
1001
        uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
1002
    }
1003 1004
}

1005
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
1006
{
1007 1008 1009 1010 1011 1012
    Q_UNUSED(uas);
    Q_UNUSED(usec);
    attXSet = pitchDesired;
    attYSet = rollDesired;
    attYawSet = yawDesired;
    altitudeSet = thrustDesired;
1013 1014
}

lm's avatar
lm committed
1015 1016 1017 1018 1019 1020 1021 1022 1023
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;
}

1024 1025
void HSIDisplay::updateUserPositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired)
{
1026
	Q_UNUSED(uasid);
1027 1028 1029 1030 1031
    uiXSetCoordinate = xDesired;
    uiYSetCoordinate = yDesired;
    uiZSetCoordinate = zDesired;
    uiYawSet = yawDesired;
    userXYSetPointSet = true;
LM's avatar
LM committed
1032 1033
    userZSetPointSet = true;
    userYawSetPointSet = true;
1034 1035 1036
    userSetPointSet = true;
}

lm's avatar
lm committed
1037
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
1038
{
1039
    Q_UNUSED(uasid);
1040
    Q_UNUSED(usec);
1041 1042 1043 1044
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
1045
    mavInitialized = true;
1046
    setPointKnown = true;
1047
    positionSetPointKnown = true;
pixhawk's avatar
pixhawk committed
1048

1049 1050 1051 1052
    if (!userSetPointSet && !dragStarted)
    {
        uiXSetCoordinate = bodyXSetCoordinate;
        uiYSetCoordinate = bodyYSetCoordinate;
1053
        //        uiZSetCoordinate = bodyZSetCoordinate;
1054 1055
        uiYawSet= bodyYawSet;
    }
1056 1057 1058 1059
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
1060 1061 1062 1063
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
1064 1065 1066 1067
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
1068 1069 1070 1071
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
1072 1073
}

lm's avatar
lm committed
1074
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
lm's avatar
lm committed
1075 1076 1077
{
    Q_UNUSED(uasid);
    // If slot is empty, insert object
1078 1079 1080 1081 1082 1083
    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
1084 1085 1086
    }
}

1087 1088 1089
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
    yawControlEnabled = enabled;
1090
    yawControlKnown = true;
1091 1092 1093 1094 1095 1096 1097 1098 1099
}

/**
 * @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;
1100
    positionFixKnown = true;
1101
    //qDebug() << "LOCALIZATION FIX CALLED";
1102 1103 1104 1105 1106 1107 1108 1109
}
/**
 * @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;
1110
    gpsFixKnown = true;
1111 1112 1113 1114 1115 1116 1117 1118
}
/**
 * @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;
1119
    visionFixKnown = true;
1120
    //qDebug() << "VISION FIX GOT CALLED";
1121 1122
}

1123 1124 1125 1126 1127 1128 1129
/**
 * @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;
1130
    iruFixKnown = true;
1131 1132
}

lm's avatar
lm committed
1133 1134
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
1135
    QColor color;
1136
    if (snr > 0 && snr < 30) {
lm's avatar
lm committed
1137
        color = QColor(250, 10, 10);
1138
    } else if (snr >= 30 && snr < 35) {
lm's avatar
lm committed
1139
        color = QColor(230, 230, 10);
1140
    } else if (snr >= 35 && snr < 40) {
lm's avatar
lm committed
1141
        color = QColor(90, 200, 90);
1142
    } else if (snr >= 40) {
lm's avatar
lm committed
1143
        color = QColor(20, 200, 20);
1144
    } else {
lm's avatar
lm committed
1145 1146 1147
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
1148 1149
}

1150
void HSIDisplay::drawSetpointXYZYaw(float x, float y, float z, float yaw, const QColor &color, QPainter &painter)
1151
{
1152 1153
    if (uas)
    {
1154
        float radius = vwidth / 18.0f;
1155
        QPen pen(color);
1156
        pen.setWidthF(refLineWidthToPen(1.6f));
1157 1158 1159 1160 1161 1162 1163 1164
        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);
1165 1166 1167 1168 1169 1170 1171 1172 1173 1174

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

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

1178 1179
        drawPolygon(poly, &painter);

1180
        radius *= 0.8f;
1181
        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);
1182 1183

        // Draw center dot
1184 1185 1186
        painter.setBrush(color);
        drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter);
    }
1187 1188
}

1189
void HSIDisplay::drawWaypoint(QPainter& painter, const QColor& color, float width, const Waypoint *w, const QPointF& p)
1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208
{
    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));
1209 1210
    float acceptRadius = w->getAcceptanceRadius();
    double yawDiff = w->getYaw()/180.0*M_PI-yaw;
1211 1212 1213

    // Draw background
    pen.setColor(Qt::black);
1214
    painter.setPen(pen);
1215
    drawLine(p.x(), p.y(), p.x()+sin(yawDiff) * radius, p.y()-cos(yawDiff) * radius, refLineWidthToPen(0.4f*3.0f), Qt::black, &painter);
1216
    drawPolygon(poly, &painter);
1217
    drawCircle(p.x(), p.y(), metricToRef(acceptRadius), 3.0, Qt::black, &painter);
1218 1219 1220 1221

    // Draw foreground
    pen.setColor(color);
    painter.setPen(pen);
1222
    drawLine(p.x(), p.y(), p.x()+sin(yawDiff) * radius, p.y()-cos(yawDiff) * radius, refLineWidthToPen(0.4f), color, &painter);
1223 1224 1225 1226
    drawPolygon(poly, &painter);
    drawCircle(p.x(), p.y(), metricToRef(acceptRadius), 1.0, Qt::green, &painter);
}

1227 1228
void HSIDisplay::drawWaypoints(QPainter& painter)
{
1229 1230
    if (uas)
    {
1231
        // Grab all waypoints.
pixhawk's avatar
pixhawk committed
1232
        const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
1233
        const int numWaypoints = list.size();
1234

1235
        // Do not work on empty lists
1236 1237 1238 1239
        if (list.size() == 0)
        {
            return;
        }
1240

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

1244
        QPointF lastWaypoint;
1245
        for (int i = 0; i < numWaypoints; i++)
1246
        {
1247
            const Waypoint *w = list.at(i);
1248
            QPointF in;
1249 1250 1251 1252 1253 1254 1255
            // 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)
1256
            {
1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271
                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;
1272
            }
1273

1274 1275 1276 1277 1278
            // Transform from world to body coordinates
            in = metricWorldToBody(in);
            // Scale from metric to screen reference coordinates
            QPointF p = metricBodyToRef(in);

1279 1280
            // Select color based on if this is the current waypoint.
            if (w->getCurrent())
1281
            {
1282
                drawWaypoint(painter, QGC::colorYellow, refLineWidthToPen(0.8f), w, p);
1283 1284 1285
            }
            else
            {
1286
                drawWaypoint(painter, QGC::colorCyan, refLineWidthToPen(0.4f), w, p);
1287 1288
            }

1289
            // Draw connecting line from last waypoint to this one.
1290 1291
            if (!lastWaypoint.isNull())
            {
1292 1293
                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);
1294 1295
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
1296 1297
        }
    }
1298 1299
}

1300 1301 1302 1303 1304
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);
1305
    pen.setBrush(Qt::NoBrush);
1306
    painter.setPen(pen);
1307
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
1308
}
lm's avatar
lm committed
1309

1310 1311 1312
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
1313
    float yCenter = yCenterPos;
lm's avatar
lm committed
1314

1315 1316 1317 1318 1319
    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
1320 1321 1322
    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
1323

pixhawk's avatar
pixhawk committed
1324 1325 1326 1327 1328
    // 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
1329
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
1330
    while (i.hasNext()) {
lm's avatar
lm committed
1331 1332 1333
        i.next();
        GPSSatellite* sat = i.value();

1334 1335
        // Check if update is not older than 10 seconds, else delete satellite
        if (sat->lastUpdate + 10000000 < currTime) {
lm's avatar
lm committed
1336 1337
            // Delete and go to next satellite
            gpsSatellites.remove(i.key());
1338
            if (i.hasNext()) {
lm's avatar
lm committed
1339 1340
                i.next();
                sat = i.value();
1341
            } else {
lm's avatar
lm committed
1342 1343 1344 1345
                continue;
            }
        }

1346
        if (sat) {
lm's avatar
lm committed
1347 1348 1349 1350
            // Draw satellite
            QBrush brush;
            QColor color = getColorForSNR(sat->snr);
            brush.setColor(color);
1351
            if (sat->used) {
lm's avatar
lm committed
1352
                brush.setStyle(Qt::SolidPattern);
1353
            } else {
lm's avatar
lm committed
1354 1355 1356 1357 1358 1359
                brush.setStyle(Qt::NoBrush);
            }
            painter.setPen(Qt::SolidLine);
            painter.setPen(color);
            painter.setBrush(brush);

1360 1361
            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
1362

1363
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
1364
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
1365
            // Draw satellite PRN
lm's avatar
lm committed
1366
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
1367 1368
        }
    }
1369 1370
}

1371
void HSIDisplay::drawObjects(QPainter &painter)
1372
{
1373
    Q_UNUSED(painter);
1374 1375
}

1376
void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1377
{
1378
    if (xyControlKnown && xyControlEnabled) {
1379
        // Draw the needle
1380
        const float maxWidth = radius / 5.0f;
1381
        const float minWidth = maxWidth * 0.3f;
1382

1383
        float angle = atan2(posXSet, -posYSet);
1384
        angle -= (float)M_PI/2.0f;
1385

1386
        QPolygonF p(6);
1387

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

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

1392 1393 1394 1395 1396 1397
        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));
1398

1399
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1400

1401 1402 1403 1404 1405 1406 1407
        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
1408

1409 1410
        //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
    }
1411 1412
}

1413
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1414
{
1415
    if (attControlKnown && attControlEnabled) {
1416 1417 1418
        // Draw the needle
        const float maxWidth = radius / 10.0f;
        const float minWidth = maxWidth * 0.3f;
1419

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

1422
        radius *= sqrt(attXSet*attXSet + attYSet*attYSet) / sqrt(attXSaturation*attXSaturation + attYSaturation*attYSaturation);
1423

1424
        QPolygonF p(6);
1425

1426 1427 1428 1429 1430 1431
        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));
1432

1433
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1434

1435 1436 1437 1438 1439 1440 1441
        QBrush indexBrush;
        indexBrush.setColor(color);
        indexBrush.setStyle(Qt::SolidPattern);
        painter->setPen(Qt::SolidLine);
        painter->setPen(color);
        painter->setBrush(indexBrush);
        drawPolygon(p, painter);
1442

1443
        // TODO Draw Yaw indicator
lm's avatar
lm committed
1444

1445 1446
        //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
    }
1447 1448 1449 1450
}

void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
{
1451
    if (zControlKnown && zControlEnabled) {
1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465
        // 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);
    }
1466
}
1467

1468 1469 1470
void HSIDisplay::wheelEvent(QWheelEvent* event)
{
    double zoomScale = 0.005; // Scaling of zoom value
1471
    if(event->delta() > 0) {
1472 1473
        // Reduce width -> Zoom in
        metricWidth -= event->delta() * zoomScale;
1474
    } else {
1475 1476 1477
        // Increase width -> Zoom out
        metricWidth -= event->delta() * zoomScale;
    }
1478
    metricWidth = qBound(0.5, metricWidth, 9999.0);
1479 1480
    emit metricWidthChanged(metricWidth);
}
pixhawk's avatar
pixhawk committed
1481

1482 1483 1484 1485
void HSIDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
1486
    Q_UNUSED(event) {
1487 1488 1489 1490 1491 1492 1493 1494
        refreshTimer->start(updateInterval);
    }
}

void HSIDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (post-display)
    // events
1495
    Q_UNUSED(event) {
1496
        refreshTimer->stop();
1497 1498 1499
    }
}

1500 1501
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
1502 1503 1504 1505 1506 1507
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
1508 1509 1510 1511
}

void HSIDisplay::pressKey(int key)
{
1512
    Q_UNUSED(key);
1513
}
pixhawk's avatar
pixhawk committed
1514 1515