Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
e3fcf441
Commit
e3fcf441
authored
Feb 13, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added parameter timeout setting options to MAVLink protocol
parent
6be3ff11
Changes
12
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
290 additions
and
20 deletions
+290
-20
GAudioOutput.cc
src/GAudioOutput.cc
+8
-4
GAudioOutput.h
src/GAudioOutput.h
+6
-2
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+42
-0
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+26
-0
MAVLinkSettingsWidget.cc
src/ui/MAVLinkSettingsWidget.cc
+45
-9
MAVLinkSettingsWidget.h
src/ui/MAVLinkSettingsWidget.h
+1
-0
MAVLinkSettingsWidget.ui
src/ui/MAVLinkSettingsWidget.ui
+95
-1
MainWindow.cc
src/ui/MainWindow.cc
+1
-0
QGCParamWidget.cc
src/ui/QGCParamWidget.cc
+26
-1
QGCParamWidget.h
src/ui/QGCParamWidget.h
+5
-1
QGCSettingsWidget.cc
src/ui/QGCSettingsWidget.cc
+9
-0
QGCSettingsWidget.ui
src/ui/QGCSettingsWidget.ui
+26
-2
No files found.
src/GAudioOutput.cc
View file @
e3fcf441
...
...
@@ -151,10 +151,14 @@ GAudioOutput::~GAudioOutput()
void
GAudioOutput
::
mute
(
bool
mute
)
{
this
->
muted
=
mute
;
QSettings
settings
;
settings
.
setValue
(
QGC_GAUDIOOUTPUT_KEY
+
"muted"
,
this
->
muted
);
settings
.
sync
();
if
(
mute
!=
muted
)
{
this
->
muted
=
mute
;
QSettings
settings
;
settings
.
setValue
(
QGC_GAUDIOOUTPUT_KEY
+
"muted"
,
this
->
muted
);
settings
.
sync
();
emit
mutedChanged
(
muted
);
}
}
bool
GAudioOutput
::
isMuted
()
...
...
src/GAudioOutput.h
View file @
e3fcf441
...
...
@@ -80,6 +80,9 @@ public:
VOICE_FEMALE
}
QGVoice
;
/** @brief Get the mute state */
bool
isMuted
();
public
slots
:
/** @brief Say this text if current output priority matches */
bool
say
(
QString
text
,
int
severity
=
1
);
...
...
@@ -101,8 +104,9 @@ public slots:
void
notifyNegative
();
/** @brief Mute/unmute sound */
void
mute
(
bool
mute
);
/** @brief Get the mute state */
bool
isMuted
();
signals:
void
mutedChanged
(
bool
);
protected:
#ifdef Q_OS_MAC
...
...
src/comm/MAVLinkProtocol.cc
View file @
e3fcf441
...
...
@@ -44,6 +44,9 @@ MAVLinkProtocol::MAVLinkProtocol() :
m_loggingEnabled
(
false
),
m_logfile
(
NULL
),
m_enable_version_check
(
true
),
m_paramRetransmissionTimeout
(
350
),
m_paramRewriteTimeout
(
500
),
m_paramGuardEnabled
(
true
),
versionMismatchIgnore
(
false
),
systemId
(
QGC
::
defaultSystemId
)
{
...
...
@@ -95,6 +98,14 @@ void MAVLinkProtocol::loadSettings()
{
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
();
}
...
...
@@ -113,6 +124,10 @@ void MAVLinkProtocol::storeSettings()
// Logfile exists, store the name
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
.
sync
();
//qDebug() << "Storing settings!";
...
...
@@ -418,6 +433,33 @@ void MAVLinkProtocol::enableMultiplexing(bool enabled)
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
)
{
bool
changed
=
false
;
...
...
src/comm/MAVLinkProtocol.h
View file @
e3fcf441
...
...
@@ -77,6 +77,12 @@ public:
int
getVersion
()
{
return
MAVLINK_VERSION
;
}
/** @brief Get the name of the packet log file */
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
:
/** @brief Receive bytes from a communication interface */
...
...
@@ -99,6 +105,15 @@ public slots:
/** @brief Enabled/disable packet multiplexing */
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 */
void
setLogfileName
(
const
QString
&
filename
);
...
...
@@ -121,6 +136,9 @@ protected:
bool
m_multiplexingEnabled
;
///< Enable/disable packet multiplexing
QFile
*
m_logfile
;
///< Logfile
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
int
lastIndex
[
256
][
256
];
int
totalReceiveCounter
;
...
...
@@ -143,6 +161,14 @@ signals:
void
versionCheckChanged
(
bool
enabled
);
/** @brief Emitted if a message from the protocol should reach the user */
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_
src/ui/MAVLinkSettingsWidget.cc
View file @
e3fcf441
...
...
@@ -50,17 +50,35 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui
->
versionCheckBox
->
setChecked
(
protocol
->
versionCheckEnabled
());
m_ui
->
multiplexingCheckBox
->
setChecked
(
protocol
->
multiplexingEnabled
());
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
// Heartbeat
connect
(
protocol
,
SIGNAL
(
heartbeatChanged
(
bool
)),
m_ui
->
heartbeatCheckBox
,
SLOT
(
setChecked
(
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
(
m_ui
->
loggingCheckBox
,
SIGNAL
(
toggled
(
bool
)),
protocol
,
SLOT
(
enableLogging
(
bool
)));
// Version check
connect
(
protocol
,
SIGNAL
(
versionCheckChanged
(
bool
)),
m_ui
->
versionCheckBox
,
SLOT
(
setChecked
(
bool
)));
connect
(
m_ui
->
versionCheckBox
,
SIGNAL
(
toggled
(
bool
)),
protocol
,
SLOT
(
enableVersionCheck
(
bool
)));
// Logfile
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
)));
// Multiplexing
connect
(
protocol
,
SIGNAL
(
multiplexingChanged
(
bool
)),
m_ui
->
multiplexingCheckBox
,
SLOT
(
setChecked
(
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
m_ui
->
versionLabel
->
setText
(
tr
(
"MAVLINK_VERSION: %1"
).
arg
(
protocol
->
getVersion
()));
...
...
@@ -71,24 +89,35 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui
->
versionLabel
->
setVisible
(
protocol
->
versionCheckEnabled
());
//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)));
// Logging visibility
connect
(
protocol
,
SIGNAL
(
loggingChanged
(
bool
)),
m_ui
->
logFileLabel
,
SLOT
(
setVisible
(
bool
)));
m_ui
->
logFileLabel
->
setVisible
(
protocol
->
loggingEnabled
());
connect
(
protocol
,
SIGNAL
(
loggingChanged
(
bool
)),
m_ui
->
logFileButton
,
SLOT
(
setVisible
(
bool
)));
m_ui
->
logFileButton
->
setVisible
(
protocol
->
loggingEnabled
());
connect
(
protocol
,
SIGNAL
(
multiplexingChanged
(
bool
)),
m_ui
->
multiplexingFilterCheckBox
,
SLOT
(
setVisible
(
bool
)));
m_ui
->
multiplexingFilterCheckBox
->
setVisible
(
protocol
->
multiplexingEnabled
());
connect
(
protocol
,
SIGNAL
(
multiplexingChanged
(
bool
)),
m_ui
->
multiplexingFilterLineEdit
,
SLOT
(
setVisible
(
bool
)));
m_ui
->
multiplexingFilterLineEdit
->
setVisible
(
protocol
->
multiplexingEnabled
());
// // Multiplexing visibility
// connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterCheckBox, SLOT(setVisible(bool)));
// m_ui->multiplexingFilterCheckBox->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
// and then remove these two lines
m_ui
->
multiplexingFilterCheckBox
->
setVisible
(
false
);
m_ui
->
multiplexingFilterLineEdit
->
setVisible
(
false
);
// Update settings
m_ui
->
loggingCheckBox
->
setChecked
(
protocol
->
loggingEnabled
());
m_ui
->
heartbeatCheckBox
->
setChecked
(
protocol
->
heartbeatsEnabled
());
m_ui
->
versionCheckBox
->
setChecked
(
protocol
->
versionCheckEnabled
());
//
// Update settings
//
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
//
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
//
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
}
void
MAVLinkSettingsWidget
::
updateLogfileName
(
const
QString
&
fileName
)
...
...
@@ -132,7 +161,8 @@ MAVLinkSettingsWidget::~MAVLinkSettingsWidget()
void
MAVLinkSettingsWidget
::
changeEvent
(
QEvent
*
e
)
{
QWidget
::
changeEvent
(
e
);
switch
(
e
->
type
())
{
switch
(
e
->
type
())
{
case
QEvent
:
:
LanguageChange
:
m_ui
->
retranslateUi
(
this
);
break
;
...
...
@@ -140,3 +170,9 @@ void MAVLinkSettingsWidget::changeEvent(QEvent *e)
break
;
}
}
void
MAVLinkSettingsWidget
::
hideEvent
(
QHideEvent
*
event
)
{
Q_UNUSED
(
event
);
protocol
->
storeSettings
();
}
src/ui/MAVLinkSettingsWidget.h
View file @
e3fcf441
...
...
@@ -24,6 +24,7 @@ public slots:
protected:
MAVLinkProtocol
*
protocol
;
void
changeEvent
(
QEvent
*
e
);
void
hideEvent
(
QHideEvent
*
event
);
private:
Ui
::
MAVLinkSettingsWidget
*
m_ui
;
...
...
src/ui/MAVLinkSettingsWidget.ui
View file @
e3fcf441
...
...
@@ -7,7 +7,7 @@
<x>
0
</x>
<y>
0
</y>
<width>
431
</width>
<height>
256
</height>
<height>
349
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -151,6 +151,100 @@
</property>
</widget>
</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>
</widget>
<resources/>
...
...
src/ui/MainWindow.cc
View file @
e3fcf441
...
...
@@ -1339,6 +1339,7 @@ void MainWindow::connectCommonActions()
// Audio output
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
)));
// User interaction
...
...
src/ui/QGCParamWidget.cc
View file @
e3fcf441
...
...
@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#include <QFileDialog>
#include <QFile>
#include <QList>
#include <QSettings>
#include "QGCParamWidget.h"
#include "UASInterface.h"
...
...
@@ -51,8 +52,13 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
parameters
(),
transmissionListMode
(
false
),
transmissionActive
(
false
),
transmissionStarted
(
0
)
transmissionStarted
(
0
),
retransmissionTimeout
(
350
),
rewriteTimeout
(
500
)
{
// Load settings
loadSettings
();
// Create tree widget
tree
=
new
QTreeWidget
(
this
);
statusLabel
=
new
QLabel
();
...
...
@@ -134,6 +140,18 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
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
* pointer is never zero.
...
...
@@ -380,6 +398,13 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
*/
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
();
parameters
.
clear
();
...
...
src/ui/QGCParamWidget.h
View file @
e3fcf441
...
...
@@ -94,15 +94,19 @@ protected:
QMap
<
int
,
QMap
<
QString
,
float
>*
>
parameters
;
///< All parameters
QVector
<
bool
>
received
;
///< Successfully received parameters
QMap
<
int
,
QList
<
int
>*
>
transmissionMissingPackets
;
///< Missing packets
QMap
<
int
,
QList
<
float
>*
>
transmissionMissingWriteAckPackets
;
///< Missing write ACK packets
bool
transmissionListMode
;
///< Currently requesting list
QMap
<
int
,
bool
>
transmissionListSizeKnown
;
///< List size initialized?
bool
transmissionActive
;
///< Missing packets, working on list?
quint64
transmissionStarted
;
///< Timeout
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 */
void
setRetransmissionGuardEnabled
(
bool
enabled
);
/** @brief Load settings */
void
loadSettings
();
};
#endif // QGCPARAMWIDGET_H
src/ui/QGCSettingsWidget.cc
View file @
e3fcf441
...
...
@@ -4,6 +4,7 @@
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
#include "GAudioOutput.h"
//, Qt::WindowFlags flags
...
...
@@ -27,8 +28,16 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) :
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
connect
(
ui
->
buttonBox
,
SIGNAL
(
accepted
()),
this
,
SLOT
(
deleteLater
()));
// Set layout options
ui
->
generalPaneGridLayout
->
setAlignment
(
Qt
::
AlignTop
);
}
QGCSettingsWidget
::~
QGCSettingsWidget
()
...
...
src/ui/QGCSettingsWidget.ui
View file @
e3fcf441
...
...
@@ -15,7 +15,29 @@
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<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>
<widget
class=
"QDialogButtonBox"
name=
"buttonBox"
>
...
...
@@ -29,7 +51,9 @@
</item>
</layout>
</widget>
<resources/>
<resources>
<include
location=
"../../mavground.qrc"
/>
</resources>
<connections>
<connection>
<sender>
buttonBox
</sender>
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment