UASView.cc 22.2 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2 3 4 5 6 7 8 9 10 11
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit

(c) 2009, 2010 PIXHAWK PROJECT  <http://pixhawk.ethz.ch>

This file is part of the PIXHAWK project

    PIXHAWK is free software: you can redistribute it and/or modify
    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.
12

pixhawk's avatar
pixhawk committed
13 14 15 16
    PIXHAWK is distributed in the hope that it will be useful,
    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.
17

pixhawk's avatar
pixhawk committed
18 19
    You should have received a copy of the GNU General Public License
    along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
20

pixhawk's avatar
pixhawk committed
21 22 23 24
======================================================================*/

/**
 * @file
pixhawk's avatar
pixhawk committed
25
 *   @brief Implementation of one airstrip
pixhawk's avatar
pixhawk committed
26 27 28 29 30 31 32 33
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <cmath>
#include <QDateTime>
#include <QDebug>
34
#include <QMenu>
35
#include <QInputDialog>
pixhawk's avatar
pixhawk committed
36

37
#include "QGC.h"
pixhawk's avatar
pixhawk committed
38 39
#include "UASManager.h"
#include "UASView.h"
40
#include "UASWaypointManager.h"
41
#include "MainWindow.h"
pixhawk's avatar
pixhawk committed
42 43 44
#include "ui_UASView.h"

UASView::UASView(UASInterface* uas, QWidget *parent) :
45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66
        QWidget(parent),
        startTime(0),
        timeout(false),
        iconIsRed(true),
        timeRemaining(0),
        chargeLevel(0),
        uas(uas),
        load(0),
        state("UNKNOWN"),
        stateDesc(tr("Unknown state")),
        mode("MAV_MODE_UNKNOWN"),
        thrust(0),
        isActive(false),
        x(0),
        y(0),
        z(0),
        totalSpeed(0),
        lat(0),
        lon(0),
        alt(0),
        groundDistance(0),
        localFrame(false),
67
        globalFrameKnown(false),
68 69 70
        removeAction(new QAction("Delete this system", this)),
        renameAction(new QAction("Rename..", this)),
        selectAction(new QAction("Control this system", this )),
71 72
        hilAction(new QAction("Enable Flightgear Hardware-in-the-Loop Simulation", this )),
        hilXAction(new QAction("Enable X-Plane Hardware-in-the-Loop Simulation", this )),
73 74
        selectAirframeAction(new QAction("Choose Airframe", this)),
        setBatterySpecsAction(new QAction("Set Battery Options", this)),
75
        lowPowerModeEnabled(true),
76 77
        generalUpdateCount(0),
        filterTime(0),
78 79 80 81 82
        m_ui(new Ui::UASView)
{
    // FIXME XXX
    lowPowerModeEnabled = MainWindow::instance()->lowPowerModeEnabled();

lm's avatar
lm committed
83
    hilAction->setCheckable(true);
84 85 86
    // Flightgear is not ready for prime time
    hilAction->setEnabled(false);
    hilXAction->setCheckable(true);
87

pixhawk's avatar
pixhawk committed
88
    m_ui->setupUi(this);
89

pixhawk's avatar
pixhawk committed
90
    // Setup communication
pixhawk's avatar
pixhawk committed
91
    //connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), this, SLOT(receiveValue(int,QString,double,quint64)));
pixhawk's avatar
pixhawk committed
92 93 94 95 96 97 98
    connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
    connect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
    connect(uas, SIGNAL(thrustChanged(UASInterface*, double)), this, SLOT(updateThrust(UASInterface*, double)));
    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(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
    connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString,QString)));
pixhawk's avatar
pixhawk committed
99
    connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
pixhawk's avatar
pixhawk committed
100
    connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
101
    connect(uas, SIGNAL(heartbeatTimeout()), this, SLOT(heartbeatTimeout()));
pixhawk's avatar
pixhawk committed
102
    connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int,int)));
pixhawk's avatar
pixhawk committed
103
    connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
pixhawk's avatar
pixhawk committed
104
    connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
105
    connect(UASManager::instance(), SIGNAL(activeUASStatusChanged(UASInterface*,bool)), this, SLOT(updateActiveUAS(UASInterface*,bool)));
106 107 108
    connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(showStatusText(int, int, int, QString)));
    connect(uas, SIGNAL(navModeChanged(int, int, QString)), this, SLOT(updateNavMode(int, int, QString)));

pixhawk's avatar
pixhawk committed
109
    // Setup UAS selection
110
    connect(m_ui->uasViewFrame, SIGNAL(clicked(bool)), this, SLOT(setUASasActive(bool)));
111

pixhawk's avatar
pixhawk committed
112 113 114 115
    // Setup user interaction
    connect(m_ui->liftoffButton, SIGNAL(clicked()), uas, SLOT(launch()));
    connect(m_ui->haltButton, SIGNAL(clicked()), uas, SLOT(halt()));
    connect(m_ui->continueButton, SIGNAL(clicked()), uas, SLOT(go()));
116
    connect(m_ui->landButton, SIGNAL(clicked()), uas, SLOT(land()));
pixhawk's avatar
pixhawk committed
117
    connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
pixhawk's avatar
pixhawk committed
118 119
    connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL()));
    connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));
120 121 122

    // Allow to delete this widget
    connect(removeAction, SIGNAL(triggered()), this, SLOT(deleteLater()));
123
    connect(renameAction, SIGNAL(triggered()), this, SLOT(rename()));
124
    connect(selectAction, SIGNAL(triggered()), uas, SLOT(setSelected()));
lm's avatar
lm committed
125
    connect(hilAction, SIGNAL(triggered(bool)), uas, SLOT(enableHil(bool)));
126
    connect(hilXAction, SIGNAL(triggered(bool)), uas, SLOT(enableHil(bool)));
127
    connect(selectAirframeAction, SIGNAL(triggered()), this, SLOT(selectAirframe()));
128
    connect(setBatterySpecsAction, SIGNAL(triggered()), this, SLOT(setBatterySpecs()));
129
    connect(uas, SIGNAL(systemRemoved()), this, SLOT(deleteLater()));
130 131 132

    // Name changes
    connect(uas, SIGNAL(nameChanged(QString)), this, SLOT(updateName(QString)));
133

pixhawk's avatar
pixhawk committed
134
    // Set static values
135

pixhawk's avatar
pixhawk committed
136
    // Name
137 138
    if (uas->getUASName() == "")
    {
pixhawk's avatar
pixhawk committed
139
        m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID()));
140 141 142
    }
    else
    {
pixhawk's avatar
pixhawk committed
143 144
        m_ui->nameLabel->setText(uas->getUASName());
    }
145

146
    setBackgroundColor();
147

pixhawk's avatar
pixhawk committed
148 149 150
    // Heartbeat fade
    refreshTimer = new QTimer(this);
    connect(refreshTimer, SIGNAL(timeout()), this, SLOT(refresh()));
151 152
    if (lowPowerModeEnabled)
    {
153
        refreshTimer->start(updateInterval*3);
154 155 156
    }
    else
    {
157 158
        refreshTimer->start(updateInterval);
    }
159 160 161 162 163

    // Hide kill and shutdown buttons per default
    m_ui->killButton->hide();
    m_ui->shutdownButton->hide();

164 165 166
    // Set state and mode
    updateMode(uas->getUASID(), uas->getShortMode(), "");
    updateState(uas, uas->getShortState(), "");
167
    setSystemType(uas, uas->getSystemType());
pixhawk's avatar
pixhawk committed
168 169 170 171 172
}

UASView::~UASView()
{
    delete m_ui;
173 174 175
    delete removeAction;
    delete renameAction;
    delete selectAction;
pixhawk's avatar
pixhawk committed
176 177
}

178 179 180 181
void UASView::heartbeatTimeout()
{
    timeout = true;
}
182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197

void UASView::updateNavMode(int uasid, int mode, const QString& text)
{
    Q_UNUSED(uasid);
    Q_UNUSED(mode);
    m_ui->navLabel->setText(text);
}

void UASView::showStatusText(int uasid, int componentid, int severity, QString text)
{
    Q_UNUSED(uasid);
    Q_UNUSED(componentid);
    Q_UNUSED(severity);
    //m_ui->statusTextLabel->setText(text);
    stateDesc = text;
}
198

199 200 201 202 203 204 205 206 207 208
/**
 * Set the background color based on the MAV color. If the MAV is selected as the
 * currently actively controlled system, the frame color is highlighted
 */
