UASView.cc 20 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 45
#include "ui_UASView.h"

UASView::UASView(UASInterface* uas, QWidget *parent) :
        QWidget(parent),
46
        startTime(0),
47
        timeout(false),
48
        iconIsRed(true),
pixhawk's avatar
pixhawk committed
49
        timeRemaining(0),
50 51 52
        chargeLevel(0),
        uas(uas),
        load(0),
pixhawk's avatar
pixhawk committed
53
        state("UNKNOWN"),
54
        stateDesc(tr("Unknown state")),
pixhawk's avatar
pixhawk committed
55 56
        mode("MAV_MODE_UNKNOWN"),
        thrust(0),
57
        isActive(false),
58 59 60 61 62 63 64 65
        x(0),
        y(0),
        z(0),
        totalSpeed(0),
        lat(0),
        lon(0),
        alt(0),
        groundDistance(0),
66
        localFrame(false),
67 68
        removeAction(new QAction("Delete this system", this)),
        renameAction(new QAction("Rename..", this)),
lm's avatar
lm committed
69 70
        selectAction(new QAction("Control this system", this )),
        selectAirframeAction(new QAction("Choose Airframe", this)),
71
        setBatterySpecsAction(new QAction("Set Battery Options", this)),
pixhawk's avatar
pixhawk committed
72 73 74
        m_ui(new Ui::UASView)
{
    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
    
pixhawk's avatar
pixhawk committed
93
    // Setup UAS selection
94
    connect(m_ui->uasViewFrame, SIGNAL(clicked(bool)), this, SLOT(setUASasActive(bool)));
95
    
pixhawk's avatar
pixhawk committed
96 97 98 99
    // 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
100 101
    connect(m_ui->landButton, SIGNAL(clicked()), uas, SLOT(home()));
    connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
pixhawk's avatar
pixhawk committed
102 103
    connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL()));
    connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));
104 105 106

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

    // Name changes
    connect(uas, SIGNAL(nameChanged(QString)), this, SLOT(updateName(QString)));
115
    
pixhawk's avatar
pixhawk committed
116
    // Set static values
117
    
pixhawk's avatar
pixhawk committed
118 119 120 121 122 123 124 125 126
    // Name
    if (uas->getUASName() == "")
    {
        m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID()));
    }
    else
    {
        m_ui->nameLabel->setText(uas->getUASName());
    }
127
    
128
    setBackgroundColor();
129
    
pixhawk's avatar
pixhawk committed
130 131 132
    // Heartbeat fade
    refreshTimer = new QTimer(this);
    connect(refreshTimer, SIGNAL(timeout()), this, SLOT(refresh()));
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 153
void UASView::heartbeatTimeout()
{
    timeout = true;
}

