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
d7137bbe
Commit
d7137bbe
authored
Aug 15, 2013
by
tstellanova
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
refactor QGCUASParamManager to be Controller-only (no View code)
parent
09a26af9
Changes
22
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
22 changed files
with
582 additions
and
438 deletions
+582
-438
qgroundcontrol.pro
qgroundcontrol.pro
+4
-2
QGCUASParamManager.cc
src/uas/QGCUASParamManager.cc
+87
-24
QGCUASParamManager.h
src/uas/QGCUASParamManager.h
+29
-13
UAS.cc
src/uas/UAS.cc
+128
-145
UAS.h
src/uas/UAS.h
+7
-21
UASInterface.h
src/uas/UASInterface.h
+1
-11
UASParameterCommsMgr.cc
src/uas/UASParameterCommsMgr.cc
+1
-10
UASParameterCommsMgr.h
src/uas/UASParameterCommsMgr.h
+0
-2
ParameterInterface.cc
src/ui/ParameterInterface.cc
+7
-6
QGCBaseParamWidget.cc
src/ui/QGCBaseParamWidget.cc
+121
-0
QGCBaseParamWidget.h
src/ui/QGCBaseParamWidget.h
+59
-0
QGCPX4VehicleConfig.cc
src/ui/QGCPX4VehicleConfig.cc
+11
-11
QGCPX4VehicleConfig.h
src/ui/QGCPX4VehicleConfig.h
+1
-1
QGCParamWidget.cc
src/ui/QGCParamWidget.cc
+41
-122
QGCParamWidget.h
src/ui/QGCParamWidget.h
+21
-32
QGCPendingParamWidget.cc
src/ui/QGCPendingParamWidget.cc
+27
-10
QGCPendingParamWidget.h
src/ui/QGCPendingParamWidget.h
+4
-2
QGCVehicleConfig.cc
src/ui/QGCVehicleConfig.cc
+7
-5
QGCVehicleConfig.h
src/ui/QGCVehicleConfig.h
+1
-0
QGCComboBox.cc
src/ui/designer/QGCComboBox.cc
+16
-16
QGCComboBox.h
src/ui/designer/QGCComboBox.h
+7
-3
QGCParamSlider.cc
src/ui/designer/QGCParamSlider.cc
+2
-2
No files found.
qgroundcontrol.pro
View file @
d7137bbe
...
...
@@ -471,7 +471,8 @@ HEADERS += src/MG.h \
src
/
ui
/
configuration
/
ApmFirmwareConfig
.
h
\
src
/
uas
/
UASParameterDataModel
.
h
\
src
/
uas
/
UASParameterCommsMgr
.
h
\
src
/
ui
/
QGCPendingParamWidget
.
h
src
/
ui
/
QGCPendingParamWidget
.
h
\
src
/
ui
/
QGCBaseParamWidget
.
h
#
Google
Earth
is
only
supported
on
Mac
OS
and
Windows
with
Visual
Studio
Compiler
macx
|
macx
-
g
++
|
macx
-
g
++
42
|
win32
-
msvc2008
|
win32
-
msvc2010
|
win32
-
msvc2012
::
HEADERS
+=
src
/
ui
/
map3D
/
QGCGoogleEarthView
.
h
...
...
@@ -689,7 +690,8 @@ SOURCES += src/main.cc \
src
/
ui
/
configuration
/
ApmFirmwareConfig
.
cc
\
src
/
uas
/
UASParameterDataModel
.
cc
\
src
/
uas
/
UASParameterCommsMgr
.
cc
\
src
/
ui
/
QGCPendingParamWidget
.
cc
src
/
ui
/
QGCPendingParamWidget
.
cc
\
src
/
ui
/
QGCBaseParamWidget
.
cc
#
Enable
Google
Earth
only
on
Mac
OS
and
Windows
with
Visual
Studio
compiler
macx
|
macx
-
g
++
|
macx
-
g
++
42
|
win32
-
msvc2008
|
win32
-
msvc2010
|
win32
-
msvc2012
::
SOURCES
+=
src
/
ui
/
map3D
/
QGCGoogleEarthView
.
cc
...
...
src/uas/QGCUASParamManager.cc
View file @
d7137bbe
...
...
@@ -2,28 +2,46 @@
#include <QApplication>>
#include <QDir>
#include <QMessageBox>
#include "UASInterface.h"
#include "UASParameterCommsMgr.h"
QGCUASParamManager
::
QGCUASParamManager
(
UASInterface
*
uas
,
QWidget
*
parent
)
:
Q
Widge
t
(
parent
),
QGCUASParamManager
::
QGCUASParamManager
(
QObject
*
parent
,
UASInterface
*
uas
)
:
Q
Objec
t
(
parent
),
mav
(
uas
),
paramDataModel
(
NULL
),
paramDataModel
(
this
),
paramCommsMgr
(
NULL
)
{
paramDataModel
=
uas
->
getParamDataModel
();
paramCommsMgr
=
uas
->
getParamCommsMgr
();
mav
->
setParamManager
(
this
);
paramCommsMgr
=
new
UASParameterCommsMgr
(
this
,
mav
);
// Load default values and tooltips
loadParamMetaInfoCSV
();
connectToCommsMgr
();
}
void
QGCUASParamManager
::
connectToCommsMgr
()
{
// Pass along comms mgr status msgs
connect
(
paramCommsMgr
,
SIGNAL
(
parameterStatusMsgUpdated
(
QString
,
int
)),
this
,
SIGNAL
(
parameterStatusMsgUpdated
(
QString
,
int
)));
connect
(
paramCommsMgr
,
SIGNAL
(
parameterListUpToDate
()),
this
,
SIGNAL
(
parameterListUpToDate
()));
}
bool
QGCUASParamManager
::
getParameterValue
(
int
component
,
const
QString
&
parameter
,
QVariant
&
value
)
const
{
return
paramDataModel
->
getOnboardParamValue
(
component
,
parameter
,
value
);
return
paramDataModel
.
getOnboardParamValue
(
component
,
parameter
,
value
);
}
...
...
@@ -42,29 +60,31 @@ void QGCUASParamManager::requestParameterUpdate(int component, const QString& pa
*/
void
QGCUASParamManager
::
requestParameterList
()
{
if
(
!
mav
)
{
return
;
if
(
mav
)
{
emit
parameterStatusMsgUpdated
(
tr
(
"Requested param list.. waiting"
),
UASParameterCommsMgr
::
ParamCommsStatusLevel_OK
);
paramCommsMgr
->
requestParameterList
();
}
setParameterStatusMsg
(
tr
(
"Requested param list.. waiting"
));
paramCommsMgr
->
requestParameterList
();
}
void
QGCUASParamManager
::
setParameterStatusMsg
(
const
QString
&
msg
)
void
QGCUASParamManager
::
requestParameterListIfEmpty
()
{
qDebug
()
<<
"parameterStatusMsg: "
<<
msg
;
parameterStatusMsg
=
msg
;
if
(
mav
)
{
int
totalOnboard
=
paramDataModel
.
countOnboardParams
();
if
(
totalOnboard
<
2
)
{
//TODO arbitrary constant, maybe 0 is OK?
requestParameterList
();
}
}
}
void
QGCUASParamManager
::
setParamDescriptions
(
const
QMap
<
QString
,
QString
>&
paramInfo
)
{
paramDataModel
->
setParamDescriptions
(
paramInfo
);
paramDataModel
.
setParamDescriptions
(
paramInfo
);
}
void
QGCUASParamManager
::
setParameter
(
int
compId
,
QString
paramName
,
QVariant
value
)
{
//paramCommsMgr->setParameter(compId,paramName,value);
paramDataModel
->
updatePendingParamWithValue
(
compId
,
paramName
,
value
);
paramDataModel
.
updatePendingParamWithValue
(
compId
,
paramName
,
value
);
}
void
QGCUASParamManager
::
sendPendingParameters
()
...
...
@@ -74,7 +94,7 @@ void QGCUASParamManager::sendPendingParameters()
void
QGCUASParamManager
::
setPendingParam
(
int
compId
,
QString
&
paramName
,
const
QVariant
&
value
)
{
paramDataModel
->
updatePendingParamWithValue
(
compId
,
paramName
,
value
);
paramDataModel
.
updatePendingParamWithValue
(
compId
,
paramName
,
value
);
}
...
...
@@ -97,16 +117,59 @@ void QGCUASParamManager::loadParamMetaInfoCSV()
}
QTextStream
in
(
&
paramMetaFile
);
paramDataModel
->
loadParamMetaInfoFromStream
(
in
);
paramDataModel
.
loadParamMetaInfoFromStream
(
in
);
paramMetaFile
.
close
();
}
/**
* @return The MAV of this mgr. Unless the MAV object has been destroyed, this
* pointer is never zero.
*/
UASInterface
*
QGCUASParamManager
::
getUAS
()
{
return
mav
;
}
UASParameterDataModel
*
QGCUASParamManager
::
dataModel
()
{
return
&
paramDataModel
;
}
void
QGCUASParamManager
::
writeOnboardParamsToStream
(
QTextStream
&
stream
,
const
QString
&
uasName
)
{
paramDataModel
.
writeOnboardParamsToStream
(
stream
,
uasName
);
}
void
QGCUASParamManager
::
readPendingParamsFromStream
(
QTextStream
&
stream
)
{
paramDataModel
.
readUpdateParamsFromStream
(
stream
);
}
void
QGCUASParamManager
::
copyVolatileParamsToPersistent
()
{
int
changedParamCount
=
paramDataModel
.
countPendingParams
();
if
(
changedParamCount
>
0
)
{
QMessageBox
msgBox
;
msgBox
.
setText
(
tr
(
"There are locally changed parameters. Please transmit them first (<TRANSMIT>) or update them with the onboard values (<REFRESH>) before storing onboard from RAM to ROM."
));
msgBox
.
exec
();
}
else
{
paramCommsMgr
->
writeParamsToPersistentStorage
();
}
}
void
QGCUASParamManager
::
copyPersistentParamsToVolatile
()
{
if
(
mav
)
{
mav
->
readParametersFromStorage
();
//TODO use comms mgr instead?
}
}
void
QGCUASParamManager
::
requestRcCalibrationParamsUpdate
()
{
paramCommsMgr
->
requestRcCalibrationParamsUpdate
();
}
src/uas/QGCUASParamManager.h
View file @
d7137bbe
...
...
@@ -6,16 +6,18 @@
#include <QTimer>
#include <QVariant>
#include "UASParameterDataModel.h"
//forward declarations
class
QTextStream
;
class
UASInterface
;
class
UASParameterCommsMgr
;
class
UASParameterDataModel
;
class
QGCUASParamManager
:
public
Q
Widge
t
class
QGCUASParamManager
:
public
Q
Objec
t
{
Q_OBJECT
public:
QGCUASParamManager
(
UASInterface
*
uas
,
QWidget
*
parent
=
0
);
QGCUASParamManager
(
QObject
*
parent
=
0
,
UASInterface
*
uas
=
0
);
/** @brief Get the known, confirmed value of a parameter */
virtual
bool
getParameterValue
(
int
component
,
const
QString
&
parameter
,
QVariant
&
value
)
const
;
...
...
@@ -28,16 +30,23 @@ public:
*/
UASInterface
*
getUAS
();
/** @return The data model managed by this class */
virtual
UASParameterDataModel
*
dataModel
();
protected:
//TODO decouple this UI message display further?
virtual
void
setParameterStatusMsg
(
const
QString
&
msg
);
/** @brief Load parameter meta information from appropriate CSV file */
virtual
void
loadParamMetaInfoCSV
();
void
connectToCommsMgr
();
signals:
void
parameterChanged
(
int
component
,
QString
parameter
,
QVariant
value
);
void
parameterChanged
(
int
component
,
int
parameterIndex
,
QVariant
value
);
/** @brief We updated the parameter status message */
void
parameterStatusMsgUpdated
(
QString
msg
,
int
level
);
/** @brief We have received a complete list of all parameters onboard the MAV */
void
parameterListUpToDate
();
public
slots
:
/** @brief Send one parameter to the MAV: changes value in transient memory of MAV */
...
...
@@ -49,25 +58,32 @@ public slots:
/** @brief Request list of parameters from MAV */
virtual
void
requestParameterList
();
/** @brief Request a list of params onboard the MAV if the onboard param list we have is empty */
virtual
void
requestParameterListIfEmpty
();
virtual
void
setPendingParam
(
int
componentId
,
QString
&
key
,
const
QVariant
&
value
);
/** @brief Request a single parameter by name from the MAV */
virtual
void
requestParameterUpdate
(
int
component
,
const
QString
&
parameter
);
virtual
void
handleParameterUpdate
(
int
component
,
const
QString
&
parameterName
,
QVariant
value
)
=
0
;
virtual
void
handleParameterListUpToDate
()
=
0
;
virtual
void
writeOnboardParamsToStream
(
QTextStream
&
stream
,
const
QString
&
uasName
);
virtual
void
readPendingParamsFromStream
(
QTextStream
&
stream
);
virtual
void
requestRcCalibrationParamsUpdate
();
/** @brief Copy the current parameters in volatile RAM to persistent storage (EEPROM/HDD) */
virtual
void
copyVolatileParamsToPersistent
();
/** @brief Copy the parameters from persistent storage to volatile RAM */
virtual
void
copyPersistentParamsToVolatile
();
protected:
// Parameter data model
UASInterface
*
mav
;
///< The MAV this manager is controlling
UASParameterDataModel
*
paramDataModel
;
///< Shared data model of parameters
UASParameterDataModel
paramDataModel
;
///< Shared data model of parameters
UASParameterCommsMgr
*
paramCommsMgr
;
///< Shared comms mgr for parameters
// Status
QString
parameterStatusMsg
;
};
#endif // QGCUASPARAMMANAGER_H
src/uas/UAS.cc
View file @
d7137bbe
This diff is collapsed.
Click to expand it.
src/uas/UAS.h
View file @
d7137bbe
...
...
@@ -492,9 +492,7 @@ protected: //COMMENTS FOR TEST UNIT
/// PARAMETERS
QMap
<
int
,
QMap
<
QString
,
QVariant
>*
>
parameters
;
///< All parameters
bool
paramsOnceRequested
;
///< If the parameter list has been read at least once
QGCUASParamManager
*
paramManager
;
///< Parameter manager class
UASParameterDataModel
*
paramDataModel
;
///< The parameter data model for this UAS
UASParameterCommsMgr
*
paramCommsMgr
;
QGCUASParamManager
paramManager
;
///< Parameter manager for this UAS
/// SIMULATION
QGCHilLink
*
simulation
;
///< Hardware in the loop simulation link
...
...
@@ -515,36 +513,22 @@ public:
/** @brief Check if vehicle is armed */
bool
isArmed
()
const
{
return
systemIsArmed
;
}
/** @brief Get reference to the waypoint manager **/
UASWaypointManager
*
getWaypointManager
()
{
return
&
waypointManager
;
}
/** @brief Get reference to the param manager **/
QGCUASParamManager
*
getParamManager
()
const
{
return
paramManager
;
}
/** @brief Get reference to the parameter data model (same one shared with the parameter manager) **/
UASParameterDataModel
*
getParamDataModel
()
{
return
paramDataModel
;
}
UASParameterCommsMgr
*
getParamCommsMgr
()
{
return
paramCommsMgr
;
/** @brief Get reference to the param manager **/
virtual
QGCUASParamManager
*
getParamManager
()
{
return
&
paramManager
;
}
/** @brief Get the HIL simulation */
QGCHilLink
*
getHILSimulation
()
const
{
return
simulation
;
}
// TODO Will be removed
/** @brief Set reference to the param manager **/
void
setParamManager
(
QGCUASParamManager
*
manager
)
{
paramManager
=
manager
;
}
int
getSystemType
();
/**
...
...
@@ -953,6 +937,8 @@ protected:
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
quint64
getUnixReferenceTime
(
quint64
time
);
virtual
void
processParamValueMsg
(
mavlink_message_t
&
msg
,
const
QString
&
paramName
,
const
mavlink_param_value_t
&
rawValue
,
mavlink_param_union_t
&
paramValue
);
int
componentID
[
256
];
bool
componentMulti
[
256
];
bool
connectionLost
;
///< Flag indicates a timed out connection
...
...
src/uas/UASInterface.h
View file @
d7137bbe
...
...
@@ -154,18 +154,8 @@ public:
/** @brief Get reference to the waypoint manager **/
virtual
UASWaypointManager
*
getWaypointManager
(
void
)
=
0
;
/** @brief Access the parameter data model for this UAS (sans widget). This is the same parameter data model used by the parameter manager. **/
virtual
UASParameterDataModel
*
getParamDataModel
()
=
0
;
virtual
UASParameterCommsMgr
*
getParamCommsMgr
()
=
0
;
/** @brief Get reference to the param manager **/
virtual
QGCUASParamManager
*
getParamManager
()
const
=
0
;
// TODO Will be removed
/** @brief Set reference to the param manager **/
virtual
void
setParamManager
(
QGCUASParamManager
*
manager
)
=
0
;
virtual
QGCUASParamManager
*
getParamManager
()
=
0
;
/* COMMUNICATION FLAGS */
...
...
src/uas/UASParameterCommsMgr.cc
View file @
d7137bbe
...
...
@@ -18,7 +18,7 @@ UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent, UASInterface *uas) :
rewriteTimeout
(
1000
),
retransmissionBurstRequestSize
(
5
)
{
paramDataModel
=
mav
->
getParam
D
ataModel
();
paramDataModel
=
mav
->
getParam
Manager
()
->
d
ataModel
();
loadParamCommsSettings
();
...
...
@@ -60,15 +60,6 @@ void UASParameterCommsMgr::loadParamCommsSettings()
}
void
UASParameterCommsMgr
::
requestParameterListIfEmpty
()
{
int
totalOnboard
=
paramDataModel
->
countOnboardParams
();
if
(
totalOnboard
<
2
)
{
//TODO arbitrary constant, maybe 0 is OK?
requestParameterList
();
}
}
/**
* Send a request to deliver the list of onboard parameters
...
...
src/uas/UASParameterCommsMgr.h
View file @
d7137bbe
...
...
@@ -72,8 +72,6 @@ public slots:
/** @brief Request list of parameters from MAV */
virtual
void
requestParameterList
();
/** @brief Request a list of params onboard the MAV if the onboard param list we have is empty */
virtual
void
requestParameterListIfEmpty
();
/** @brief Check for missing parameters */
virtual
void
retransmissionGuardTick
();
...
...
src/ui/ParameterInterface.cc
View file @
d7137bbe
...
...
@@ -97,14 +97,15 @@ void ParameterInterface::addUAS(UASInterface* uas)
return
;
}
QGCParamWidget
*
param
=
new
QGCParamWidget
(
uas
,
this
);
param
->
init
();
QGCParamWidget
*
paramWidget
=
new
QGCParamWidget
(
this
);
paramWidget
=
(
QGCParamWidget
*
)
paramWidget
->
initWithUAS
(
uas
);
QString
ptrStr
;
ptrStr
.
sprintf
(
"QGCParamWidget %8p (parent %8p)"
,
param
,
this
);
ptrStr
.
sprintf
(
"QGCParamWidget %8p (parent %8p)"
,
param
Widget
,
this
);
qDebug
()
<<
"Created "
<<
ptrStr
<<
" for UAS id: "
<<
uasId
<<
" count: "
<<
paramWidgets
->
count
();
paramWidgets
->
insert
(
uasId
,
param
);
m_ui
->
stackedWidget
->
addWidget
(
param
);
paramWidgets
->
insert
(
uasId
,
param
Widget
);
m_ui
->
stackedWidget
->
addWidget
(
param
Widget
);
QGCSensorSettingsWidget
*
sensor
=
NULL
;
...
...
@@ -119,7 +120,7 @@ void ParameterInterface::addUAS(UASInterface* uas)
// Clear
if
(
m_ui
->
sensorSettings
&&
sensor
)
m_ui
->
sensorSettings
->
setCurrentWidget
(
sensor
);
m_ui
->
stackedWidget
->
setCurrentWidget
(
param
);
m_ui
->
stackedWidget
->
setCurrentWidget
(
param
Widget
);
curr
=
0
;
}
}
...
...
src/ui/QGCBaseParamWidget.cc
0 → 100644
View file @
d7137bbe
#include "QGCBaseParamWidget.h"
#include <QFileDialog>
#include <QFile>
#include <QVariant>
#include <QTextStream>>
#include "QGCUASParamManager.h"
#include "UASInterface.h"
QGCBaseParamWidget
::
QGCBaseParamWidget
(
QWidget
*
parent
)
:
QWidget
(
parent
),
mav
(
NULL
),
paramMgr
(
NULL
),
updatingParamNameLock
(
""
)
{
}
QGCBaseParamWidget
*
QGCBaseParamWidget
::
initWithUAS
(
UASInterface
*
uas
)
{
setUAS
(
uas
);
layoutWidget
();
return
this
;
}
void
QGCBaseParamWidget
::
setUAS
(
UASInterface
*
uas
)
{
if
(
mav
)
{
//TODO disconnect any connections as needed
disconnectViewSignalsAndSlots
();
disconnectFromParamManager
();
clearOnboardParamDisplay
();
clearPendingParamDisplay
();
}
mav
=
uas
;
connectToParamManager
();
connectViewSignalsAndSlots
();
paramMgr
->
requestParameterListIfEmpty
();
}
void
QGCBaseParamWidget
::
connectToParamManager
()
{
//TODO route via paramManager instead?
// Listen to updated param signals from the data model
connect
(
paramMgr
->
dataModel
(),
SIGNAL
(
parameterUpdated
(
int
,
QString
,
QVariant
)),
this
,
SLOT
(
handleOnboardParamUpdate
(
int
,
QString
,
QVariant
)));
connect
(
paramMgr
->
dataModel
(),
SIGNAL
(
pendingParamUpdate
(
int
,
const
QString
&
,
QVariant
,
bool
)),
this
,
SLOT
(
handlePendingParamUpdate
(
int
,
const
QString
&
,
QVariant
,
bool
)));
// Listen for param list reload finished
connect
(
paramMgr
,
SIGNAL
(
parameterListUpToDate
()),
this
,
SLOT
(
handleOnboardParameterListUpToDate
()));
// Listen to communications status messages so we can display them
connect
(
paramMgr
,
SIGNAL
(
parameterStatusMsgUpdated
(
QString
,
int
)),
this
,
SLOT
(
handleParamStatusMsgUpdate
(
QString
,
int
)));
}
void
QGCBaseParamWidget
::
disconnectFromParamManager
()
{
disconnect
(
paramMgr
->
dataModel
(),
SIGNAL
(
parameterUpdated
(
int
,
QString
,
QVariant
)),
this
,
SLOT
(
handleOnboardParamUpdate
(
int
,
QString
,
QVariant
)));
disconnect
(
paramMgr
->
dataModel
(),
SIGNAL
(
pendingParamUpdate
(
int
,
const
QString
&
,
QVariant
,
bool
)),
this
,
SLOT
(
handlePendingParamUpdate
(
int
,
const
QString
&
,
QVariant
,
bool
)));
disconnect
(
paramMgr
,
SIGNAL
(
parameterListUpToDate
()),
this
,
SLOT
(
handleOnboardParameterListUpToDate
()));
// Listen to communications status messages so we can display them
disconnect
(
paramMgr
,
SIGNAL
(
parameterStatusMsgUpdated
(
QString
,
int
)),
this
,
SLOT
(
handleParamStatusMsgUpdate
(
QString
,
int
)));
}
void
QGCBaseParamWidget
::
requestOnboardParamsUpdate
()
{
paramMgr
->
requestParameterList
();
}
void
QGCBaseParamWidget
::
saveParametersToFile
()
{
if
(
!
mav
)
return
;
QString
fileName
=
QFileDialog
::
getSaveFileName
(
this
,
tr
(
"Save File"
),
"./parameters.txt"
,
tr
(
"Parameter File (*.txt)"
));
QFile
file
(
fileName
);
if
(
!
file
.
open
(
QIODevice
::
WriteOnly
|
QIODevice
::
Text
))
{
return
;
}
QTextStream
outstream
(
&
file
);
paramMgr
->
writeOnboardParamsToStream
(
outstream
,
mav
->
getUASName
());
file
.
close
();
}
void
QGCBaseParamWidget
::
loadParametersFromFile
()
{
if
(
!
mav
)
return
;
QString
fileName
=
QFileDialog
::
getOpenFileName
(
this
,
tr
(
"Load File"
),
"."
,
tr
(
"Parameter file (*.txt)"
));
QFile
file
(
fileName
);
if
(
!
file
.
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
return
;
QTextStream
in
(
&
file
);
paramMgr
->
readPendingParamsFromStream
(
in
);
file
.
close
();
}
src/ui/QGCBaseParamWidget.h
0 → 100644
View file @
d7137bbe
#ifndef QGCBASEPARAMWIDGET_H
#define QGCBASEPARAMWIDGET_H
#include <QVariant>
#include <QWidget>
//forward declarations
class
QGCUASParamManager
;
class
UASInterface
;
class
QGCBaseParamWidget
:
public
QWidget
{
Q_OBJECT
public:
explicit
QGCBaseParamWidget
(
QWidget
*
parent
=
0
);
virtual
QGCBaseParamWidget
*
initWithUAS
(
UASInterface
*
uas
);
///< Two-stage construction: initialize this object
virtual
void
setUAS
(
UASInterface
*
uas
);
///< Allows swapping the underlying UAS
protected:
virtual
void
setParameterStatusMsg
(
const
QString
&
msg
)
=
0
;
virtual
void
layoutWidget
()
=
0
;
///< Layout the appearance of this widget
virtual
void
connectViewSignalsAndSlots
()
=
0
;
///< Connect view signals/slots as needed
virtual
void
disconnectViewSignalsAndSlots
()
=
0
;
///< Disconnect view signals/slots as needed
virtual
void
connectToParamManager
();
///>Connect to any required param manager signals
virtual
void
disconnectFromParamManager
();
///< Disconnect from any connected param manager signals
signals:
public
slots
:
virtual
void
handleOnboardParamUpdate
(
int
component
,
const
QString
&
parameterName
,
QVariant
value
)
=
0
;
virtual
void
handlePendingParamUpdate
(
int
compId
,
const
QString
&
paramName
,
QVariant
value
,
bool
isPending
)
=
0
;
virtual
void
handleOnboardParameterListUpToDate
()
=
0
;
virtual
void
handleParamStatusMsgUpdate
(
QString
msg
,
int
level
)
=
0
;
/** @brief Clear the rendering of onboard parameters */
virtual
void
clearOnboardParamDisplay
()
=
0
;
/** @brief Clear the rendering of pending parameters */
virtual
void
clearPendingParamDisplay
()
=
0
;
/** @brief Request list of parameters from MAV */
virtual
void
requestOnboardParamsUpdate
();
/** @brief Store parameters to a file */
virtual
void
saveParametersToFile
();
/** @brief Load parameters from a file */
virtual
void
loadParametersFromFile
();
protected:
QGCUASParamManager
*
paramMgr
;
UASInterface
*
mav
;
QString
updatingParamNameLock
;
///< Name of param currently being updated-- used for reducing echo on param change
};
#endif // QGCBASEPARAMWIDGET_H
src/ui/QGCPX4VehicleConfig.cc
View file @
d7137bbe
...
...
@@ -84,7 +84,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
//connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions()));
//TODO connect buttons here to save/clear actions?
ui
->
pendingCommitsWidget
->
init
(
);
ui
->
pendingCommitsWidget
->
init
WithUAS
(
this
->
mav
);
ui
->
pendingCommitsWidget
->
update
();
//TODO the following methods are not yet implemented
...
...
@@ -798,11 +798,11 @@ void QGCPX4VehicleConfig::loadConfig()
}
if
(
!
paramTooltips
.
isEmpty
())
{
mav
->
getParamManager
()
->
setParamDescriptions
(
paramTooltips
);
paramMgr
->
setParamDescriptions
(
paramTooltips
);
}
doneLoadingConfig
=
true
;
//Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished.
param
Comms
Mgr
->
requestParameterListIfEmpty
();
paramMgr
->
requestParameterListIfEmpty
();
}
void
QGCPX4VehicleConfig
::
setActiveUAS
(
UASInterface
*
active
)
...
...
@@ -828,6 +828,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
if
(
mav
)
{
// Disconnect old system
disconnect
(
mav
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanged
(
int
,
float
)));
...
...
@@ -835,7 +836,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
disconnect
(
mav
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
disconnect
(
ui
->
refreshButton
,
SIGNAL
(
clicked
()),
param
Comms
Mgr
,
SLOT
(
requestParameterList
()));
paramMgr
,
SLOT
(
requestParameterList
()));
// Delete all children from all fixed tabs.
foreach
(
QWidget
*
child
,
ui
->
generalLeftContents
->
findChildren
<
QWidget
*>
())
{
...
...
@@ -868,22 +869,23 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
// Connect new system
mav
=
active
;
paramCommsMgr
=
mav
->
getParamCommsMgr
();
paramMgr
=
mav
->
getParamManager
();
// Reset current state
resetCalibrationRC
();
requestCalibrationRC
();
//TODO eliminate the separate RC_TYPE call
mav
->
requestParameter
(
0
,
"RC_TYPE"
);
chanCount
=
0
;
//TODO get parameter changes via Param Mgr instead
// Connect new system
connect
(
mav
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanged
(
int
,
float
)));
connect
(
mav
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
connect
(
ui
->
refreshButton
,
SIGNAL
(
clicked
()),
param
Comms
Mgr
,
SLOT
(
requestParameterList
()));
paramMgr
,
SLOT
(
requestParameterList
()));
if
(
systemTypeToParamMap
.
contains
(
mav
->
getSystemTypeName
()))
{
paramToWidgetMap
=
systemTypeToParamMap
[
mav
->
getSystemTypeName
()];
...
...
@@ -978,9 +980,7 @@ void QGCPX4VehicleConfig::writeCalibrationRC()
void
QGCPX4VehicleConfig
::
requestCalibrationRC
()
{
if
(
paramCommsMgr
)
{
paramCommsMgr
->
requestRcCalibrationParamsUpdate
();
}
paramMgr
->
requestRcCalibrationParamsUpdate
();
}
void
QGCPX4VehicleConfig
::
writeParameters
()
...
...
src/ui/QGCPX4VehicleConfig.h
View file @
d7137bbe
...
...
@@ -161,7 +161,7 @@ protected slots:
protected:
bool
doneLoadingConfig
;
UASInterface
*
mav
;
///< The current MAV
UASParameterCommsMgr
*
paramCommsMgr
;
///< param com
ms mgr for the mav
QGCUASParamManager
*
paramMgr
;
///< para
ms mgr for the mav
static
const
unsigned
int
chanMax
=
8
;
///< Maximum number of channels
unsigned
int
chanCount
;
///< Actual channels
int
rcType
;
///< Type of the remote control
...
...
src/ui/QGCParamWidget.cc
View file @
d7137bbe
This diff is collapsed.
Click to expand it.
src/ui/QGCParamWidget.h
View file @
d7137bbe
...
...
@@ -37,64 +37,54 @@ This file is part of the QGROUNDCONTROL project
#include <QLabel>
#include <QTimer>
#include "QGCUASParamManager.h"
#include "UASInterface.h"
#include "QGCBaseParamWidget.h"
//forward declarations
class
UASInterface
;
/**
* @brief Widget to read/set onboard parameters
*/
class
QGCParamWidget
:
public
QGC
UASParamManager
class
QGCParamWidget
:
public
QGC
BaseParamWidget
{
Q_OBJECT
public:
QGCParamWidget
(
UASInterface
*
uas
,
QWidget
*
parent
=
0
);
virtual
void
init
();
///< Two-stage construction: initialize the object
QGCParamWidget
(
QWidget
*
parent
=
0
);
protected:
virtual
void
setParameterStatusMsg
(
const
QString
&
msg
);
virtual
void
layoutWidget
();
///< Layout the appearance of this widget
virtual
void
connectSignalsAndSlots
();
///< Connect signals/slots as needed
virtual
void
connectViewSignalsAndSlots
();
///< Connect view signals/slots as needed
virtual
void
disconnectViewSignalsAndSlots
();
///< Connect view signals/slots as needed
virtual
QTreeWidgetItem
*
getParentWidgetItemForParam
(
int
compId
,
const
QString
&
paramName
);
virtual
QTreeWidgetItem
*
findChildWidgetItemForParam
(
QTreeWidgetItem
*
parentItem
,
const
QString
&
paramName
);
signals: