UASView.cc 20.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 40
#include "MG.h"
#include "UASManager.h"
#include "UASView.h"
41
#include "UASWaypointManager.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 67 68 69 70 71 72
    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),
    removeAction(new QAction("Delete this system", this)),
    renameAction(new QAction("Rename..", this)),
    selectAction(new QAction("Control this system", this )),
    selectAirframeAction(new QAction("Choose Airframe", this)),
    setBatterySpecsAction(new QAction("Set Battery Options", this)),
    m_ui(new Ui::UASView)
pixhawk's avatar
pixhawk committed
73 74
{
    m_ui->setupUi(this);
75

pixhawk's avatar
pixhawk committed
76
    // Setup communication
pixhawk's avatar
pixhawk committed
77
    //connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), this, SLOT(receiveValue(int,QString,double,quint64)));
pixhawk's avatar
pixhawk committed
78 79 80 81 82 83 84
    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
85
    connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
pixhawk's avatar
pixhawk committed
86
    connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
87
    connect(uas, SIGNAL(heartbeatTimeout()), this, SLOT(heartbeatTimeout()));
pixhawk's avatar
pixhawk committed
88
    connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int,int)));
pixhawk's avatar
pixhawk committed
89
    connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
pixhawk's avatar
pixhawk committed
90
    connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
91
    connect(UASManager::instance(), SIGNAL(activeUASStatusChanged(UASInterface*,bool)), this, SLOT(updateActiveUAS(UASInterface*,bool)));
92 93 94
    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
95
    // Setup UAS selection
96
    connect(m_ui->uasViewFrame, SIGNAL(clicked(bool)), this, SLOT(setUASasActive(bool)));
97

pixhawk's avatar
pixhawk committed
98 99 100 101
    // 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()));
pixhawk's avatar
pixhawk committed
102 103
    connect(m_ui->landButton, SIGNAL(clicked()), uas, SLOT(home()));
    connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
pixhawk's avatar
pixhawk committed
104 105
    connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL()));
    connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));
106 107 108

    // Allow to delete this widget
    connect(removeAction, SIGNAL(triggered()), this, SLOT(deleteLater()));
109
    connect(renameAction, SIGNAL(triggered()), this, SLOT(rename()));
110
    connect(selectAction, SIGNAL(triggered()), uas, SLOT(setSelected()));
111
    connect(selectAirframeAction, SIGNAL(triggered()), this, SLOT(selectAirframe()));
112
    connect(setBatterySpecsAction, SIGNAL(triggered()), this, SLOT(setBatterySpecs()));
113
    connect(uas, SIGNAL(systemRemoved()), this, SLOT(deleteLater()));
114 115 116

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

pixhawk's avatar
pixhawk committed
118
    // Set static values
119

pixhawk's avatar
pixhawk committed
120
    // Name
121
    if (uas->getUASName() == "") {
pixhawk's avatar
pixhawk committed
122
        m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID()));
123
    } else {
pixhawk's avatar
pixhawk committed
124 125
        m_ui->nameLabel->setText(uas->getUASName());
    }
126

127
    setBackgroundColor();
128

pixhawk's avatar
pixhawk committed
129 130 131
    // Heartbeat fade
    refreshTimer = new QTimer(this);
    connect(refreshTimer, SIGNAL(timeout()), this, SLOT(refresh()));
lm's avatar
lm committed
132
    refreshTimer->start(updateInterval);
133 134 135 136 137

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

138
    setSystemType(uas, uas->getSystemType());
pixhawk's avatar
pixhawk committed
139 140 141 142 143
}

UASView::~UASView()
{
    delete m_ui;
144 145 146
    delete removeAction;
    delete renameAction;
    delete selectAction;
pixhawk's avatar
pixhawk committed
147 148
}

149 150 151 152
void UASView::heartbeatTimeout()
{
    timeout = true;
}
153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168

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

170 171 172 173 174 175 176 177 178 179
/**
 * 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";
180
    if (isActive) {
181 182
        borderColor = "#FA4A4F";
        uasColor = uasColor.darker(475);
183
    } else {
184 185
        uasColor = uasColor.darker(675);
    }
186
    colorstyle = colorstyle.sprintf("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }",
187 188 189 190 191
                                    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
192
{
193
    if (active) {
194 195 196 197 198 199
        UASManager::instance()->setActiveUAS(this->uas);
    }
}

void UASView::updateActiveUAS(UASInterface* uas, bool active)
{
200
    if (uas == this->uas) {
201 202 203
        this->isActive = active;
        setBackgroundColor();
    }
pixhawk's avatar
pixhawk committed
204 205
}

pixhawk's avatar
pixhawk committed
206 207
void UASView::updateMode(int sysId, QString status, QString description)
{
208
    Q_UNUSED(description);
209 210

    //int aa=this->uas->getUASID();
pixhawk's avatar
pixhawk committed
211
    if (sysId == this->uas->getUASID()) m_ui->modeLabel->setText(status);
212 213

    m_ui->modeLabel->setText(status);
pixhawk's avatar
pixhawk committed
214 215
}

pixhawk's avatar
pixhawk committed
216 217
void UASView::mouseDoubleClickEvent (QMouseEvent * event)
{
218
    Q_UNUSED(event);
pixhawk's avatar
pixhawk committed
219 220 221 222 223 224
    UASManager::instance()->setActiveUAS(uas);
    qDebug() << __FILE__ << __LINE__ << "DOUBLECLICKED";
}

void UASView::enterEvent(QEvent* event)
{
225
    if (event->type() == QEvent::MouseMove) {
226
        emit uasInFocus(uas);
227
        if (uas != UASManager::instance()->getActiveUAS()) {
228 229 230
            grabMouse(QCursor(Qt::PointingHandCursor));
        }
    }
pixhawk's avatar
pixhawk committed
231
    qDebug() << __FILE__ << __LINE__ << "IN FOCUS";
232 233

    if (event->type() == QEvent::MouseButtonDblClick) {
234 235
        qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
    }
pixhawk's avatar
pixhawk committed
236 237 238 239
}

void UASView::leaveEvent(QEvent* event)
{
240
    if (event->type() == QEvent::MouseMove) {
241 242 243 244 245 246 247 248 249
        emit uasOutFocus(uas);
        releaseMouse();
    }
}

void UASView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
250 251 252 253 254 255 256 257 258 259
    Q_UNUSED(event);
    refreshTimer->start(updateInterval);
}

void UASView::hideEvent(QHideEvent* event)
{
    // React only to internal (pre-display)
    // events
    Q_UNUSED(event);
    refreshTimer->stop();
pixhawk's avatar
pixhawk committed
260 261 262 263
}

void UASView::receiveHeartbeat(UASInterface* uas)
{
264
    Q_UNUSED(uas);
265
    heartbeatColor = QColor(20, 200, 20);
lm's avatar
lm committed
266
    QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 0px; border: 0px; background-color: %1; }");
267
    m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
268 269 270 271 272 273
    if (timeout) setBackgroundColor();
    timeout = false;
}

void UASView::updateName(const QString& name)
{
274
    if (uas) m_ui->nameLabel->setText(name);
pixhawk's avatar
pixhawk committed
275 276 277 278 279 280 281 282 283 284 285
}

/**
 * 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)
{
286
    if (uas == this->uas) {
pixhawk's avatar
pixhawk committed
287
        // Set matching icon
288
        switch (systemType) {
pixhawk's avatar
pixhawk committed
289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304
        case 0:
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/generic.svg"));
            break;
        case 1:
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/fixed-wing.svg"));
            break;
        case 2:
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/quadrotor.svg"));
            break;
        case 3:
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/coaxial.svg"));
            break;
        case 4:
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/helicopter.svg"));
            break;
        case 5:
lm's avatar
lm committed
305 306
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/unknown.svg"));
            break;
307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325
        case 6: {
            // A groundstation is a special system type, update widget
            QString result;
            m_ui->nameLabel->setText(tr("OCU ") + result.sprintf("%03d", uas->getUASID()));
            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();
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/groundstation.svg"));
        }
        break;
pixhawk's avatar
pixhawk committed
326 327 328 329 330 331 332 333 334
        default:
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/unknown.svg"));
            break;
        }
    }
}

void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double z, quint64 usec)
{
335
    Q_UNUSED(usec);
336 337 338 339
    Q_UNUSED(uas);
    this->x = x;
    this->y = y;
    this->z = z;
340
    if (!localFrame) {
341
        localFrame = true;
pixhawk's avatar
pixhawk committed
342 343 344
    }
}

345
void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
pixhawk's avatar
pixhawk committed
346
{
347 348
    Q_UNUSED(uas);
    Q_UNUSED(usec);
pixhawk's avatar
pixhawk committed
349 350 351
    this->lon = lon;
    this->lat = lat;
    this->alt = alt;
pixhawk's avatar
pixhawk committed
352 353 354 355
}

void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec)
{
356
    Q_UNUSED(usec);
357
    totalSpeed = sqrt(x*x + y*y + z*z);
pixhawk's avatar
pixhawk committed
358 359
}

360 361 362 363 364
void UASView::currentWaypointUpdated(quint16 waypoint)
{
    m_ui->waypointLabel->setText(tr("WP") + QString::number(waypoint));
}

pixhawk's avatar
pixhawk committed
365 366
void UASView::setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current)
{
367 368 369 370 371
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
    Q_UNUSED(autocontinue);
372 373
    if (uasId == this->uas->getUASID()) {
        if (current) {
pixhawk's avatar
pixhawk committed
374 375 376 377 378 379 380
            m_ui->waypointLabel->setText(tr("WP") + QString::number(id));
        }
    }
}

void UASView::selectWaypoint(int uasId, int id)
{
381
    if (uasId == this->uas->getUASID()) {
pixhawk's avatar
pixhawk committed
382 383 384 385 386 387
        m_ui->waypointLabel->setText(tr("WP") + QString::number(id));
    }
}

void UASView::updateThrust(UASInterface* uas, double thrust)
{
388
    if (this->uas == uas) {
pixhawk's avatar
pixhawk committed
389
        this->thrust = thrust;
pixhawk's avatar
pixhawk committed
390 391 392 393 394
    }
}

void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
395
    Q_UNUSED(voltage);
396
    if (this->uas == uas) {
pixhawk's avatar
pixhawk committed
397 398 399 400 401 402 403
        timeRemaining = seconds;
        chargeLevel = percent;
    }
}

void UASView::updateState(UASInterface* uas, QString uasState, QString stateDescription)
{
404
    if (this->uas == uas) {
pixhawk's avatar
pixhawk committed
405 406 407 408 409 410 411
        state = uasState;
        stateDesc = stateDescription;
    }
}

void UASView::updateLoad(UASInterface* uas, double load)
{
412
    if (this->uas == uas) {
pixhawk's avatar
pixhawk committed
413 414 415 416
        this->load = load;
    }
}

417 418
void UASView::contextMenuEvent (QContextMenuEvent* event)
{
419
    QMenu menu(this);
lm's avatar
lm committed
420 421
    menu.addAction(selectAction);
    menu.addSeparator();
422
    menu.addAction(renameAction);
423
    if (timeout) {
424
        menu.addAction(removeAction);
425
    }
426
    menu.addAction(selectAirframeAction);
427
    menu.addAction(setBatterySpecsAction);
428 429 430
    menu.exec(event->globalPos());
}

431 432
void UASView::setBatterySpecs()
{
433
    if (uas) {
434 435
        bool ok;
        QString newName = QInputDialog::getText(this, tr("Set Battery Specifications for %1").arg(uas->getUASName()),
436
                                                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,
437 438 439 440 441 442
                                                uas->getBatterySpecs(), &ok);

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

443 444
void UASView::rename()
{
445
    if (uas) {
446 447 448 449 450 451
        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);
452 453 454
    }
}

455 456
void UASView::selectAirframe()
{
457
    if (uas) {
458 459 460
        // Get list of airframes from UAS
        QStringList airframes;
        airframes << "Generic"
461 462 463 464 465 466 467 468 469
                  << "Multiplex Easystar"
                  << "Multiplex Twinstar"
                  << "Multiplex Merlin"
                  << "Pixhawk Cheetah"
                  << "Mikrokopter"
                  << "Reaper"
                  << "Predator"
                  << "Coaxial"
                  << "Pteryx";
470 471 472 473

        bool ok;
        QString item = QInputDialog::getItem(this, tr("Select Airframe for %1").arg(uas->getUASName()),
                                             tr("Airframe"), airframes, uas->getAirframe(), false, &ok);
474
        if (ok && !item.isEmpty()) {
475 476 477 478 479 480
            // Set this airframe as UAS airframe
            uas->setAirframe(airframes.indexOf(item));
        }
    }
}

pixhawk's avatar
pixhawk committed
481 482
void UASView::refresh()
{
483
    //setUpdatesEnabled(false);
484 485
    //setUpdatesEnabled(true);
    //repaint();
486 487

    static quint64 lastupdate = 0;
pixhawk's avatar
pixhawk committed
488
    //qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
489 490 491 492 493
    lastupdate = MG::TIME::getGroundTimeNow();

    // FIXME
    static int generalUpdateCount = 0;

494
    if (generalUpdateCount == 4) {
495 496 497
#if (QGC_EVENTLOOP_DEBUG)
        qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
498
        generalUpdateCount = 0;
pixhawk's avatar
pixhawk committed
499
        //qDebug() << "UPDATING EVERYTHING";
500 501 502 503 504 505 506 507 508 509 510
        // 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
        QString position;
511
        position = position.sprintf("%05.1f %05.1f %06.1f m", x, y, z);
512 513 514
        m_ui->positionLabel->setText(position);
        QString globalPosition;
        QString latIndicator;
515
        if (lat > 0) {
516
            latIndicator = "N";
517
        } else {
518 519 520
            latIndicator = "S";
        }
        QString lonIndicator;
521
        if (lon > 0) {
522
            lonIndicator = "E";
523
        } else {
524 525
            lonIndicator = "W";
        }
526 527
        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);
pixhawk's avatar
pixhawk committed
528

529
        // Altitude
530
        if (groundDistance == 0 && alt != 0) {
531
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0'));
532
        } else {
533
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0'));
534
        }
535

536
        // Speed
537 538
        QString speed("%1 m/s");
        m_ui->speedLabel->setText(speed.arg(totalSpeed, 4, 'f', 1, '0'));
pixhawk's avatar
pixhawk committed
539

540 541
        // Thrust
        m_ui->thrustBar->setValue(thrust * 100);
pixhawk's avatar
pixhawk committed
542

543
        if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME) {
544 545 546 547 548 549 550 551 552 553
            // Filter output to get a higher stability
            static double filterTime = static_cast<int>(this->timeRemaining);
            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);
554
        } else {
555
            m_ui->timeRemainingLabel->setText(tr("Calc.."));
556 557 558 559 560 561 562
        }

        // 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
563 564 565 566
        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);
567
        m_ui->timeElapsedLabel->setText(timeText);
pixhawk's avatar
pixhawk committed
568
    }
569
    generalUpdateCount++;
pixhawk's avatar
pixhawk committed
570

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

573
    if (timeout) {
574 575
        // CRITICAL CONDITION, NO HEARTBEAT

576
        QString borderColor = "#FFFF00";
577
        if (isActive) {
578 579 580
            borderColor = "#FA4A4F";
        }

581
        if (iconIsRed) {
582 583
            QColor warnColor(Qt::red);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
584
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
585
            m_ui->uasViewFrame->setStyleSheet(style);
586
        } else {
587 588
            QColor warnColor(Qt::black);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
589
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
590 591 592
            m_ui->uasViewFrame->setStyleSheet(style);
        }
        iconIsRed = !iconIsRed;
593
    } else {
594 595 596
        // Fade heartbeat icon
        // Make color darker
        heartbeatColor = heartbeatColor.darker(150);
597

598 599
        //m_ui->heartbeatIcon->setAutoFillBackground(true);
        m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
600
    }
601
    //setUpdatesEnabled(true);
602 603

    //setUpdatesEnabled(false);
pixhawk's avatar
pixhawk committed
604 605 606 607 608 609 610 611 612 613 614 615 616
}

void UASView::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
    switch (e->type()) {
    case QEvent::LanguageChange:
        m_ui->retranslateUi(this);
        break;
    default:
        break;
    }
}