void UASView::setBackgroundColor()
{
    // UAS color
    QColor uasColor = uas->getColor();
    QString colorstyle;
    QString borderColor = "#4A4A4F";
209 210
    if (isActive)
    {
211 212
        borderColor = "#FA4A4F";
        uasColor = uasColor.darker(475);
213 214 215
    }
    else
    {
216 217
        uasColor = uasColor.darker(675);
    }
218
    colorstyle = colorstyle.sprintf("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }",
219 220 221 222 223
                                    uasColor.red(), uasColor.green(), uasColor.blue(), borderColor.toStdString().c_str());
    m_ui->uasViewFrame->setStyleSheet(colorstyle);
}

void UASView::setUASasActive(bool active)
pixhawk's avatar
pixhawk committed
224
{
225 226
    if (active)
    {
227 228 229 230 231 232
        UASManager::instance()->setActiveUAS(this->uas);
    }
}

void UASView::updateActiveUAS(UASInterface* uas, bool active)
{
233 234
    if (uas == this->uas)
    {
235 236 237
        this->isActive = active;
        setBackgroundColor();
    }
pixhawk's avatar
pixhawk committed
238 239
}

pixhawk's avatar
pixhawk committed
240 241
void UASView::updateMode(int sysId, QString status, QString description)
{
242
    Q_UNUSED(description);
243 244

    //int aa=this->uas->getUASID();
pixhawk's avatar
pixhawk committed
245
    if (sysId == this->uas->getUASID()) m_ui->modeLabel->setText(status);
246 247

    m_ui->modeLabel->setText(status);
pixhawk's avatar
pixhawk committed
248 249
}

