Browse Source

Fixed Logging, MAVLink API adjustments

QGC4.4
Lorenz Meier 13 years ago
parent
commit
106ffa74e5
  1. 15
      src/LogCompressor.cc
  2. 2
      src/comm/MAVLinkSimulationLink.cc
  3. 3
      src/comm/MAVLinkSimulationMAV.cc
  4. 6
      src/uas/UAS.cc
  5. 2
      src/ui/QGCVehicleConfig.cc
  6. 6
      src/ui/linechart/LinechartPlot.cc
  7. 47
      src/ui/linechart/LinechartWidget.cc
  8. 3
      src/ui/linechart/LinechartWidget.h

15
src/LogCompressor.cc

@ -60,8 +60,17 @@ void LogCompressor::run()
return; 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 // Verify that the output file is useable
QFile outTmpFile("processed_" + outFileName); QFile outTmpFile(outFileName);
if (!outTmpFile.open(QIODevice::WriteOnly | QIODevice::Text)) { 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())); emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since output file %1 is not writable").arg(QFileInfo(outTmpFile.fileName()).absoluteFilePath()));
return; return;
@ -146,11 +155,11 @@ void LogCompressor::run()
// QFile::remove(outFileName); // QFile::remove(outFileName);
// outTmpFile.copy(outFileName); // outTmpFile.copy(outFileName);
// outTmpFile.close(); // 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. // Clean up and update the status before we return.
currentDataLine = 0; 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); emit finishedFile(outFileName);
qDebug() << "Done with logfile processing"; qDebug() << "Done with logfile processing";
running = false; running = false;

2
src/comm/MAVLinkSimulationLink.cc

@ -766,7 +766,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
case MAVLINK_MSG_ID_MANUAL_CONTROL: { case MAVLINK_MSG_ID_MANUAL_CONTROL: {
mavlink_manual_control_t control; mavlink_manual_control_t control;
mavlink_msg_manual_control_decode(&msg, &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; break;
#endif #endif

3
src/comm/MAVLinkSimulationMAV.cc

@ -1,6 +1,7 @@
#include <QDebug> #include <QDebug>
#include <cmath> #include <cmath>
#include <qmath.h> #include <qmath.h>
#include <QGC.h>
#include "MAVLinkSimulationMAV.h" #include "MAVLinkSimulationMAV.h"
@ -76,7 +77,7 @@ void MAVLinkSimulationMAV::mainloop()
planner.handleMessage(msg); planner.handleMessage(msg);
mavlink_servo_output_raw_t servos; mavlink_servo_output_raw_t servos;
servos.time_usec = 0; servos.time_boot_ms = 0;
servos.servo1_raw = 1000; servos.servo1_raw = 1000;
servos.servo2_raw = 1250; servos.servo2_raw = 1250;
servos.servo3_raw = 1400; servos.servo3_raw = 1400;

6
src/uas/UAS.cc

@ -1652,7 +1652,7 @@ void UAS::sendMessage(mavlink_message_t message)
foreach (LinkInterface* link, *links) foreach (LinkInterface* link, *links)
{ {
//qDebug() << "ITERATING THROUGH LINKS"; //qDebug() << "ITERATING THROUGH LINKS";
if (link) if (LinkManager::instance()->getLinks().contains(link))
{ {
sendMessage(link, message); sendMessage(link, message);
//qDebug() << "SENT 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 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)) 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_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); sendMessage(message);
//qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; //qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;

2
src/ui/QGCVehicleConfig.cc

@ -26,7 +26,7 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
setActiveUAS(UASManager::instance()->getActiveUAS()); setActiveUAS(UASManager::instance()->getActiveUAS());
for (int i = 0; i < chanMax; i++) for (unsigned int i = 0; i < chanMax; i++)
{ {
rcValue[i] = 1500; rcValue[i] = 1500;
} }

6
src/ui/linechart/LinechartPlot.cc

@ -280,9 +280,9 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value)
if(!data.contains(dataname)) { if(!data.contains(dataname)) {
addCurve(dataname); addCurve(dataname);
enforceGroundTime(m_groundTime); enforceGroundTime(m_groundTime);
qDebug() << "ADDING CURVE WITH" << dataname << ms << value; // qDebug() << "ADDING CURVE WITH" << dataname << ms << value;
qDebug() << "MINTIME:" << minTime << "MAXTIME:" << maxTime; // qDebug() << "MINTIME:" << minTime << "MAXTIME:" << maxTime;
qDebug() << "LASTTIME:" << lastTime; // qDebug() << "LASTTIME:" << lastTime;
} }
// Add new value // Add new value

47
src/ui/linechart/LinechartWidget.cc

@ -181,7 +181,8 @@ void LinechartWidget::writeSettings()
{ {
QSettings settings; QSettings settings;
settings.beginGroup("LINECHART"); 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.showUnitsCheckBox) settings.setValue("SHOW_UNITS", ui.showUnitsCheckBox->isChecked());
if (ui.shortNameCheckBox) settings.setValue("SHORT_NAMES", ui.shortNameCheckBox->isChecked()); if (ui.shortNameCheckBox) settings.setValue("SHORT_NAMES", ui.shortNameCheckBox->isChecked());
settings.endGroup(); settings.endGroup();
@ -197,6 +198,7 @@ void LinechartWidget::readSettings()
timeButton->setChecked(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool()); timeButton->setChecked(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool());
activePlot->enforceGroundTime(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()); 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.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()); 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); 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 // Log data
if (logging) if (logging)
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds(); if (usec == 0 || autoGroundTimeSet) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;
logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1()); 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); 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 // Log data
if (logging) if (logging)
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds(); if (usec == 0 || autoGroundTimeSet) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; 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 // Log data
if (logging) if (logging)
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds(); if (usec == 0 || autoGroundTimeSet) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;

3
src/ui/linechart/LinechartWidget.h

@ -173,6 +173,9 @@ protected:
LogCompressor* compressor; LogCompressor* compressor;
QCheckBox* selectAllCheckBox; QCheckBox* selectAllCheckBox;
int selectedMAV; ///< The MAV for which plot items are accepted, -1 for all systems 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 updateInterval = 1000; ///< Time between number updates, in milliseconds
static const int MAX_CURVE_MENUITEM_NUMBER = 8; static const int MAX_CURVE_MENUITEM_NUMBER = 8;

Loading…
Cancel
Save