UASInfoWidget.cc 7.43 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34
/*=====================================================================

PIXHAWK Micro Air Vehicle Flying Robotics Toolkit

(c) 2009 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.

    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.

    You should have received a copy of the GNU General Public License
    along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

/**
 * @file
 *   @brief Implementation of class UASInfoWidget
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QtGlobal>
#include <QTimer>
#include <QDir>
35 36 37
#include <QDebug>

#include <float.h>
38 39 40
#include <cstdlib>
#include <cmath>

41 42 43 44
#include "UASInfoWidget.h"
#include "MultiVehicleManager.h"
#include "QGC.h"
#include "UAS.h"
45
#include "QGCApplication.h"
46

47 48
UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *parent, QString name)
    : QGCDockWidget(title, action, parent)
49 50 51
    , _activeUAS(NULL)
    , _seqLossPercent(0)
    , _seqLossTotal(0)
52 53 54 55
{
    ui.setupUi(this);
    this->name = name;

56 57
    connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &UASInfoWidget::_activeVehicleChanged);
    _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle());
58

59
    startTime = QGC::groundTimeMilliseconds();
60 61 62 63 64 65 66 67 68 69 70 71 72 73 74

    // Set default values
    /** Set two voltage decimals and zero charge level decimals **/
    this->voltageDecimals = 2;
    this->loadDecimals = 2;

    this->voltage = 0;
    this->chargeLevel = 0;
    this->load = 0;
    receiveLoss = 0;
    sendLoss = 0;
    changed = true;
    errors = QMap<QString, int>();

    updateTimer = new QTimer(this);
75
    connect(updateTimer, &QTimer::timeout, this, &UASInfoWidget::refresh);
76 77 78
    updateTimer->start(updateInterval);

    this->setVisible(false);
79 80
    
    loadSettings();
81 82 83

    connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::receiveLossPercentChanged, this, &UASInfoWidget::updateSeqLossPercent);
    connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::receiveLossTotalChanged, this, &UASInfoWidget::updateSeqLossTotal);
84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106
}

UASInfoWidget::~UASInfoWidget()
{

}

void UASInfoWidget::showEvent(QShowEvent* event)
{
    // React only to internal (pre-display)
    // events
    Q_UNUSED(event);
    updateTimer->start(updateInterval);
}

void UASInfoWidget::hideEvent(QHideEvent* event)
{
    // React only to internal (pre-display)
    // events
    Q_UNUSED(event);
    updateTimer->stop();
}

107
void UASInfoWidget::_activeVehicleChanged(Vehicle* vehicle)
108
{
109 110 111 112 113 114
    if (_activeUAS) {
        disconnect(_activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
        disconnect(_activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
        disconnect(static_cast<UAS*>(_activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
        disconnect(_activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
        _activeUAS = NULL;
115 116 117
    }
    
    if (vehicle) {
118 119 120 121 122
        _activeUAS = vehicle->uas();
        connect(_activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
        connect(_activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
        connect(static_cast<UAS*>(_activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
        connect(_activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
123 124 125
    }
}

dongfang's avatar
dongfang committed
126
void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds)
127
{
dongfang's avatar
dongfang committed
128
    Q_UNUSED(current)
129 130 131 132 133 134 135
    setVoltage(uas, voltage);
    setChargeLevel(uas, percent);
    setTimeRemaining(uas, seconds);
}

void UASInfoWidget::updateErrorCount(int uasid, QString component, QString device, int count)
{
136 137
    //qDebug() << __FILE__ << __LINE__ << _activeUAS->getUASID() << "=" << uasid;
    if (_activeUAS->getUASID() == uasid) {
138 139 140 141 142 143 144 145 146 147
        errors.remove(component + ":" + device);
        errors.insert(component + ":" + device, count);
    }
}

/**
 *
 */
void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
{
148
    if (_activeUAS == uas) {
149 150 151 152 153 154 155 156 157 158
        this->load = load;
    }
}

void UASInfoWidget::updateReceiveLoss(int uasId, float receiveLoss)
{
    Q_UNUSED(uasId);
    this->receiveLoss = this->receiveLoss * 0.8f + receiveLoss * 0.2f;
}

159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176
void UASInfoWidget::updateSeqLossPercent(int uasId, float seqLossPercent)
{
    if (_activeUAS && _activeUAS->getUASID() == uasId) {
        _seqLossPercent = _seqLossPercent * 0.8f + seqLossPercent * 0.2f;
    } else {
        _seqLossPercent = 0;
    }
}

void UASInfoWidget::updateSeqLossTotal(int uasId, int seqLossTotal)
{
    if (_activeUAS && _activeUAS->getUASID() == uasId) {
        _seqLossTotal = seqLossTotal;
    } else {
        _seqLossTotal = 0;
    }
}

177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194
/**
  The send loss is typically calculated on the GCS based on packets
  that were received scrambled from the MAV
 */
void UASInfoWidget::updateSendLoss(int uasId, float sendLoss)
{
    Q_UNUSED(uasId);
    this->sendLoss = this->sendLoss * 0.8f + sendLoss * 0.2f;
}

void UASInfoWidget::setVoltage(UASInterface* uas, double voltage)
{
    Q_UNUSED(uas);
    this->voltage = voltage;
}

void UASInfoWidget::setChargeLevel(UASInterface* uas, double chargeLevel)
{
195
    if (_activeUAS == uas) {
196 197 198 199 200 201
        this->chargeLevel = chargeLevel;
    }
}

void UASInfoWidget::setTimeRemaining(UASInterface* uas, double seconds)
{
202
    if (_activeUAS == uas) {
203 204 205 206 207 208 209 210 211 212 213 214 215 216 217
        this->timeRemaining = seconds;
    }
}

void UASInfoWidget::refresh()
{
    ui.voltageLabel->setText(QString::number(this->voltage, 'f', voltageDecimals));
    ui.batteryBar->setValue(qMax(0,qMin(static_cast<int>(this->chargeLevel), 100)));

    ui.loadLabel->setText(QString::number(this->load, 'f', loadDecimals));
    ui.loadBar->setValue(qMax(0, qMin(static_cast<int>(this->load), 100)));

    ui.receiveLossBar->setValue(qMax(0, qMin(static_cast<int>(receiveLoss), 100)));
    ui.receiveLossLabel->setText(QString::number(receiveLoss, 'f', 2));

218 219 220 221 222
    ui.seqLossBar->setValue(qMax(0, qMin(static_cast<int>(_seqLossPercent), 100)));
    ui.seqLossLabel->setText(QString::number(_seqLossPercent, 'f', 2));

    ui.seqcntLossLabel->setText(QString::number(_seqLossTotal));

223 224 225 226 227 228 229 230
    ui.sendLossBar->setValue(sendLoss);
    ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2));

    ui.label_5->setText(QString::number(this->load, 'f', loadDecimals));
    ui.progressBar->setValue(qMax(0, qMin(static_cast<int>(this->load), 100)));

    QString errorString;
    QMapIterator<QString, int> i(errors);
231
    while (i.hasNext()) {
232 233 234 235 236 237 238 239 240 241
        i.next();
        errorString += QString(i.key() + ": %1 ").arg(i.value());

        // FIXME
        errorString.replace("IMU:", "");


    }
    ui.errorLabel->setText(errorString);
}