HSIDisplay.cc 30.1 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 40
#include "UASManager.h"
#include "HSIDisplay.h"
#include "MG.h"
41
#include "QGC.h"
pixhawk's avatar
pixhawk committed
42
#include "Waypoint.h"
43
#include "UASWaypointManager.h"
44
#include "Waypoint2DIcon.h"
45 46 47

#include <QDebug>

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

105 106 107

//    this->setScene(new QGraphicsScene(-metricWidth/2.0f, -metricWidth/2.0f, metricWidth, metricWidth, this));

108
    xCenterPos = vwidth/2.0f;
pixhawk's avatar
pixhawk committed
109
    yCenterPos = vheight/2.0f + topMargin - bottomMargin;
110 111 112 113 114 115 116 117 118 119 120 121 122 123

    // Add interaction elements
    QHBoxLayout* layout = new QHBoxLayout(this);
    layout->setMargin(2);
    layout->setSpacing(0);
    QDoubleSpinBox* spinBox = new QDoubleSpinBox(this);
    spinBox->setMinimum(0.1);
    spinBox->setMaximum(9999);
    connect(spinBox, SIGNAL(valueChanged(double)), this, SLOT(setMetricWidth(double)));
    connect(this, SIGNAL(metricWidthChanged(double)), spinBox, SLOT(setValue(double)));
    layout->addWidget(spinBox);
    layout->setAlignment(spinBox, Qt::AlignBottom | Qt::AlignLeft);
    this->setLayout(layout);

124
    this->setVisible(false);
125 126
    // Do first update
    setMetricWidth(metricWidth);
127 128
}

lm's avatar
lm committed
129 130 131 132 133
void HSIDisplay::paintEvent(QPaintEvent * event)
{
    Q_UNUSED(event);
    //paintGL();
    static quint64 interval = 0;
134
    //qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
lm's avatar
lm committed
135
    interval = MG::TIME::getGroundTimeNow();
136
    renderOverlay();
lm's avatar
lm committed
137 138
}

139
void HSIDisplay::renderOverlay()
140
{
141 142
    // Center location of the HSI gauge items

143
    float bottomMargin = 3.0f;
144 145

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

149 150 151 152 153 154 155 156
    // 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;

157
    QPainter painter(viewport());
158 159
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
160 161

    // Draw background
162 163
    //painter.fillRect(QRect(0, 0, width(), height()), backgroundColor);

lm's avatar
lm committed
164

165 166
    // Draw base instrument
    // ----------------------
lm's avatar
lm committed
167
    painter.setBrush(Qt::NoBrush);
168
    const QColor ringColor = QColor(200, 250, 200);
lm's avatar
lm committed
169 170 171 172
    QPen pen;
    pen.setColor(ringColor);
    pen.setWidth(refLineWidthToPen(0.1f));
    painter.setPen(pen);
lm's avatar
lm committed
173 174 175
    const int ringCount = 2;
    for (int i = 0; i < ringCount; i++)
    {
pixhawk's avatar
pixhawk committed
176
        float radius = (vwidth - topMargin - bottomMargin) / (2.0f * i+1) / 2.0f - bottomMargin / 2.0f;
177
        drawCircle(xCenterPos, yCenterPos, radius, 0.1f, ringColor, &painter);
lm's avatar
lm committed
178 179
    }

180 181 182
    // Draw orientation labels
    // Translate and rotate coordinate frame
    painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
183
    painter.rotate((yaw/(M_PI))*180.0f);
184 185 186 187
    paintText(tr("N"), ringColor, 3.5f, - 1.0f, - baseRadius - 5.5f, &painter);
    paintText(tr("S"), ringColor, 3.5f, - 1.0f, + baseRadius + 1.5f, &painter);
    paintText(tr("E"), ringColor, 3.5f, + baseRadius + 2.0f, - 1.75f, &painter);
    paintText(tr("W"), ringColor, 3.5f, - baseRadius - 5.5f, - 1.75f, &painter);
188
    painter.rotate((-yaw/(M_PI))*180.0f);
189 190
    painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);

