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
39bb543e
Commit
39bb543e
authored
Aug 07, 2013
by
tstellanova
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
fix build
parent
74f1acf5
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
161 additions
and
123 deletions
+161
-123
QGCUASParamManager.cc
src/uas/QGCUASParamManager.cc
+11
-4
QGCUASParamManager.h
src/uas/QGCUASParamManager.h
+5
-4
UASParameterCommsMgr.cc
src/uas/UASParameterCommsMgr.cc
+19
-13
UASParameterCommsMgr.h
src/uas/UASParameterCommsMgr.h
+14
-11
QGCParamWidget.cc
src/ui/QGCParamWidget.cc
+108
-89
QGCParamWidget.h
src/ui/QGCParamWidget.h
+4
-2
No files found.
src/uas/QGCUASParamManager.cc
View file @
39bb543e
#include "QGCUASParamManager.h"
#include "UASInterface.h"
#include <QApplication>>
#include <QDir>
#include "UASInterface.h"
#include "UASParameterCommsMgr.h"
QGCUASParamManager
::
QGCUASParamManager
(
UASInterface
*
uas
,
QWidget
*
parent
)
:
...
...
@@ -28,15 +31,15 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) :
void
parameterUpdated
(
int
compId
,
int
paramId
,
QString
paramName
,
QVariant
value
);
connect
(
paramDataModel
,
SIGNAL
(
parameterUpdated
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
handleParameterUpdate
(
int
,
int
,
int
,
QString
,
QVariant
));
this
,
SLOT
(
handleParameterUpdate
(
int
,
int
,
int
,
QString
,
QVariant
))
)
;
// connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)),
// this, SLOT(receivedParameterUpdate(int,int,int,int,QString,QVariant)));
// Listen for param list reload finished
connect
(
paramCommsMgr
,
SIGNAL
(
parameterListUpToDate
(
int
)),
this
,
SLOT
(
handleParameterListUpToDate
(
int
)
)));
connect
(
paramCommsMgr
,
SIGNAL
(
parameterListUpToDate
()),
this
,
SLOT
(
handleParameterListUpToDate
()));
...
...
@@ -206,6 +209,10 @@ void QGCUASParamManager::setParamDescriptions(const QMap<QString,QString>& param
}
void
QGCUASParamManager
::
setParameter
(
int
component
,
QString
parameterName
,
QVariant
value
)
{
paramCommsMgr
->
setParameter
(
component
,
parameterName
,
value
);
}
void
QGCUASParamManager
::
loadParamMetaInfoCSV
()
...
...
src/uas/QGCUASParamManager.h
View file @
39bb543e
...
...
@@ -43,16 +43,17 @@ signals:
public
slots
:
/** @brief Write one parameter to the MAV */
virtual
void
setParameter
(
int
component
,
QString
parameterName
,
QVariant
value
)
=
0
;
/** @brief Send one parameter to the MAV: changes value in transient memory of MAV */
virtual
void
setParameter
(
int
component
,
QString
parameterName
,
QVariant
value
);
/** @brief Request list of parameters from MAV */
virtual
void
requestParameterList
();
/** @brief Request a single parameter by name */
/** @brief Request a single parameter by name
from the MAV
*/
virtual
void
requestParameterUpdate
(
int
component
,
const
QString
&
parameter
);
virtual
void
handleParameterUpdate
(
int
component
,
int
paramCount
,
int
paramId
,
const
QString
&
parameterName
,
QVariant
value
)
=
0
;
virtual
void
handleParameterListUpToDate
(
int
component
)
=
0
;
virtual
void
handleParameterListUpToDate
()
=
0
;
protected:
...
...
src/uas/UASParameterCommsMgr.cc
View file @
39bb543e
#include "UASParameterCommsMgr.h"
#include <QSettings>
#include "QGCUASParamManager.h"
#include "UASInterface.h"
...
...
@@ -38,14 +40,14 @@ void UASParameterCommsMgr::loadParamCommsSettings()
{
QSettings
settings
;
settings
.
beginGroup
(
"QGC_MAVLINK_PROTOCOL"
);
bool
valid
;
bool
ok
;
int
val
=
settings
.
value
(
"PARAMETER_RETRANSMISSION_TIMEOUT"
,
retransmissionTimeout
).
toInt
(
&
ok
);
if
(
valid
)
{
retransmissionTimeout
=
temp
;
if
(
ok
)
{
retransmissionTimeout
=
val
;
}
val
=
settings
.
value
(
"PARAMETER_REWRITE_TIMEOUT"
,
rewriteTimeout
).
toInt
(
&
ok
);
if
(
valid
)
{
rewriteTimeout
=
temp
;
if
(
ok
)
{
rewriteTimeout
=
val
;
}
settings
.
endGroup
();
}
...
...
@@ -224,17 +226,23 @@ void UASParameterCommsMgr::setParameter(int component, QString parameterName, QV
double
dblValue
=
value
.
toDouble
();
if
(
paramDataModel
->
isValueLessThanParamMin
(
parameterName
,
dblValue
))
{
setParameterStatusMsg
(
tr
(
"REJ. %1, %2 < min"
).
arg
(
parameterName
).
arg
(
dblValue
));
setParameterStatusMsg
(
tr
(
"REJ. %1, %2 < min"
).
arg
(
parameterName
).
arg
(
dblValue
),
ParamCommsStatusLevel_Error
);
return
;
}
if
(
paramDataModel
->
isValueGreaterThanParamMax
(
parameterName
,
dblValue
))
{
setParameterStatusMsg
(
tr
(
"REJ. %1, %2 > max"
).
arg
(
parameterName
).
arg
(
dblValue
));
setParameterStatusMsg
(
tr
(
"REJ. %1, %2 > max"
).
arg
(
parameterName
).
arg
(
dblValue
),
ParamCommsStatusLevel_Error
);
return
;
}
QVariant
onboardVal
;
paramDataModel
->
getOnboardParameterValue
(
component
,
parameterName
,
onboardVal
);
if
(
onboardVal
==
value
)
{
setParameterStatusMsg
(
tr
(
"REJ. %1 already %2"
).
arg
(
parameterName
).
arg
(
dblValue
));
setParameterStatusMsg
(
tr
(
"REJ. %1 already %2"
).
arg
(
parameterName
).
arg
(
dblValue
),
ParamCommsStatusLevel_Warning
);
return
;
}
...
...
@@ -246,28 +254,24 @@ void UASParameterCommsMgr::setParameter(int component, QString parameterName, QV
{
QVariant
fixedValue
(
QChar
((
unsigned
char
)
value
.
toInt
()));
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
case
QVariant
:
:
Int
:
{
QVariant
fixedValue
(
value
.
toInt
());
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
case
QVariant
:
:
UInt
:
{
QVariant
fixedValue
(
value
.
toUInt
());
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
case
QMetaType
:
:
Float
:
{
QVariant
fixedValue
(
value
.
toFloat
());
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
default:
...
...
@@ -309,6 +313,8 @@ void UASParameterCommsMgr::setParameterStatusMsg(const QString& msg, ParamCommsS
qDebug
()
<<
"parameterStatusMsg: "
<<
msg
;
parameterStatusMsg
=
msg
;
emit
parameterStatusMsgUpdated
(
msg
,
level
);
//TODO indicate OK status somehow (eg color)
// QPalette pal = statusLabel->palette();
// pal.setColor(backgroundRole(), QGC::colorGreen);
...
...
@@ -360,7 +366,7 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
// Start retransmission guard
// or reset timer
paramCommsMgr
->
setRetransmissionGuardEnabled
(
true
);
//TODO
setRetransmissionGuardEnabled
(
true
);
//TODO
}
// Mark this parameter as received in read list
...
...
src/uas/UASParameterCommsMgr.h
View file @
39bb543e
...
...
@@ -16,16 +16,16 @@ class UASParameterCommsMgr : public QObject
{
Q_OBJECT
typedef
enum
ParamCommsStatusLevel
{
ParamCommsStatusLevel_OK
=
0
,
ParamCommsStatusLevel_Warning
=
2
,
ParamCommsStatusLevel_Error
=
4
,
ParamCommsStatusLevel_Count
}
ParamCommsStatusLevel_t
;
public:
explicit
UASParameterCommsMgr
(
QObject
*
parent
=
0
,
UASInterface
*
uas
=
NULL
);
typedef
enum
ParamCommsStatusLevel
{
ParamCommsStatusLevel_OK
=
0
,
ParamCommsStatusLevel_Warning
=
2
,
ParamCommsStatusLevel_Error
=
4
,
ParamCommsStatusLevel_Count
}
ParamCommsStatusLevel_t
;
protected:
/** @brief Activate / deactivate parameter retransmission */
...
...
@@ -41,7 +41,9 @@ signals:
void
parameterChanged
(
int
component
,
int
parameterIndex
,
QVariant
value
);
void
parameterValueConfirmed
(
int
uas
,
int
component
,
int
paramCount
,
int
paramId
,
QString
parameter
,
QVariant
value
);
void
parameterListUpToDate
(
int
component
);
/** @brief We have received a complete list of all parameters onboard the MAV */
void
parameterListUpToDate
();
void
parameterUpdateRequested
(
int
component
,
const
QString
&
parameter
);
void
parameterUpdateRequestedById
(
int
componentId
,
int
paramId
);
...
...
@@ -57,6 +59,7 @@ public slots:
/** @brief Write one parameter to the MAV */
virtual
void
setParameter
(
int
component
,
QString
parameterName
,
QVariant
value
);
/** @brief Request list of parameters from MAV */
virtual
void
requestParameterList
();
/** @brief Check for missing parameters */
...
...
@@ -67,9 +70,9 @@ public slots:
virtual
void
receivedParameterUpdate
(
int
uas
,
int
compId
,
int
paramCount
,
int
paramId
,
QString
paramName
,
QVariant
value
);
protected
slots
:
void
receivedParameterChange
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
void
receivedParameterListChange
(
int
uas
,
int
component
,
int
parameterCount
,
int
parameterId
,
QString
parameterName
,
QVariant
value
);
//
protected slots:
//
void receivedParameterChange(int uas, int component, QString parameterName, QVariant value);
//
void receivedParameterListChange(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
protected:
...
...
src/ui/QGCParamWidget.cc
View file @
39bb543e
...
...
@@ -27,16 +27,17 @@ This file is part of the QGROUNDCONTROL project
*/
#include <cmath>
#include <float.h>
#include <QGridLayout>
#include <QPushButton>
#include <QFileDialog>
#include <QApplication>
#include <QDebug>
#include <QFile>
#include <QFileDialog>
#include <QGridLayout>
#include <QList>
#include <QTime>
#include <QSettings>
#include <QMessageBox>
#include <QApplication>
#include <QDebug>
#include <QPushButton>
#include <QSettings>
#include <QTime>
#include "MainWindow.h"
#include "QGC.h"
...
...
@@ -338,7 +339,7 @@ void QGCParamWidget::handleParameterUpdate(int componentId, int paramCount, int
}
void
QGCParamWidget
::
handleParameterListUpToDate
(
int
component
)
void
QGCParamWidget
::
handleParameterListUpToDate
()
{
// Expand visual tree
tree
->
expandItem
(
tree
->
topLevelItem
(
0
));
...
...
@@ -593,94 +594,95 @@ void QGCParamWidget::writeParameters()
* @param parameterName name of the parameter, as delivered by the system
* @param value value of the parameter
*/
void
QGCParamWidget
::
setParameter
(
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
parameterName
.
isEmpty
())
{
return
;
}
//void QGCParamWidget::setParameter(int component, QString parameterName, QVariant value)
//{
double
dblValue
=
value
.
toDouble
();
// if (parameterName.isEmpty()) {
// return;
// }
if
(
paramDataModel
->
isValueLessThanParamMin
(
parameterName
,
dblValue
))
{
statusLabel
->
setText
(
tr
(
"REJ. %1, %2 < min"
).
arg
(
parameterName
).
arg
(
dblValue
));
return
;
}
if
(
paramDataModel
->
isValueGreaterThanParamMax
(
parameterName
,
dblValue
))
{
statusLabel
->
setText
(
tr
(
"REJ. %1, %2 > max"
).
arg
(
parameterName
).
arg
(
dblValue
));
return
;
}
QVariant
onboardVal
;
paramDataModel
->
getOnboardParameterValue
(
component
,
parameterName
,
onboardVal
);
if
(
onboardVal
==
value
)
{
statusLabel
->
setText
(
tr
(
"REJ. %1 already %2"
).
arg
(
parameterName
).
arg
(
dblValue
));
return
;
}
// double dblValue = value.toDouble();
//int paramType = (int)onboardParameters.value(component)->value(parameterName).type();
int
paramType
=
(
int
)
value
.
type
();
switch
(
paramType
)
{
case
QVariant
:
:
Char
:
{
QVariant
fixedValue
(
QChar
((
unsigned
char
)
value
.
toInt
()));
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
case
QVariant
:
:
Int
:
{
QVariant
fixedValue
(
value
.
toInt
());
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
case
QVariant
:
:
UInt
:
{
QVariant
fixedValue
(
value
.
toUInt
());
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
case
QMetaType
:
:
Float
:
{
QVariant
fixedValue
(
value
.
toFloat
());
emit
parameterChanged
(
component
,
parameterName
,
fixedValue
);
//qDebug() << "PARAM WIDGET SENT:" << fixedValue;
}
break
;
default:
qCritical
()
<<
"ABORTED PARAM SEND, NO VALID QVARIANT TYPE"
;
return
;
}
// if (paramDataModel->isValueLessThanParamMin(parameterName,dblValue)) {
// statusLabel->setText(tr("REJ. %1, %2 < min").arg(parameterName).arg(dblValue));
// return;
// }
// if (paramDataModel->isValueGreaterThanParamMax(parameterName,dblValue)) {
// statusLabel->setText(tr("REJ. %1, %2 > max").arg(parameterName).arg(dblValue));
// return;
// }
// QVariant onboardVal;
// paramDataModel->getOnboardParameterValue(component,parameterName,onboardVal);
// if (onboardVal == value) {
// statusLabel->setText(tr("REJ. %1 already %2").arg(parameterName).arg(dblValue));
// return;
// }
// Wait for parameter to be written back
// mark it therefore as missing
if
(
!
transmissionMissingWriteAckPackets
.
contains
(
component
))
{
transmissionMissingWriteAckPackets
.
insert
(
component
,
new
QMap
<
QString
,
QVariant
>
());
}
// //int paramType = (int)onboardParameters.value(component)->value(parameterName).type();
// int paramType = (int)value.type();
// switch (paramType)
// {
// case QVariant::Char:
// {
// QVariant fixedValue(QChar((unsigned char)value.toInt()));
// emit parameterChanged(component, parameterName, fixedValue);
// //qDebug() << "PARAM WIDGET SENT:" << fixedValue;
// }
// break;
// case QVariant::Int:
// {
// QVariant fixedValue(value.toInt());
// emit parameterChanged(component, parameterName, fixedValue);
// //qDebug() << "PARAM WIDGET SENT:" << fixedValue;
// }
// break;
// case QVariant::UInt:
// {
// QVariant fixedValue(value.toUInt());
// emit parameterChanged(component, parameterName, fixedValue);
// //qDebug() << "PARAM WIDGET SENT:" << fixedValue;
// }
// break;
// case QMetaType::Float:
// {
// QVariant fixedValue(value.toFloat());
// emit parameterChanged(component, parameterName, fixedValue);
// //qDebug() << "PARAM WIDGET SENT:" << fixedValue;
// }
// break;
// default:
// qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
// return;
// }
// Insert it in missing write ACK list
transmissionMissingWriteAckPackets
.
value
(
component
)
->
insert
(
parameterName
,
value
);
// // Wait for parameter to be written back
// // mark it therefore as missing
// if (!transmissionMissingWriteAckPackets.contains(component))
// {
// transmissionMissingWriteAckPackets.insert(component, new QMap<QString, QVariant>());
// }
// Set timeouts
if
(
transmissionActive
)
{
transmissionTimeout
+=
rewriteTimeout
;
}
else
{
quint64
newTransmissionTimeout
=
QGC
::
groundTimeMilliseconds
()
+
rewriteTimeout
;
if
(
newTransmissionTimeout
>
transmissionTimeout
)
{
transmissionTimeout
=
newTransmissionTimeout
;
}
transmissionActive
=
true
;
}
// // Insert it in missing write ACK list
// transmissionMissingWriteAckPackets.value(component)->insert(parameterName, value);
// Enable guard / reset timeouts
paramCommsMgr
->
setRetransmissionGuardEnabled
(
true
);
//TODO
}
// // Set timeouts
// if (transmissionActive)
// {
// transmissionTimeout += rewriteTimeout;
// }
// else
// {
// quint64 newTransmissionTimeout = QGC::groundTimeMilliseconds() + rewriteTimeout;
// if (newTransmissionTimeout > transmissionTimeout)
// {
// transmissionTimeout = newTransmissionTimeout;
// }
// transmissionActive = true;
// }
// // Enable guard / reset timeouts
// paramCommsMgr->setRetransmissionGuardEnabled(true); //TODO
//}
void
QGCParamWidget
::
readParameters
()
{
...
...
@@ -696,3 +698,20 @@ void QGCParamWidget::clear()
tree
->
clear
();
componentItems
->
clear
();
}
void
QGCParamWidget
::
handleParamStatusMsgUpdate
(
QString
msg
,
int
level
)
{
QColor
bgColor
=
QGC
::
colorGreen
;
if
((
int
)
UASParameterCommsMgr
::
ParamCommsStatusLevel_Warning
==
level
)
{
bgColor
=
QGC
::
colorOrange
;
}
else
if
((
int
)
UASParameterCommsMgr
::
ParamCommsStatusLevel_Error
==
level
)
{
bgColor
=
QGC
::
colorRed
;
}
QPalette
pal
=
statusLabel
->
palette
();
pal
.
setColor
(
backgroundRole
(),
bgColor
);
statusLabel
->
setPalette
(
pal
);
statusLabel
->
setText
(
msg
);
}
src/ui/QGCParamWidget.h
View file @
39bb543e
...
...
@@ -68,14 +68,16 @@ public slots:
// void receivedParameterUpdate(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value);
virtual
void
handleParameterUpdate
(
int
component
,
int
paramCount
,
int
paramId
,
const
QString
&
parameterName
,
QVariant
value
);
virtual
void
handleParameterListUpToDate
(
int
component
);
virtual
void
handleParameterListUpToDate
();
virtual
void
handleParamStatusMsgUpdate
(
QString
msg
,
int
level
);
/** @brief Ensure that view of parameter matches data in the model */
void
updateParameterDisplay
(
int
component
,
QString
parameterName
,
QVariant
value
);
/** @brief Request list of parameters from MAV */
void
requestAllParamsUpdate
();
/** @brief Set one parameter, changes value in RAM of MAV */
virtual
void
setParameter
(
int
component
,
QString
parameterName
,
QVariant
value
);
//
virtual void setParameter(int component, QString parameterName, QVariant value);
/** @brief Set all parameters, changes the value in RAM of MAV */
void
setParameters
();
/** @brief Write the current parameters to permanent storage (EEPROM/HDD) */
...
...
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