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

3
QGroundControl Open Source Ground Control Station
4

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

7
This file is part of the QGROUNDCONTROL project
8

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

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

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

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

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

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

#include <QDebug>

49

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

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

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

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

125 126 127
    uas = NULL;
    resetMAVState();

128 129
    // Do first update
    setMetricWidth(metricWidth);
130 131 132
    // 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."));
133 134

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

    setFocusPolicy(Qt::StrongFocus);
138 139
}

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

}

145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170
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;
171 172 173 174

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

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

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

195
    //float bottomMargin = 3.0f;
196 197

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

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

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

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

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

242
    // Draw trail
243 244 245 246 247 248
    //    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);
249 250


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

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

    // ----------------------
270

271 272 273
    // Draw satellites
    drawGPS(painter);

274 275 276
    // Draw state indicator

    // Draw position
277
    QColor positionColor(20, 20, 200);
278
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
279 280 281

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
282
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
283 284


285
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
286

287 288 289 290 291 292
    float xSpDiff = uiXSetCoordinate - bodyXSetCoordinate;
    float ySpDiff = uiYSetCoordinate - bodyYSetCoordinate;
    float zSpDiff = uiZSetCoordinate - bodyZSetCoordinate;

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

293 294 295 296
    float angleDiff = uiYawSet - bodyYawSet;

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

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

299

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

    // Draw waypoints
    drawWaypoints(painter);

305
    // Draw status flags
306 307 308 309
    drawStatusFlag(2,  1, tr("ATT"), attControlEnabled, attControlKnown, painter);
    drawStatusFlag(22, 1, tr("PXY"), xyControlEnabled,  xyControlKnown,  painter);
    drawStatusFlag(44, 1, tr("PZ"),  zControlEnabled,   zControlKnown,   painter);
    drawStatusFlag(66, 1, tr("YAW"), yawControlEnabled, yawControlKnown, painter);
310

311
    // Draw position lock indicators
312 313 314 315
    drawPositionLock(2,  5, tr("POS"), positionFix, positionFixKnown, painter);
    drawPositionLock(22, 5, tr("VIS"), visionFix,   visionFixKnown,   painter);
    drawPositionLock(44, 5, tr("GPS"), gpsFix,      gpsFixKnown,      painter);
    drawPositionLock(66, 5, tr("IRU"), iruFix,      iruFixKnown,      painter);
316 317 318

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

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

    // Draw position to bottom left
327 328
    if (localAvailable > 0)
    {
329 330
        // Position
        QString str;
331
        float offset = (globalAvailable > 0) ? -3.0f : 0.0f;
332
        str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
333 334
        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);
335 336
    }

337 338
    if (globalAvailable > 0)
    {
339 340
        // Position
        QString str;
341
        str.sprintf("lat: %05.2f lon: %06.2f alt: %06.2f", lat, lon, alt);
342 343
        paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 2.0f, &painter);
        paintText(str, Qt::white, 2.6f, 10, vheight - 2.0f, &painter);
344 345
    }

346 347 348
    // Draw Safety
    double x1, y1, z1, x2, y2, z2;
    UASManager::instance()->getLocalNEDSafetyLimits(&x1, &y1, &z1, &x2, &y2, &z2);
349
    //    drawSafetyArea(QPointF(x1, y1), QPointF(x2, y2), QGC::colorYellow, painter);
350 351

    // Draw status message
352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372
    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);
    }
373
}
374

375
void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, QPainter& painter)
376
{
377
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
378
    QColor statusColor(250, 250, 250);
379
    if(status) {
pixhawk's avatar
pixhawk committed
380
        painter.setBrush(QGC::colorGreen);
381
    } else {
382
        painter.setBrush(QGC::colorDarkYellow);
383 384
    }
    painter.setPen(Qt::NoPen);
385 386 387 388 389

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

    painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), indicatorWidth, indicatorHeight));
390
    paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
391
    // Cross out instrument if state unknown
392 393
    if (!known)
    {
394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410
        QPen pen(Qt::yellow);
        pen.setWidth(2);
        painter.setPen(pen);
        // Top left to bottom right
        QPointF p1, p2, p3, p4;
        p1.setX(refToScreenX(x));
        p1.setY(refToScreenX(y));
        p2.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
        p2.setY(p1.y()+indicatorHeight);
        painter.drawLine(p1, p2);
        // Bottom left to top right
        p3.setX(refToScreenX(x));
        p3.setY(refToScreenX(y)+indicatorHeight);
        p4.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
        p4.setY(p1.y());
        painter.drawLine(p3, p4);
    }