lm's avatar
lm committed
191
    // Draw center indicator
192 193 194 195 196
    QPolygonF p(3);
    p.replace(0, QPointF(xCenterPos, yCenterPos-2.8484f));
    p.replace(1, QPointF(xCenterPos-2.0f, yCenterPos+2.0f));
    p.replace(2, QPointF(xCenterPos+2.0f, yCenterPos+2.0f));
    drawPolygon(p, &painter);
197 198

    // ----------------------
199

200 201 202
    // Draw satellites
    drawGPS(painter);

203 204 205
    // Draw state indicator

    // Draw position
206
    QColor positionColor(20, 20, 200);
207
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
208 209 210

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
211
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
212 213


214
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
215

216 217 218 219 220 221 222 223 224
    if (uiXSetCoordinate != 0 || uiYSetCoordinate != 0)
    {
        QColor spColor(150, 150, 150);
        drawSetpointXY(uiXSetCoordinate, uiYSetCoordinate, uiYawSet, spColor, painter);
    }

    if (bodyXSetCoordinate != 0 || bodyYSetCoordinate != 0)
    {
        // Draw setpoint
225
        drawSetpointXY(bodyXSetCoordinate, bodyYSetCoordinate, bodyYawSet, QGC::colorCyan, painter);
226 227
        // Draw travel direction line
        QPointF m(bodyXSetCoordinate, bodyYSetCoordinate);
lm's avatar
lm committed
228 229 230
        // Transform from body to world coordinates
        m = metricWorldToBody(m);
        // Scale from metric body to screen reference units
231
        QPointF s = metricBodyToRef(m);
232
        drawLine(s.x(), s.y(), xCenterPos, yCenterPos, 1.5f, QGC::colorCyan, &painter);
233 234 235
    }

    // Labels on outer part and bottom
236

pixhawk's avatar
pixhawk committed
237
    if (localAvailable > 0)
238
    {
239
        // Position
240 241
        QString str;
        str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
242 243 244 245
        paintText(str, ringColor, 3.0f, xCenterPos + baseRadius - 30.75f, vheight - 5.0f, &painter);

        // Speed
        str.sprintf("%05.2f m/s", speed);
lm's avatar
lm committed
246
        paintText(str, ringColor, 3.0f, 10.0f, vheight - 5.0f, &painter);
247 248
    }

249 250 251 252 253 254 255 256
    // Draw waypoints
    drawWaypoints(painter);

    // Draw status flags
    drawStatusFlag(2,  1, tr("ATT"), attControlEnabled, painter);
    drawStatusFlag(22, 1, tr("PXY"), xyControlEnabled,  painter);
    drawStatusFlag(44, 1, tr("PZ"),  zControlEnabled,   painter);
    drawStatusFlag(66, 1, tr("YAW"), yawControlEnabled, painter);
257

258 259 260 261 262
    // Draw position lock indicators
    drawPositionLock(2,  5, tr("POS"), positionFix, painter);
    drawPositionLock(22, 5, tr("VIS"), visionFix, painter);
    drawPositionLock(44, 5, tr("GPS"), gpsFix, painter);
    drawPositionLock(66, 5, tr("IRU"), iruFix, painter);
263
}
264

265 266 267 268 269 270
void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, QPainter& painter)
{
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.35f, &painter);
    QColor statusColor(250, 250, 250);
    if(status)
    {
pixhawk's avatar
pixhawk committed
271
        painter.setBrush(QGC::colorGreen);
272 273 274
    }
    else
    {
275
        painter.setBrush(QGC::colorDarkYellow);
276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319
    }
    painter.setPen(Qt::NoPen);
    painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), refToScreenX(7.0f), refToScreenY(4.0f)));
    paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.35f, &painter);
}

void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, QPainter& painter)
{
    paintText(label, QGC::colorCyan, 2.6f, x, y+0.35f, &painter);
    QColor negStatusColor(200, 20, 20);
    QColor posStatusColor(20, 200, 20);
    QColor statusColor(250, 250, 250);
    if(status > 0 && status < 4)
    {
        painter.setBrush(posStatusColor);
    }
    else
    {
        painter.setBrush(negStatusColor);
    }

    // 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;
    }

    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.35f, &painter);
}

lm's avatar
lm committed
320 321
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
322
    Q_UNUSED(uas);
lm's avatar
lm committed
323 324 325
    positionLock = lock;
}

pixhawk's avatar
pixhawk committed
326
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
327 328 329 330
{
    attControlEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
331
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
332 333 334 335
{
    xyControlEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
336
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
337 338 339 340
{
    zControlEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
341 342 343 344
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
    // First translate to body-centered coordinates
    // Rotate around -yaw
345 346
    float angle = yaw + M_PI;
    QPointF result(cos(angle) * (x - world.x()) - sin(angle) * (y - world.y()), sin(angle) * (x - world.x()) + cos(angle) * (y - world.y()));
pixhawk's avatar
pixhawk committed
347 348 349 350 351 352 353
    return result;
}

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
354
    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
355
    return result;
356
}
357

358 359
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
lm's avatar
lm committed
360
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth - x, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth - y);
361 362 363 364
}

QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
lm's avatar
lm committed
365
    return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
366 367 368 369 370
}

/**
 * @see refToScreenX()
 */
371
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
372 373 374 375
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

376 377 378 379 380 381 382 383
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

384 385 386 387 388 389 390 391 392 393 394 395 396 397 398
void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
    static bool dragStarted;
    static float startX;

    if (event->MouseButtonDblClick)
    {
        //setBodySetpointCoordinateXY(-refToMetric(screenToRefY(event->y()) - yCenterPos), refToMetric(screenToRefX(event->x()) - xCenterPos));

        QPointF p = screenToMetricBody(event->posF());
        setBodySetpointCoordinateXY(p.x(), p.y());
        qDebug() << "Double click at x: " << screenToRefX(event->x()) - xCenterPos << "y:" << screenToRefY(event->y()) - yCenterPos;
    }
    else if (event->MouseButtonPress)
    {
399
        startX = event->globalX();
400 401
        if (event->button() == Qt::RightButton)
        {
402 403
            // Start tracking mouse move
            dragStarted = true;
404 405 406 407 408 409
        }
        else if (event->button() == Qt::LeftButton)
        {

        }
    }
410 411 412 413
    else if (event->MouseButtonRelease)
    {
        dragStarted = false;
    }
pixhawk's avatar
pixhawk committed
414 415
    else if (event->MouseMove)
    {
416
        if (dragStarted) uiYawSet += (startX - event->globalX()) / this->frameSize().width();
pixhawk's avatar
pixhawk committed
417
    }
418 419
}

420 421 422 423 424 425 426 427 428
void HSIDisplay::setMetricWidth(double width)
{
    if (width != metricWidth)
    {
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

429 430 431 432 433 434 435 436 437 438 439 440
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
    if (this->uas != NULL && this->uas != uas)
    {
        // Disconnect any previously connected active MAV
        //disconnect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
    }

441 442 443 444 445

    HDDisplay::setActiveUAS(uas);
    //qDebug() << "ATTEMPTING TO SET UAS";


lm's avatar
lm committed
446
    connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
447 448 449
    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)));
lm's avatar
lm committed
450
    connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
451
    connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
lm's avatar
lm committed
452
    connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
lm's avatar
lm committed
453

pixhawk's avatar
pixhawk committed
454 455 456 457
    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)));
458 459 460 461

    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)));
462
    connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
463

464 465 466 467 468 469 470 471 472 473
    // Now connect the new UAS

    //if (this->uas != uas)
    // {
    //qDebug() << "UAS SET!" << "ID:" << uas->getUASID();
    // Setup communication
    //connect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
    //}
}

