HSIDisplay.cc 32.5 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) :
pixhawk's avatar
pixhawk committed
49
        HDDisplay(NULL, "HSI", 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(updateInterval);
104

pixhawk's avatar
pixhawk committed
105 106
    columns = 1;

107

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

pixhawk's avatar
pixhawk committed
110 111 112
    vwidth = 80;
    vheight = 80;

113
    xCenterPos = vwidth/2.0f;
pixhawk's avatar
pixhawk committed
114
    yCenterPos = vheight/2.0f + topMargin - bottomMargin;
pixhawk's avatar
pixhawk committed
115
    qDebug() << "CENTER" << xCenterPos << yCenterPos;
116 117 118 119 120 121 122 123 124 125 126 127 128 129

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

130
    this->setVisible(false);
131 132
    // Do first update
    setMetricWidth(metricWidth);
133 134
}

lm's avatar
lm committed
135 136 137 138 139
void HSIDisplay::paintEvent(QPaintEvent * event)
{
    Q_UNUSED(event);
    //paintGL();
    static quint64 interval = 0;
140
    //qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
lm's avatar
lm committed
141
    interval = MG::TIME::getGroundTimeNow();
142
    renderOverlay();
lm's avatar
lm committed
143 144
}

145
void HSIDisplay::renderOverlay()
146
{
147 148 149
#if (QGC_EVENTLOOP_DEBUG)
    qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
150 151
    // Center location of the HSI gauge items

152
    float bottomMargin = 3.0f;
153 154

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

158 159 160 161 162 163 164 165
    // 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;

166
    QPainter painter(viewport());
167 168
    painter.setRenderHint(QPainter::Antialiasing, true);
    painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
169 170

    // Draw background
171 172
    //painter.fillRect(QRect(0, 0, width(), height()), backgroundColor);

lm's avatar
lm committed
173

174 175
    // Draw base instrument
    // ----------------------
lm's avatar
lm committed
176
    painter.setBrush(Qt::NoBrush);
177
    const QColor ringColor = QColor(200, 250, 200);
lm's avatar
lm committed
178 179 180 181
    QPen pen;
    pen.setColor(ringColor);
    pen.setWidth(refLineWidthToPen(0.1f));
    painter.setPen(pen);
lm's avatar
lm committed
182 183 184
    const int ringCount = 2;
    for (int i = 0; i < ringCount; i++)
    {
pixhawk's avatar
pixhawk committed
185
        float radius = (vwidth - topMargin - bottomMargin) / (2.0f * i+1) / 2.0f - bottomMargin / 2.0f;
186
        drawCircle(xCenterPos, yCenterPos, radius, 0.1f, ringColor, &painter);
lm's avatar
lm committed
187 188
    }

189 190 191
    // Draw orientation labels
    // Translate and rotate coordinate frame
    painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
192
    painter.rotate((yaw/(M_PI))*180.0f);
193 194 195 196
    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);
197
    painter.rotate((-yaw/(M_PI))*180.0f);
198 199
    painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);

lm's avatar
lm committed
200
    // Draw center indicator
201 202 203 204 205
    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);
206 207

    // ----------------------
208

209 210 211
    // Draw satellites
    drawGPS(painter);

212 213 214
    // Draw state indicator

    // Draw position
215
    QColor positionColor(20, 20, 200);
216
    drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
217 218 219

    // Draw attitude
    QColor attitudeColor(200, 20, 20);
220
    drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
221 222


223
    // Draw position setpoints in body coordinates
lm's avatar
lm committed
224

225 226 227 228 229 230 231 232 233
    if (uiXSetCoordinate != 0 || uiYSetCoordinate != 0)
    {
        QColor spColor(150, 150, 150);
        drawSetpointXY(uiXSetCoordinate, uiYSetCoordinate, uiYawSet, spColor, painter);
    }

    if (bodyXSetCoordinate != 0 || bodyYSetCoordinate != 0)
    {
        // Draw setpoint
234
        drawSetpointXY(bodyXSetCoordinate, bodyYSetCoordinate, bodyYawSet, QGC::colorCyan, painter);
235 236
        // Draw travel direction line
        QPointF m(bodyXSetCoordinate, bodyYSetCoordinate);
lm's avatar
lm committed
237 238 239
        // Transform from body to world coordinates
        m = metricWorldToBody(m);
        // Scale from metric body to screen reference units
240
        QPointF s = metricBodyToRef(m);
241
        drawLine(s.x(), s.y(), xCenterPos, yCenterPos, 1.5f, QGC::colorCyan, &painter);
242 243 244
    }

    // Labels on outer part and bottom
