diff --git a/src/LogCompressor.cc b/src/LogCompressor.cc index 0a36b2e0be5fb50bc8ee572c0f35c9260bac5f57..ffaeed864e8a74ccc94e2dd07be460604a22241e 100644 --- a/src/LogCompressor.cc +++ b/src/LogCompressor.cc @@ -60,8 +60,17 @@ void LogCompressor::run() return; } +// outFileName = logFileName; + + QString outFileName; + + QStringList parts = QFileInfo(infile.fileName()).absoluteFilePath().split(".", QString::SkipEmptyParts); + + parts.replace(parts.size()-2, "compressed." + parts.last()); + outFileName = parts.join("."); + // Verify that the output file is useable - QFile outTmpFile("processed_" + outFileName); + QFile outTmpFile(outFileName); if (!outTmpFile.open(QIODevice::WriteOnly | QIODevice::Text)) { emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since output file %1 is not writable").arg(QFileInfo(outTmpFile.fileName()).absoluteFilePath())); return; @@ -146,11 +155,11 @@ void LogCompressor::run() // QFile::remove(outFileName); // outTmpFile.copy(outFileName); // outTmpFile.close(); - emit logProcessingStatusChanged(tr("Log Compressor: Writing output to file %1").arg(QFileInfo(outFileName).absoluteFilePath())); + emit logProcessingStatusChanged(tr("Log Compressor: Writing output to file %1").arg(QFileInfo(outFileName).absoluteFilePath())); // Clean up and update the status before we return. currentDataLine = 0; - emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outFileName)); + emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outFileName)); emit finishedFile(outFileName); qDebug() << "Done with logfile processing"; running = false; diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index dd605760da28a2d79bba87c23ed3f512f7e97ef3..25547d1307503dc62de1e9c07501b3138dadc2d5 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -766,7 +766,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) case MAVLINK_MSG_ID_MANUAL_CONTROL: { mavlink_manual_control_t control; mavlink_msg_manual_control_decode(&msg, &control); - qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch; + qDebug() << "\n" << "ROLL:" << control.x << "PITCH:" << control.y; } break; #endif diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 948fcecbd4cdf5cc7889159e41c223b2cfc8fafe..8a0e2c5e0630a862c6e8219d1fb2bfd64d7adda3 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -1,6 +1,7 @@ #include #include #include +#include #include "MAVLinkSimulationMAV.h" @@ -76,7 +77,7 @@ void MAVLinkSimulationMAV::mainloop() planner.handleMessage(msg); mavlink_servo_output_raw_t servos; - servos.time_usec = 0; + servos.time_boot_ms = 0; servos.servo1_raw = 1000; servos.servo2_raw = 1250; servos.servo3_raw = 1400; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index e299fafba1f865d1645704240172ec7ba38f3ca8..a7c9547d03a4c175c4673a2e0533183269d09588 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1652,7 +1652,7 @@ void UAS::sendMessage(mavlink_message_t message) foreach (LinkInterface* link, *links) { //qDebug() << "ITERATING THROUGH LINKS"; - if (link) + if (LinkManager::instance()->getLinks().contains(link)) { sendMessage(link, message); //qDebug() << "SENT MESSAGE"; @@ -2407,8 +2407,10 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double // If system has manual inputs enabled and is armed if(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (mode & MAV_MODE_FLAG_HIL_ENABLED)) { + // XXX FIXME ADD BUTTON SUPPORT + quint16 buttons = 0; mavlink_message_t message; - mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual); + mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualThrust, (float)manualYawAngle, buttons); sendMessage(message); //qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index b393f77803cb3e1765acec732615a5094a4ef7ec..9744e8794a5519bc6c1d2e8339fbb5bba8e326c4 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -26,7 +26,7 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : setActiveUAS(UASManager::instance()->getActiveUAS()); - for (int i = 0; i < chanMax; i++) + for (unsigned int i = 0; i < chanMax; i++) { rcValue[i] = 1500; } diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc index c17613393e379056912e709d50a675b58d943942..baf7dcc498fc88d9a39f4c12703726696864ae52 100644 --- a/src/ui/linechart/LinechartPlot.cc +++ b/src/ui/linechart/LinechartPlot.cc @@ -280,9 +280,9 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value) if(!data.contains(dataname)) { addCurve(dataname); enforceGroundTime(m_groundTime); - qDebug() << "ADDING CURVE WITH" << dataname << ms << value; - qDebug() << "MINTIME:" << minTime << "MAXTIME:" << maxTime; - qDebug() << "LASTTIME:" << lastTime; +// qDebug() << "ADDING CURVE WITH" << dataname << ms << value; +// qDebug() << "MINTIME:" << minTime << "MAXTIME:" << maxTime; +// qDebug() << "LASTTIME:" << lastTime; } // Add new value diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc index 85834ce5ac1fe51032a4266f29f6f40a8225e178..1b009ce6f1feaa0552580aee9f2a767810485f55 100644 --- a/src/ui/linechart/LinechartWidget.cc +++ b/src/ui/linechart/LinechartWidget.cc @@ -181,7 +181,8 @@ void LinechartWidget::writeSettings() { QSettings settings; settings.beginGroup("LINECHART"); - if (timeButton) settings.setValue("ENFORCE_GROUNDTIME", timeButton->isChecked()); + bool enforceGT = (!autoGroundTimeSet && timeButton->isChecked()) ? true : false; + if (timeButton) settings.setValue("ENFORCE_GROUNDTIME", enforceGT); if (ui.showUnitsCheckBox) settings.setValue("SHOW_UNITS", ui.showUnitsCheckBox->isChecked()); if (ui.shortNameCheckBox) settings.setValue("SHORT_NAMES", ui.shortNameCheckBox->isChecked()); settings.endGroup(); @@ -197,6 +198,7 @@ void LinechartWidget::readSettings() timeButton->setChecked(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool()); activePlot->enforceGroundTime(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool()); timeButton->setChecked(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool()); + //userGroundTimeSet = settings.value("USER_GROUNDTIME", timeButton->isChecked()).toBool(); } if (ui.showUnitsCheckBox) ui.showUnitsCheckBox->setChecked(settings.value("SHOW_UNITS", ui.showUnitsCheckBox->isChecked()).toBool()); if (ui.shortNameCheckBox) ui.shortNameCheckBox->setChecked(settings.value("SHORT_NAMES", ui.shortNameCheckBox->isChecked()).toBool()); @@ -349,18 +351,29 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString& intData.insert(curve+unit, value); } + if (lastTimestamp == 0 && usec != 0) + { + lastTimestamp = usec; + } else if (usec != 0) { + // Difference larger than 5 secs, enforce ground time + if (abs((int)((qint64)usec - (quint64)lastTimestamp)) > 5000) + { + autoGroundTimeSet = true; + if (activePlot) activePlot->groundTime(); + } + } + // Log data if (logging) { if (activePlot->isVisible(curve+unit)) { - if (usec == 0) usec = QGC::groundTimeMilliseconds(); + if (usec == 0 || autoGroundTimeSet) usec = QGC::groundTimeMilliseconds(); if (logStartTime == 0) logStartTime = usec; qint64 time = usec - logStartTime; if (time < 0) time = 0; logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1()); - logFile->flush(); } } } @@ -384,12 +397,24 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString& intData.insert(curve+unit, value); } + if (lastTimestamp == 0 && usec != 0) + { + lastTimestamp = usec; + } else if (usec != 0) { + // Difference larger than 5 secs, enforce ground time + if (abs((int)((qint64)usec - (quint64)lastTimestamp)) > 5000) + { + autoGroundTimeSet = true; + if (activePlot) activePlot->groundTime(); + } + } + // Log data if (logging) { if (activePlot->isVisible(curve+unit)) { - if (usec == 0) usec = QGC::groundTimeMilliseconds(); + if (usec == 0 || autoGroundTimeSet) usec = QGC::groundTimeMilliseconds(); if (logStartTime == 0) logStartTime = usec; qint64 time = usec - logStartTime; if (time < 0) time = 0; @@ -416,12 +441,24 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString& } } + if (lastTimestamp == 0 && usec != 0) + { + lastTimestamp = usec; + } else if (usec != 0) { + // Difference larger than 1 sec, enforce ground time + if (abs((int)((qint64)usec - (quint64)lastTimestamp)) > 1000) + { + autoGroundTimeSet = true; + if (activePlot) activePlot->groundTime(); + } + } + // Log data if (logging) { if (activePlot->isVisible(curve+unit)) { - if (usec == 0) usec = QGC::groundTimeMilliseconds(); + if (usec == 0 || autoGroundTimeSet) usec = QGC::groundTimeMilliseconds(); if (logStartTime == 0) logStartTime = usec; qint64 time = usec - logStartTime; if (time < 0) time = 0; diff --git a/src/ui/linechart/LinechartWidget.h b/src/ui/linechart/LinechartWidget.h index d111b2548f15a0234e711f5e33e980142dcc0722..3e57975c73529fc5f284a60c74d7100fd3777030 100644 --- a/src/ui/linechart/LinechartWidget.h +++ b/src/ui/linechart/LinechartWidget.h @@ -173,6 +173,9 @@ protected: LogCompressor* compressor; QCheckBox* selectAllCheckBox; int selectedMAV; ///< The MAV for which plot items are accepted, -1 for all systems + quint64 lastTimestamp; + bool userGroundTimeSet; + bool autoGroundTimeSet; static const int updateInterval = 1000; ///< Time between number updates, in milliseconds static const int MAX_CURVE_MENUITEM_NUMBER = 8;