411 412
}

413
void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, bool known, QPainter& painter)
414
{
415 416 417 418 419 420 421 422 423 424 425 426
    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);
    }
427

428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443
    // 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;
    }
444

445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469
    float indicatorWidth = refToScreenX(7.0f);
    float indicatorHeight = refToScreenY(4.0f);

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

lm's avatar
lm committed
472 473
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
474
    Q_UNUSED(uas);
475
    bool changed = positionLock != lock;
lm's avatar
lm committed
476
    positionLock = lock;
477 478 479 480
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
481 482
}

pixhawk's avatar
pixhawk committed
483
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
484
{
485
    bool changed = attControlEnabled != enabled;
lm's avatar
lm committed
486
    attControlEnabled = enabled;
487
    attControlKnown = true;
488 489 490 491
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
492 493
}

pixhawk's avatar
pixhawk committed
494
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
495
{
496
    bool changed = xyControlEnabled != enabled;
lm's avatar
lm committed
497
    xyControlEnabled = enabled;
498
    xyControlKnown = true;
499 500 501 502
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
503 504
}

pixhawk's avatar
pixhawk committed
505
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
506
{
507
    bool changed = zControlEnabled != enabled;
lm's avatar
lm committed
508
    zControlEnabled = enabled;
509
    zControlKnown = true;
510 511 512 513
    if (changed)
    {
        update();
    }
lm's avatar
lm committed
514 515
}

LM's avatar
LM committed
516 517
void HSIDisplay::updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance)
{
518 519 520 521 522
    Q_UNUSED(quality);
    Q_UNUSED(name);
    Q_UNUSED(type);
    Q_UNUSED(id);
    Q_UNUSED(time);
LM's avatar
LM committed
523 524 525 526 527 528 529 530 531 532 533 534 535 536 537
    // 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
538 539 540 541
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
    // First translate to body-centered coordinates
    // Rotate around -yaw
542
    float angle = -yaw - M_PI;
543
    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
544 545 546 547 548 549 550
    return result;
}

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
551
    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
552
    return result;
553
}
554

555 556
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
557
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth);
558 559 560 561
}

QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
lm's avatar
lm committed
562
    return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
563 564 565 566 567
}

/**
 * @see refToScreenX()
 */
568
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
569 570 571 572
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

573 574 575 576 577 578 579 580 581 582
double HSIDisplay::metricToRef(double metric)
{
    return (metric / metricWidth) * vwidth;
}

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

583 584 585 586 587 588 589 590
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

591 592
void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
593 594
    if (event->type() == QMouseEvent::MouseButtonDblClick)
    {
595
        QPointF p = screenToMetricBody(event->posF());
LM's avatar
LM committed
596
        if (!directSending) setBodySetpointCoordinateXY(p.x(), p.y());
597
        //        qDebug() << "Double click at x: " << screenToRefX(event->x()) - xCenterPos << "y:" << screenToRefY(event->y()) - yCenterPos;
598 599 600 601 602
    }
}

void HSIDisplay::mouseReleaseEvent(QMouseEvent * event)
{
603
    if (mouseHasMoved)
604
    {
605 606 607 608
        if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::RightButton)
        {
            if (dragStarted)
            {
LM's avatar
LM committed
609
                if (!directSending) setBodySetpointCoordinateYaw(uiYawSet);
610 611 612 613 614 615 616
                dragStarted = false;
            }
        }
        if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::LeftButton)
        {
            if (leftDragStarted)
            {
LM's avatar
LM committed
617
                if (!directSending) setBodySetpointCoordinateZ(uiZSetCoordinate);
618
                leftDragStarted = false;
619 620
            }
        }
621
    }
622
    mouseHasMoved = false;
623 624 625 626 627 628 629 630 631
}

void HSIDisplay::mousePressEvent(QMouseEvent * event)
{
    if (event->type() == QMouseEvent::MouseButtonPress)
    {
        if (event->button() == Qt::RightButton)
        {
            startX = event->x();
632 633
            // Start tracking mouse move
            dragStarted = true;
634 635 636
        }
        else if (event->button() == Qt::LeftButton)
        {
637 638
            startY = event->y();
            leftDragStarted = true;
639
        }
pixhawk's avatar
pixhawk committed
640
    }
641
    mouseHasMoved = false;
642
}
643