pixhawk's avatar
pixhawk committed
250 251
void UASView::mouseDoubleClickEvent (QMouseEvent * event)
{
252
    Q_UNUSED(event);
pixhawk's avatar
pixhawk committed
253
    UASManager::instance()->setActiveUAS(uas);
254
    // qDebug() << __FILE__ << __LINE__ << "DOUBLECLICKED";
pixhawk's avatar
pixhawk committed
255 256 257 258
}

void UASView::enterEvent(QEvent* event)
{
259 260
    if (event->type() == QEvent::MouseMove)
    {
261
        emit uasInFocus(uas);
262 263
        if (uas != UASManager::instance()->getActiveUAS())
        {
264 265 266
            grabMouse(QCursor(Qt::PointingHandCursor));
        }
    }
267

268 269
    if (event->type() == QEvent::MouseButtonDblClick)
    {
270
        // qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
271
    }
pixhawk's avatar
pixhawk committed
272 273 274 275
}

void UASView::leaveEvent(QEvent* event)
{
276 277
    if (event->type() == QEvent::MouseMove)
    {
278 279 280 281 282 283 284 285 286
        emit uasOutFocus(uas);
        releaseMouse();
    }
}

void UASView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
287
    Q_UNUSED(event);
288
    refreshTimer->start(updateInterval*10);
289 290 291 292 293 294 295 296
}

void UASView::hideEvent(QHideEvent* event)
{
    // React only to internal (pre-display)
    // events
    Q_UNUSED(event);
    refreshTimer->stop();
pixhawk's avatar
pixhawk committed
297 298 299 300
}

void UASView::receiveHeartbeat(UASInterface* uas)
{
301
    Q_UNUSED(uas);
302
    heartbeatColor = QColor(20, 200, 20);
lm's avatar
lm committed
303
    QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 0px; border: 0px; background-color: %1; }");
304
    m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
305 306 307 308 309 310
    if (timeout) setBackgroundColor();
    timeout = false;
}

void UASView::updateName(const QString& name)
{
311
    if (uas) m_ui->nameLabel->setText(name);
pixhawk's avatar
pixhawk committed
312 313 314 315 316 317 318 319 320 321 322
}

/**
 * The current system type is represented through the system icon.
 *
 * @param uas Source system, has to be the same as this->uas
 * @param systemType type ID, following the MAVLink system type conventions
 * @see http://pixhawk.ethz.ch/software/mavlink
 */
