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
cc520f07
Unverified
Commit
cc520f07
authored
Jun 06, 2019
by
Don Gagne
Committed by
GitHub
Jun 06, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7498 from DonLakeFlyer/ParameterMetaData
Parameter meta data cleanup
parents
07e72c2b
9e754647
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
30 additions
and
16 deletions
+30
-16
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+7
-2
APMParameterMetaData.cc
src/FirmwarePlugin/APM/APMParameterMetaData.cc
+2
-0
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+1
-0
PX4ParameterMetaData.cc
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
+19
-14
PX4ParameterMetaData.h
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
+1
-0
No files found.
src/FactSystem/ParameterManager.cc
View file @
cc520f07
...
...
@@ -1177,7 +1177,7 @@ void ParameterManager::_initialRequestTimeout(void)
QString
ParameterManager
::
parameterMetaDataFile
(
Vehicle
*
vehicle
,
MAV_AUTOPILOT
firmwareType
,
int
wantedMajorVersion
,
int
&
majorVersion
,
int
&
minorVersion
)
{
bool
cacheHit
=
false
;
FirmwarePlugin
*
plugin
=
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
()
->
firmwarePluginForAutopilot
(
firmwareType
,
MAV_TYPE_QUADROTOR
);
FirmwarePlugin
*
plugin
=
vehicle
->
firmwarePlugin
(
);
// Cached files are stored in settings location
QSettings
settings
;
...
...
@@ -1272,7 +1272,12 @@ QString ParameterManager::parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT
void
ParameterManager
::
cacheMetaDataFile
(
const
QString
&
metaDataFile
,
MAV_AUTOPILOT
firmwareType
)
{
FirmwarePlugin
*
plugin
=
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
()
->
firmwarePluginForAutopilot
(
firmwareType
,
MAV_TYPE_QUADROTOR
);
// In order to call FirmwarePlugin::getParameterMetaDataVersionInfo we need the firmware plugin. But at this point we do not have a vehicle associated
// with the call. Since the call to FirmwarePlugin::getParameterMetaDataVersionInfo is invariant to vehicle type we just need to use any one of the
// supported vehicle types to get the correct FirmwarePlugin.
MAV_TYPE
anySupportedVehicleType
=
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
()
->
supportedVehicleTypes
(
firmwareType
)[
0
];
FirmwarePlugin
*
plugin
=
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
()
->
firmwarePluginForAutopilot
(
firmwareType
,
anySupportedVehicleType
);
int
newMajorVersion
,
newMinorVersion
;
plugin
->
getParameterMetaDataVersionInfo
(
metaDataFile
,
newMajorVersion
,
newMinorVersion
);
...
...
src/FirmwarePlugin/APM/APMParameterMetaData.cc
View file @
cc520f07
...
...
@@ -611,5 +611,7 @@ void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDa
if
(
regExp
.
exactMatch
(
metaDataFile
)
&&
regExp
.
captureCount
()
==
2
)
{
majorVersion
=
regExp
.
cap
(
2
).
toInt
();
minorVersion
=
0
;
}
else
{
qWarning
()
<<
QStringLiteral
(
"Unable to parse version from parameter meta data file name: '%1'"
).
arg
(
metaDataFile
);
}
}
src/FirmwarePlugin/FirmwarePlugin.h
View file @
cc520f07
...
...
@@ -207,6 +207,7 @@ public:
virtual
QString
getVersionParam
(
void
)
{
return
QString
();
}
/// Returns the parameter set version info pulled from inside the meta data file. -1 if not found.
/// Note: The implementation for this must not vary by vehicle type.
virtual
void
getParameterMetaDataVersionInfo
(
const
QString
&
metaDataFile
,
int
&
majorVersion
,
int
&
minorVersion
);
/// Returns the internal resource parameter meta date file.
...
...
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
View file @
cc520f07
...
...
@@ -112,7 +112,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
QString
factGroup
;
QString
errorString
;
FactMetaData
*
metaData
=
NULL
;
FactMetaData
*
metaData
=
nullptr
;
int
xmlState
=
XmlStateNone
;
bool
badMetaData
=
true
;
...
...
@@ -392,7 +392,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
}
// Reset for next parameter
metaData
=
NULL
;
metaData
=
nullptr
;
badMetaData
=
false
;
xmlState
=
XmlStateFoundGroup
;
}
else
if
(
elementName
==
"group"
)
{
...
...
@@ -412,7 +412,7 @@ FactMetaData* PX4ParameterMetaData::getMetaDataForFact(const QString& name, MAV_
if
(
_mapParameterName2FactMetaData
.
contains
(
name
))
{
return
_mapParameterName2FactMetaData
[
name
];
}
else
{
return
NULL
;
return
nullptr
;
}
}
...
...
@@ -428,27 +428,28 @@ void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
void
PX4ParameterMetaData
::
getParameterMetaDataVersionInfo
(
const
QString
&
metaDataFile
,
int
&
majorVersion
,
int
&
minorVersion
)
{
QFile
xmlFile
(
metaDataFile
);
QString
errorString
;
majorVersion
=
-
1
;
minorVersion
=
-
1
;
if
(
!
xmlFile
.
exists
())
{
qWarning
()
<<
"Internal error: metaDataFile mission"
<<
metaDataFile
;
_outputFileWarning
(
metaDataFile
,
QStringLiteral
(
"Does not exist"
),
QString
())
;
return
;
}
if
(
!
xmlFile
.
open
(
QIODevice
::
ReadOnly
))
{
qWarning
()
<<
"Internal error: Unable to open parameter file:"
<<
metaDataFile
<<
xmlFile
.
errorString
(
);
_outputFileWarning
(
metaDataFile
,
QStringLiteral
(
"Unable to open file"
),
xmlFile
.
errorString
()
);
return
;
}
QXmlStreamReader
xml
(
xmlFile
.
readAll
());
xmlFile
.
close
();
if
(
xml
.
hasError
())
{
qWarning
()
<<
"Badly formed XML"
<<
xml
.
errorString
(
);
_outputFileWarning
(
metaDataFile
,
QStringLiteral
(
"Badly formed XML"
),
xml
.
errorString
()
);
return
;
}
majorVersion
=
-
1
;
minorVersion
=
-
1
;
while
(
!
xml
.
atEnd
()
&&
(
majorVersion
==
-
1
||
minorVersion
==
-
1
))
{
if
(
xml
.
isStartElement
())
{
QString
elementName
=
xml
.
name
().
toString
();
...
...
@@ -458,7 +459,7 @@ void PX4ParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDa
QString
strVersion
=
xml
.
readElementText
();
majorVersion
=
strVersion
.
toInt
(
&
convertOk
);
if
(
!
convertOk
)
{
qWarning
()
<<
"Badly formed XML"
;
_outputFileWarning
(
metaDataFile
,
QStringLiteral
(
"Unable to convert parameter_version_major value to int"
),
QString
())
;
return
;
}
}
else
if
(
elementName
==
"parameter_version_minor"
)
{
...
...
@@ -466,7 +467,7 @@ void PX4ParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDa
QString
strVersion
=
xml
.
readElementText
();
minorVersion
=
strVersion
.
toInt
(
&
convertOk
);
if
(
!
convertOk
)
{
qWarning
()
<<
"Badly formed XML"
;
_outputFileWarning
(
metaDataFile
,
QStringLiteral
(
"Unable to convert parameter_version_minor value to int"
),
QString
())
;
return
;
}
}
...
...
@@ -474,11 +475,15 @@ void PX4ParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDa
xml
.
readNext
();
}
// Assume defaults if not found
if
(
majorVersion
==
-
1
)
{
majorVersion
=
1
;
_outputFileWarning
(
metaDataFile
,
QStringLiteral
(
"parameter_version_major is missing"
),
QString
())
;
}
if
(
minorVersion
==
-
1
)
{
minorVersion
=
1
;
_outputFileWarning
(
metaDataFile
,
QStringLiteral
(
"parameter_version_minor tag is missing"
),
QString
())
;
}
}
void
PX4ParameterMetaData
::
_outputFileWarning
(
const
QString
&
metaDataFile
,
const
QString
&
error1
,
const
QString
&
error2
)
{
qWarning
()
<<
QStringLiteral
(
"Internal Error: Parameter meta data file '%1'. %2. error: %3"
).
arg
(
metaDataFile
).
arg
(
error1
).
arg
(
error2
);
}
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
View file @
cc520f07
...
...
@@ -50,6 +50,7 @@ private:
};
QVariant
_stringToTypedVariant
(
const
QString
&
string
,
FactMetaData
::
ValueType_t
type
,
bool
*
convertOk
);
static
void
_outputFileWarning
(
const
QString
&
metaDataFile
,
const
QString
&
error1
,
const
QString
&
error2
);
bool
_parameterMetaDataLoaded
;
///< true: parameter meta data already loaded
QMap
<
QString
,
FactMetaData
*>
_mapParameterName2FactMetaData
;
///< Maps from a parameter name to FactMetaData
...
...
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