644 645 646 647
void HSIDisplay::mouseMoveEvent(QMouseEvent * event)
{
    if (event->type() == QMouseEvent::MouseMove)
    {
648
        if (dragStarted) uiYawSet -= 0.06f*(startX - event->x()) / this->frameSize().width();
649 650 651

        if (leftDragStarted)
        {
652 653
            //            uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height();
            //            setBodySetpointCoordinateZ(uiZSetCoordinate);
654
        }
655 656

        if (leftDragStarted || dragStarted) mouseHasMoved = true;
pixhawk's avatar
pixhawk committed
657
    }
658 659
}

pixhawk's avatar
pixhawk committed
660 661
void HSIDisplay::keyPressEvent(QKeyEvent* event)
{
662 663
    QPointF bodySP = metricWorldToBody(QPointF(uiXSetCoordinate, uiYSetCoordinate));

664
    if ((event->key() == Qt::Key_Enter || event->key() == Qt::Key_Return) && actionPending)
pixhawk's avatar
pixhawk committed
665 666 667 668 669 670
    {
        actionPending = false;
        statusMessage = "SETPOINT SENT";
        statusClearTimer.start();
        sendBodySetPointCoordinates();
    }
671 672

    if ((event->key() ==  Qt::Key_W))
pixhawk's avatar
pixhawk committed
673
    {
674 675 676 677 678 679 680 681 682 683 684
        if (!directSending)
        {
            setBodySetpointCoordinateZ(uas->getLocalZ());
            setBodySetpointCoordinateYaw(uas->getYaw());
            setBodySetpointCoordinateXY(1.0, 0);
        }
        else
        {
            setBodySetpointCoordinateXY(qBound(-1.5, bodySP.x()+0.2, +1.5), bodySP.y());
        }

pixhawk's avatar
pixhawk committed
685
    }
686 687

    if ((event->key() ==  Qt::Key_S))
PIXHAWK Team's avatar
PIXHAWK Team committed
688
    {
689 690 691 692 693 694 695 696 697 698
        if (!directSending)
        {
            setBodySetpointCoordinateZ(uas->getLocalZ());
            setBodySetpointCoordinateYaw(uas->getYaw());
            setBodySetpointCoordinateXY(-1.0, 0);
        }
        else
        {
            setBodySetpointCoordinateXY(qBound(-1.5, bodySP.x()-0.2, +1.5), bodySP.y());
        }
PIXHAWK Team's avatar
PIXHAWK Team committed
699
    }
700 701

    if ((event->key() ==  Qt::Key_A))
PIXHAWK Team's avatar
PIXHAWK Team committed
702
    {
703 704 705 706 707 708 709 710 711 712
        if (!directSending)
        {
            setBodySetpointCoordinateZ(uas->getLocalZ());
            setBodySetpointCoordinateYaw(uas->getYaw());
            setBodySetpointCoordinateXY(0, -1.0);
        }
        else
        {
            setBodySetpointCoordinateXY(bodySP.x(), qBound(-1.5, bodySP.y()-0.2, +1.5));
        }
PIXHAWK Team's avatar
PIXHAWK Team committed
713
    }
714 715

    if ((event->key() ==  Qt::Key_D))
PIXHAWK Team's avatar
PIXHAWK Team committed
716
    {
717 718 719 720 721 722 723 724 725 726
        if (!directSending)
        {
            setBodySetpointCoordinateZ(uas->getLocalZ());
            setBodySetpointCoordinateYaw(uas->getYaw());
            setBodySetpointCoordinateXY(0, 1.0);
        }
        else
        {
            setBodySetpointCoordinateXY(bodySP.x(), qBound(-1.5, bodySP.y()+0.2, +1.5));
        }
pixhawk's avatar
pixhawk committed
727
    }
728 729

    if ((event->key() ==  Qt::Key_Up))
PIXHAWK Team's avatar
PIXHAWK Team committed
730
    {
731 732 733 734 735 736
        if (!directSending)
        {
            setBodySetpointCoordinateXY(0, 0);
            setBodySetpointCoordinateYaw(uas->getYaw());
        }
        setBodySetpointCoordinateZ(-0.5);
PIXHAWK Team's avatar
PIXHAWK Team committed
737
    }
738 739

    if ((event->key() ==  Qt::Key_Down))
PIXHAWK Team's avatar
PIXHAWK Team committed
740
    {
741 742 743 744 745 746
        if (!directSending)
        {
            setBodySetpointCoordinateXY(0, 0);
            setBodySetpointCoordinateYaw(uas->getYaw());
        }
        setBodySetpointCoordinateZ(+0.5);
PIXHAWK Team's avatar
PIXHAWK Team committed
747
    }
748 749

    if ((event->key() ==  Qt::Key_Left))
PIXHAWK Team's avatar
PIXHAWK Team committed
750
    {
751 752 753 754 755 756
        if (!directSending)
        {
            setBodySetpointCoordinateXY(0, 0);
            setBodySetpointCoordinateZ(uas->getLocalZ());
        }
        setBodySetpointCoordinateYaw(-0.2);
PIXHAWK Team's avatar
PIXHAWK Team committed
757
    }
758 759

    if ((event->key() ==  Qt::Key_Right))
PIXHAWK Team's avatar
PIXHAWK Team committed
760
    {
761 762 763 764 765 766
        if (!directSending)
        {
            setBodySetpointCoordinateXY(0, 0);
            setBodySetpointCoordinateZ(uas->getLocalZ());
        }
        setBodySetpointCoordinateYaw(0.2);
PIXHAWK Team's avatar
PIXHAWK Team committed
767
    }
768 769 770


    if ((event->key() == Qt::Key_Escape))
PIXHAWK Team's avatar
PIXHAWK Team committed
771
    {
LM's avatar
LM committed
772
        setBodySetpointCoordinateXY(0, 0);
773 774 775
        setBodySetpointCoordinateZ(0);
        setBodySetpointCoordinateYaw(0);
        statusMessage = "CANCELLED, PRESS <ENTER> TO SEND";
PIXHAWK Team's avatar
PIXHAWK Team committed
776
    }
777 778

    if ((event->key() == Qt::Key_T))
PIXHAWK Team's avatar
PIXHAWK Team committed
779
    {
780 781 782
        directSending = !directSending;
        statusMessage = (directSending) ? "DIRECT SEND ON" : "DIRECT SEND OFF";
        statusClearTimer.start();
PIXHAWK Team's avatar
PIXHAWK Team committed
783
    }
784 785

    if (actionPending && (directSending || (event->key() == Qt::Key_Escape)))
PIXHAWK Team's avatar
PIXHAWK Team committed
786
    {
787 788 789 790
        actionPending = false;
        statusMessage = "SETPOINT SENT";
        statusClearTimer.start();
        sendBodySetPointCoordinates();
PIXHAWK Team's avatar
PIXHAWK Team committed
791
    }
792 793

    HDDisplay::keyPressEvent(event);
pixhawk's avatar
pixhawk committed
794 795
}