void UASView::setSystemType(UASInterface* uas, unsigned int systemType)
{
323 324
    if (uas == this->uas)
    {
pixhawk's avatar
pixhawk committed
325
        // Set matching icon
326 327
        switch (systemType)
        {
pixhawk's avatar
pixhawk committed
328
        case 0:
329
            m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/generic.svg"));
pixhawk's avatar
pixhawk committed
330 331
            break;
        case 1:
332
            m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/fixed-wing.svg"));
pixhawk's avatar
pixhawk committed
333 334
            break;
        case 2:
335
            m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/quadrotor.svg"));
pixhawk's avatar
pixhawk committed
336 337
            break;
        case 3:
338
            m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/coaxial.svg"));
pixhawk's avatar
pixhawk committed
339 340
            break;
        case 4:
341
            m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/helicopter.svg"));
pixhawk's avatar
pixhawk committed
342 343
            break;
        case 5:
344
            m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/unknown.svg"));
lm's avatar
lm committed
345
            break;
346
        case 6: {
347 348
                // A groundstation is a special system type, update widget
                QString result;
lm's avatar
lm committed
349
                m_ui->nameLabel->setText(tr("GCS ") + result.sprintf("%03d", uas->getUASID()));
350 351 352 353 354 355 356 357 358 359 360 361
                m_ui->waypointLabel->setText("");
                m_ui->timeRemainingLabel->setText("Online:");
                m_ui->batteryBar->hide();
                m_ui->thrustBar->hide();
                m_ui->stateLabel->hide();
                m_ui->statusTextLabel->hide();
                m_ui->waypointLabel->hide();
                m_ui->liftoffButton->hide();
                m_ui->haltButton->hide();
                m_ui->landButton->hide();
                m_ui->shutdownButton->hide();
                m_ui->abortButton->hide();
362
                m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/groundstation.svg"));
363 364
            }
            break;
pixhawk's avatar
pixhawk committed
365
        default:
366
            m_ui->typeButton->setIcon(QIcon(":/files/images/mavs/unknown.svg"));
pixhawk's avatar
pixhawk committed
367 368 369 370 371 372 373
            break;
        }
    }
}

void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double z, quint64 usec)
{
374
    Q_UNUSED(usec);
375 376 377 378
    Q_UNUSED(uas);
    this->x = x;
    this->y = y;
    this->z = z;
379
    localFrame = true;
pixhawk's avatar
pixhawk committed
380 381
}

382
void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
pixhawk's avatar
pixhawk committed
383
{
384 385
    Q_UNUSED(uas);
    Q_UNUSED(usec);
pixhawk's avatar
pixhawk committed
386 387 388
    this->lon = lon;
    this->lat = lat;
    this->alt = alt;
389
    globalFrameKnown = true;
pixhawk's avatar
pixhawk committed
390 391 392 393
}

void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec)
{
394
    Q_UNUSED(usec);
395
    totalSpeed = sqrt(x*x + y*y + z*z);
pixhawk's avatar
pixhawk committed
396 397
}

398 399 400 401 402
void UASView::currentWaypointUpdated(quint16 waypoint)
{
    m_ui->waypointLabel->setText(tr("WP") + QString::number(waypoint));
}

pixhawk's avatar
pixhawk committed
403 404
void UASView::setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current)
{
405 406 407 408 409
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
    Q_UNUSED(autocontinue);
410 411 412 413
    if (uasId == this->uas->getUASID())
    {
        if (current)
        {
pixhawk's avatar
pixhawk committed
414 415 416 417 418 419 420
            m_ui->waypointLabel->setText(tr("WP") + QString::number(id));
        }
    }
}

void UASView::selectWaypoint(int uasId, int id)
{
421 422
    if (uasId == this->uas->getUASID())
    {
pixhawk's avatar
pixhawk committed
423 424 425 426 427 428
        m_ui->waypointLabel->setText(tr("WP") + QString::number(id));
    }
}

void UASView::updateThrust(UASInterface* uas, double thrust)
{
429 430
    if (this->uas == uas)
    {
pixhawk's avatar
pixhawk committed
431
        this->thrust = thrust;
pixhawk's avatar
pixhawk committed
432 433 434 435 436
    }
}

void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
437
    Q_UNUSED(voltage);
438 439
    if (this->uas == uas)
    {
pixhawk's avatar
pixhawk committed
440 441 442 443 444 445 446
        timeRemaining = seconds;
        chargeLevel = percent;
    }
}

void UASView::updateState(UASInterface* uas, QString uasState, QString stateDescription)
{
447 448
    if (this->uas == uas)
    {
pixhawk's avatar
pixhawk committed
449 450 451 452 453 454 455
        state = uasState;
        stateDesc = stateDescription;
    }
}

