QGCMAVLinkLogPlayer.cc 11.3 KB
Newer Older
1 2 3 4
#include <QFileDialog>
#include <QMessageBox>
#include <QDesktopServices>

5
#include "MainWindow.h"
6
#include "QGCMAVLinkLogPlayer.h"
7
#include "QGC.h"
8 9 10 11 12 13 14 15
#include "ui_QGCMAVLinkLogPlayer.h"

QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *parent) :
    QWidget(parent),
    lineCounter(0),
    totalLines(0),
    startTime(0),
    endTime(0),
16 17
    currentStartTime(0),
    accelerationFactor(1.0f),
18
    mavlink(mavlink),
19 20
    logLink(NULL),
    loopCounter(0),
21 22 23 24 25
    ui(new Ui::QGCMAVLinkLogPlayer)
{
    ui->setupUi(this);
    ui->gridLayout->setAlignment(Qt::AlignTop);

26 27 28
    // Connect protocol
    connect(this, SIGNAL(bytesReady(LinkInterface*,QByteArray)), mavlink, SLOT(receiveBytes(LinkInterface*,QByteArray)));

29 30 31
    // Setup timer
    connect(&loopTimer, SIGNAL(timeout()), this, SLOT(logLoop()));

32 33 34 35
    // Setup buttons
    connect(ui->selectFileButton, SIGNAL(clicked()), this, SLOT(selectLogFile()));
    connect(ui->pauseButton, SIGNAL(clicked()), this, SLOT(pause()));
    connect(ui->playButton, SIGNAL(clicked()), this, SLOT(play()));
36
    connect(ui->speedSlider, SIGNAL(valueChanged(int)), this, SLOT(setAccelerationFactorInt(int)));
37 38
    connect(ui->positionSlider, SIGNAL(valueChanged(int)), this, SLOT(jumpToSliderVal(int)));
    connect(ui->positionSlider, SIGNAL(sliderPressed()), this, SLOT(pause()));
39

40 41
    setAccelerationFactorInt(49);
    ui->speedSlider->setValue(49);
42
    ui->positionSlider->setValue(ui->positionSlider->minimum());
43 44 45 46 47 48 49 50 51 52 53 54
}

QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
{
    delete ui;
}

void QGCMAVLinkLogPlayer::play()
{
    if (logFile.isOpen())
    {
        ui->pauseButton->setChecked(false);
55
        ui->selectFileButton->setEnabled(false);
56
        if (logLink)
57
        {
58 59
            logLink->disconnect();
            LinkManager::instance()->removeLink(logLink);
60 61 62 63 64 65
            delete logLink;
        }
        logLink = new MAVLinkSimulationLink("");

        // Start timer
        loopTimer.start(1);
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81
    }
    else
    {
        ui->playButton->setChecked(false);
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Information);
        msgBox.setText(tr("No logfile selected"));
        msgBox.setInformativeText(tr("Please select first a MAVLink log file before playing it."));
        msgBox.setStandardButtons(QMessageBox::Ok);
        msgBox.setDefaultButton(QMessageBox::Ok);
        msgBox.exec();
    }
}

void QGCMAVLinkLogPlayer::pause()
{
82
    loopTimer.stop();
83
    ui->playButton->setChecked(false);
84
    ui->selectFileButton->setEnabled(true);
85 86 87 88 89 90 91
    if (logLink)
    {
        logLink->disconnect();
        LinkManager::instance()->removeLink(logLink);
        delete logLink;
        logLink = NULL;
    }
92 93
}