796 797 798 799 800
void HSIDisplay::contextMenuEvent (QContextMenuEvent* event)
{
    event->ignore();
}

801 802
void HSIDisplay::setMetricWidth(double width)
{
803
    if (width != metricWidth) {
804 805 806 807 808
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

809 810 811 812 813 814
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
815 816 817 818 819 820
    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)));
821
        disconnect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
822 823 824 825 826 827 828 829 830 831 832 833
        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
834
        disconnect(this->uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
835
    }
836

837 838 839 840 841
    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)));
842
    connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
843 844
    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)));
845

846 847 848 849
    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)));
850

851 852 853 854
    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
855
    connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
856

857
    this->uas = uas;
858

859
    resetMAVState();
860 861
}

862 863 864 865 866 867 868
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;
869
    this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
870 871 872 873
}

void HSIDisplay::setBodySetpointCoordinateXY(double x, double y)
{
874 875 876 877 878
    if (uas)
    {
        userSetPointSet = true;
        userXYSetPointSet = true;
        // Set coordinates and send them out to MAV
879

880 881 882 883 884 885
        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
886

pixhawk's avatar
pixhawk committed
887

pixhawk's avatar
pixhawk committed
888 889 890 891
        //sendBodySetPointCoordinates();
        statusMessage = "POSITION SET, PRESS <ENTER> TO SEND";
        actionPending = true;
        statusClearTimer.start();
pixhawk's avatar
pixhawk committed
892
    }
893 894 895 896
}