void UASView::updateLoad(UASInterface* uas, double load)
{
456 457
    if (this->uas == uas)
    {
pixhawk's avatar
pixhawk committed
458 459 460 461
        this->load = load;
    }
}

462 463
void UASView::contextMenuEvent (QContextMenuEvent* event)
{
464
    QMenu menu(this);
lm's avatar
lm committed
465 466
    menu.addAction(selectAction);
    menu.addSeparator();
467
    menu.addAction(renameAction);
468 469
    if (timeout)
    {
470
        menu.addAction(removeAction);
471
    }
472 473
    menu.addAction(hilXAction);
    // XXX Re-enable later menu.addAction(hilXAction);
474
    menu.addAction(selectAirframeAction);
475
    menu.addAction(setBatterySpecsAction);
476 477 478
    menu.exec(event->globalPos());
}

479 480
void UASView::setBatterySpecs()
{
481 482
    if (uas)
    {
483 484
        bool ok;
        QString newName = QInputDialog::getText(this, tr("Set Battery Specifications for %1").arg(uas->getUASName()),
485
                                                tr("Specs: (empty,warn,full), e.g. (9V,9.5V,12.6V) or just warn level in percent (e.g. 15%) to use estimate from MAV"), QLineEdit::Normal,
486 487 488 489 490 491
                                                uas->getBatterySpecs(), &ok);

        if (ok && !newName.isEmpty()) uas->setBatterySpecs(newName);
    }
}

492 493
void UASView::rename()
{
494 495
    if (uas)
    {
496 497 498 499 500 501
        bool ok;
        QString newName = QInputDialog::getText(this, tr("Rename System %1").arg(uas->getUASName()),
                                                tr("System Name:"), QLineEdit::Normal,
                                                uas->getUASName(), &ok);

        if (ok && !newName.isEmpty()) uas->setUASName(newName);
502 503 504
    }
}

505 506
void UASView::selectAirframe()
{
507 508
    if (uas)
    {
509 510 511
        // Get list of airframes from UAS
        QStringList airframes;
        airframes << "Generic"
512 513 514 515 516 517 518 519
                << "Multiplex Easystar"
                << "Multiplex Twinstar"
                << "Multiplex Merlin"
                << "Pixhawk Cheetah"
                << "Mikrokopter"
                << "Reaper"
                << "Predator"
                << "Coaxial"
520 521
                << "Pteryx"
                << "Asctec Firefly";
522 523 524 525

        bool ok;
        QString item = QInputDialog::getItem(this, tr("Select Airframe for %1").arg(uas->getUASName()),
                                             tr("Airframe"), airframes, uas->getAirframe(), false, &ok);
526 527
        if (ok && !item.isEmpty())
        {
528 529 530 531 532 533
            // Set this airframe as UAS airframe
            uas->setAirframe(airframes.indexOf(item));
        }
    }
}

