Commit 645ab2c1 authored by Lorenz Meier's avatar Lorenz Meier

Partial fix to ground time issue

parent d2e92162
...@@ -175,23 +175,23 @@ bool UAS::getSelected() const ...@@ -175,23 +175,23 @@ bool UAS::getSelected() const
return (UASManager::instance()->getActiveUAS() == this); return (UASManager::instance()->getActiveUAS() == this);
} }
void UAS::receiveMessageNamedValue(const mavlink_message_t& message) //void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{ //{
if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT) // if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
{ // {
mavlink_named_value_float_t val; // mavlink_named_value_float_t val;
mavlink_msg_named_value_float_decode(&message, &val); // mavlink_msg_named_value_float_decode(&message, &val);
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN); // QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime()); // emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
} // }
else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT) // else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
{ // {
mavlink_named_value_int_t val; // mavlink_named_value_int_t val;
mavlink_msg_named_value_int_decode(&message, &val); // mavlink_msg_named_value_int_decode(&message, &val);
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN); // QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime()); // emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
} // }
} //}
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{ {
...@@ -356,11 +356,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -356,11 +356,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: // case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
case MAVLINK_MSG_ID_NAMED_VALUE_INT: // case MAVLINK_MSG_ID_NAMED_VALUE_INT:
// Receive named value message // // Receive named value message
receiveMessageNamedValue(message); // receiveMessageNamedValue(message);
break; // break;
case MAVLINK_MSG_ID_SYS_STATUS: case MAVLINK_MSG_ID_SYS_STATUS:
{ {
if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2) if (multiComponentSourceDetected && message.compid != MAV_COMP_ID_IMU_2)
...@@ -938,10 +938,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -938,10 +938,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_SCALED_PRESSURE: case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW: case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
case MAVLINK_MSG_ID_OPTICAL_FLOW: case MAVLINK_MSG_ID_OPTICAL_FLOW:
break;
case MAVLINK_MSG_ID_DEBUG_VECT: case MAVLINK_MSG_ID_DEBUG_VECT:
break;
case MAVLINK_MSG_ID_DEBUG: case MAVLINK_MSG_ID_DEBUG:
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
break; break;
default: default:
{ {
......
...@@ -577,9 +577,9 @@ protected slots: ...@@ -577,9 +577,9 @@ protected slots:
/** @brief Read settings from disk */ /** @brief Read settings from disk */
void readSettings(); void readSettings();
// MESSAGE RECEPTION // // MESSAGE RECEPTION
/** @brief Receive a named value message */ // /** @brief Receive a named value message */
void receiveMessageNamedValue(const mavlink_message_t& message); // void receiveMessageNamedValue(const mavlink_message_t& message);
private: private:
// unsigned int mode; ///< The current mode of the MAV // unsigned int mode; ///< The current mode of the MAV
......
...@@ -27,8 +27,6 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : ...@@ -27,8 +27,6 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
messageFilter.insert(MAVLINK_MSG_ID_MISSION_ITEM, false); messageFilter.insert(MAVLINK_MSG_ID_MISSION_ITEM, false);
messageFilter.insert(MAVLINK_MSG_ID_MISSION_COUNT, false); messageFilter.insert(MAVLINK_MSG_ID_MISSION_COUNT, false);
messageFilter.insert(MAVLINK_MSG_ID_MISSION_ACK, false); messageFilter.insert(MAVLINK_MSG_ID_MISSION_ACK, false);
messageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, false);
messageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_INT, false);
textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG, false); textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG, false);
textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG_VECT, false); textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG_VECT, false);
...@@ -177,6 +175,27 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 ...@@ -177,6 +175,27 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
name = name.arg(QString(debug.name), fieldName); name = name.arg(QString(debug.name), fieldName);
time = debug.time_usec / 1000; time = debug.time_usec / 1000;
} }
else if (msgid == MAVLINK_MSG_ID_DEBUG)
{
mavlink_debug_t debug;
mavlink_msg_debug_decode(msg, &debug);
name = name.arg(QString("debug")).arg(debug.ind);
time = debug.time_boot_ms;
}
else if (msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
{
mavlink_named_value_float_t debug;
mavlink_msg_named_value_float_decode(msg, &debug);
name = name.arg(debug.name).arg(fieldName);
time = debug.time_boot_ms;
}
else if (msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
{
mavlink_named_value_int_t debug;
mavlink_msg_named_value_int_decode(msg, &debug);
name = name.arg(debug.name).arg(fieldName);
time = debug.time_boot_ms;
}
else else
{ {
name = name.arg(messageInfo[msgid].name, fieldName); name = name.arg(messageInfo[msgid].name, fieldName);
......
...@@ -32,8 +32,10 @@ ...@@ -32,8 +32,10 @@
* @param interval The maximum interval for which data is stored (default: 30 minutes) in milliseconds * @param interval The maximum interval for which data is stored (default: 30 minutes) in milliseconds
**/ **/
LinechartPlot::LinechartPlot(QWidget *parent, int plotid, quint64 interval): QwtPlot(parent), LinechartPlot::LinechartPlot(QWidget *parent, int plotid, quint64 interval): QwtPlot(parent),
minTime(QUINT64_MAX), minTime(0),
maxTime(QUINT64_MIN), lastTime(0),
maxTime(100),
plotPosition(0),
maxInterval(MAX_STORAGE_INTERVAL), maxInterval(MAX_STORAGE_INTERVAL),
timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds
automaticScrollActive(false), automaticScrollActive(false),
...@@ -84,8 +86,6 @@ LinechartPlot::LinechartPlot(QWidget *parent, int plotid, quint64 interval): Qwt ...@@ -84,8 +86,6 @@ LinechartPlot::LinechartPlot(QWidget *parent, int plotid, quint64 interval): Qwt
colors.append(QColor(87,231,246)); colors.append(QColor(87,231,246));
colors.append(QColor(230,126,23)); colors.append(QColor(230,126,23));
plotPosition = 0;
setAutoReplot(false); setAutoReplot(false);
// Set grid // Set grid
...@@ -257,12 +257,16 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value) ...@@ -257,12 +257,16 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value)
/* Check if dataset identifier already exists */ /* Check if dataset identifier already exists */
if(!data.contains(dataname)) { if(!data.contains(dataname)) {
addCurve(dataname); addCurve(dataname);
enforceGroundTime(m_groundTime);
qDebug() << "ADDING CURVE WITH" << dataname << ms << value;
qDebug() << "MINTIME:" << minTime << "MAXTIME:" << maxTime;
qDebug() << "LASTTIME:" << lastTime;
} }
// Add new value // Add new value
TimeSeriesData* dataset = data.value(dataname); TimeSeriesData* dataset = data.value(dataname);
quint64 time = QGC::groundTimeMilliseconds(); quint64 time;
// Append data // Append data
if (!m_groundTime) if (!m_groundTime)
...@@ -270,6 +274,10 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value) ...@@ -270,6 +274,10 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value)
// Use timestamp from dataset // Use timestamp from dataset
time = ms; time = ms;
} }
else
{
time = QGC::groundTimeMilliseconds();
}
dataset->append(time, value); dataset->append(time, value);
lastUpdate.insert(dataname, time); lastUpdate.insert(dataname, time);
...@@ -302,7 +310,19 @@ void LinechartPlot::enforceGroundTime(bool enforce) ...@@ -302,7 +310,19 @@ void LinechartPlot::enforceGroundTime(bool enforce)
{ {
m_groundTime = enforce; m_groundTime = enforce;
lastTime = QGC::groundTimeUsecs()/1000; if (enforce)
{
lastTime = QGC::groundTimeMilliseconds();
plotPosition = lastTime;
maxTime = lastTime;
}
else
{
lastTime = 0;
plotPosition = 0;
minTime = 0;
maxTime = 100;
}
} }
/** /**
......
...@@ -184,6 +184,7 @@ void LinechartWidget::readSettings() ...@@ -184,6 +184,7 @@ void LinechartWidget::readSettings()
if (activePlot) { if (activePlot) {
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());
} }
if (unitsCheckBox) unitsCheckBox->setChecked(settings.value("SHOW_UNITS", unitsCheckBox->isChecked()).toBool()); if (unitsCheckBox) unitsCheckBox->setChecked(settings.value("SHOW_UNITS", unitsCheckBox->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());
...@@ -258,9 +259,6 @@ void LinechartWidget::createLayout() ...@@ -258,9 +259,6 @@ void LinechartWidget::createLayout()
timeButton->setText(tr("Ground Time")); timeButton->setText(tr("Ground 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->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."));
bool gTimeDefault = true;
if (activePlot) activePlot->enforceGroundTime(gTimeDefault);
timeButton->setChecked(gTimeDefault);
layout->addWidget(timeButton, 1, 4); layout->addWidget(timeButton, 1, 4);
layout->setColumnStretch(4, 0); layout->setColumnStretch(4, 0);
connect(timeButton, SIGNAL(clicked(bool)), activePlot, SLOT(enforceGroundTime(bool))); connect(timeButton, SIGNAL(clicked(bool)), activePlot, SLOT(enforceGroundTime(bool)));
......
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