QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMParameterMetaData.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QLoggingCategory>
4#include <QtCore/QMap>
5#include <QtCore/QObject>
6#include <QtCore/QXmlStreamReader>
7
8#include "MAVLinkLib.h"
9#include "FactMetaData.h"
10
11Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
12Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog)
13
14class APMFactMetaDataRaw : public QObject
15{
16 Q_OBJECT
17public:
18 explicit APMFactMetaDataRaw(QObject *parent = nullptr)
19 : QObject(parent)
20 { }
22
23 QString name;
24 QString category;
25 QString group;
28 QString min;
29 QString max;
31 QString units;
32 bool rebootRequired = false;
33 bool readOnly = false;
34 QList<QPair<QString, QString>> values;
35 QList<QPair<QString, QString>> bitmask;
36};
37
38/*===========================================================================*/
39
40typedef QMap<QString, APMFactMetaDataRaw*> ParameterNametoFactMetaDataMap;
41
43class APMParameterMetaData : public QObject
44{
45 Q_OBJECT
46
47public:
48 explicit APMParameterMetaData(QObject *parent = nullptr);
50
51 FactMetaData *getMetaDataForFact(const QString &name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type);
52 void loadParameterFactMetaDataFile(const QString &metaDataFile);
53
54 static void getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion);
55
56private:
57 enum XmlState {
58 None,
59 ParamFileFound,
60 FoundVehicles,
61 FoundLibraries,
62 FoundParameters,
63 FoundVersion,
64 FoundGroup,
65 FoundParameter,
66 Done
67 };
68
69 static bool _skipXMLBlock(QXmlStreamReader &xml, const QString &blockName);
70 bool _parseParameterAttributes(QXmlStreamReader &xml, APMFactMetaDataRaw *rawMetaData);
71 static void _correctGroupMemberships(ParameterNametoFactMetaDataMap &parameterToFactMetaDataMap, QMap<QString,QStringList> &groupMembers);
72 static QString _mavTypeToString(MAV_TYPE vehicleTypeEnum);
73 static QString _groupFromParameterName(const QString &name);
74
75 bool _parameterMetaDataLoaded = false;
76 // FIXME: metadata is vehicle type specific now
77 QMap<QString, ParameterNametoFactMetaDataMap> _vehicleTypeToParametersMap;
78};
QMap< QString, APMFactMetaDataRaw * > ParameterNametoFactMetaDataMap
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
APMFactMetaDataRaw(QObject *parent=nullptr)
QList< QPair< QString, QString > > values
QList< QPair< QString, QString > > bitmask
Collection of Parameter Facts for ArduPilot.
void loadParameterFactMetaDataFile(const QString &metaDataFile)
static void getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion)
FactMetaData * getMetaDataForFact(const QString &name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type)