474 475 476 477 478 479 480 481 482 483 484 485 486 487
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;
    this->speed = sqrt(pow(vx, 2.0f) + pow(vy, 2.0f) + pow(vz, 2.0f));
}

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

lm's avatar
lm committed
488 489 490 491 492
    QPointF sp(x, y);
    sp = metricBodyToWorld(sp);
    uiXSetCoordinate = sp.x();
    uiYSetCoordinate = sp.y();

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

    if (uas && mavInitialized)
pixhawk's avatar
pixhawk committed
496 497 498 499
    {
        uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
        qDebug() << "Setting new setpoint at x: " << x << "metric y:" << y;
    }
500 501 502 503 504 505 506 507 508 509 510 511 512
}

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

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

513
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
514
{
515 516 517 518 519 520
    Q_UNUSED(uas);
    Q_UNUSED(usec);
    attXSet = pitchDesired;
    attYSet = rollDesired;
    attYawSet = yawDesired;
    altitudeSet = thrustDesired;
521 522
}

lm's avatar
lm committed
523 524 525 526 527 528 529 530 531
void HSIDisplay::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 time)
{
    Q_UNUSED(uas);
    Q_UNUSED(time);
    this->roll = roll;
    this->pitch = pitch;
    this->yaw = yaw;
}

lm's avatar
lm committed
532
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
533
{
534 535
    Q_UNUSED(usec);
    Q_UNUSED(uasid);
536 537 538 539
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
540 541
    mavInitialized = true;

542 543 544 545 546
    //    qDebug() << "Received setpoint at x: " << x << "metric y:" << y;
    //    posXSet = xDesired;
    //    posYSet = yDesired;
    //    posZSet = zDesired;
    //    posYawSet = yawDesired;
547 548 549 550
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
551 552 553 554
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
555 556 557 558
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
559 560 561 562
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
563 564
}

lm's avatar
lm committed
565
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
lm's avatar
lm committed
566 567
{
    Q_UNUSED(uasid);
lm's avatar
lm committed
568
    //qDebug() << "UPDATED SATELLITE";
lm's avatar
lm committed
569
    // If slot is empty, insert object
lm's avatar
lm committed
570
    if (gpsSatellites.contains(satid))
lm's avatar
lm committed
571
    {
lm's avatar
lm committed
572
        gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
lm's avatar
lm committed
573 574 575
    }
    else
    {
lm's avatar
lm committed
576
        gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
lm's avatar
lm committed
577 578 579
    }
}

580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
    yawControlEnabled = enabled;
}

