Commit efb95d00 authored by LM's avatar LM

Fixed log buttons, replay pausing does not work yet properly, but issue / solution is now known

parent c31ba506
This diff is collapsed.
...@@ -161,12 +161,14 @@ void MAVLinkSettingsWidget::chooseLogfileName() ...@@ -161,12 +161,14 @@ void MAVLinkSettingsWidget::chooseLogfileName()
{ {
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify MAVLink log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink Logfile (*.mavlink);;")); QString fileName = QFileDialog::getSaveFileName(this, tr("Specify MAVLink log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink Logfile (*.mavlink);;"));
if (!fileName.endsWith(".mavlink")) { if (!fileName.endsWith(".mavlink"))
{
fileName.append(".mavlink"); fileName.append(".mavlink");
} }
QFileInfo file(fileName); QFileInfo file(fileName);
if (file.exists() && !file.isWritable()) { if (file.exists() && !file.isWritable())
{
QMessageBox msgBox; QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical); msgBox.setIcon(QMessageBox::Critical);
msgBox.setText(tr("The selected logfile is not writable")); msgBox.setText(tr("The selected logfile is not writable"));
...@@ -174,7 +176,9 @@ void MAVLinkSettingsWidget::chooseLogfileName() ...@@ -174,7 +176,9 @@ void MAVLinkSettingsWidget::chooseLogfileName()
msgBox.setStandardButtons(QMessageBox::Ok); msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok); msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec(); msgBox.exec();
} else { }
else
{
updateLogfileName(fileName); updateLogfileName(fileName);
protocol->setLogfileName(fileName); protocol->setLogfileName(fileName);
} }
...@@ -189,12 +193,15 @@ void MAVLinkSettingsWidget::enableDroneOS(bool enable) ...@@ -189,12 +193,15 @@ void MAVLinkSettingsWidget::enableDroneOS(bool enable)
// Delete from all lists first // Delete from all lists first
UDPLink* firstUdp = NULL; UDPLink* firstUdp = NULL;
QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(protocol); QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(protocol);
foreach (LinkInterface* link, links) { foreach (LinkInterface* link, links)
{
UDPLink* udp = dynamic_cast<UDPLink*>(link); UDPLink* udp = dynamic_cast<UDPLink*>(link);
if (udp) { if (udp)
{
if (!firstUdp) firstUdp = udp; if (!firstUdp) firstUdp = udp;
// Remove current hosts // Remove current hosts
for (int i = 0; i < m_ui->droneOSComboBox->count(); ++i) { for (int i = 0; i < m_ui->droneOSComboBox->count(); ++i)
{
QString oldHostString = m_ui->droneOSComboBox->itemText(i); QString oldHostString = m_ui->droneOSComboBox->itemText(i);
oldHostString = hostString.split(":").first(); oldHostString = hostString.split(":").first();
udp->removeHost(oldHostString); udp->removeHost(oldHostString);
...@@ -203,8 +210,10 @@ void MAVLinkSettingsWidget::enableDroneOS(bool enable) ...@@ -203,8 +210,10 @@ void MAVLinkSettingsWidget::enableDroneOS(bool enable)
} }
// Re-add if enabled // Re-add if enabled
if (enable) { if (enable)
if (firstUdp) { {
if (firstUdp)
{
firstUdp->addHost(hostString); firstUdp->addHost(hostString);
} }
// Set key // Set key
......
...@@ -21,6 +21,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare ...@@ -21,6 +21,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
mavlinkLogFormat(true), mavlinkLogFormat(true),
binaryBaudRate(57600), binaryBaudRate(57600),
isPlaying(false), isPlaying(false),
currPacketCount(0),
ui(new Ui::QGCMAVLinkLogPlayer) ui(new Ui::QGCMAVLinkLogPlayer)
{ {
ui->setupUi(this); ui->setupUi(this);
...@@ -102,6 +103,7 @@ void QGCMAVLinkLogPlayer::play() ...@@ -102,6 +103,7 @@ void QGCMAVLinkLogPlayer::play()
loopTimer.start(interval*accelerationFactor); loopTimer.start(interval*accelerationFactor);
} }
isPlaying = true; isPlaying = true;
ui->logStatsLabel->setText(tr("Started playing.."));
ui->playButton->setIcon(QIcon(":images/actions/media-playback-pause.svg")); ui->playButton->setIcon(QIcon(":images/actions/media-playback-pause.svg"));
} }
else else
...@@ -272,7 +274,8 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file) ...@@ -272,7 +274,8 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
minutes -= 60*hours; minutes -= 60*hours;
QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2); 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)); currPacketCount = logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64));
ui->logStatsLabel->setText(tr("%2 MB, %3 packets, %4").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(currPacketCount).arg(timelabel));
} }
else else
{ {
...@@ -302,6 +305,10 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file) ...@@ -302,6 +305,10 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2); QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
ui->logStatsLabel->setText(tr("%2 MB, %4 at %5 KB/s").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(timelabel).arg(binaryBaudRate/10.0f/1024.0f, 0, 'f', 2)); ui->logStatsLabel->setText(tr("%2 MB, %4 at %5 KB/s").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(timelabel).arg(binaryBaudRate/10.0f/1024.0f, 0, 'f', 2));
} }
// Reset current state
reset(0);
return true; return true;
} }
} }
...@@ -458,7 +465,7 @@ void QGCMAVLinkLogPlayer::logLoop() ...@@ -458,7 +465,7 @@ void QGCMAVLinkLogPlayer::logLoop()
// Update status label // Update status label
// Update progress bar // Update progress bar
if (loopCounter % 40 == 0) if (loopCounter % 40 == 0 || currPacketCount < 500)
{ {
QFileInfo logFileInfo(logFile); QFileInfo logFileInfo(logFile);
int progress = (ui->positionSlider->maximum()-ui->positionSlider->minimum())*(logFile.pos()/static_cast<float>(logFileInfo.size())); int progress = (ui->positionSlider->maximum()-ui->positionSlider->minimum())*(logFile.pos()/static_cast<float>(logFileInfo.size()));
......
...@@ -78,6 +78,7 @@ protected: ...@@ -78,6 +78,7 @@ protected:
bool mavlinkLogFormat; bool mavlinkLogFormat;
int binaryBaudRate; int binaryBaudRate;
bool isPlaying; bool isPlaying;
unsigned int currPacketCount;
static const int packetLen = MAVLINK_MAX_PACKET_LEN; static const int packetLen = MAVLINK_MAX_PACKET_LEN;
static const int timeLen = sizeof(quint64); static const int timeLen = sizeof(quint64);
void changeEvent(QEvent *e); void changeEvent(QEvent *e);
......
...@@ -45,7 +45,7 @@ QGCToolBar::QGCToolBar(QWidget *parent) : ...@@ -45,7 +45,7 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
toggleLoggingAction = new QAction(QIcon(":"), "Logging", this); toggleLoggingAction = new QAction(QIcon(":"), "Logging", this);
toggleLoggingAction->setCheckable(true); toggleLoggingAction->setCheckable(true);
logReplayAction = new QAction(QIcon(":"), "Replay", this); logReplayAction = new QAction(QIcon(":"), "Replay", this);
logReplayAction->setCheckable(true); logReplayAction->setCheckable(false);
addAction(toggleLoggingAction); addAction(toggleLoggingAction);
addAction(logReplayAction); addAction(logReplayAction);
...@@ -143,7 +143,7 @@ void QGCToolBar::logging(bool enabled) ...@@ -143,7 +143,7 @@ void QGCToolBar::logging(bool enabled)
} }
QFileInfo file(fileName); QFileInfo file(fileName);
if (file.exists() && !file.isWritable()) if ((file.exists() && !file.isWritable()))
{ {
QMessageBox msgBox; QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical); msgBox.setIcon(QMessageBox::Critical);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment