if(m_logfile->write(b)<MAVLINK_MAX_PACKET_LEN+sizeof(quint64))qDebug()<<"WRITING TO LOG FAILED!";
//qDebug() << "WROTE LOGFILE";
}
}
// ORDER MATTERS HERE!
// ORDER MATTERS HERE!
...
@@ -170,7 +161,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
...
@@ -170,7 +161,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
if(!versionMismatchIgnore)
if(!versionMismatchIgnore)
{
{
emitprotocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
emitprotocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
versionMismatchIgnore=true;
versionMismatchIgnore=true;
}
}
...
@@ -189,37 +180,37 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
...
@@ -189,37 +180,37 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
break;
break;
caseMAV_AUTOPILOT_PIXHAWK:
caseMAV_AUTOPILOT_PIXHAWK:
{
{
// Fixme differentiate between quadrotor and coaxial here
// Fixme differentiate between quadrotor and coaxial here
PxQuadMAV*mav=newPxQuadMAV(this,message.sysid);
PxQuadMAV*mav=newPxQuadMAV(this,message.sysid);
// Connect this robot to the UAS object
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// else the slot of the parent object is called (and thus the special
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()));
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));
msgBox.setIcon(QMessageBox::Critical);
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));
* For scientific logging, the use of onboard timestamps and the log
* For scientific logging, the use of onboard timestamps and the log
* functionality of the line chart plot is recommended.
* functionality of the line chart plot is recommended.
*/
*/
voidQGCMAVLinkLogPlayer::readLine()
voidQGCMAVLinkLogPlayer::logLoop()
{
{
constintpacketLen=MAVLINK_MAX_PACKET_LEN;
constinttimeLen=sizeof(quint64);
boolok;
// Ui update: Only every 20 messages
// First check initialization
// to prevent flickering and high CPU load
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->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."));
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."));