/**
 * @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;
}
/**
 * @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;
}
/**
 * @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;
}

610 611 612 613 614 615 616 617 618
/**
 * @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;
}

lm's avatar
lm committed
619 620
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
621
    QColor color;
lm's avatar
lm committed
622 623 624 625 626
    if (snr > 0 && snr < 30)
    {
        color = QColor(250, 10, 10);
    }
    else if (snr >= 30 && snr < 35)
lm's avatar
lm committed
627
    {
lm's avatar
lm committed
628
        color = QColor(230, 230, 10);
lm's avatar
lm committed
629
    }
lm's avatar
lm committed
630
    else if (snr >= 35 && snr < 40)
lm's avatar
lm committed
631
    {
lm's avatar
lm committed
632
        color = QColor(90, 200, 90);
lm's avatar
lm committed
633
    }
lm's avatar
lm committed
634
    else if (snr >= 40)
lm's avatar
lm committed
635
    {
lm's avatar
lm committed
636
        color = QColor(20, 200, 20);
lm's avatar
lm committed
637 638 639 640 641 642
    }
    else
    {
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
643 644
}

645
void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color, QPainter &painter)
646
{
647 648 649 650 651 652 653
    float radius = vwidth / 20.0f;
    QPen pen(color);
    pen.setWidthF(refLineWidthToPen(0.4f));
    pen.setColor(color);
    painter.setPen(pen);
    painter.setBrush(Qt::NoBrush);
    QPointF in(x, y);
lm's avatar
lm committed
654 655 656
    // Transform from body to world coordinates
    in = metricWorldToBody(in);
    // Scale from metric to screen reference coordinates
657
    QPointF p = metricBodyToRef(in);
658 659 660 661 662 663 664
    drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter);
    radius *= 0.8;
    drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * radius, refLineWidthToPen(0.4f), color, &painter);
    painter.setBrush(color);
    drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter);
}

665 666
void HSIDisplay::drawWaypoints(QPainter& painter)
{
667
    if (uas)
pixhawk's avatar
pixhawk committed
668
    {
669
        const QVector<Waypoint*>& list = uas->getWaypointManager().getWaypointList();
670 671 672 673 674 675 676 677 678 679 680 681
//        for (int i = 0; i < list.size(); i++)
//        {
//            QPointF in(list.at(i)->getX(), list.at(i)->getY());
//            // Transform from world to body coordinates
//            in = metricWorldToBody(in);
//            // Scale from metric to screen reference coordinates
//            QPointF p = metricBodyToRef(in);
//            Waypoint2DIcon* wp = new Waypoint2DIcon();
//            wp->setLocalPosition(list.at(i)->getX(), list.at(i)->getY());
//            wp->setPos(0, 0);
//            scene()->addItem(wp);
//        }
682 683 684

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

686
        QPointF lastWaypoint;
pixhawk's avatar
pixhawk committed
687

688
        for (int i = 0; i < list.size(); i++)
pixhawk's avatar
pixhawk committed
689
        {
690 691 692 693 694 695
            QPointF in(list.at(i)->getX(), list.at(i)->getY());
            // Transform from world to body coordinates
            in = metricWorldToBody(in);
            // Scale from metric to screen reference coordinates
            QPointF p = metricBodyToRef(in);

696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711
            // Setup pen
            QPen pen(color);
            painter.setBrush(Qt::NoBrush);

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

712 713 714
            // Select color based on if this is the current waypoint
            if (list.at(i)->getCurrent())
            {
715 716
                color = QGC::colorCyan;//uas->getColor();
                pen.setWidthF(refLineWidthToPen(0.8f));
717 718 719 720
            }
            else
            {
                color = uas->getColor();
721
                pen.setWidthF(refLineWidthToPen(0.4f));
722 723
            }

724
            pen.setColor(color);
725
            painter.setPen(pen);
726
            float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
727
            drawLine(p.x(), p.y(), p.x()+sin(list.at(i)->getYaw()+yaw) * radius, p.y()-cos(list.at(i)->getYaw()+yaw) * radius, refLineWidthToPen(0.4f), color, &painter);
728
            drawPolygon(poly, &painter);
729

730
            // DRAW CONNECTING LINE
731 732 733
            // Draw line from last waypoint to this one
            if (!lastWaypoint.isNull())
            {
734 735 736
                pen.setWidthF(refLineWidthToPen(0.4f));
                painter.setPen(pen);
                color = uas->getColor();
737 738 739
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f), color, &painter);
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
740 741
        }
    }
742 743
}

744 745 746 747 748 749
void HSIDisplay::drawSafetyArea(const QPointF &topLeft, const QPointF &bottomRight, const QColor &color, QPainter &painter)
{
    QPen pen(color);
    pen.setWidthF(refLineWidthToPen(0.1f));
    pen.setColor(color);
    painter.setPen(pen);
750
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
751
}
lm's avatar
lm committed
752

753 754 755 756
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
    float yCenter = xCenterPos;
lm's avatar
lm committed
757 758
    // Max satellite circle radius

lm's avatar
lm committed
759 760 761
    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
762

pixhawk's avatar
pixhawk committed
763 764 765 766 767
    // 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
768 769
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
    while (i.hasNext())
lm's avatar
lm committed
770
    {
lm's avatar
lm committed
771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789
        i.next();
        GPSSatellite* sat = i.value();

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

lm's avatar
lm committed
790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807
        if (sat)
        {
            // Draw satellite
            QBrush brush;
            QColor color = getColorForSNR(sat->snr);
            brush.setColor(color);
            if (sat->used)
            {
                brush.setStyle(Qt::SolidPattern);
            }
            else
            {
                brush.setStyle(Qt::NoBrush);
            }
            painter.setPen(Qt::SolidLine);
            painter.setPen(color);
            painter.setBrush(brush);

lm's avatar
lm committed
808 809
            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
810

811
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
812
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
813
            // Draw satellite PRN
lm's avatar
lm committed
814
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
815 816
        }
    }
817 818
}

819
void HSIDisplay::drawObjects(QPainter &painter)
820
{
821
    Q_UNUSED(painter);
822 823
}

824
void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
825
{
826 827 828
    // Draw the needle
    const float maxWidth = radius / 10.0f;
    const float minWidth = maxWidth * 0.3f;
829

lm's avatar
lm committed
830 831
    float angle = atan2(posXSet, -posYSet);
    angle -= M_PI/2.0f;
832 833

    QPolygonF p(6);
834

lm's avatar
lm committed
835 836 837 838 839
    //radius *= ((posXSaturation + posYSaturation) - sqrt(pow(posXSet, 2), pow(posYSet, 2))) / (2*posXSaturation);

    radius *= sqrt(pow(posXSet, 2) + pow(posYSet, 2)) / sqrt(posXSaturation + posYSaturation);

    p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f));
840 841
    p.replace(1, QPointF(xRef-minWidth/2.0f, yRef-radius * 0.9f));
    p.replace(2, QPointF(xRef+minWidth/2.0f, yRef-radius * 0.9f));
lm's avatar
lm committed
842 843 844
    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));
845 846 847 848 849 850 851 852 853 854

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

    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
855

856
    //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
857 858
}

859
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
860
{
861 862 863 864
    // Draw the needle
    const float maxWidth = radius / 10.0f;
    const float minWidth = maxWidth * 0.3f;

lm's avatar
lm committed
865 866 867 868
    float angle = atan2(attXSet, attYSet);
    angle -= M_PI/2.0f;

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

870 871
    QPolygonF p(6);

lm's avatar
lm committed
872
    p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f));
873 874
    p.replace(1, QPointF(xRef-minWidth/2.0f, yRef-radius * 0.9f));
    p.replace(2, QPointF(xRef+minWidth/2.0f, yRef-radius * 0.9f));
lm's avatar
lm committed
875 876 877
    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));
878

879
    rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
880 881

    QBrush indexBrush;
882
    indexBrush.setColor(color);
883 884
    indexBrush.setStyle(Qt::SolidPattern);
    painter->setPen(Qt::SolidLine);
885
    painter->setPen(color);
886 887
    painter->setBrush(indexBrush);
    drawPolygon(p, painter);
888 889

    // TODO Draw Yaw indicator
lm's avatar
lm committed
890

891
    //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908
}

void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
{
    // 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);
909
}
910

911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926
void HSIDisplay::wheelEvent(QWheelEvent* event)
{
    double zoomScale = 0.005; // Scaling of zoom value
    if(event->delta() > 0)
    {
        // Reduce width -> Zoom in
        metricWidth -= event->delta() * zoomScale;
    }
    else
    {
        // Increase width -> Zoom out
        metricWidth -= event->delta() * zoomScale;
    }
    metricWidth = qBound(0.1, metricWidth, 9999.0);
    emit metricWidthChanged(metricWidth);
}
pixhawk's avatar
pixhawk committed
927

928 929
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
930 931 932 933 934 935
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
936 937 938 939
}

void HSIDisplay::pressKey(int key)
{
940
    Q_UNUSED(key);
941
}
pixhawk's avatar
pixhawk committed
942 943