Commit e3fcf441 authored by lm's avatar lm

Added parameter timeout setting options to MAVLink protocol

parent 6be3ff11
...@@ -151,10 +151,14 @@ GAudioOutput::~GAudioOutput() ...@@ -151,10 +151,14 @@ GAudioOutput::~GAudioOutput()
void GAudioOutput::mute(bool mute) void GAudioOutput::mute(bool mute)
{ {
this->muted = mute; if (mute != muted)
QSettings settings; {
settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", this->muted); this->muted = mute;
settings.sync(); QSettings settings;
settings.setValue(QGC_GAUDIOOUTPUT_KEY+"muted", this->muted);
settings.sync();
emit mutedChanged(muted);
}
} }
bool GAudioOutput::isMuted() bool GAudioOutput::isMuted()
......
...@@ -80,6 +80,9 @@ public: ...@@ -80,6 +80,9 @@ public:
VOICE_FEMALE VOICE_FEMALE
} QGVoice; } QGVoice;
/** @brief Get the mute state */
bool isMuted();
public slots: public slots:
/** @brief Say this text if current output priority matches */ /** @brief Say this text if current output priority matches */
bool say(QString text, int severity=1); bool say(QString text, int severity=1);
...@@ -101,8 +104,9 @@ public slots: ...@@ -101,8 +104,9 @@ public slots:
void notifyNegative(); void notifyNegative();
/** @brief Mute/unmute sound */ /** @brief Mute/unmute sound */
void mute(bool mute); void mute(bool mute);
/** @brief Get the mute state */
bool isMuted(); signals:
void mutedChanged(bool);
protected: protected:
#ifdef Q_OS_MAC #ifdef Q_OS_MAC
......
...@@ -44,6 +44,9 @@ MAVLinkProtocol::MAVLinkProtocol() : ...@@ -44,6 +44,9 @@ MAVLinkProtocol::MAVLinkProtocol() :
m_loggingEnabled(false), m_loggingEnabled(false),
m_logfile(NULL), m_logfile(NULL),
m_enable_version_check(true), m_enable_version_check(true),
m_paramRetransmissionTimeout(350),
m_paramRewriteTimeout(500),
m_paramGuardEnabled(true),
versionMismatchIgnore(false), versionMismatchIgnore(false),
systemId(QGC::defaultSystemId) systemId(QGC::defaultSystemId)
{ {
...@@ -95,6 +98,14 @@ void MAVLinkProtocol::loadSettings() ...@@ -95,6 +98,14 @@ void MAVLinkProtocol::loadSettings()
{ {
systemId = temp; systemId = temp;
} }
// Parameter interface settings
bool ok;
temp = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout).toInt(&ok);
if (ok) m_paramRetransmissionTimeout = temp;
temp = settings.value("PARAMETER_REWRITE_TIMEOUT", m_paramRewriteTimeout).toInt(&ok);
if (ok) m_paramRewriteTimeout = temp;
m_paramGuardEnabled = settings.value("PARAMETER_TRANSMISSION_GUARD_ENABLED", m_paramGuardEnabled).toBool();
settings.endGroup(); settings.endGroup();
} }
...@@ -113,6 +124,10 @@ void MAVLinkProtocol::storeSettings() ...@@ -113,6 +124,10 @@ void MAVLinkProtocol::storeSettings()
// Logfile exists, store the name // Logfile exists, store the name
settings.setValue("LOGFILE_NAME", m_logfile->fileName()); settings.setValue("LOGFILE_NAME", m_logfile->fileName());
} }
// Parameter interface settings
settings.setValue("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout);
settings.setValue("PARAMETER_REWRITE_TIMEOUT", m_paramRewriteTimeout);
settings.setValue("PARAMETER_TRANSMISSION_GUARD_ENABLED", m_paramGuardEnabled);
settings.endGroup(); settings.endGroup();
settings.sync(); settings.sync();
//qDebug() << "Storing settings!"; //qDebug() << "Storing settings!";
...@@ -418,6 +433,33 @@ void MAVLinkProtocol::enableMultiplexing(bool enabled) ...@@ -418,6 +433,33 @@ void MAVLinkProtocol::enableMultiplexing(bool enabled)
if (changed) emit multiplexingChanged(m_multiplexingEnabled); if (changed) emit multiplexingChanged(m_multiplexingEnabled);
} }
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
if (enabled != m_paramGuardEnabled)
{
m_paramGuardEnabled = enabled;
emit paramGuardChanged(m_paramGuardEnabled);
}
}
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
if (ms != m_paramRetransmissionTimeout)
{
m_paramRetransmissionTimeout = ms;
emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
}
}
void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
if (ms != m_paramRewriteTimeout)
{
m_paramRewriteTimeout = ms;
emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
}
}
void MAVLinkProtocol::enableLogging(bool enabled) void MAVLinkProtocol::enableLogging(bool enabled)
{ {
bool changed = false; bool changed = false;
......
...@@ -77,6 +77,12 @@ public: ...@@ -77,6 +77,12 @@ public:
int getVersion() { return MAVLINK_VERSION; } int getVersion() { return MAVLINK_VERSION; }
/** @brief Get the name of the packet log file */ /** @brief Get the name of the packet log file */
QString getLogfileName(); QString getLogfileName();
/** @brief Enable / disable parameter retransmission */
bool paramGuardEnabled() { return m_paramGuardEnabled; }
/** @brief Set parameter read timeout */
int getParamRetransmissionTimeout() { return m_paramRetransmissionTimeout; }
/** @brief Set parameter wrtie timeout */
int getParamRewriteTimeout() { return m_paramRewriteTimeout; }
public slots: public slots:
/** @brief Receive bytes from a communication interface */ /** @brief Receive bytes from a communication interface */
...@@ -99,6 +105,15 @@ public slots: ...@@ -99,6 +105,15 @@ public slots:
/** @brief Enabled/disable packet multiplexing */ /** @brief Enabled/disable packet multiplexing */
void enableMultiplexing(bool enabled); void enableMultiplexing(bool enabled);
/** @brief Enable / disable parameter retransmission */
void enableParamGuard(bool enabled);
/** @brief Set parameter read timeout */
void setParamRetransmissionTimeout(int ms);
/** @brief Set parameter write timeout */
void setParamRewriteTimeout(int ms);
/** @brief Set log file name */ /** @brief Set log file name */
void setLogfileName(const QString& filename); void setLogfileName(const QString& filename);
...@@ -121,6 +136,9 @@ protected: ...@@ -121,6 +136,9 @@ protected:
bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing
QFile* m_logfile; ///< Logfile QFile* m_logfile; ///< Logfile
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC
int m_paramRetransmissionTimeout; ///< Timeout for parameter retransmission
int m_paramRewriteTimeout; ///< Timeout for sending re-write request
bool m_paramGuardEnabled; ///< Retransmission/rewrite enabled
QMutex receiveMutex; ///< Mutex to protect receiveBytes function QMutex receiveMutex; ///< Mutex to protect receiveBytes function
int lastIndex[256][256]; int lastIndex[256][256];
int totalReceiveCounter; int totalReceiveCounter;
...@@ -143,6 +161,14 @@ signals: ...@@ -143,6 +161,14 @@ signals:
void versionCheckChanged(bool enabled); void versionCheckChanged(bool enabled);
/** @brief Emitted if a message from the protocol should reach the user */ /** @brief Emitted if a message from the protocol should reach the user */
void protocolStatusMessage(const QString& title, const QString& message); void protocolStatusMessage(const QString& title, const QString& message);
/** @brief Emitted if a new system ID was set */
void systemIdChanged(int systemId);
/** @brief Emitted if param guard status changed */
void paramGuardChanged(bool enabled);
/** @brief Emitted if param read timeout changed */
void paramRetransmissionTimeoutChanged(int ms);
/** @brief Emitted if param write timeout changed */
void paramRewriteTimeoutChanged(int ms);
}; };
#endif // MAVLINKPROTOCOL_H_ #endif // MAVLINKPROTOCOL_H_
...@@ -50,17 +50,35 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget ...@@ -50,17 +50,35 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled()); m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
m_ui->multiplexingCheckBox->setChecked(protocol->multiplexingEnabled()); m_ui->multiplexingCheckBox->setChecked(protocol->multiplexingEnabled());
m_ui->systemIdSpinBox->setValue(protocol->getSystemId()); m_ui->systemIdSpinBox->setValue(protocol->getSystemId());
m_ui->paramGuardCheckBox->setChecked(protocol->paramGuardEnabled());
m_ui->paramRetransmissionSpinBox->setValue(protocol->getParamRetransmissionTimeout());
m_ui->paramRewriteSpinBox->setValue(protocol->getParamRewriteTimeout());
// Connect actions // Connect actions
// Heartbeat
connect(protocol, SIGNAL(heartbeatChanged(bool)), m_ui->heartbeatCheckBox, SLOT(setChecked(bool))); connect(protocol, SIGNAL(heartbeatChanged(bool)), m_ui->heartbeatCheckBox, SLOT(setChecked(bool)));
connect(m_ui->heartbeatCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableHeartbeats(bool))); connect(m_ui->heartbeatCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableHeartbeats(bool)));
// Logging
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->loggingCheckBox, SLOT(setChecked(bool))); connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->loggingCheckBox, SLOT(setChecked(bool)));
connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableLogging(bool))); connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableLogging(bool)));
// Version check
connect(protocol, SIGNAL(versionCheckChanged(bool)), m_ui->versionCheckBox, SLOT(setChecked(bool))); connect(protocol, SIGNAL(versionCheckChanged(bool)), m_ui->versionCheckBox, SLOT(setChecked(bool)));
connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableVersionCheck(bool))); connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableVersionCheck(bool)));
// Logfile
connect(m_ui->logFileButton, SIGNAL(clicked()), this, SLOT(chooseLogfileName())); connect(m_ui->logFileButton, SIGNAL(clicked()), this, SLOT(chooseLogfileName()));
// System ID
connect(protocol, SIGNAL(systemIdChanged(int)), m_ui->systemIdSpinBox, SLOT(setValue(int)));
connect(m_ui->systemIdSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setSystemId(int))); connect(m_ui->systemIdSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setSystemId(int)));
// Multiplexing
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingCheckBox, SLOT(setChecked(bool)));
connect(m_ui->multiplexingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableMultiplexing(bool))); connect(m_ui->multiplexingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableMultiplexing(bool)));
// Parameter guard
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramGuardCheckBox, SLOT(setChecked(bool)));
connect(m_ui->paramGuardCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableParamGuard(bool)));
connect(protocol, SIGNAL(paramRetransmissionTimeoutChanged(int)), m_ui->paramRetransmissionSpinBox, SLOT(setValue(int)));
connect(m_ui->paramRetransmissionSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setParamRetransmissionTimeout(int)));
connect(protocol, SIGNAL(paramRewriteTimeoutChanged(int)), m_ui->paramRewriteSpinBox, SLOT(setValue(int)));
connect(m_ui->paramRewriteSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setParamRewriteTimeout(int)));
// Update values // Update values
m_ui->versionLabel->setText(tr("MAVLINK_VERSION: %1").arg(protocol->getVersion())); m_ui->versionLabel->setText(tr("MAVLINK_VERSION: %1").arg(protocol->getVersion()));
...@@ -71,24 +89,35 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget ...@@ -71,24 +89,35 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui->versionLabel->setVisible(protocol->versionCheckEnabled()); m_ui->versionLabel->setVisible(protocol->versionCheckEnabled());
//connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), m_ui->versionSpacer, SLOT(setVisible(bool))); //connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), m_ui->versionSpacer, SLOT(setVisible(bool)));
//connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), m_ui->logFileSpacer, SLOT(setVisible(bool))); //connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), m_ui->logFileSpacer, SLOT(setVisible(bool)));
// Logging visibility
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileLabel, SLOT(setVisible(bool))); connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileLabel, SLOT(setVisible(bool)));
m_ui->logFileLabel->setVisible(protocol->loggingEnabled()); m_ui->logFileLabel->setVisible(protocol->loggingEnabled());
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileButton, SLOT(setVisible(bool))); connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileButton, SLOT(setVisible(bool)));
m_ui->logFileButton->setVisible(protocol->loggingEnabled()); m_ui->logFileButton->setVisible(protocol->loggingEnabled());
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterCheckBox, SLOT(setVisible(bool))); // // Multiplexing visibility
m_ui->multiplexingFilterCheckBox->setVisible(protocol->multiplexingEnabled()); // connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterCheckBox, SLOT(setVisible(bool)));
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterLineEdit, SLOT(setVisible(bool))); // m_ui->multiplexingFilterCheckBox->setVisible(protocol->multiplexingEnabled());
m_ui->multiplexingFilterLineEdit->setVisible(protocol->multiplexingEnabled()); // connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterLineEdit, SLOT(setVisible(bool)));
// m_ui->multiplexingFilterLineEdit->setVisible(protocol->multiplexingEnabled());
// Param guard visibility
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRetransmissionSpinBox, SLOT(setVisible(bool)));
m_ui->paramRetransmissionSpinBox->setVisible(protocol->paramGuardEnabled());
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRetransmissionLabel, SLOT(setVisible(bool)));
m_ui->paramRetransmissionLabel->setVisible(protocol->paramGuardEnabled());
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRewriteSpinBox, SLOT(setVisible(bool)));
m_ui->paramRewriteSpinBox->setVisible(protocol->paramGuardEnabled());
connect(protocol, SIGNAL(paramGuardChanged(bool)), m_ui->paramRewriteLabel, SLOT(setVisible(bool)));
m_ui->paramRewriteLabel->setVisible(protocol->paramGuardEnabled());
// TODO implement filtering // TODO implement filtering
// and then remove these two lines // and then remove these two lines
m_ui->multiplexingFilterCheckBox->setVisible(false); m_ui->multiplexingFilterCheckBox->setVisible(false);
m_ui->multiplexingFilterLineEdit->setVisible(false); m_ui->multiplexingFilterLineEdit->setVisible(false);
// Update settings // // Update settings
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled()); // m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled()); // m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled()); // m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
} }
void MAVLinkSettingsWidget::updateLogfileName(const QString& fileName) void MAVLinkSettingsWidget::updateLogfileName(const QString& fileName)
...@@ -132,7 +161,8 @@ MAVLinkSettingsWidget::~MAVLinkSettingsWidget() ...@@ -132,7 +161,8 @@ MAVLinkSettingsWidget::~MAVLinkSettingsWidget()
void MAVLinkSettingsWidget::changeEvent(QEvent *e) void MAVLinkSettingsWidget::changeEvent(QEvent *e)
{ {
QWidget::changeEvent(e); QWidget::changeEvent(e);
switch (e->type()) { switch (e->type())
{
case QEvent::LanguageChange: case QEvent::LanguageChange:
m_ui->retranslateUi(this); m_ui->retranslateUi(this);
break; break;
...@@ -140,3 +170,9 @@ void MAVLinkSettingsWidget::changeEvent(QEvent *e) ...@@ -140,3 +170,9 @@ void MAVLinkSettingsWidget::changeEvent(QEvent *e)
break; break;
} }
} }
void MAVLinkSettingsWidget::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
protocol->storeSettings();
}
...@@ -24,6 +24,7 @@ public slots: ...@@ -24,6 +24,7 @@ public slots:
protected: protected:
MAVLinkProtocol* protocol; MAVLinkProtocol* protocol;
void changeEvent(QEvent *e); void changeEvent(QEvent *e);
void hideEvent(QHideEvent* event);
private: private:
Ui::MAVLinkSettingsWidget *m_ui; Ui::MAVLinkSettingsWidget *m_ui;
......
...@@ -7,7 +7,7 @@ ...@@ -7,7 +7,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>431</width> <width>431</width>
<height>256</height> <height>349</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
...@@ -151,6 +151,100 @@ ...@@ -151,6 +151,100 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="11" column="0" colspan="3">
<widget class="QCheckBox" name="paramGuardCheckBox">
<property name="text">
<string>Enable retransmission of parameter read/write requests</string>
</property>
</widget>
</item>
<item row="12" column="0">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="13" column="0">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="12" column="1">
<widget class="QLabel" name="paramRetransmissionLabel">
<property name="text">
<string>Read request retransmission timeout</string>
</property>
</widget>
</item>
<item row="13" column="1">
<widget class="QLabel" name="paramRewriteLabel">
<property name="text">
<string>Write request retransmission timeout</string>
</property>
</widget>
</item>
<item row="12" column="2">
<widget class="QSpinBox" name="paramRetransmissionSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>50</number>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>50</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="13" column="2">
<widget class="QSpinBox" name="paramRewriteSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>50</number>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>50</number>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
<resources/> <resources/>
......
...@@ -1339,6 +1339,7 @@ void MainWindow::connectCommonActions() ...@@ -1339,6 +1339,7 @@ void MainWindow::connectCommonActions()
// Audio output // Audio output
ui.actionMuteAudioOutput->setChecked(GAudioOutput::instance()->isMuted()); ui.actionMuteAudioOutput->setChecked(GAudioOutput::instance()->isMuted());
connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), ui.actionMuteAudioOutput, SLOT(setChecked(bool)));
connect(ui.actionMuteAudioOutput, SIGNAL(triggered(bool)), GAudioOutput::instance(), SLOT(mute(bool))); connect(ui.actionMuteAudioOutput, SIGNAL(triggered(bool)), GAudioOutput::instance(), SLOT(mute(bool)));
// User interaction // User interaction
......
...@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#include <QFileDialog> #include <QFileDialog>
#include <QFile> #include <QFile>
#include <QList> #include <QList>
#include <QSettings>
#include "QGCParamWidget.h" #include "QGCParamWidget.h"
#include "UASInterface.h" #include "UASInterface.h"
...@@ -51,8 +52,13 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : ...@@ -51,8 +52,13 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
parameters(), parameters(),
transmissionListMode(false), transmissionListMode(false),
transmissionActive(false), transmissionActive(false),
transmissionStarted(0) transmissionStarted(0),
retransmissionTimeout(350),
rewriteTimeout(500)
{ {
// Load settings
loadSettings();
// Create tree widget // Create tree widget
tree = new QTreeWidget(this); tree = new QTreeWidget(this);
statusLabel = new QLabel(); statusLabel = new QLabel();
...@@ -134,6 +140,18 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : ...@@ -134,6 +140,18 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick())); connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick()));
} }
void QGCParamWidget::loadSettings()
{
QSettings settings;
settings.beginGroup("QGC_MAVLINK_PROTOCOL");
bool ok;
int temp = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", retransmissionTimeout).toInt(&ok);
if (ok) retransmissionTimeout = temp;
temp = settings.value("PARAMETER_REWRITE_TIMEOUT", rewriteTimeout).toInt(&ok);
if (ok) rewriteTimeout = temp;
settings.endGroup();
}
/** /**
* @return The MAV of this widget. Unless the MAV object has been destroyed, this * @return The MAV of this widget. Unless the MAV object has been destroyed, this
* pointer is never zero. * pointer is never zero.
...@@ -380,6 +398,13 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName, ...@@ -380,6 +398,13 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
*/ */
void QGCParamWidget::requestParameterList() void QGCParamWidget::requestParameterList()
{ {
// FIXME This call does not belong here
// Once the comm handling is moved to a new
// Param manager class the settings can be directly
// loaded from MAVLink protocol
loadSettings();
// End of FIXME
// Clear view and request param list // Clear view and request param list
clear(); clear();
parameters.clear(); parameters.clear();
......
...@@ -94,15 +94,19 @@ protected: ...@@ -94,15 +94,19 @@ protected:
QMap<int, QMap<QString, float>* > parameters; ///< All parameters QMap<int, QMap<QString, float>* > parameters; ///< All parameters
QVector<bool> received; ///< Successfully received parameters QVector<bool> received; ///< Successfully received parameters
QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets
QMap<int, QList<float>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
bool transmissionListMode; ///< Currently requesting list bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized? QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list? bool transmissionActive; ///< Missing packets, working on list?
quint64 transmissionStarted; ///< Timeout quint64 transmissionStarted; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission QTimer retransmissionTimer; ///< Timer handling parameter retransmission
const static int retransmissionTimeout = 250; ///< Retransmission request timeout, in milliseconds int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds
/** @brief Activate / deactivate parameter retransmission */ /** @brief Activate / deactivate parameter retransmission */
void setRetransmissionGuardEnabled(bool enabled); void setRetransmissionGuardEnabled(bool enabled);
/** @brief Load settings */
void loadSettings();
}; };
#endif // QGCPARAMWIDGET_H #endif // QGCPARAMWIDGET_H
...@@ -4,6 +4,7 @@ ...@@ -4,6 +4,7 @@
#include "LinkManager.h" #include "LinkManager.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h" #include "MAVLinkSettingsWidget.h"
#include "GAudioOutput.h"
//, Qt::WindowFlags flags //, Qt::WindowFlags flags
...@@ -27,8 +28,16 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) : ...@@ -27,8 +28,16 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) :
this->window()->setWindowTitle(tr("QGroundControl Settings")); this->window()->setWindowTitle(tr("QGroundControl Settings"));
// Audio preferences
ui->audioMuteCheckBox->setChecked(GAudioOutput::instance()->isMuted());
connect(ui->audioMuteCheckBox, SIGNAL(toggled(bool)), GAudioOutput::instance(), SLOT(mute(bool)));
connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), ui->audioMuteCheckBox, SLOT(setChecked(bool)));
// Close / destroy // Close / destroy
connect(ui->buttonBox, SIGNAL(accepted()), this, SLOT(deleteLater())); connect(ui->buttonBox, SIGNAL(accepted()), this, SLOT(deleteLater()));
// Set layout options
ui->generalPaneGridLayout->setAlignment(Qt::AlignTop);
} }
QGCSettingsWidget::~QGCSettingsWidget() QGCSettingsWidget::~QGCSettingsWidget()
......
...@@ -15,7 +15,29 @@ ...@@ -15,7 +15,29 @@
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<item> <item>
<widget class="QTabWidget" name="tabWidget"/> <widget class="QTabWidget" name="tabWidget">
<widget class="QWidget" name="general">
<attribute name="title">
<string>General</string>
</attribute>
<attribute name="toolTip">
<string>General Settings</string>
</attribute>
<layout class="QGridLayout" name="generalPaneGridLayout">
<item row="0" column="0">
<widget class="QCheckBox" name="audioMuteCheckBox">
<property name="text">
<string>Mute all audio output</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/audio-volume-muted.svg</normaloff>:/images/status/audio-volume-muted.svg</iconset>
</property>
</widget>
</item>
</layout>
</widget>
</widget>
</item> </item>
<item> <item>
<widget class="QDialogButtonBox" name="buttonBox"> <widget class="QDialogButtonBox" name="buttonBox">
...@@ -29,7 +51,9 @@ ...@@ -29,7 +51,9 @@
</item> </item>
</layout> </layout>
</widget> </widget>
<resources/> <resources>
<include location="../../mavground.qrc"/>
</resources>
<connections> <connections>
<connection> <connection>
<sender>buttonBox</sender> <sender>buttonBox</sender>
......
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