Commit 9ecf6a95 authored by pixhawk's avatar pixhawk

Fixed audio error on Linux, added Hz rate to MAVLink inspector, fixed logging for 0 timestamps

parent 56e11079
......@@ -184,8 +184,8 @@ bool GAudioOutput::say(QString text, int severity)
cst_wave* wav = flite_text_to_wave(text.toStdString().c_str(), v);
// file.fileName() returns the unique file name
cst_wave_save(wav, file.fileName().toStdString().c_str(), "riff");
m_media->setCurrentSource(Phonon::MediaSource(file.fileName().toStdString().c_str()));
m_media->play();
//m_media->setCurrentSource(Phonon::MediaSource(file.fileName().toStdString().c_str()));
//m_media->play();
res = true;
}
#endif
......
......@@ -37,10 +37,11 @@ void QGCMAVLinkInspector::refreshView()
// Ignore NULL values
if (!msg) continue;
// Update the tree view
QString messageName("%1 (%2 Hz, #%3)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(messagesHz.value(msg->msgid, 0)).arg(msg->msgid);
if (!treeWidgetItems.contains(msg->msgid))
{
QString messageName("%1 (#%2)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msg->msgid);
QStringList fields;
fields << messageName;
QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
......@@ -56,7 +57,10 @@ void QGCMAVLinkInspector::refreshView()
ui->treeWidget->addTopLevelItem(widget);
}
// Set Hz
QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid);
message->setFirstColumnSpanned(true);
message->setData(0, Qt::DisplayRole, QVariant(messageName));
for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
{
updateField(msg->msgid, i, message->child(i));
......@@ -71,6 +75,19 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
// int filterValue = ui->systemComboBox()->value().toInt();
// if (filterValue != )
memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));
float msgHz = 0.0f;
quint64 receiveTime = QGC::groundTimeMilliseconds();
if (lastMessageUpdate.contains(message.msgid))
{
msgHz = ((float)((float)receiveTime - (float)lastMessageUpdate.value(message.msgid)))/1000.0f;
qDebug() << "DIFF:" << receiveTime - lastMessageUpdate.value(message.msgid);
messagesHz.insert(message.msgid, 0.1f*msgHz+0.9f*messagesHz.value(message.msgid, 1));
}
qDebug() << "MSGHZ:" << messagesHz.value(message.msgid, 1000);
lastMessageUpdate.insert(message.msgid, receiveTime);
}
QGCMAVLinkInspector::~QGCMAVLinkInspector()
......
......@@ -26,7 +26,8 @@ public slots:
void refreshView();
protected:
QMap<int, quint64> lastFieldUpdate; ///< Used to switch between highlight and non-highlighting color
QMap<int, quint64> lastMessageUpdate; ///< Used to switch between highlight and non-highlighting color
QMap<int, quint64> messagesHz; ///< Used to store update rate in Hz
mavlink_message_t receivedMessages[256]; ///< Available / known messages
QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items
QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI
......
......@@ -315,6 +315,7 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64
{
if (activePlot->isVisible(curve+unit))
{
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
......@@ -347,6 +348,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{
if (activePlot->isVisible(curve+unit))
{
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
......@@ -391,6 +393,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{
if (activePlot->isVisible(curve+unit))
{
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
......@@ -425,6 +428,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{
if (activePlot->isVisible(curve+unit))
{
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
......
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