UASView.cc 18.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 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 54
        state("UNKNOWN"),
        stateDesc(tr("Unknown system 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)),
pixhawk's avatar
pixhawk committed
69 70 71
        m_ui(new Ui::UASView)
{
    m_ui->setupUi(this);
72
    
pixhawk's avatar
pixhawk committed
73
    // Setup communication
pixhawk's avatar
pixhawk committed
74
    //connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), this, SLOT(receiveValue(int,QString,double,quint64)));
pixhawk's avatar
pixhawk committed
75 76 77 78 79 80 81
    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
82
    connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
pixhawk's avatar
pixhawk committed
83
    connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
84
    connect(uas, SIGNAL(heartbeatTimeout()), this, SLOT(heartbeatTimeout()));
pixhawk's avatar
pixhawk committed
85
    connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int,int)));
86
    connect(&(uas->getWaypointManager()), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
pixhawk's avatar
pixhawk committed
87
    connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
88
    connect(UASManager::instance(), SIGNAL(activeUASStatusChanged(UASInterface*,bool)), this, SLOT(updateActiveUAS(UASInterface*,bool)));
89
    
pixhawk's avatar
pixhawk committed
90
    // Setup UAS selection
91
    connect(m_ui->uasViewFrame, SIGNAL(clicked(bool)), this, SLOT(setUASasActive(bool)));
92
    
pixhawk's avatar
pixhawk committed
93 94 95 96
    // 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
97 98
    connect(m_ui->landButton, SIGNAL(clicked()), uas, SLOT(home()));
    connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
pixhawk's avatar
pixhawk committed
99 100
    connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL()));
    connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));
101 102 103

    // Allow to delete this widget
    connect(removeAction, SIGNAL(triggered()), this, SLOT(deleteLater()));
104
    connect(renameAction, SIGNAL(triggered()), this, SLOT(rename()));
105
    connect(uas, SIGNAL(systemRemoved()), this, SLOT(deleteLater()));
106 107 108

    // Name changes
    connect(uas, SIGNAL(nameChanged(QString)), this, SLOT(updateName(QString)));
109
    
pixhawk's avatar
pixhawk committed
110
    // Set static values
111
    
pixhawk's avatar
pixhawk committed
112 113 114 115 116 117 118 119 120
    // Name
    if (uas->getUASName() == "")
    {
        m_ui->nameLabel->setText(tr("UAS") + QString::number(uas->getUASID()));
    }
    else
    {
        m_ui->nameLabel->setText(uas->getUASName());
    }
121
    
122
    setBackgroundColor();
123
    
pixhawk's avatar
pixhawk committed
124 125 126
    // Heartbeat fade
    refreshTimer = new QTimer(this);
    connect(refreshTimer, SIGNAL(timeout()), this, SLOT(refresh()));
127 128 129 130 131 132 133 134 135 136 137 138 139

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

    if (localFrame)
    {
        m_ui->gpsLabel->hide();
    }
    else
    {
        m_ui->positionLabel->hide();
    }
140 141

    setSystemType(uas, uas->getSystemType());
pixhawk's avatar
pixhawk committed
142 143 144 145 146 147 148
}

UASView::~UASView()
{
    delete m_ui;
}

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 335 336
        localFrame = true;
        m_ui->gpsLabel->hide();
        m_ui->positionLabel->show();
pixhawk's avatar
pixhawk committed
337 338 339
    }
}

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

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

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

pixhawk's avatar
pixhawk committed
360 361
void UASView::setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current)
{
362 363 364 365 366
    Q_UNUSED(x);
    Q_UNUSED(y);
    Q_UNUSED(z);
    Q_UNUSED(yaw);
    Q_UNUSED(autocontinue);
pixhawk's avatar
pixhawk committed
367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387
    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
388
        this->thrust = thrust;
pixhawk's avatar
pixhawk committed
389 390 391 392 393
    }
}

void UASView::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
394
    Q_UNUSED(voltage);
pixhawk's avatar
pixhawk committed
395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418
    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;
    }
}

