emitprotocolStatusMessage(tr("Opening MAVLink logfile for writing failed"),tr("MAVLink cannot log to the file %1, please choose a different file.").arg(m_logfile->fileName()));
msgBox.setText(tr("The selected logfile is unreadable"));
msgBox.setInformativeText(tr("Please make sure that the file %1 is readable or select a different file").arg(file));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
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));
* For scientific logging, the use of onboard timestamps and the log
* functionality of the line chart plot is recommended.
*/
voidQGCMAVLinkLogPlayer::readLine()
voidQGCMAVLinkLogPlayer::logLoop()
{
constintpacketLen=MAVLINK_MAX_PACKET_LEN;
constinttimeLen=sizeof(quint64);
boolok;
// First check initialization
if(startTime==0)
{
QByteArraystartBytes=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
QByteArraychunk=logFile.read(timeLen+packetLen);
QByteArraypacket=chunk.mid(0,packetLen);
// Emit this packet
mavlink->receiveBytes(logLink,packet);
// Check if reached end of file before reading next timestamp
timeButton->setToolTip(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));
timeButton->setWhatsThis(tr("Overwrite timestamp of data from vehicle with ground receive time. Helps if the plots are not visible because of missing or invalid onboard time."));