245

pixhawk's avatar
pixhawk committed
246
    if (localAvailable > 0)
247
    {
248
        // Position
249 250
        QString str;
        str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
251 252 253 254
        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
255
        paintText(str, ringColor, 3.0f, 10.0f, vheight - 5.0f, &painter);
256 257
    }

258 259 260 261 262 263 264 265
    // 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);
266

267 268 269 270 271
    // 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);
272
}
273

274 275 276 277 278 279
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
280
        painter.setBrush(QGC::colorGreen);
281 282 283
    }
    else
    {
284
        painter.setBrush(QGC::colorDarkYellow);
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 320 321 322 323 324 325 326 327 328
    }
    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
329 330
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
331
    Q_UNUSED(uas);
lm's avatar
lm committed
332 333 334
    positionLock = lock;
}

pixhawk's avatar
pixhawk committed
335
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
lm's avatar
lm committed
336 337 338 339
{
    attControlEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
340
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
lm's avatar
lm committed
341 342 343 344
{
    xyControlEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
345
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
lm's avatar
lm committed
346 347 348 349
{
    zControlEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
350 351 352 353
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
    // First translate to body-centered coordinates
    // Rotate around -yaw
354 355
    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
356 357 358 359 360 361 362
    return result;
}

QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
    // First rotate into world coordinates
    // then translate to world position
363
    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
364
    return result;
365
}
366

367 368
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
lm's avatar
lm committed
369
    return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth - x, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth - y);
370 371 372 373
}

QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
lm's avatar
lm committed
374
    return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
375 376 377 378 379
}

/**
 * @see refToScreenX()
 */
380
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
381 382 383 384
{
    return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}

385 386 387 388 389 390 391 392
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
    QPointF ref = metricBodyToRef(metric);
    ref.setX(refToScreenX(ref.x()));
    ref.setY(refToScreenY(ref.y()));
    return ref;
}

393 394 395 396 397 398 399 400 401 402 403 404 405 406 407
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)
    {
408
        startX = event->globalX();
409 410
        if (event->button() == Qt::RightButton)
        {
411 412
            // Start tracking mouse move
            dragStarted = true;
413 414 415 416 417 418
        }
        else if (event->button() == Qt::LeftButton)
        {

        }
    }
419 420 421 422
    else if (event->MouseButtonRelease)
    {
        dragStarted = false;
    }
pixhawk's avatar
pixhawk committed
423 424
    else if (event->MouseMove)
    {
425
        if (dragStarted) uiYawSet += (startX - event->globalX()) / this->frameSize().width();
pixhawk's avatar
pixhawk committed
426
    }
427 428
}

429 430 431 432 433 434 435 436 437
void HSIDisplay::setMetricWidth(double width)
{
    if (width != metricWidth)
    {
        metricWidth = width;
        emit metricWidthChanged(metricWidth);
    }
}