void HSIDisplay::setBodySetpointCoordinateZ(double z)
{
897 898 899 900 901 902 903 904 905
    if (uas)
    {
        userSetPointSet = true;
        // 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
906
    //sendBodySetPointCoordinates();
907 908 909 910
}

void HSIDisplay::setBodySetpointCoordinateYaw(double yaw)
{
911
    if (uas)
912
    {
913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929
        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;
        // 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;
930
    }
pixhawk's avatar
pixhawk committed
931
    //sendBodySetPointCoordinates();
932 933 934 935 936
}

void HSIDisplay::sendBodySetPointCoordinates()
{
    // Send the coordinates to the MAV
937
    if (uas)
938 939 940 941
    {
        double dx = uiXSetCoordinate - uas->getLocalX();
        double dy = uiYSetCoordinate - uas->getLocalY();
        double dz = uiZSetCoordinate - uas->getLocalZ();
942
        bool valid = (sqrt(dx*dx + dy*dy + dz*dz) < 2.0);//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
943 944 945 946 947 948 949 950 951
        if (valid)
        {
            uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
        }
        else
        {
            setStatusMessage("REJECTED NEW SETPOINT: OUT OF BOUNDS");
        }
    }
952 953
}

954
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
955
{
956 957 958 959 960 961
    Q_UNUSED(uas);
    Q_UNUSED(usec);
    attXSet = pitchDesired;
    attYSet = rollDesired;
    attYawSet = yawDesired;
    altitudeSet = thrustDesired;
962 963
}

lm's avatar
lm committed
964 965 966 967 968 969 970 971 972
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;
}

973 974
void HSIDisplay::updateUserPositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired)
{
975
	Q_UNUSED(uasid);
976 977 978 979 980 981 982 983
    uiXSetCoordinate = xDesired;
    uiYSetCoordinate = yDesired;
    uiZSetCoordinate = zDesired;
    uiYawSet = yawDesired;
    userXYSetPointSet = true;
    userSetPointSet = true;
}

lm's avatar
lm committed
984
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
985
{
986
    Q_UNUSED(uasid);
987
    Q_UNUSED(usec);
988 989 990 991
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
992
    mavInitialized = true;
993
    setPointKnown = true;
994
    positionSetPointKnown = true;
pixhawk's avatar
pixhawk committed
995

996 997 998 999
    if (!userSetPointSet && !dragStarted)
    {
        uiXSetCoordinate = bodyXSetCoordinate;
        uiYSetCoordinate = bodyYSetCoordinate;
1000
        //        uiZSetCoordinate = bodyZSetCoordinate;
1001 1002
        uiYawSet= bodyYawSet;
    }
1003 1004 1005 1006
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
1007 1008 1009 1010
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
1011 1012 1013 1014
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
1015 1016 1017 1018
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
1019 1020
}

lm's avatar
lm committed
1021
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
lm's avatar
lm committed
1022 1023
{
    Q_UNUSED(uasid);
lm's avatar
lm committed
1024
    //qDebug() << "UPDATED SATELLITE";
lm's avatar
lm committed
1025
    // If slot is empty, insert object
1026
    if (gpsSatellites.contains(satid)) {
lm's avatar
lm committed
1027
        gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
1028
    } else {
lm's avatar
lm committed
1029
        gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
lm's avatar
lm committed
1030 1031 1032
    }
}

1033 1034 1035
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
    yawControlEnabled = enabled;
1036
    yawControlKnown = true;
1037 1038 1039 1040 1041 1042 1043 1044 1045
}