419 420
void UASView::contextMenuEvent (QContextMenuEvent* event)
{
421 422 423
    QMenu menu(this);
    menu.addAction(renameAction);
    if (timeout)
424 425
    {
        menu.addAction(removeAction);
426 427 428 429 430 431 432 433 434 435 436 437 438 439
    }
    menu.exec(event->globalPos());
}

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);
440 441 442
    }
}

pixhawk's avatar
pixhawk committed
443 444
void UASView::refresh()
{
445
    //setUpdatesEnabled(false);
446 447
    //setUpdatesEnabled(true);
    //repaint();
448 449

    static quint64 lastupdate = 0;
pixhawk's avatar
pixhawk committed
450
    //qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
451 452 453 454 455 456 457
    lastupdate = MG::TIME::getGroundTimeNow();

    // FIXME
    static int generalUpdateCount = 0;

    if (generalUpdateCount == 4)
    {
458 459 460
#if (QGC_EVENTLOOP_DEBUG)
        qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
461
        generalUpdateCount = 0;
pixhawk's avatar
pixhawk committed
462
        //qDebug() << "UPDATING EVERYTHING";
463 464 465 466 467 468 469 470 471 472 473
        // 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;
474
        position = position.sprintf("%05.1f %05.1f %05.1f m", x, y, z);
475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494
        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";
        }
495
        globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %05.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt);
496
        m_ui->gpsLabel->setText(globalPosition);
pixhawk's avatar
pixhawk committed
497

498 499 500
        // Altitude
        if (groundDistance == 0 && alt != 0)
        {
501
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 5, 'f', 1, '0'));
502 503 504
        }
        else
        {
505
            m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 5, 'f', 1, '0'));
506
        }
507

508
        // Speed
509 510
        QString speed("%1 m/s");
        m_ui->speedLabel->setText(speed.arg(totalSpeed, 4, 'f', 1, '0'));
pixhawk's avatar
pixhawk committed
511

512 513
        // Thrust
        m_ui->thrustBar->setValue(thrust * 100);
pixhawk's avatar
pixhawk committed
514

515
        if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME)
516 517 518 519 520 521 522 523 524 525 526 527 528 529
        {
            // 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
        {
530
            m_ui->timeRemainingLabel->setText(tr("Calc.."));
531 532 533 534 535 536 537
        }

        // 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
538 539 540 541
        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);
542
        m_ui->timeElapsedLabel->setText(timeText);
pixhawk's avatar
pixhawk committed
543
    }
544
    generalUpdateCount++;
pixhawk's avatar
pixhawk committed
545

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

548
    if (timeout)
549 550 551
    {
        // CRITICAL CONDITION, NO HEARTBEAT

552 553 554 555 556 557
        QString borderColor = "#FFFF00";
        if (isActive)
        {
            borderColor = "#FA4A4F";
        }

558 559 560 561
        if (iconIsRed)
        {
            QColor warnColor(Qt::red);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
562
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
563 564 565 566 567 568
            m_ui->uasViewFrame->setStyleSheet(style);
        }
        else
        {
            QColor warnColor(Qt::black);
            m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(warnColor.name()));
569
            QString style = QString("QGroupBox { border-radius: 12px; padding: 0px; margin: 0px; border: 2px solid %1; background-color: %2; }").arg(borderColor, warnColor.name());
570 571 572 573 574 575
            m_ui->uasViewFrame->setStyleSheet(style);
        }
        iconIsRed = !iconIsRed;
    }
    else
    {
576 577 578
        // Fade heartbeat icon
        // Make color darker
        heartbeatColor = heartbeatColor.darker(150);
579

580 581
        //m_ui->heartbeatIcon->setAutoFillBackground(true);
        m_ui->heartbeatIcon->setStyleSheet(colorstyle.arg(heartbeatColor.name()));
582
    }
583
    //setUpdatesEnabled(true);
584 585

    //setUpdatesEnabled(false);
pixhawk's avatar
pixhawk committed
586 587 588 589 590 591 592 593 594 595 596 597 598
}

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