pixhawk's avatar
pixhawk committed
534 535
void UASView::refresh()
{
536
    //setUpdatesEnabled(false);
537 538
    //setUpdatesEnabled(true);
    //repaint();
539
    //qDebug() << "UPDATING UAS WIDGET!" << uas->getUASName();
540 541


542 543 544
    quint64 lastupdate = 0;
    //// qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
    lastupdate = QGC::groundTimeMilliseconds();
545

546 547
    if (generalUpdateCount == 4)
    {
548
#if (QGC_EVENTLOOP_DEBUG)
549
        // qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
550
#endif
551
        generalUpdateCount = 0;
552
        //// qDebug() << "UPDATING EVERYTHING";
553 554 555 556 557 558 559 560 561 562
        // State
        m_ui->stateLabel->setText(state);
        m_ui->statusTextLabel->setText(stateDesc);

        // Battery
        m_ui->batteryBar->setValue(static_cast<int>(this->chargeLevel));
        //m_ui->loadBar->setValue(static_cast<int>(this->load));
        m_ui->thrustBar->setValue(this->thrust);

        // Position
563 564 565 566 567 568 569
        // If global position is known, prefer it over local coordinates

        if (!globalFrameKnown && localFrame)
        {
            QString position;
            position = position.sprintf("%05.1f %05.1f %06.1f m", x, y, z);
            m_ui->positionLabel->setText(position);
570
        }
571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595

        if (globalFrameKnown)
        {
            QString globalPosition;
            QString latIndicator;
            if (lat > 0)
            {
                latIndicator = "N";
            }
            else
            {
                latIndicator = "S";
            }
            QString lonIndicator;
            if (lon > 0)
            {
                lonIndicator = "E";
            }
            else
            {
                lonIndicator = "W";
            }

            globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %06.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt);
            m_ui->positionLabel->setText(globalPosition);
596
        }
pixhawk's avatar
pixhawk committed
597

598
        // Altitude
599 600
        if (groundDistance == 0 && alt != 0)
        {
601
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0'));
602 603 604
        }
        else
        {
605
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0'));
606
        }
607

608
        // Speed
609 610
        QString speed("%1 m/s");
        m_ui->speedLabel->setText(speed.arg(totalSpeed, 4, 'f', 1, '0'));
pixhawk's avatar
pixhawk committed
611

612 613
        // Thrust
        m_ui->thrustBar->setValue(thrust * 100);
pixhawk's avatar
pixhawk committed
614

615 616
        if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME)
        {
617
            // Filter output to get a higher stability
618
            filterTime = static_cast<int>(this->timeRemaining);
619 620 621 622 623 624 625 626
            filterTime = 0.8 * filterTime + 0.2 * static_cast<int>(this->timeRemaining);
            int sec = static_cast<int>(filterTime - static_cast<int>(filterTime / 60.0f) * 60);
            int min = static_cast<int>(filterTime / 60);
            int hours = static_cast<int>(filterTime - min * 60 - sec);

            QString timeText;
            timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec);
            m_ui->timeRemainingLabel->setText(timeText);
627 628 629
        }
        else
        {
630
            m_ui->timeRemainingLabel->setText(tr("Calc.."));
631 632 633 634 635 636 637
        }

        // Time Elapsed
        //QDateTime time = MG::TIME::msecToQDateTime(uas->getUptime());

        quint64 filterTime = uas->getUptime() / 1000;
        int sec = static_cast<int>(filterTime - static_cast<int>(filterTime / 60) * 60);
pixhawk's avatar
pixhawk committed
638 639 640 641
        int min = static_cast<int>(filterTime / 60);
        int hours = static_cast<int>(filterTime - min * 60 - sec);
        QString timeText;
        timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec);
642
        m_ui->timeElapsedLabel->setText(timeText);
pixhawk's avatar
pixhawk committed
643
    }
644
    generalUpdateCount++;
pixhawk's avatar
pixhawk committed
645

lm's avatar
lm committed
646
    QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 0px; border: 0px; background-color: %1; }");
647

648 649
    if (timeout)
    {
650 651
        // CRITICAL CONDITION, NO HEARTBEAT

652
        QString borderColor = "#FFFF00";
653 654
        if (isActive)
        {
655 656 657
            borderColor = "#FA4A4F";
        }

658 659
        if (iconIsRed)
        {
660 661
            QColor warnColor(Qt::red);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
662
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
663
            m_ui->uasViewFrame->setStyleSheet(style);
664 665 666
        }
        else
        {
667 668
            QColor warnColor(Qt::black);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
669
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
670
            m_ui->uasViewFrame->setStyleSheet(style);
LM's avatar
LM committed
671 672

            refreshTimer->setInterval(errorUpdateInterval);
673
            refreshTimer->start();
674 675
        }
        iconIsRed = !iconIsRed;
676 677 678
    }
    else
    {
679 680 681 682
        if (!lowPowerModeEnabled)
        {
            // Fade heartbeat icon
            // Make color darker
LM's avatar
LM committed
683
            heartbeatColor = heartbeatColor.darker(210);
684 685 686

            //m_ui->heartbeatIcon->setAutoFillBackground(true);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
LM's avatar
LM committed
687
            refreshTimer->setInterval(updateInterval);
688
            refreshTimer->start();
689
        }
690
    }
691
    //setUpdatesEnabled(true);
692 693

    //setUpdatesEnabled(false);
pixhawk's avatar
pixhawk committed
694 695 696 697 698
}

void UASView::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
699 700
    switch (e->type())
    {
pixhawk's avatar
pixhawk committed
701 702 703 704 705 706 707
    case QEvent::LanguageChange:
        m_ui->retranslateUi(this);
        break;
    default:
        break;
    }
}