438 439 440 441 442 443
/**
 *
 * @param uas the UAS/MAV to monitor/display with the HUD
 */
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463
        if (this->uas != NULL)
        {
            disconnect(this->uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
            disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
            disconnect(this->uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
            disconnect(this->uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
            disconnect(this->uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
            disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
            disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));

            disconnect(this->uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
            disconnect(this->uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
            disconnect(this->uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
            disconnect(this->uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));

            disconnect(this->uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
            disconnect(this->uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
            disconnect(this->uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
            disconnect(this->uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
        }
464

465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483
        connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
        connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
        connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
        connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
        connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
        connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
        connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));

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

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

        this->uas = uas;
484 485
}

486 487 488 489 490 491 492
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;
493
    this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
494 495 496 497 498 499
}

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

lm's avatar
lm committed
500 501 502 503 504
    QPointF sp(x, y);
    sp = metricBodyToWorld(sp);
    uiXSetCoordinate = sp.x();
    uiYSetCoordinate = sp.y();

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

    if (uas && mavInitialized)
pixhawk's avatar
pixhawk committed
508 509 510 511
    {
        uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
        qDebug() << "Setting new setpoint at x: " << x << "metric y:" << y;
    }
512 513 514 515 516 517 518 519 520 521 522 523 524
}

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

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

525
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
526
{
527 528 529 530 531 532
    Q_UNUSED(uas);
    Q_UNUSED(usec);
    attXSet = pitchDesired;
    attYSet = rollDesired;
    attYawSet = yawDesired;
    altitudeSet = thrustDesired;
533 534
}

lm's avatar
lm committed
535 536 537 538 539 540 541 542 543
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
544
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
545
{
546 547
    Q_UNUSED(usec);
    Q_UNUSED(uasid);
548 549 550 551
    bodyXSetCoordinate = xDesired;
    bodyYSetCoordinate = yDesired;
    bodyZSetCoordinate = zDesired;
    bodyYawSet = yawDesired;
pixhawk's avatar
pixhawk committed
552 553
    mavInitialized = true;

554 555 556 557 558
    //    qDebug() << "Received setpoint at x: " << x << "metric y:" << y;
    //    posXSet = xDesired;
    //    posYSet = yDesired;
    //    posZSet = zDesired;
    //    posYawSet = yawDesired;
559 560 561 562
}

void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
563 564 565 566
    this->x = x;
    this->y = y;
    this->z = z;
    localAvailable = usec;
567 568 569 570
}

void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
571 572 573 574
    this->lat = lat;
    this->lon = lon;
    this->alt = alt;
    globalAvailable = usec;
575 576
}

lm's avatar
lm committed
577
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
lm's avatar
lm committed
578 579
{
    Q_UNUSED(uasid);
lm's avatar
lm committed
580
    //qDebug() << "UPDATED SATELLITE";
lm's avatar
lm committed
581
    // If slot is empty, insert object
lm's avatar
lm committed
582
    if (gpsSatellites.contains(satid))
lm's avatar
lm committed
583
    {
lm's avatar
lm committed
584
        gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
lm's avatar
lm committed
585 586 587
    }
    else
    {
lm's avatar
lm committed
588
        gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
lm's avatar
lm committed
589 590 591
    }
}

592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621
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;
}