/**
 * @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;
1046
    positionFixKnown = true;
1047
    //qDebug() << "LOCALIZATION FIX CALLED";
1048 1049 1050 1051 1052 1053 1054 1055
}
/**
 * @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;
1056
    gpsFixKnown = true;
1057 1058 1059 1060 1061 1062 1063 1064
}
/**
 * @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;
1065
    visionFixKnown = true;
1066
    //qDebug() << "VISION FIX GOT CALLED";
1067 1068
}

1069 1070 1071 1072 1073 1074 1075
/**
 * @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;
1076
    iruFixKnown = true;
1077 1078
}

lm's avatar
lm committed
1079 1080
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
1081
    QColor color;
1082
    if (snr > 0 && snr < 30) {
lm's avatar
lm committed
1083
        color = QColor(250, 10, 10);
1084
    } else if (snr >= 30 && snr < 35) {
lm's avatar
lm committed
1085
        color = QColor(230, 230, 10);
1086
    } else if (snr >= 35 && snr < 40) {
lm's avatar
lm committed
1087
        color = QColor(90, 200, 90);
1088
    } else if (snr >= 40) {
lm's avatar
lm committed
1089
        color = QColor(20, 200, 20);
1090
    } else {
lm's avatar
lm committed
1091 1092 1093
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
1094 1095
}

1096
void HSIDisplay::drawSetpointXYZYaw(float x, float y, float z, float yaw, const QColor &color, QPainter &painter)
1097
{
1098 1099
    if (uas)
    {
1100
        float radius = vwidth / 18.0f;
1101
        QPen pen(color);
1102
        pen.setWidthF(refLineWidthToPen(1.6f));
1103 1104 1105 1106 1107 1108 1109 1110
        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);
1111 1112 1113 1114 1115 1116 1117 1118 1119 1120

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

1121
        // Label
1122
        paintText(QString("z: %1").arg(z), color, 2.1f, p.x()-radius, p.y()-radius-3.5f, &painter);
1123

1124 1125
        drawPolygon(poly, &painter);

1126
        radius *= 0.8f;
1127
        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);
1128 1129

        // Draw center dot
1130 1131 1132
        painter.setBrush(color);
        drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter);
    }
1133 1134
}

1135 1136
void HSIDisplay::drawWaypoints(QPainter& painter)
{
1137 1138
    if (uas)
    {
pixhawk's avatar
pixhawk committed
1139
        const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
1140 1141 1142

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

1144
        QPointF lastWaypoint;
pixhawk's avatar
pixhawk committed
1145

1146
        for (int i = 0; i < list.size(); i++) {
1147
            QPointF in;
1148 1149
            if (list.at(i)->getFrame() == MAV_FRAME_LOCAL_NED)
            {
1150 1151
                // Do not transform
                in = QPointF(list.at(i)->getX(), list.at(i)->getY());
1152
            } else {
1153 1154 1155 1156 1157
                // Transform to local coordinates first
                double x = list.at(i)->getX();
                double y = list.at(i)->getY();
                in = QPointF(x, y);
            }
1158 1159 1160 1161 1162
            // Transform from world to body coordinates
            in = metricWorldToBody(in);
            // Scale from metric to screen reference coordinates
            QPointF p = metricBodyToRef(in);

1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177
            // Setup pen
            QPen pen(color);
            painter.setBrush(Qt::NoBrush);

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

1178
            // Select color based on if this is the current waypoint
1179
            if (list.at(i)->getCurrent()) {
1180
                color = QGC::colorYellow;//uas->getColor();
1181
                pen.setWidthF(refLineWidthToPen(0.8f));
1182
            } else {
1183
                color = QGC::colorCyan;
1184
                pen.setWidthF(refLineWidthToPen(0.4f));
1185 1186
            }

1187
            pen.setColor(color);
1188
            painter.setPen(pen);
1189
            float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
1190
            drawLine(p.x(), p.y(), p.x()+sin(list.at(i)->getYaw()/180.0*M_PI-yaw) * radius, p.y()-cos(list.at(i)->getYaw()/180.0*M_PI-yaw) * radius, refLineWidthToPen(0.4f), color, &painter);
1191
            drawPolygon(poly, &painter);
1192 1193
            float acceptRadius = list.at(i)->getAcceptanceRadius();
            drawCircle(p.x(), p.y(), metricToRef(acceptRadius), 1.0, Qt::green, &painter);
1194

1195
            // DRAW CONNECTING LINE
1196
            // Draw line from last waypoint to this one
1197 1198
            if (!lastWaypoint.isNull())
            {
1199 1200
                pen.setWidthF(refLineWidthToPen(0.4f));
                painter.setPen(pen);
1201
                color = QGC::colorCyan;
1202 1203 1204
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f), color, &painter);
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
1205 1206
        }
    }
1207 1208
}

1209 1210 1211 1212 1213
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);
1214
    pen.setBrush(Qt::NoBrush);
1215
    painter.setPen(pen);
1216
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
1217
}
lm's avatar
lm committed
1218

1219 1220 1221 1222
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
    float yCenter = xCenterPos;
lm's avatar
lm committed
1223 1224
    // Max satellite circle radius

lm's avatar
lm committed
1225 1226 1227
    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
1228

pixhawk's avatar
pixhawk committed
1229 1230 1231 1232 1233
    // 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
1234
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
1235
    while (i.hasNext()) {
lm's avatar
lm committed
1236 1237 1238
        i.next();
        GPSSatellite* sat = i.value();

1239 1240
        // Check if update is not older than 10 seconds, else delete satellite
        if (sat->lastUpdate + 10000000 < currTime) {
lm's avatar
lm committed
1241 1242
            // Delete and go to next satellite
            gpsSatellites.remove(i.key());
1243
            if (i.hasNext()) {
lm's avatar
lm committed
1244 1245
                i.next();
                sat = i.value();
1246
            } else {
lm's avatar
lm committed
1247 1248 1249 1250
                continue;
            }
        }

1251
        if (sat) {
lm's avatar
lm committed
1252 1253 1254 1255
            // Draw satellite
            QBrush brush;
            QColor color = getColorForSNR(sat->snr);
            brush.setColor(color);
1256
            if (sat->used) {
lm's avatar
lm committed
1257
                brush.setStyle(Qt::SolidPattern);
1258
            } else {
lm's avatar
lm committed
1259 1260 1261 1262 1263 1264
                brush.setStyle(Qt::NoBrush);
            }
            painter.setPen(Qt::SolidLine);
            painter.setPen(color);
            painter.setBrush(brush);

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

1268
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
1269
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
1270
            // Draw satellite PRN
lm's avatar
lm committed
1271
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
1272 1273
        }
    }
1274 1275
}

1276
void HSIDisplay::drawObjects(QPainter &painter)
1277
{
1278
    Q_UNUSED(painter);
1279 1280
}

1281
void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1282
{
1283
    if (xyControlKnown && xyControlEnabled) {
1284
        // Draw the needle
1285
        const float maxWidth = radius / 5.0f;
1286
        const float minWidth = maxWidth * 0.3f;
1287

1288
        float angle = atan2(posXSet, -posYSet);
1289
        angle -= (float)M_PI/2.0f;
1290

1291
        QPolygonF p(6);
1292

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

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

1297 1298 1299 1300 1301 1302
        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));
1303

1304
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1305

1306 1307 1308 1309 1310 1311 1312
        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
1313

1314 1315
        //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
    }
1316 1317
}

1318
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
1319
{
1320
    if (attControlKnown && attControlEnabled) {
1321 1322 1323
        // Draw the needle
        const float maxWidth = radius / 10.0f;
        const float minWidth = maxWidth * 0.3f;
1324

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

1327
        radius *= sqrt(attXSet*attXSet + attYSet*attYSet) / sqrt(attXSaturation*attXSaturation + attYSaturation*attYSaturation);
1328

1329
        QPolygonF p(6);
1330

1331 1332 1333 1334 1335 1336
        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));
1337

1338
        rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
1339

1340 1341 1342 1343 1344 1345 1346
        QBrush indexBrush;
        indexBrush.setColor(color);
        indexBrush.setStyle(Qt::SolidPattern);
        painter->setPen(Qt::SolidLine);
        painter->setPen(color);
        painter->setBrush(indexBrush);
        drawPolygon(p, painter);
1347

1348
        // TODO Draw Yaw indicator
lm's avatar
lm committed
1349

1350 1351
        //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
    }
1352 1353 1354 1355
}

void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
{
1356
    if (zControlKnown && zControlEnabled) {
1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370
        // 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);
    }
1371
}
1372

1373 1374 1375
void HSIDisplay::wheelEvent(QWheelEvent* event)
{
    double zoomScale = 0.005; // Scaling of zoom value
1376
    if(event->delta() > 0) {
1377 1378
        // Reduce width -> Zoom in
        metricWidth -= event->delta() * zoomScale;
1379
    } else {
1380 1381 1382
        // Increase width -> Zoom out
        metricWidth -= event->delta() * zoomScale;
    }
1383
    metricWidth = qBound(0.5, metricWidth, 9999.0);
1384 1385
    emit metricWidthChanged(metricWidth);
}
pixhawk's avatar
pixhawk committed
1386

1387 1388 1389 1390
void HSIDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
1391
    Q_UNUSED(event) {
1392 1393 1394 1395 1396 1397 1398 1399
        refreshTimer->start(updateInterval);
    }
}

void HSIDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (post-display)
    // events
1400
    Q_UNUSED(event) {
1401
        refreshTimer->stop();
1402 1403 1404
    }
}

1405 1406
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
1407 1408 1409 1410 1411 1412
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
1413 1414 1415 1416
}

void HSIDisplay::pressKey(int key)
{
1417
    Q_UNUSED(key);
1418
}
pixhawk's avatar
pixhawk committed
1419 1420