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
781997b2
Commit
781997b2
authored
Dec 14, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #2395 from pritamghanghas/apm_metadata
Apm metadata
parents
fc853305
159bce05
Changes
15
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
15 changed files
with
6284 additions
and
30 deletions
+6284
-30
qgcresources.qrc
qgcresources.qrc
+3
-0
FactMetaData.cc
src/FactSystem/FactMetaData.cc
+5
-3
ParameterLoader.cc
src/FactSystem/ParameterLoader.cc
+1
-1
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+3
-2
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+1
-1
APMParameterMetaData.cc
src/FirmwarePlugin/APM/APMParameterMetaData.cc
+370
-10
APMParameterMetaData.h
src/FirmwarePlugin/APM/APMParameterMetaData.h
+28
-3
apm.pdef.xml
src/FirmwarePlugin/APM/apm.pdef.xml
+5859
-0
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+2
-2
GenericFirmwarePlugin.cc
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
+3
-1
GenericFirmwarePlugin.h
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
+1
-1
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+2
-2
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+1
-1
PX4ParameterMetaData.cc
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
+4
-2
PX4ParameterMetaData.h
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
+1
-1
No files found.
qgcresources.qrc
View file @
781997b2
...
@@ -209,4 +209,7 @@
...
@@ -209,4 +209,7 @@
<file alias="ParameterFactMetaData.xml">src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml</file>
<file alias="ParameterFactMetaData.xml">src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml</file>
</qresource>
</qresource>
<qresource prefix="/FirmwarePlugin/APM">
<file alias="apm.pdef.xml">src/FirmwarePlugin/APM/apm.pdef.xml</file>
</qresource>
</RCC>
</RCC>
src/FactSystem/FactMetaData.cc
View file @
781997b2
...
@@ -121,7 +121,9 @@ void FactMetaData::setMin(const QVariant& min)
...
@@ -121,7 +121,9 @@ void FactMetaData::setMin(const QVariant& min)
_min
=
min
;
_min
=
min
;
_minIsDefaultForType
=
false
;
_minIsDefaultForType
=
false
;
}
else
{
}
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
();
_min
=
_minForType
();
}
}
}
}
...
@@ -189,7 +191,7 @@ QVariant FactMetaData::_maxForType(void) const
...
@@ -189,7 +191,7 @@ QVariant FactMetaData::_maxForType(void) const
bool
FactMetaData
::
convertAndValidate
(
const
QVariant
&
value
,
bool
convertOnly
,
QVariant
&
typedValue
,
QString
&
errorString
)
bool
FactMetaData
::
convertAndValidate
(
const
QVariant
&
value
,
bool
convertOnly
,
QVariant
&
typedValue
,
QString
&
errorString
)
{
{
bool
convertOk
;
bool
convertOk
=
false
;
errorString
.
clear
();
errorString
.
clear
();
...
@@ -236,7 +238,7 @@ bool FactMetaData::convertAndValidate(const QVariant& value, bool convertOnly, Q
...
@@ -236,7 +238,7 @@ bool FactMetaData::convertAndValidate(const QVariant& value, bool convertOnly, Q
}
}
if
(
!
convertOk
)
{
if
(
!
convertOk
)
{
errorString
=
"Invalid number"
;
errorString
+
=
"Invalid number"
;
}
}
return
convertOk
&&
errorString
.
isEmpty
();
return
convertOk
&&
errorString
.
isEmpty
();
...
...
src/FactSystem/ParameterLoader.cc
View file @
781997b2
...
@@ -254,7 +254,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
...
@@ -254,7 +254,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
fact
->
_containerSetRawValue
(
value
);
fact
->
_containerSetRawValue
(
value
);
if
(
setMetaData
)
{
if
(
setMetaData
)
{
_vehicle
->
firmwarePlugin
()
->
addMetaDataToFact
(
fact
);
_vehicle
->
firmwarePlugin
()
->
addMetaDataToFact
(
fact
,
_vehicle
->
vehicleType
()
);
}
}
_dataMutex
.
unlock
();
_dataMutex
.
unlock
();
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
781997b2
...
@@ -405,11 +405,12 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
...
@@ -405,11 +405,12 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
return
true
;
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
>
APMFirmwarePlugin
::
supportedMissionCommands
(
void
)
{
{
QList
<
MAV_CMD
>
list
;
QList
<
MAV_CMD
>
list
;
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
781997b2
...
@@ -89,7 +89,7 @@ public:
...
@@ -89,7 +89,7 @@ public:
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
bool
sendHomePositionToVehicle
(
void
);
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
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
...
...
src/FirmwarePlugin/APM/APMParameterMetaData.cc
View file @
781997b2
This diff is collapsed.
Click to expand it.
src/FirmwarePlugin/APM/APMParameterMetaData.h
View file @
781997b2
...
@@ -26,6 +26,7 @@
...
@@ -26,6 +26,7 @@
#include <QObject>
#include <QObject>
#include <QMap>
#include <QMap>
#include <QPointer>
#include <QXmlStreamReader>
#include <QXmlStreamReader>
#include <QLoggingCategory>
#include <QLoggingCategory>
...
@@ -33,6 +34,20 @@
...
@@ -33,6 +34,20 @@
#include "AutoPilotPlugin.h"
#include "AutoPilotPlugin.h"
#include "Vehicle.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
/// @file
/// @author Don Gagne <don@thegagnes.com>
/// @author Don Gagne <don@thegagnes.com>
...
@@ -40,6 +55,8 @@ Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
...
@@ -40,6 +55,8 @@ Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
/// Collection of Parameter Facts for PX4 AutoPilot
/// Collection of Parameter Facts for PX4 AutoPilot
typedef
QMap
<
QString
,
APMFactMetaDataRaw
*>
ParameterNametoFactMetaDataMap
;
class
APMParameterMetaData
:
public
QObject
class
APMParameterMetaData
:
public
QObject
{
{
Q_OBJECT
Q_OBJECT
...
@@ -52,11 +69,15 @@ public:
...
@@ -52,11 +69,15 @@ public:
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
// Overrides from ParameterLoader
// 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:
private:
enum
{
enum
{
XmlStateNone
,
XmlStateNone
,
XmlstateParamFileFound
,
XmlStateFoundVehicles
,
XmlStateFoundLibraries
,
XmlStateFoundParameters
,
XmlStateFoundParameters
,
XmlStateFoundVersion
,
XmlStateFoundVersion
,
XmlStateFoundGroup
,
XmlStateFoundGroup
,
...
@@ -65,11 +86,15 @@ private:
...
@@ -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
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
bool
_parameterMetaDataLoaded
;
///< true: parameter meta data already loaded
static
QMap
<
QString
,
FactMetaData
*>
_mapParameterName2FactMetaData
;
///< Maps from a parameter name to FactMetaData
static
QMap
<
QString
,
ParameterNametoFactMetaDataMap
>
_vehicleTypeToParametersMap
;
///< Maps from a vehicle type to paramametertoFactMeta map>
};
};
#endif
#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:
...
@@ -79,7 +79,7 @@ public:
/// @param[out] custom_mode Custom mode for SET_MODE mavlink message
/// @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
;
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.
/// 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
/// 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.
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
...
@@ -108,7 +108,7 @@ public:
...
@@ -108,7 +108,7 @@ public:
virtual
QString
getDefaultComponentIdParam
(
void
)
const
=
0
;
virtual
QString
getDefaultComponentIdParam
(
void
)
const
=
0
;
/// Adds the parameter meta data to the Fact
/// 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.
/// List of supported mission commands. Empty list for all commands supported.
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
=
0
;
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
=
0
;
...
...
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
View file @
781997b2
...
@@ -112,8 +112,10 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
...
@@ -112,8 +112,10 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
return
false
;
return
false
;
}
}
void
GenericFirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
)
void
GenericFirmwarePlugin
::
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
{
{
Q_UNUSED
(
vehicleType
)
// Add default meta data
// Add default meta data
FactMetaData
*
metaData
=
new
FactMetaData
(
fact
->
type
(),
fact
);
FactMetaData
*
metaData
=
new
FactMetaData
(
fact
->
type
(),
fact
);
fact
->
setMetaData
(
metaData
);
fact
->
setMetaData
(
metaData
);
...
...
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
View file @
781997b2
...
@@ -45,7 +45,7 @@ public:
...
@@ -45,7 +45,7 @@ public:
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
bool
sendHomePositionToVehicle
(
void
);
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
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
();
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
};
};
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
781997b2
...
@@ -203,9 +203,9 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
...
@@ -203,9 +203,9 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
return
false
;
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
)
QList
<
MAV_CMD
>
PX4FirmwarePlugin
::
supportedMissionCommands
(
void
)
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
781997b2
...
@@ -45,7 +45,7 @@ public:
...
@@ -45,7 +45,7 @@ public:
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
adjustMavlinkMessage
(
mavlink_message_t
*
message
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
virtual
bool
sendHomePositionToVehicle
(
void
);
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
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYS_AUTOSTART"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
...
...
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
View file @
781997b2
...
@@ -188,7 +188,7 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
...
@@ -188,7 +188,7 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
QString
name
=
xml
.
attributes
().
value
(
"name"
).
toString
();
QString
name
=
xml
.
attributes
().
value
(
"name"
).
toString
();
QString
type
=
xml
.
attributes
().
value
(
"type"
).
toString
();
QString
type
=
xml
.
attributes
().
value
(
"type"
).
toString
();
QString
strDefault
=
xml
.
attributes
().
value
(
"default"
).
toString
();
QString
strDefault
=
xml
.
attributes
().
value
(
"default"
).
toString
();
qCDebug
(
PX4ParameterMetaDataLog
)
<<
"Found parameter name:"
<<
name
<<
" type:"
<<
type
<<
" default:"
<<
strDefault
;
qCDebug
(
PX4ParameterMetaDataLog
)
<<
"Found parameter name:"
<<
name
<<
" type:"
<<
type
<<
" default:"
<<
strDefault
;
...
@@ -345,8 +345,10 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
...
@@ -345,8 +345,10 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
}
}
/// Override from FactLoad which connects the meta data to the fact
/// 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
();
_loadParameterFactMetaData
();
if
(
_mapParameterName2FactMetaData
.
contains
(
fact
->
name
()))
{
if
(
_mapParameterName2FactMetaData
.
contains
(
fact
->
name
()))
{
fact
->
setMetaData
(
_mapParameterName2FactMetaData
[
fact
->
name
()]);
fact
->
setMetaData
(
_mapParameterName2FactMetaData
[
fact
->
name
()]);
...
...
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
View file @
781997b2
...
@@ -47,7 +47,7 @@ class PX4ParameterMetaData : public QObject
...
@@ -47,7 +47,7 @@ class PX4ParameterMetaData : public QObject
public:
public:
PX4ParameterMetaData
(
QObject
*
parent
=
NULL
);
PX4ParameterMetaData
(
QObject
*
parent
=
NULL
);
void
addMetaDataToFact
(
Fact
*
fact
);
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
private:
private:
enum
{
enum
{
...
...
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