622 623 624 625 626 627 628 629 630
/**
 * @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
631 632
QColor HSIDisplay::getColorForSNR(float snr)
{
lm's avatar
lm committed
633
    QColor color;
lm's avatar
lm committed
634 635 636 637 638
    if (snr > 0 && snr < 30)
    {
        color = QColor(250, 10, 10);
    }
    else if (snr >= 30 && snr < 35)
lm's avatar
lm committed
639
    {
lm's avatar
lm committed
640
        color = QColor(230, 230, 10);
lm's avatar
lm committed
641
    }
lm's avatar
lm committed
642
    else if (snr >= 35 && snr < 40)
lm's avatar
lm committed
643
    {
lm's avatar
lm committed
644
        color = QColor(90, 200, 90);
lm's avatar
lm committed
645
    }
lm's avatar
lm committed
646
    else if (snr >= 40)
lm's avatar
lm committed
647
    {
lm's avatar
lm committed
648
        color = QColor(20, 200, 20);
lm's avatar
lm committed
649 650 651 652 653 654
    }
    else
    {
        color = QColor(180, 180, 180);
    }
    return color;
lm's avatar
lm committed
655 656
}

657
void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color, QPainter &painter)
658
{
659 660 661 662 663 664 665
    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
666 667 668
    // Transform from body to world coordinates
    in = metricWorldToBody(in);
    // Scale from metric to screen reference coordinates
669
    QPointF p = metricBodyToRef(in);
670 671 672 673 674 675 676
    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);
}

677 678
void HSIDisplay::drawWaypoints(QPainter& painter)
{
679
    if (uas)
pixhawk's avatar
pixhawk committed
680
    {
681
        const QVector<Waypoint*>& list = uas->getWaypointManager().getWaypointList();
682 683 684 685 686 687 688 689 690 691 692 693
        //        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);
        //        }
694 695 696

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

698
        QPointF lastWaypoint;
pixhawk's avatar
pixhawk committed
699

700
        for (int i = 0; i < list.size(); i++)
pixhawk's avatar
pixhawk committed
701
        {
702 703 704 705 706 707
            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);

708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723
            // 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()));

724 725 726
            // Select color based on if this is the current waypoint
            if (list.at(i)->getCurrent())
            {
727 728
                color = QGC::colorCyan;//uas->getColor();
                pen.setWidthF(refLineWidthToPen(0.8f));
729 730 731 732
            }
            else
            {
                color = uas->getColor();
733
                pen.setWidthF(refLineWidthToPen(0.4f));
734 735
            }

736
            pen.setColor(color);
737
            painter.setPen(pen);
738
            float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
739
            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);
740
            drawPolygon(poly, &painter);
741

742
            // DRAW CONNECTING LINE
743 744 745
            // Draw line from last waypoint to this one
            if (!lastWaypoint.isNull())
            {
746 747 748
                pen.setWidthF(refLineWidthToPen(0.4f));
                painter.setPen(pen);
                color = uas->getColor();
749 750 751
                drawLine(lastWaypoint.x(), lastWaypoint.y(), p.x(), p.y(), refLineWidthToPen(0.4f), color, &painter);
            }
            lastWaypoint = p;
pixhawk's avatar
pixhawk committed
752 753
        }
    }
754 755
}

756 757 758 759 760 761
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);
762
    painter.drawRect(QRectF(metricBodyToScreen(metricWorldToBody(topLeft)), metricBodyToScreen(metricWorldToBody(bottomRight))));
763
}
lm's avatar
lm committed
764

765 766 767 768
void HSIDisplay::drawGPS(QPainter &painter)
{
    float xCenter = xCenterPos;
    float yCenter = xCenterPos;
lm's avatar
lm committed
769 770
    // Max satellite circle radius

lm's avatar
lm committed
771 772 773
    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
774

pixhawk's avatar
pixhawk committed
775 776 777 778 779
    // 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
780 781
    QMapIterator<int, GPSSatellite*> i(gpsSatellites);
    while (i.hasNext())
lm's avatar
lm committed
782
    {
lm's avatar
lm committed
783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801
        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
802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819
        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
820 821
            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
822

823
            // Draw circle for satellite, filled for used satellites
lm's avatar
lm committed
824
            drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
825
            // Draw satellite PRN
lm's avatar
lm committed
826
            paintText(QString::number(sat->id), QColor(255, 255, 255), 2.9f, xPos+1.7f, yPos+2.0f, &painter);
lm's avatar
lm committed
827 828
        }
    }
829 830
}

831
void HSIDisplay::drawObjects(QPainter &painter)
832
{
833
    Q_UNUSED(painter);
834 835
}

836
void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
837
{
838 839 840
    // Draw the needle
    const float maxWidth = radius / 10.0f;
    const float minWidth = maxWidth * 0.3f;
841

lm's avatar
lm committed
842 843
    float angle = atan2(posXSet, -posYSet);
    angle -= M_PI/2.0f;
844 845

    QPolygonF p(6);
846

lm's avatar
lm committed
847 848 849 850 851
    //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));
852 853
    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
854 855 856
    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));
857 858 859 860 861 862 863 864 865 866

    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
867

868
    //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle;
869 870
}

871
void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter)
872
{
873 874 875 876
    // Draw the needle
    const float maxWidth = radius / 10.0f;
    const float minWidth = maxWidth * 0.3f;

lm's avatar
lm committed
877 878 879 880
    float angle = atan2(attXSet, attYSet);
    angle -= M_PI/2.0f;

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

882 883
    QPolygonF p(6);

lm's avatar
lm committed
884
    p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f));
885 886
    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
887 888 889
    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));
890

891
    rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef));
892 893

    QBrush indexBrush;
894
    indexBrush.setColor(color);
895 896
    indexBrush.setStyle(Qt::SolidPattern);
    painter->setPen(Qt::SolidLine);
897
    painter->setPen(color);
898 899
    painter->setBrush(indexBrush);
    drawPolygon(p, painter);
900 901

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

903
    //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle;
904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920
}

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);
921
}
922

923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938
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
939

940 941 942 943
void HSIDisplay::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
944
    Q_UNUSED(event)
945
    {
946 947 948 949 950 951 952 953 954 955 956
        refreshTimer->start(updateInterval);
    }
}

void HSIDisplay::hideEvent(QHideEvent* event)
{
    // React only to internal (post-display)
    // events
    Q_UNUSED(event)
    {
        refreshTimer->stop();
957 958 959
    }
}

960 961
void HSIDisplay::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat)
{
962 963 964 965 966 967
    Q_UNUSED(roll);
    Q_UNUSED(pitch);
    Q_UNUSED(yaw);
    Q_UNUSED(thrust);
    Q_UNUSED(xHat);
    Q_UNUSED(yHat);
968 969 970 971
}

void HSIDisplay::pressKey(int key)
{
972
    Q_UNUSED(key);
973
}
pixhawk's avatar
pixhawk committed
974 975