94
bool QGCMAVLinkLogPlayer::reset(int packetIndex)
95
{
96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122
    // Reset only for valid values
    if (packetIndex >= 0 && packetIndex <= logFile.size() - (packetLen+timeLen))
    {
        bool result = true;
        pause();
        loopCounter = 0;
        logFile.reset();
        if (!logFile.seek(packetIndex*(timeLen + packetLen)))
        {
            // Fallback: Start from scratch
            logFile.reset();
            ui->logStatsLabel->setText(tr("Changing packet index failed, back to start."));
            result = false;
        }

        ui->pauseButton->setChecked(true);
        ui->positionSlider->blockSignals(true);
        int sliderVal = (packetIndex / (double)(logFile.size()/(packetLen+timeLen))) * (ui->positionSlider->maximum() - ui->positionSlider->minimum());
        ui->positionSlider->setValue(sliderVal);
        ui->positionSlider->blockSignals(false);
        startTime = 0;
        return result;
    }
    else
    {
        return false;
    }
123 124 125 126 127 128 129 130 131
}

void QGCMAVLinkLogPlayer::selectLogFile()
{
    QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink Logfile (*.mavlink);;"));

    loadLogFile(fileName);
}

132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150
/**
 * @param factor 0: 0.01X, 50: 1.0X, 100: 100.0X
 */
void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor)
{
    float f = factor+1.0f;
    f -= 50.0f;

    if (f < 0.0f)
    {
        accelerationFactor = 1.0f / (-f/2.0f);
    }
    else
    {
        accelerationFactor = 1+(f/2.0f);
    }

    //qDebug() << "FACTOR:" << accelerationFactor;

151
    ui->speedLabel->setText(tr("Speed: %1X").arg(accelerationFactor, 5, 'f', 2, '0'));
152 153
}

154 155
void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
{
lm's avatar
lm committed
156 157 158 159 160 161 162
    // Check if logging is still enabled
    if (mavlink->loggingEnabled())
    {
        mavlink->enableLogging(false);
        MainWindow::instance()->showInfoMessage(tr("MAVLink Logging Stopped during Replay"), tr("MAVLink logging has been stopped during the log replay. To re-enable logging, use the link properties in the communication menu."));
    }

163 164 165
    // Ensure that the playback process is stopped
    if (logFile.isOpen())
    {
166
        pause();
167 168
        logFile.close();
    }
169 170 171 172
    logFile.setFileName(file);

    if (!logFile.open(QFile::ReadOnly))
    {
173
        MainWindow::instance()->showCriticalMessage(tr("The selected logfile is unreadable"), tr("Please make sure that the file %1 is readable or select a different file").arg(file));
174 175 176 177
        logFile.setFileName("");
    }
    else
    {
178 179 180 181
        QFileInfo logFileInfo(file);
        logFile.reset();
        startTime = 0;
        ui->logFileNameLabel->setText(tr("%1").arg(logFileInfo.baseName()));
182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206

        // Get the time interval from the logfile
        QByteArray timestamp = logFile.read(timeLen);

        // First timestamp
        quint64 starttime = *((quint64*)(timestamp.constData()));

        // Last timestamp
        logFile.seek(logFile.size()-packetLen-timeLen);
        QByteArray timestamp2 = logFile.read(timeLen);
        quint64 endtime = *((quint64*)(timestamp2.constData()));
        // Reset everything
        logFile.reset();

        qDebug() << "Starttime:" << starttime << "End:" << endtime;

        // WARNING: Order matters in this computation
        int seconds = (endtime - starttime)/1000000;
        int minutes = seconds / 60;
        int hours = minutes / 60;
        seconds -= 60*minutes;
        minutes -= 60*hours;

        QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
        ui->logStatsLabel->setText(tr("%2 MB, %3 packets, %4").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))).arg(timelabel));
207 208 209
    }
}

210 211 212 213
/**
 * Jumps to the current percentage of the position slider
 */
void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
214
{
215 216 217 218 219 220 221 222 223 224 225 226 227
    loopTimer.stop();
    // Set the logfile to the correct percentage and
    // align to the timestamp values
    int packetCount = logFile.size() / (packetLen + timeLen);
    int packetIndex = (packetCount - 1) * (slidervalue / (double)(ui->positionSlider->maximum() - ui->positionSlider->minimum()));

    // Do only accept valid jumps
    if (reset(packetIndex))
    {
        ui->logStatsLabel->setText(tr("Jumped to packet %1").arg(packetIndex));
        //qDebug() << "SET POSITION TO PACKET:" << packetIndex;
    }
}
228

229 230 231 232 233 234 235 236
/**
 * This function is the "mainloop" of the log player, reading one line
 * and adjusting the mainloop timer to read the next line in time.
 * It might not perfectly match the timing of the log file,
 * but it will never induce a static drift into the log file replay.
 * For scientific logging, the use of onboard timestamps and the log
 * functionality of the line chart plot is recommended.
 */
237
void QGCMAVLinkLogPlayer::logLoop()
238
{
239
    bool ok;
240

241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277
    // First check initialization
    if (startTime == 0)
    {
        QByteArray startBytes = logFile.read(timeLen);

        // Check if the correct number of bytes could be read
        if (startBytes.length() != timeLen)
        {
            ui->logStatsLabel->setText(tr("Error reading first %1 bytes").arg(timeLen));
            MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"), tr("Error reading first %1 bytes from logfile. Got %2 instead of %1 bytes. Is the logfile readable?").arg(timeLen).arg(startBytes.length()));
            reset();
            return;
        }

        // Convert data to timestamp
        startTime = *((quint64*)(startBytes.constData()));
        currentStartTime = QGC::groundTimeUsecs();
        ok = true;

        //qDebug() << "START TIME: " << startTime;

        // Check if these bytes could be correctly decoded
        if (!ok)
        {
            ui->logStatsLabel->setText(tr("Error decoding first timestamp, aborting."));
            MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"), tr("Could not load initial timestamp from file %1. Is the file corrupted?").arg(logFile.fileName()));
            reset();
            return;
        }
    }


    // Initialization seems fine, load next chunk
    QByteArray chunk = logFile.read(timeLen+packetLen);
    QByteArray packet = chunk.mid(0, packetLen);

    // Emit this packet
278
    emit bytesReady(logLink, packet);
279 280 281 282 283 284 285 286 287 288 289 290 291 292 293

    // Check if reached end of file before reading next timestamp
    if (chunk.length() < timeLen+packetLen || logFile.atEnd())
    {
        // Reached end of file
        reset();

        QString status = tr("Reached end of MAVLink log file.");
        ui->logStatsLabel->setText(status);
        MainWindow::instance()->showStatusMessage(status);
        return;
    }

    // End of file not reached, read next timestamp
    QByteArray rawTime = chunk.mid(packetLen);
294

295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334
    // This is the timestamp of the next packet
    quint64 time = *((quint64*)(rawTime.constData()));
    ok = true;
    if (!ok)
    {
        // Convert it to 64bit number
        QString status = tr("Time conversion error during log replay. Continuing..");
        ui->logStatsLabel->setText(status);
        MainWindow::instance()->showStatusMessage(status);
    }
    else
    {
        // Normal processing, passed all checks
        // start timer to match time offset between
        // this and next packet


        // Offset in ms
        qint64 timediff = (time - startTime)/accelerationFactor;

        // Immediately load any data within
        // a 3 ms interval

        int nextExecutionTime = (((qint64)currentStartTime + (qint64)timediff) - (qint64)QGC::groundTimeUsecs())/1000;

        //qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;

        if (nextExecutionTime < 5)
        {
            logLoop();
        }
        else
        {
            loopTimer.start(nextExecutionTime);
        }
//        loopTimer.start(20);

        if (loopCounter % 40 == 0)
        {
            QFileInfo logFileInfo(logFile);
335
            int progress = (ui->positionSlider->maximum()-ui->positionSlider->minimum())*(logFile.pos()/static_cast<float>(logFileInfo.size()));
336
            //qDebug() << "Progress:" << progress;
337 338 339
            ui->positionSlider->blockSignals(true);
            ui->positionSlider->setValue(progress);
            ui->positionSlider->blockSignals(false);
340 341 342 343 344 345 346 347
        }
        loopCounter++;
        // Ui update: Only every 20 messages
        // to prevent flickering and high CPU load

        // Update status label
        // Update progress bar
    }
348 349 350 351 352 353 354 355 356 357 358 359 360
}

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