Commit d4f5cb86 authored by lm's avatar lm

Fixed stupid logging bug

parent 7e337668
......@@ -157,7 +157,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/mission/QGCCustomWaypointAction.ui \
src/ui/QGCUDPLinkConfiguration.ui
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui
INCLUDEPATH += src \
src/ui \
......@@ -268,7 +269,8 @@ HEADERS += src/MG.h \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|win32-msvc2008: {
......@@ -394,7 +396,8 @@ SOURCES += src/main.cc \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc
macx|win32-msvc2008: {
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
......@@ -164,13 +164,15 @@ void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
mavlink_named_value_float_t val;
mavlink_msg_named_value_float_decode(&message, &val);
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime());
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
}
else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
{
mavlink_named_value_int_t val;
mavlink_msg_named_value_int_decode(&message, &val);
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime());
QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
}
}
......@@ -590,7 +592,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// SANITY CHECK
// only accept values in a realistic range
// quint64 time = getUnixTime(pos.usec);
quint64 time = MG::TIME::getGroundTimeNow();
quint64 time = getUnixTime();
emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
......@@ -828,7 +830,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
b.resize(256);
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
//b.append('\0');
QString text = QString(b);
......
#include "QGCSettingsWidget.h"
#include "ui_QGCSettingsWidget.h"
QGCSettingsWidget::QGCSettingsWidget(QWidget *parent) :
QDialog(parent),
ui(new Ui::QGCSettingsWidget)
{
ui->setupUi(this);
}
QGCSettingsWidget::~QGCSettingsWidget()
{
delete ui;
}
#ifndef QGCSETTINGSWIDGET_H
#define QGCSETTINGSWIDGET_H
#include <QDialog>
namespace Ui {
class QGCSettingsWidget;
}
class QGCSettingsWidget : public QDialog
{
Q_OBJECT
public:
explicit QGCSettingsWidget(QWidget *parent = 0);
~QGCSettingsWidget();
private:
Ui::QGCSettingsWidget *ui;
};
#endif // QGCSETTINGSWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCSettingsWidget</class>
<widget class="QDialog" name="QGCSettingsWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>467</width>
<height>294</height>
</rect>
</property>
<property name="windowTitle">
<string>Dialog</string>
</property>
<widget class="QDialogButtonBox" name="buttonBox">
<property name="geometry">
<rect>
<x>30</x>
<y>240</y>
<width>341</width>
<height>32</height>
</rect>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="standardButtons">
<set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
</property>
</widget>
<widget class="QLabel" name="label">
<property name="geometry">
<rect>
<x>30</x>
<y>20</y>
<width>401</width>
<height>16</height>
</rect>
</property>
<property name="text">
<string>QGroundControl Settings - Work in Progress, no Settings yet</string>
</property>
</widget>
</widget>
<resources/>
<connections>
<connection>
<sender>buttonBox</sender>
<signal>accepted()</signal>
<receiver>QGCSettingsWidget</receiver>
<slot>accept()</slot>
<hints>
<hint type="sourcelabel">
<x>248</x>
<y>254</y>
</hint>
<hint type="destinationlabel">
<x>157</x>
<y>274</y>
</hint>
</hints>
</connection>
<connection>
<sender>buttonBox</sender>
<signal>rejected()</signal>
<receiver>QGCSettingsWidget</receiver>
<slot>reject()</slot>
<hints>
<hint type="sourcelabel">
<x>316</x>
<y>260</y>
</hint>
<hint type="destinationlabel">
<x>286</x>
<y>274</y>
</hint>
</hints>
</connection>
</connections>
</ui>
......@@ -365,7 +365,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
// Log data
if (logging)
{
if (activePlot->isVisible(curve))
if (activePlot->isVisible(curve+unit))
{
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
......
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