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
4bfb3701
Commit
4bfb3701
authored
Mar 29, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Switched to ParameterLoader, added component id support
parent
4b128fba
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
397 additions
and
2 deletions
+397
-2
qgroundcontrol.pro
qgroundcontrol.pro
+2
-2
ParameterLoader.cc
src/FactSystem/ParameterLoader.cc
+282
-0
ParameterLoader.h
src/FactSystem/ParameterLoader.h
+113
-0
No files found.
qgroundcontrol.pro
View file @
4bfb3701
...
...
@@ -776,7 +776,7 @@ HEADERS += \
src
/
FactSystem
/
FactBinder
.
h
\
src
/
FactSystem
/
FactMetaData
.
h
\
src
/
FactSystem
/
FactValidator
.
h
\
src
/
FactSystem
/
Fact
Loader
.
h
\
src
/
FactSystem
/
Parameter
Loader
.
h
\
SOURCES
+=
\
src
/
FactSystem
/
FactSystem
.
cc
\
...
...
@@ -784,4 +784,4 @@ SOURCES += \
src
/
FactSystem
/
FactBinder
.
cc
\
src
/
FactSystem
/
FactMetaData
.
cc
\
src
/
FactSystem
/
FactValidator
.
cc
\
src
/
FactSystem
/
Fact
Loader
.
cc
\
src
/
FactSystem
/
Parameter
Loader
.
cc
\
src/FactSystem/
Fact
Loader.cc
→
src/FactSystem/
Parameter
Loader.cc
View file @
4bfb3701
...
...
@@ -24,20 +24,20 @@
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "
Fact
Loader.h"
#include "
Parameter
Loader.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include <QFile>
#include <QDebug>
QGC_LOGGING_CATEGORY
(
FactLoaderLog
,
"Fact
LoaderLog"
)
QGC_LOGGING_CATEGORY
(
ParameterLoaderLog
,
"Parameter
LoaderLog"
)
FactLoader
::
Fact
Loader
(
UASInterface
*
uas
,
QObject
*
parent
)
:
ParameterLoader
::
Parameter
Loader
(
UASInterface
*
uas
,
QObject
*
parent
)
:
QObject
(
parent
),
_lastSeenComponent
(
-
1
),
_paramMgr
(
NULL
),
_factsReady
(
false
)
_parametersReady
(
false
),
_defaultComponentId
(
FactSystem
::
defaultComponentId
)
{
Q_ASSERT
(
uas
);
...
...
@@ -53,32 +53,37 @@ FactLoader::FactLoader(UASInterface* uas, QObject* parent) :
connect
(
_paramMgr
,
SIGNAL
(
parameterListUpToDate
()),
this
,
SLOT
(
_paramMgrParameterListUpToDate
()));
// We track parameters changes to keep Facts up to date.
connect
(
uas
,
&
UASInterface
::
parameterUpdate
,
this
,
&
Fact
Loader
::
_parameterUpdate
);
connect
(
uas
,
&
UASInterface
::
parameterUpdate
,
this
,
&
Parameter
Loader
::
_parameterUpdate
);
}
FactLoader
::~
Fact
Loader
()
ParameterLoader
::~
Parameter
Loader
()
{
}
/// Called whenever a parameter is updated or first seen.
void
FactLoader
::
_parameterUpdate
(
int
uas
,
int
component
,
QString
parameterName
,
int
mavType
,
QVariant
value
)
void
ParameterLoader
::
_parameterUpdate
(
int
uas
,
int
componentId
,
QString
parameterName
,
int
mavType
,
QVariant
value
)
{
bool
setMetaData
=
false
;
// Is this for our uas?
if
(
uas
!=
_uasId
)
{
return
;
}
if
(
_lastSeenComponent
==
-
1
)
{
_lastSeenComponent
=
component
;
}
else
{
// Code cannot handle parameters coming form different components yets
Q_ASSERT
(
component
==
_lastSeenComponent
);
// Attempt to determine default component id
if
(
_defaultComponentId
==
FactSystem
::
defaultComponentId
&&
_defaultComponentIdParam
.
isEmpty
())
{
_defaultComponentIdParam
=
getDefaultComponentIdParam
();
}
if
(
!
_defaultComponentIdParam
.
isEmpty
()
&&
_defaultComponentIdParam
==
parameterName
)
{
_defaultComponentId
=
componentId
;
}
bool
setMetaData
=
false
;
if
(
!
_mapParameterName2Variant
.
contains
(
parameterName
))
{
qCDebug
(
FactLoaderLog
)
<<
"Adding new fact"
<<
parameterName
;
if
(
!
_mapParameterName2Variant
.
contains
(
componentId
)
||
!
_mapParameterName2Variant
[
componentId
].
contains
(
parameterName
))
{
// These should not get our of sync
Q_ASSERT
(
_mapParameterName2Variant
.
contains
(
componentId
)
==
_mapFact2ParameterName
.
contains
(
componentId
));
qCDebug
(
ParameterLoaderLog
)
<<
"Adding new fact (component:"
<<
componentId
<<
"name:"
<<
parameterName
<<
")"
;
FactMetaData
::
ValueType_t
factType
;
switch
(
mavType
)
{
...
...
@@ -112,21 +117,21 @@ void FactLoader::_parameterUpdate(int uas, int component, QString parameterName,
break
;
}
Fact
*
fact
=
new
Fact
(
parameterName
,
factType
,
this
);
Fact
*
fact
=
new
Fact
(
componentId
,
parameterName
,
factType
,
this
);
setMetaData
=
true
;
_mapParameterName2Variant
[
parameterName
]
=
QVariant
::
fromValue
(
fact
);
_mapFact2ParameterName
[
fact
]
=
parameterName
;
_mapParameterName2Variant
[
componentId
][
parameterName
]
=
QVariant
::
fromValue
(
fact
);
_mapFact2ParameterName
[
componentId
][
fact
]
=
parameterName
;
// We need to know when the fact changes from QML so that we can send the new value to the parameter manager
connect
(
fact
,
&
Fact
::
_containerValueChanged
,
this
,
&
Fact
Loader
::
_valueUpdated
);
connect
(
fact
,
&
Fact
::
_containerValueChanged
,
this
,
&
Parameter
Loader
::
_valueUpdated
);
}
Q_ASSERT
(
_mapParameterName2Variant
.
contains
(
parameterName
));
Q_ASSERT
(
_mapParameterName2Variant
[
componentId
]
.
contains
(
parameterName
));
qCDebug
(
FactLoaderLog
)
<<
"Updating fact value"
<<
parameterName
<<
value
;
qCDebug
(
ParameterLoaderLog
)
<<
"Updating fact value (component:"
<<
componentId
<<
"name:"
<<
parameterName
<<
value
<<
")"
;
Fact
*
fact
=
_mapParameterName2Variant
[
parameterName
].
value
<
Fact
*>
();
Fact
*
fact
=
_mapParameterName2Variant
[
componentId
][
parameterName
].
value
<
Fact
*>
();
Q_ASSERT
(
fact
);
fact
->
_containerSetValue
(
value
);
...
...
@@ -138,14 +143,16 @@ void FactLoader::_parameterUpdate(int uas, int component, QString parameterName,
/// Connected to Fact::valueUpdated
///
/// Sets the new value into the Parameter Manager. Parameter is persisted after send.
void
Fact
Loader
::
_valueUpdated
(
const
QVariant
&
value
)
void
Parameter
Loader
::
_valueUpdated
(
const
QVariant
&
value
)
{
Fact
*
fact
=
qobject_cast
<
Fact
*>
(
sender
());
Q_ASSERT
(
fact
);
Q_ASSERT
(
_lastSeenComponent
!=
-
1
);
int
componentId
=
fact
->
componentId
();
Q_ASSERT
(
_paramMgr
);
Q_ASSERT
(
_mapFact2ParameterName
.
contains
(
fact
));
Q_ASSERT
(
_mapFact2ParameterName
.
contains
(
componentId
));
Q_ASSERT
(
_mapFact2ParameterName
[
componentId
].
contains
(
fact
));
QVariant
typedValue
;
switch
(
fact
->
type
())
{
...
...
@@ -170,17 +177,17 @@ void FactLoader::_valueUpdated(const QVariant& value)
break
;
}
qCDebug
(
FactLoaderLog
)
<<
"Set parameter"
<<
fact
->
name
()
<<
typedValue
;
qCDebug
(
ParameterLoaderLog
)
<<
"Set parameter (componentId:"
<<
componentId
<<
"name:"
<<
fact
->
name
()
<<
typedValue
<<
")"
;
_paramMgr
->
setParameter
(
_lastSeenComponent
,
_mapFact2ParameterName
[
fact
]
,
typedValue
);
_paramMgr
->
setParameter
(
componentId
,
fact
->
name
()
,
typedValue
);
_paramMgr
->
sendPendingParameters
(
true
/* persistAfterSend */
,
false
/* forceSend */
);
}
// Called when param mgr list is up to date
void
Fact
Loader
::
_paramMgrParameterListUpToDate
(
void
)
void
Parameter
Loader
::
_paramMgrParameterListUpToDate
(
void
)
{
if
(
!
_
fact
sReady
)
{
_
fact
sReady
=
true
;
if
(
!
_
parameter
sReady
)
{
_
parameter
sReady
=
true
;
// We don't need this any more
disconnect
(
_paramMgr
,
SIGNAL
(
parameterListUpToDate
()),
this
,
SLOT
(
_paramMgrParameterListUpToDate
()));
...
...
@@ -188,13 +195,88 @@ void FactLoader::_paramMgrParameterListUpToDate(void)
// There may be parameterUpdated signals still in our queue. Flush them out.
qgcApp
()
->
processEvents
();
// We should have all paramters now so we can signal ready
emit
factsReady
();
_determineDefaultComponentId
();
// We should have all parameters now so we can signal ready
emit
parametersReady
();
}
}
void
Fact
Loader
::
_addMetaDataToFact
(
Fact
*
fact
)
void
Parameter
Loader
::
_addMetaDataToFact
(
Fact
*
fact
)
{
FactMetaData
*
metaData
=
new
FactMetaData
(
this
);
metaData
->
initFromTypeOnly
(
fact
->
type
());
}
void
ParameterLoader
::
refreshAllParameters
(
void
)
{
Q_ASSERT
(
_paramMgr
);
_paramMgr
->
requestParameterList
();
}
void
ParameterLoader
::
_determineDefaultComponentId
(
void
)
{
if
(
_defaultComponentId
==
FactSystem
::
defaultComponentId
)
{
// We don't have a default component id yet. That means the plugin can't provide
// the param to trigger off of. Instead we use the most prominent component id in
// the set of parameters. Better than nothing!
_defaultComponentId
=
-
1
;
foreach
(
int
componentId
,
_mapParameterName2Variant
.
keys
())
{
if
(
_mapParameterName2Variant
[
componentId
].
count
()
>
_defaultComponentId
)
{
_defaultComponentId
=
componentId
;
}
}
Q_ASSERT
(
_defaultComponentId
!=
-
1
);
}
}
/// Translates FactSystem::defaultComponentId to real component id if needed
int
ParameterLoader
::
_actualComponentId
(
int
componentId
)
{
if
(
componentId
==
FactSystem
::
defaultComponentId
)
{
componentId
=
_defaultComponentId
;
Q_ASSERT
(
componentId
!=
FactSystem
::
defaultComponentId
);
}
return
componentId
;
}
void
ParameterLoader
::
refreshParameter
(
int
componentId
,
const
QString
&
name
)
{
Q_ASSERT
(
_paramMgr
);
_paramMgr
->
requestParameterUpdate
(
_actualComponentId
(
componentId
),
name
);
}
void
ParameterLoader
::
refreshParametersPrefix
(
int
componentId
,
const
QString
&
namePrefix
)
{
Q_ASSERT
(
_paramMgr
);
componentId
=
_actualComponentId
(
componentId
);
Q_ASSERT
(
_mapFact2ParameterName
.
contains
(
componentId
));
foreach
(
QString
name
,
_mapParameterName2Variant
[
componentId
].
keys
())
{
if
(
name
.
startsWith
(
namePrefix
))
{
refreshParameter
(
componentId
,
name
);
}
}
}
bool
ParameterLoader
::
factExists
(
int
componentId
,
const
QString
&
name
)
{
componentId
=
_actualComponentId
(
componentId
);
if
(
_mapParameterName2Variant
.
contains
(
componentId
))
{
return
_mapParameterName2Variant
[
componentId
].
contains
(
name
);
}
return
false
;
}
Fact
*
ParameterLoader
::
getFact
(
int
componentId
,
const
QString
&
name
)
{
componentId
=
_actualComponentId
(
componentId
);
Q_ASSERT
(
_mapParameterName2Variant
.
contains
(
componentId
));
Q_ASSERT
(
_mapParameterName2Variant
[
componentId
].
contains
(
name
));
Fact
*
fact
=
_mapParameterName2Variant
[
componentId
][
name
].
value
<
Fact
*>
();
Q_ASSERT
(
fact
);
return
fact
;
}
src/FactSystem/
Fact
Loader.h
→
src/FactSystem/
Parameter
Loader.h
View file @
4bfb3701
...
...
@@ -21,42 +21,62 @@
======================================================================*/
#ifndef
FactLoader_h
#define
FactLoader_h
#ifndef
PARAMETERLOADER_H
#define
PARAMETERLOADER_H
#include <QObject>
#include <QMap>
#include <QXmlStreamReader>
#include <QLoggingCategory>
#include "Fact.h"
#include "Fact
System
.h"
#include "UASInterface.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY
(
Fact
LoaderLog
)
Q_DECLARE_LOGGING_CATEGORY
(
Parameter
LoaderLog
)
/// Connects to Parameter Manager to load/update Facts
class
Fact
Loader
:
public
QObject
class
Parameter
Loader
:
public
QObject
{
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
Fact
Loader
(
UASInterface
*
uas
,
QObject
*
parent
=
NULL
);
Parameter
Loader
(
UASInterface
*
uas
,
QObject
*
parent
=
NULL
);
~
Fact
Loader
();
~
Parameter
Loader
();
/// Returns true if the full set of facts are ready
bool
factsAreReady
(
void
)
{
return
_factsReady
;
}
/// Returns the fact QVariantMap
const
QVariantMap
&
factMap
(
void
)
{
return
_mapParameterName2Variant
;
}
bool
parametersAreReady
(
void
)
{
return
_parametersReady
;
}
/// Re-request the full set of parameters from the autopilot
void
refreshAllParameters
(
void
);
/// Request a refresh on the specific parameter
void
refreshParameter
(
int
componentId
,
const
QString
&
name
);
/// Request a refresh on all parameters that begin with the specified prefix
void
refreshParametersPrefix
(
int
componentId
,
const
QString
&
namePrefix
);
/// Returns true if the specifed fact exists
bool
factExists
(
int
componentId
,
///< fact component, -1=default component
const
QString
&
name
);
///< fact name
/// Returns the specified Fact.
/// WARNING: Will assert if fact does not exists. If that possibily exists, check for existince first with
/// factExists.
Fact
*
getFact
(
int
componentId
,
///< fact component, -1=default component
const
QString
&
name
);
///< fact name
/// Return the parameter for which the default component id is derived from. Return an empty
/// string is this is not available.
virtual
QString
getDefaultComponentIdParam
(
void
)
const
=
0
;
signals:
/// Signalled when the full set of facts are ready
void
fact
sReady
(
void
);
void
parameter
sReady
(
void
);
protected:
/// Base implementation adds generic meta data based on variant type. Derived class can override to provide
...
...
@@ -64,23 +84,30 @@ protected:
virtual
void
_addMetaDataToFact
(
Fact
*
fact
);
private
slots
:
void
_parameterUpdate
(
int
uas
,
int
component
,
QString
parameterName
,
int
mavType
,
QVariant
value
);
void
_parameterUpdate
(
int
uas
,
int
component
Id
,
QString
parameterName
,
int
mavType
,
QVariant
value
);
void
_valueUpdated
(
const
QVariant
&
value
);
void
_paramMgrParameterListUpToDate
(
void
);
private:
static
QVariant
_stringToTypedVariant
(
const
QString
&
string
,
FactMetaData
::
ValueType_t
type
,
bool
failOk
=
false
);
int
_actualComponentId
(
int
componentId
);
void
_determineDefaultComponentId
(
void
);
QMap
<
Fact
*
,
QString
>
_mapFact2ParameterName
;
///< Maps from a Fact to a parameter name
/// First mapping is by component id
/// Second mapping is parameter name, to Fact
QMap
<
int
,
QMap
<
Fact
*
,
QString
>
>
_mapFact2ParameterName
;
int
_uasId
;
///< Id for uas which this set of Facts are associated with
int
_lastSeenComponent
;
QGCUASParamManagerInterface
*
_paramMgr
;
QVariantMap
_mapParameterName2Variant
;
/// First mapping id\s by component id
/// Second mapping is parameter name, to Fact* in QVariant
QMap
<
int
,
QVariantMap
>
_mapParameterName2Variant
;
bool
_factsReady
;
///< All facts received from param mgr
bool
_parametersReady
;
///< All params received from param mgr
int
_defaultComponentId
;
QString
_defaultComponentIdParam
;
};
#endif
\ No newline at end of file
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