Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
781997b2
Commit
781997b2
authored
Dec 14, 2015
by
Don Gagne
Browse files
Merge pull request #2395 from pritamghanghas/apm_metadata
Apm metadata
parents
fc853305
159bce05
Changes
15
Expand all
Show whitespace changes
Inline
Side-by-side
qgcresources.qrc
View file @
781997b2
...
...
@@ -209,4 +209,7 @@
<file alias="ParameterFactMetaData.xml">src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml</file>
</qresource>
<qresource prefix="/FirmwarePlugin/APM">
<file alias="apm.pdef.xml">src/FirmwarePlugin/APM/apm.pdef.xml</file>
</qresource>
</RCC>
src/FactSystem/FactMetaData.cc
View file @
781997b2
...
...
@@ -121,7 +121,9 @@ void FactMetaData::setMin(const QVariant& min)
_min
=
min
;
_minIsDefaultForType
=
false
;
}
else
{
qWarning
()
<<
"Attempt to set min below allowable value"
;
qWarning
()
<<
"Attempt to set min below allowable value for fact: "
<<
name
()
<<
", value attempted: "
<<
min
<<
", type: "
<<
type
()
<<
", min for type: "
<<
_minForType
();
_min
=
_minForType
();
}
}
...
...
@@ -189,7 +191,7 @@ QVariant FactMetaData::_maxForType(void) const
bool
FactMetaData
::
convertAndValidate
(
const
QVariant
&
value
,
bool
convertOnly
,
QVariant
&
typedValue
,
QString
&
errorString
)
{
bool
convertOk
;
bool
convertOk
=
false
;
errorString
.
clear
();
...
...
@@ -236,7 +238,7 @@ bool FactMetaData::convertAndValidate(const QVariant& value, bool convertOnly, Q
}
if
(
!
convertOk
)
{
errorString
=
"Invalid number"
;
errorString
+
=
"Invalid number"
;
}
return
convertOk
&&
errorString
.
isEmpty
();
...
...
src/FactSystem/ParameterLoader.cc
View file @
781997b2
...
...
@@ -254,7 +254,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
fact
->
_containerSetRawValue
(
value
);
if
(
setMetaData
)
{
_vehicle
->
firmwarePlugin
()
->
addMetaDataToFact
(
fact
);
_vehicle
->
firmwarePlugin
()
->
addMetaDataToFact
(
fact
,
_vehicle
->
vehicleType
()
);
}
_dataMutex
.
unlock
();
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
781997b2
...
...
@@ -405,11 +405,12 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
return
true
;
}
void
APMFirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
)
void
APMFirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
{
_parameterMetaData
.
addMetaDataToFact
(
fact
);
_parameterMetaData
.
addMetaDataToFact
(
fact
,
vehicleType
);
}
QList
<
MAV_CMD
>
APMFirmwarePlugin
::
supportedMissionCommands
(
void
)
{
QList
<
MAV_CMD
>
list
;
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
781997b2
...
...
@@ -89,7 +89,7 @@ public:
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
bool
sendHomePositionToVehicle
(
void
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
...
...
src/FirmwarePlugin/APM/APMParameterMetaData.cc
View file @
781997b2
...
...
@@ -36,7 +36,7 @@
QGC_LOGGING_CATEGORY
(
APMParameterMetaDataLog
,
"APMParameterMetaDataLog"
)
bool
APMParameterMetaData
::
_parameterMetaDataLoaded
=
false
;
QMap
<
QString
,
FactMetaData
*>
APMParameterMetaData
::
_
mapParameterName2FactMetaData
;
QMap
<
QString
,
ParameterNameto
FactMetaData
Map
>
APMParameterMetaData
::
_
vehicleTypeToParametersMap
;
APMParameterMetaData
::
APMParameterMetaData
(
QObject
*
parent
)
:
QObject
(
parent
)
...
...
@@ -49,7 +49,8 @@ APMParameterMetaData::APMParameterMetaData(QObject* parent) :
/// @param type Type for Fact which dictates the QVariant type as well
/// @param convertOk Returned: true: conversion success, false: conversion failure
/// @return Returns the correctly type QVariant
QVariant
APMParameterMetaData
::
_stringToTypedVariant
(
const
QString
&
string
,
FactMetaData
::
ValueType_t
type
,
bool
*
convertOk
)
QVariant
APMParameterMetaData
::
_stringToTypedVariant
(
const
QString
&
string
,
FactMetaData
::
ValueType_t
type
,
bool
*
convertOk
)
{
QVariant
var
(
string
);
...
...
@@ -78,29 +79,388 @@ QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, Fact
return
var
;
}
QString
APMParameterMetaData
::
mavTypeToString
(
MAV_TYPE
vehicleTypeEnum
)
{
QString
vehicleName
;
switch
(
vehicleTypeEnum
)
{
case
MAV_TYPE_FIXED_WING
:
vehicleName
=
"ArduPlane"
;
break
;
case
MAV_TYPE_QUADROTOR
:
case
MAV_TYPE_COAXIAL
:
case
MAV_TYPE_HELICOPTER
:
case
MAV_TYPE_SUBMARINE
:
case
MAV_TYPE_HEXAROTOR
:
case
MAV_TYPE_OCTOROTOR
:
case
MAV_TYPE_TRICOPTER
:
vehicleName
=
"ArduCopter"
;
break
;
case
MAV_TYPE_ANTENNA_TRACKER
:
vehicleName
=
"Antenna Tracker"
;
case
MAV_TYPE_GENERIC
:
case
MAV_TYPE_GCS
:
case
MAV_TYPE_AIRSHIP
:
case
MAV_TYPE_FREE_BALLOON
:
case
MAV_TYPE_ROCKET
:
break
;
case
MAV_TYPE_GROUND_ROVER
:
case
MAV_TYPE_SURFACE_BOAT
:
vehicleName
=
"ArduRover"
;
break
;
case
MAV_TYPE_FLAPPING_WING
:
case
MAV_TYPE_KITE
:
case
MAV_TYPE_ONBOARD_CONTROLLER
:
case
MAV_TYPE_VTOL_DUOROTOR
:
case
MAV_TYPE_VTOL_QUADROTOR
:
case
MAV_TYPE_VTOL_TILTROTOR
:
case
MAV_TYPE_VTOL_RESERVED2
:
case
MAV_TYPE_VTOL_RESERVED3
:
case
MAV_TYPE_VTOL_RESERVED4
:
case
MAV_TYPE_VTOL_RESERVED5
:
case
MAV_TYPE_GIMBAL
:
case
MAV_TYPE_ENUM_END
:
default:
break
;
}
return
vehicleName
;
}
/// Load Parameter Fact meta data
///
/// The meta data comes from firmware parameters.xml file.
void
APMParameterMetaData
::
_loadParameterFactMetaData
(
void
)
void
APMParameterMetaData
::
_loadParameterFactMetaData
()
{
if
(
_parameterMetaDataLoaded
)
{
return
;
}
_parameterMetaDataLoaded
=
true
;
// FIXME: NYI
QRegExp
parameterCategories
=
QRegExp
(
"ArduCopter|ArduPlane|APMrover2|AntennaTracker"
);
QString
currentCategory
;
QString
parameterFilename
;
// Fixme:: always picking up the bundled xml, we would like to update it from web
// just not sure right now as the xml is in bad shape.
if
(
parameterFilename
.
isEmpty
()
||
!
QFile
(
parameterFilename
).
exists
())
{
parameterFilename
=
":/FirmwarePlugin/APM/apm.pdef.xml"
;
}
qCDebug
(
APMParameterMetaDataLog
)
<<
"Loading parameter meta data:"
<<
parameterFilename
;
QFile
xmlFile
(
parameterFilename
);
Q_ASSERT
(
xmlFile
.
exists
());
bool
success
=
xmlFile
.
open
(
QIODevice
::
ReadOnly
);
Q_UNUSED
(
success
);
Q_ASSERT
(
success
);
QXmlStreamReader
xml
(
xmlFile
.
readAll
());
xmlFile
.
close
();
if
(
xml
.
hasError
())
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, reading failed: "
<<
xml
.
errorString
();
return
;
}
QString
errorString
;
bool
badMetaData
=
true
;
QStack
<
int
>
xmlState
;
APMFactMetaDataRaw
*
rawMetaData
=
NULL
;
// Static meta data should load all MAV_TYPEs from single meta data file in such a way that the loader
// has multiple sets of static meta data
xmlState
.
push
(
XmlStateNone
);
QMap
<
QString
,
QStringList
>
groupMembers
;
//used to remove groups with single item
while
(
!
xml
.
atEnd
())
{
if
(
xml
.
isStartElement
())
{
QString
elementName
=
xml
.
name
().
toString
();
if
(
elementName
.
isEmpty
())
{
// skip empty elements
}
else
if
(
elementName
==
"paramfile"
)
{
if
(
xmlState
.
top
()
!=
XmlStateNone
)
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, paramfile matched"
;
}
xmlState
.
push
(
XmlstateParamFileFound
);
// we don't really do anything with this element
}
else
if
(
elementName
==
"vehicles"
)
{
if
(
xmlState
.
top
()
!=
XmlstateParamFileFound
)
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, vehicles matched"
;
return
;
}
xmlState
.
push
(
XmlStateFoundVehicles
);
}
else
if
(
elementName
==
"libraries"
)
{
if
(
xmlState
.
top
()
!=
XmlstateParamFileFound
)
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, libraries matched"
;
return
;
}
currentCategory
=
"libraries"
;
xmlState
.
push
(
XmlStateFoundLibraries
);
}
else
if
(
elementName
==
"parameters"
)
{
if
(
xmlState
.
top
()
!=
XmlStateFoundVehicles
&&
xmlState
.
top
()
!=
XmlStateFoundLibraries
)
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, parameters matched"
<<
"but we don't have proper vehicle or libraries yet"
;
return
;
}
if
(
xml
.
attributes
().
hasAttribute
(
"name"
))
{
// we will handle metadata only for specific MAV_TYPEs and libraries
const
QString
nameValue
=
xml
.
attributes
().
value
(
"name"
).
toString
();
if
(
nameValue
.
contains
(
parameterCategories
))
{
xmlState
.
push
(
XmlStateFoundParameters
);
currentCategory
=
nameValue
;
}
else
if
(
xmlState
.
top
()
==
XmlStateFoundLibraries
)
{
// we handle all libraries section under the same category libraries
// so not setting currentCategory
xmlState
.
push
(
XmlStateFoundParameters
);
}
else
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"not interested in this block of parameters skip"
;
if
(
skipXMLBlock
(
xml
,
"parameters"
))
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"something wrong with the xml, skip of the xml failed"
;
return
;
}
xml
.
readNext
();
continue
;
}
}
}
else
if
(
elementName
==
"param"
)
{
if
(
xmlState
.
top
()
!=
XmlStateFoundParameters
)
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, element param matched"
<<
"while we are not yet in parameters"
;
return
;
}
xmlState
.
push
(
XmlStateFoundParameter
);
if
(
!
xml
.
attributes
().
hasAttribute
(
"name"
))
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, parameter attribute name missing"
;
return
;
}
QString
name
=
xml
.
attributes
().
value
(
"name"
).
toString
();
if
(
name
.
contains
(
':'
))
{
name
=
name
.
split
(
':'
).
last
();
}
QString
group
=
name
.
split
(
'_'
).
first
();
group
=
group
.
remove
(
QRegExp
(
"[0-9]*$"
));
// remove any numbers from the end
QString
shortDescription
=
xml
.
attributes
().
value
(
"humanName"
).
toString
();
QString
longDescription
=
xml
.
attributes
().
value
(
"docmentation"
).
toString
();
QString
userLevel
=
xml
.
attributes
().
value
(
"user"
).
toString
();
qCDebug
(
APMParameterMetaDataLog
)
<<
"Found parameter name:"
<<
name
<<
"short Desc:"
<<
shortDescription
<<
"longDescription:"
<<
longDescription
<<
"user level: "
<<
userLevel
<<
"group: "
<<
group
;
Q_ASSERT
(
!
rawMetaData
);
rawMetaData
=
new
APMFactMetaDataRaw
();
if
(
_vehicleTypeToParametersMap
[
currentCategory
].
contains
(
name
))
{
// We can't trust the meta dafa since we have dups
qCWarning
(
APMParameterMetaDataLog
)
<<
"Duplicate parameter found:"
<<
name
;
badMetaData
=
true
;
}
else
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"inserting metadata for field"
<<
name
;
_vehicleTypeToParametersMap
[
currentCategory
][
name
]
=
rawMetaData
;
rawMetaData
->
name
=
name
;
rawMetaData
->
group
=
group
;
rawMetaData
->
shortDescription
=
shortDescription
;
rawMetaData
->
longDescription
=
longDescription
;
groupMembers
[
group
]
<<
name
;
}
}
else
{
// We should be getting meta data now
if
(
xmlState
.
top
()
!=
XmlStateFoundParameter
)
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, while reading parameter fields wrong state"
;
return
;
}
if
(
!
badMetaData
)
{
if
(
!
parseParameterAttributes
(
xml
,
rawMetaData
))
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"Badly formed XML, failed to read parameter attributes"
;
return
;
}
continue
;
}
}
}
else
if
(
xml
.
isEndElement
())
{
QString
elementName
=
xml
.
name
().
toString
();
if
(
elementName
==
"param"
&&
xmlState
.
top
()
==
XmlStateFoundParameter
)
{
// Done loading this parameter
// Reset for next parameter
qCDebug
(
APMParameterMetaDataLog
)
<<
"done loading parameter"
;
rawMetaData
=
NULL
;
badMetaData
=
false
;
xmlState
.
pop
();
}
else
if
(
elementName
==
"parameters"
)
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"end of parameters for category: "
<<
currentCategory
;
correctGroupMemberships
(
_vehicleTypeToParametersMap
[
currentCategory
],
groupMembers
);
groupMembers
.
clear
();
xmlState
.
pop
();
}
else
if
(
elementName
==
"vehicles"
)
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"vehicles end here, libraries will follow"
;
xmlState
.
pop
();
}
}
xml
.
readNext
();
}
}
void
APMParameterMetaData
::
correctGroupMemberships
(
ParameterNametoFactMetaDataMap
&
parameterToFactMetaDataMap
,
QMap
<
QString
,
QStringList
>&
groupMembers
)
{
foreach
(
const
QString
&
groupName
,
groupMembers
.
keys
())
{
if
(
groupMembers
[
groupName
].
count
()
==
1
)
{
foreach
(
const
QString
&
parameter
,
groupMembers
.
value
(
groupName
))
{
parameterToFactMetaDataMap
[
parameter
]
->
group
=
"others"
;
}
}
}
}
bool
APMParameterMetaData
::
skipXMLBlock
(
QXmlStreamReader
&
xml
,
const
QString
&
blockName
)
{
QString
elementName
;
do
{
xml
.
readNext
();
elementName
=
xml
.
name
().
toString
();
}
while
((
elementName
!=
blockName
)
&&
(
xml
.
isEndElement
()));
return
!
xml
.
isEndDocument
();
}
bool
APMParameterMetaData
::
parseParameterAttributes
(
QXmlStreamReader
&
xml
,
APMFactMetaDataRaw
*
rawMetaData
)
{
QString
elementName
=
xml
.
name
().
toString
();
QList
<
QPair
<
QString
,
QString
>
>
values
;
// as long as param doens't end
while
(
!
(
elementName
==
"param"
&&
xml
.
isEndElement
()))
{
if
(
elementName
.
isEmpty
())
{
// skip empty elements. Somehow I am getting lot of these. Dont know what to do with them.
}
else
if
(
elementName
==
"field"
)
{
QString
attributeName
=
xml
.
attributes
().
value
(
"name"
).
toString
();
if
(
attributeName
==
"Range"
)
{
QString
range
=
xml
.
readElementText
().
trimmed
();
QStringList
rangeList
=
range
.
split
(
' '
);
if
(
rangeList
.
count
()
!=
2
)
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"space seperator didn't work',trying 'to' separator"
;
rangeList
=
range
.
split
(
"to"
);
if
(
rangeList
.
count
()
!=
2
)
{
qCDebug
(
APMParameterMetaDataLog
)
<<
" 'to' seperaator didn't work', trying '-' as seperator"
;
rangeList
=
range
.
split
(
'-'
);
if
(
rangeList
.
count
()
!=
2
)
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"something wrong with range, all three separators have failed"
<<
range
;
}
}
}
// everything should be good. lets collect min and max
if
(
rangeList
.
count
()
==
2
)
{
rawMetaData
->
min
=
rangeList
.
first
().
trimmed
();
rawMetaData
->
max
=
rangeList
.
last
().
trimmed
();
// sanitize min and max off any comments that they may have
if
(
rawMetaData
->
min
.
contains
(
' '
))
{
rawMetaData
->
min
=
rawMetaData
->
min
.
split
(
' '
).
first
();
}
if
(
rawMetaData
->
max
.
contains
(
' '
))
{
rawMetaData
->
max
=
rawMetaData
->
max
.
split
(
' '
).
first
();
}
qCDebug
(
APMParameterMetaDataLog
)
<<
"read field parameter "
<<
"min: "
<<
rawMetaData
->
min
<<
"max: "
<<
rawMetaData
->
max
;
}
}
else
if
(
attributeName
==
"Increment"
)
{
QString
increment
=
xml
.
readElementText
();
qCDebug
(
APMParameterMetaDataLog
)
<<
"read Increment: "
<<
increment
;
rawMetaData
->
incrementSize
=
increment
;
}
else
if
(
attributeName
==
"Units"
)
{
QString
units
=
xml
.
readElementText
();
qCDebug
(
APMParameterMetaDataLog
)
<<
"read Units: "
<<
units
;
rawMetaData
->
units
=
units
;
}
}
else
if
(
elementName
==
"values"
)
{
// doing nothing individual value will follow anyway. May be used for sanity checking.
}
else
if
(
elementName
==
"value"
)
{
QString
valueValue
=
xml
.
attributes
().
value
(
"code"
).
toString
();
QString
valueName
=
xml
.
readElementText
();
qCDebug
(
APMParameterMetaDataLog
)
<<
"read value parameter "
<<
"value desc: "
<<
valueName
<<
"code: "
<<
valueValue
;
values
<<
QPair
<
QString
,
QString
>
(
valueValue
,
valueName
);
rawMetaData
->
values
=
values
;
}
else
{
qCWarning
(
APMParameterMetaDataLog
)
<<
"Unknown parameter element in XML: "
<<
elementName
;
}
xml
.
readNext
();
elementName
=
xml
.
name
().
toString
();
}
return
true
;
}
/// Override from FactLoad which connects the meta data to the fact
void
APMParameterMetaData
::
addMetaDataToFact
(
Fact
*
fact
)
void
APMParameterMetaData
::
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
{
_loadParameterFactMetaData
();
// FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data
const
QString
mavTypeString
=
mavTypeToString
(
vehicleType
);
APMFactMetaDataRaw
*
rawMetaData
=
NULL
;
// check if we have metadata for fact, use generic otherwise
if
(
_vehicleTypeToParametersMap
[
mavTypeString
].
contains
(
fact
->
name
()))
{
rawMetaData
=
_vehicleTypeToParametersMap
[
mavTypeString
][
fact
->
name
()];
}
else
if
(
_vehicleTypeToParametersMap
[
"libraries"
].
contains
(
fact
->
name
()))
{
rawMetaData
=
_vehicleTypeToParametersMap
[
"libraries"
][
fact
->
name
()];
}
FactMetaData
*
metaData
=
new
FactMetaData
(
fact
->
type
(),
fact
);
// we don't have data for this fact
if
(
!
rawMetaData
)
{
fact
->
setMetaData
(
metaData
);
qCDebug
(
APMParameterMetaDataLog
)
<<
"No metaData for "
<<
fact
->
name
()
<<
"using generic metadata"
;
return
;
}
metaData
->
setName
(
rawMetaData
->
name
);
metaData
->
setGroup
(
rawMetaData
->
group
);
if
(
!
rawMetaData
->
shortDescription
.
isEmpty
())
{
metaData
->
setShortDescription
(
rawMetaData
->
shortDescription
);
}
if
(
!
rawMetaData
->
longDescription
.
isEmpty
())
{
metaData
->
setLongDescription
(
rawMetaData
->
longDescription
);
}
if
(
!
rawMetaData
->
units
.
isEmpty
())
{
metaData
->
setUnits
(
rawMetaData
->
units
);
}
if
(
!
rawMetaData
->
min
.
isEmpty
())
{
QVariant
varMin
;
QString
errorString
;
if
(
metaData
->
convertAndValidate
(
rawMetaData
->
min
,
false
/* validate as well */
,
varMin
,
errorString
))
{
metaData
->
setMin
(
varMin
);
}
else
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"Invalid min value, name:"
<<
metaData
->
name
()
<<
" type:"
<<
metaData
->
type
()
<<
" min:"
<<
rawMetaData
->
min
<<
" error:"
<<
errorString
;
}
}
if
(
!
rawMetaData
->
max
.
isEmpty
())
{
QVariant
varMax
;
QString
errorString
;
if
(
metaData
->
convertAndValidate
(
rawMetaData
->
max
,
false
/* validate as well */
,
varMax
,
errorString
))
{
metaData
->
setMax
(
varMax
);
}
else
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"Invalid max value, name:"
<<
metaData
->
name
()
<<
" type:"
<<
metaData
->
type
()
<<
" max:"
<<
rawMetaData
->
max
<<
" error:"
<<
errorString
;
}
}
FactMetaData
*
metaData
=
new
FactMetaData
(
fact
->
type
(),
fact
);
// FixMe:: not handling values and increment size as their is no place for them in FactMetaData and no ui
fact
->
setMetaData
(
metaData
);
}
src/FirmwarePlugin/APM/APMParameterMetaData.h
View file @
781997b2
...
...
@@ -26,6 +26,7 @@
#include
<QObject>
#include
<QMap>
#include
<QPointer>
#include
<QXmlStreamReader>
#include
<QLoggingCategory>
...
...
@@ -33,6 +34,20 @@
#include
"AutoPilotPlugin.h"
#include
"Vehicle.h"
class
APMFactMetaDataRaw
{
public:
QString
name
;
QString
group
;
QString
shortDescription
;
QString
longDescription
;
QString
min
;
QString
max
;
QString
incrementSize
;
QString
units
;
QList
<
QPair
<
QString
,
QString
>
>
values
;
};
/// @file
/// @author Don Gagne <don@thegagnes.com>
...
...
@@ -40,6 +55,8 @@ Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
/// Collection of Parameter Facts for PX4 AutoPilot
typedef
QMap
<
QString
,
APMFactMetaDataRaw
*>
ParameterNametoFactMetaDataMap
;
class
APMParameterMetaData
:
public
QObject
{
Q_OBJECT
...
...
@@ -52,11 +69,15 @@ public:
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
// Overrides from ParameterLoader
static
void
addMetaDataToFact
(
Fact
*
fact
);
static
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
static
void
addMetaDataToFacts
(
QVariantMap
&
facts
,
MAV_TYPE
vehicleType
);
private:
enum
{
XmlStateNone
,
XmlstateParamFileFound
,
XmlStateFoundVehicles
,
XmlStateFoundLibraries
,
XmlStateFoundParameters
,
XmlStateFoundVersion
,
XmlStateFoundGroup
,
...
...
@@ -65,11 +86,15 @@ private:
};
static
void
_loadParameterFactMetaData
(
void
);
static
void
_loadParameterFactMetaData
();
static
QVariant
_stringToTypedVariant
(
const
QString
&
string
,
FactMetaData
::
ValueType_t
type
,
bool
*
convertOk
);
static
bool
skipXMLBlock
(
QXmlStreamReader
&
xml
,
const
QString
&
blockName
);
static
bool
parseParameterAttributes
(
QXmlStreamReader
&
xml
,
APMFactMetaDataRaw
*
rawMetaData
);
static
void
correctGroupMemberships
(
ParameterNametoFactMetaDataMap
&
parameterToFactMetaDataMap
,
QMap
<
QString
,
QStringList
>&
groupMembers
);
static
QString
mavTypeToString
(
MAV_TYPE
vehicleTypeEnum
);
static
bool
_parameterMetaDataLoaded
;
///< true: parameter meta data already loaded
static
QMap
<
QString
,
FactMetaData
*>
_mapParameterName2FactMetaData
;
///< Maps from a parameter
name
to
FactMeta
Data
static
QMap
<
QString
,
ParameterNametoFactMetaDataMap
>
_vehicleTypeToParametersMap
;
///< Maps from a
vehicle type to
param
am
etertoFactMeta
map>
};
#endif
src/FirmwarePlugin/APM/apm.pdef.xml
0 → 100644
View file @
781997b2
This diff is collapsed.
Click to expand it.
src/FirmwarePlugin/FirmwarePlugin.h
View file @
781997b2
...
...
@@ -79,7 +79,7 @@ public:
/// @param[out] custom_mode Custom mode for SET_MODE mavlink message
virtual
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
)
=
0
;
/// FIXME: This isn't quite correct being here. All code for Joystick support is currently firmware specific
/// FIXME: This isn't quite correct being here. All code for Joystick su
vehicleType
pport is currently firmware specific
/// not just this. I'm going to try to change that. If not, this will need to be removed.
/// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
...
...
@@ -108,7 +108,7 @@ public:
virtual
QString
getDefaultComponentIdParam
(
void
)
const
=
0
;
/// Adds the parameter meta data to the Fact
virtual
void
addMetaDataToFact
(
Fact
*
fact
)
=
0
;
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
=
0
;
/// List of supported mission commands. Empty list for all commands supported.
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
=
0
;
...
...
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
View file @
781997b2
...
...
@@ -112,8 +112,10 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
return
false
;
}
void
GenericFirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
)
void
GenericFirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
{
Q_UNUSED
(
vehicleType
)
// Add default meta data
FactMetaData
*
metaData
=
new
FactMetaData
(
fact
->
type
(),
fact
);
fact
->
setMetaData
(
metaData
);
...
...
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
View file @
781997b2
...
...
@@ -45,7 +45,7 @@ public:
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
bool
sendHomePositionToVehicle
(
void
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
();
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
};
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
781997b2
...
...
@@ -203,9 +203,9 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
return
false
;
}
void
PX4FirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
)
void
PX4FirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
{
_parameterMetaData
.
addMetaDataToFact
(
fact
);
_parameterMetaData
.
addMetaDataToFact
(
fact
,
vehicleType
);
}
QList
<
MAV_CMD
>
PX4FirmwarePlugin
::
supportedMissionCommands
(
void
)
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
781997b2
...
...
@@ -45,7 +45,7 @@ public:
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
bool
sendHomePositionToVehicle
(
void
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYS_AUTOSTART"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
...
...
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
View file @
781997b2
...
...
@@ -345,8 +345,10 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
}
/// Override from FactLoad which connects the meta data to the fact
void
PX4ParameterMetaData
::
addMetaDataToFact
(
Fact
*
fact
)
void
PX4ParameterMetaData
::
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
{
Q_UNUSED
(
vehicleType
)
_loadParameterFactMetaData
();
if
(
_mapParameterName2FactMetaData
.
contains
(
fact
->
name
()))
{
fact
->
setMetaData
(
_mapParameterName2FactMetaData
[
fact
->
name
()]);
...
...
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
View file @
781997b2
...
...
@@ -47,7 +47,7 @@ class PX4ParameterMetaData : public QObject
public:
PX4ParameterMetaData
(
QObject
*
parent
=
NULL
);
void
addMetaDataToFact
(
Fact
*
fact
);
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
private:
enum
{
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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