154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172
/**
 * 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";
    if (isActive)
    {
        borderColor = "#FA4A4F";
        uasColor = uasColor.darker(475);
    }
    else
    {
        uasColor = uasColor.darker(675);
    }
173
    colorstyle = colorstyle.sprintf("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }",
174 175 176 177 178
                                    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
179
{
180 181 182 183 184 185 186 187 188 189 190 191 192
    if (active)
    {
        UASManager::instance()->setActiveUAS(this->uas);
    }
}

void UASView::updateActiveUAS(UASInterface* uas, bool active)
{
    if (uas == this->uas)
    {
        this->isActive = active;
        setBackgroundColor();
    }
pixhawk's avatar
pixhawk committed
193 194
}

pixhawk's avatar
pixhawk committed
195 196
void UASView::updateMode(int sysId, QString status, QString description)
{
197
    Q_UNUSED(description);
pixhawk's avatar
pixhawk committed
198 199 200
    if (sysId == this->uas->getUASID()) m_ui->modeLabel->setText(status);
}

pixhawk's avatar
pixhawk committed
201 202
void UASView::mouseDoubleClickEvent (QMouseEvent * event)
{
203
    Q_UNUSED(event);
pixhawk's avatar
pixhawk committed
204 205 206 207 208 209
    UASManager::instance()->setActiveUAS(uas);
    qDebug() << __FILE__ << __LINE__ << "DOUBLECLICKED";
}

void UASView::enterEvent(QEvent* event)
{
210 211 212 213 214 215 216 217
    if (event->type() == QEvent::MouseMove)
    {
        emit uasInFocus(uas);
        if (uas != UASManager::instance()->getActiveUAS())
        {
            grabMouse(QCursor(Qt::PointingHandCursor));
        }
    }
pixhawk's avatar
pixhawk committed
218
    qDebug() << __FILE__ << __LINE__ << "IN FOCUS";
219
    
220 221 222 223
    if (event->type() == QEvent::MouseButtonDblClick)
    {
        qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
    }
pixhawk's avatar
pixhawk committed
224 225 226 227
}

void UASView::leaveEvent(QEvent* event)
{
228 229 230 231 232 233 234 235 236 237 238
    if (event->type() == QEvent::MouseMove)
    {
        emit uasOutFocus(uas);
        releaseMouse();
    }
}

void UASView::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
239 240 241 242 243 244 245 246 247 248
    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
249 250 251 252
}

void UASView::receiveHeartbeat(UASInterface* uas)
{
253
    Q_UNUSED(uas);
254
    heartbeatColor = QColor(20, 200, 20);
255 256
    QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 2px; border: 0px; background-color: %1; }");
    m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
257 258 259 260 261 262
    if (timeout) setBackgroundColor();
    timeout = false;
}

void UASView::updateName(const QString& name)
{
263
    if (uas) m_ui->nameLabel->setText(name);
pixhawk's avatar
pixhawk committed
264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295
}

/**
 * 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)
{
    if (uas == this->uas)
    {
        // Set matching icon
        switch (systemType)
        {
        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
296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/unknown.svg"));
            break;
        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();
315 316
                m_ui->typeButton->setIcon(QIcon(":/images/mavs/groundstation.svg"));
            }
pixhawk's avatar
pixhawk committed
317 318 319 320 321 322 323 324 325 326
            break;
        default:
            m_ui->typeButton->setIcon(QIcon(":/images/mavs/unknown.svg"));
            break;
        }
    }
}

void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double z, quint64 usec)
{
327
    Q_UNUSED(usec);
328 329 330 331 332
    Q_UNUSED(uas);
    this->x = x;
    this->y = y;
    this->z = z;
    if (!localFrame)
pixhawk's avatar
pixhawk committed
333
    {
334
        localFrame = true;
pixhawk's avatar
pixhawk committed
335 336 337
    }
}

338
void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
pixhawk's avatar
pixhawk committed
339
{
340 341
    Q_UNUSED(uas);
    Q_UNUSED(usec);
pixhawk's avatar
pixhawk committed
342 343 344
    this->lon = lon;
    this->lat = lat;
    this->alt = alt;
pixhawk's avatar
pixhawk committed
345 346 347 348
}

void UASView::updateSpeed(UASInterface*, double x, double y, double z, quint64 usec)
{
349
    Q_UNUSED(usec);
pixhawk's avatar
pixhawk committed
350
    totalSpeed = sqrt((pow(x, 2) + pow(y, 2) + pow(z, 2)));
pixhawk's avatar
pixhawk committed
351 352
}

353 354 355 356 357
void UASView::currentWaypointUpdated(quint16 waypoint)
{
    m_ui->waypointLabel->setText(tr("WP") + QString::number(waypoint));
}

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

void UASView::selectWaypoint(int uasId, int id)
{
    if (uasId == this->uas->getUASID())
    {
        m_ui->waypointLabel->setText(tr("WP") + QString::number(id));
    }
}

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

void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
392
    Q_UNUSED(voltage);
pixhawk's avatar
pixhawk committed
393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416
    if (this->uas == uas)
    {
        timeRemaining = seconds;
        chargeLevel = percent;
    }
}

void UASView::updateState(UASInterface* uas, QString uasState, QString stateDescription)
{
    if (this->uas == uas)
    {
        state = uasState;
        stateDesc = stateDescription;
    }
}

void UASView::updateLoad(UASInterface* uas, double load)
{
    if (this->uas == uas)
    {
        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 423
    menu.addAction(renameAction);
    if (timeout)
424 425
    {
        menu.addAction(removeAction);
426
    }
427
    menu.addAction(selectAirframeAction);
428
    menu.addAction(setBatterySpecsAction);
429 430 431
    menu.exec(event->globalPos());
}

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

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

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

458 459 460 461 462 463 464 465 466 467 468 469 470 471
void UASView::selectAirframe()
{
    if (uas)
    {
        // Get list of airframes from UAS
        QStringList airframes;
        airframes << "Generic"
                << "Multiplex Easystar"
                << "Multiplex Twinstar"
                << "Multiplex Merlin"
                << "Pixhawk Cheetah"
                << "Mikrokopter"
                << "Reaper"
                << "Predator"
472 473
                << "Coaxial"
                << "Pteryx";
474 475 476 477 478 479 480 481 482 483 484 485

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

pixhawk's avatar
pixhawk committed
486 487
void UASView::refresh()
{
488
    //setUpdatesEnabled(false);
489 490
    //setUpdatesEnabled(true);
    //repaint();
491 492

    static quint64 lastupdate = 0;
pixhawk's avatar
pixhawk committed
493
    //qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
494 495 496 497 498 499 500
    lastupdate = MG::TIME::getGroundTimeNow();

    // FIXME
    static int generalUpdateCount = 0;

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

541 542 543
        // Altitude
        if (groundDistance == 0 && alt != 0)
        {
544
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0'));
545 546 547
        }
        else
        {
548
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0'));
549
        }
550

551
        // Speed
552 553
        QString speed("%1 m/s");
        m_ui->speedLabel->setText(speed.arg(totalSpeed, 4, 'f', 1, '0'));
pixhawk's avatar
pixhawk committed
554

555 556
        // Thrust
        m_ui->thrustBar->setValue(thrust * 100);
pixhawk's avatar
pixhawk committed
557

558
        if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME)
559 560 561 562 563 564 565 566 567 568 569 570 571 572
        {
            // 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);
        }
        else
        {
573
            m_ui->timeRemainingLabel->setText(tr("Calc.."));
574 575 576 577 578 579 580
        }

        // 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
581 582 583 584
        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);
585
        m_ui->timeElapsedLabel->setText(timeText);
pixhawk's avatar
pixhawk committed
586
    }
587
    generalUpdateCount++;
pixhawk's avatar
pixhawk committed
588

589 590
    QString colorstyle("QGroupBox { border-radius: 5px; padding: 2px; margin: 2px; border: 0px; background-color: %1; }");

591
    if (timeout)
592 593 594
    {
        // CRITICAL CONDITION, NO HEARTBEAT

595 596 597 598 599 600
        QString borderColor = "#FFFF00";
        if (isActive)
        {
            borderColor = "#FA4A4F";
        }

601 602 603 604
        if (iconIsRed)
        {
            QColor warnColor(Qt::red);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
605
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
606 607 608 609 610 611
            m_ui->uasViewFrame->setStyleSheet(style);
        }
        else
        {
            QColor warnColor(Qt::black);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
612
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
613 614 615 616 617 618
            m_ui->uasViewFrame->setStyleSheet(style);
        }
        iconIsRed = !iconIsRed;
    }
    else
    {
619 620 621
        // Fade heartbeat icon
        // Make color darker
        heartbeatColor = heartbeatColor.darker(150);
622

623 624
        //m_ui->heartbeatIcon->setAutoFillBackground(true);
        m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
625
    }
626
    //setUpdatesEnabled(true);
627 628

    //setUpdatesEnabled(false);
pixhawk's avatar
pixhawk committed
629 630 631 632 633 634 635 636 637 638 639 640 641
}

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