Commit 46604020 authored by Don Gagne's avatar Don Gagne

Merge pull request #2414 from DonLakeFlyer/UnknownEnum

Handle unknown enum values in meta data
parents 9b842b72 763635c9
...@@ -165,7 +165,7 @@ QVariant Fact::cookedValue(void) const ...@@ -165,7 +165,7 @@ QVariant Fact::cookedValue(void) const
} }
} }
QString Fact::enumStringValue(void) const QString Fact::enumStringValue(void)
{ {
if (_metaData) { if (_metaData) {
int enumIndex = this->enumIndex(); int enumIndex = this->enumIndex();
...@@ -179,16 +179,23 @@ QString Fact::enumStringValue(void) const ...@@ -179,16 +179,23 @@ QString Fact::enumStringValue(void) const
return QString(); return QString();
} }
int Fact::enumIndex(void) const int Fact::enumIndex(void)
{ {
if (_metaData) { if (_metaData) {
int index = 0; int index = 0;
foreach (QVariant enumValue, _metaData->enumValues()) { foreach (QVariant enumValue, _metaData->enumValues()) {
if (enumValue == rawValue()) { if (enumValue == rawValue()) {
return index; return index;
} }
index ++; index ++;
} }
// Current value is not in list, add it manually
_metaData->addEnumInfo(QString("Unknown: %1").arg(rawValue().toString()), rawValue());
emit enumStringsChanged();
emit enumValuesChanged();
return index;
} else { } else {
qWarning() << "Meta data pointer missing"; qWarning() << "Meta data pointer missing";
} }
......
...@@ -52,9 +52,9 @@ public: ...@@ -52,9 +52,9 @@ public:
Q_PROPERTY(QString defaultValueString READ defaultValueString CONSTANT) Q_PROPERTY(QString defaultValueString READ defaultValueString CONSTANT)
Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT)
Q_PROPERTY(int enumIndex READ enumIndex WRITE setEnumIndex NOTIFY valueChanged) Q_PROPERTY(int enumIndex READ enumIndex WRITE setEnumIndex NOTIFY valueChanged)
Q_PROPERTY(QStringList enumStrings READ enumStrings CONSTANT) Q_PROPERTY(QStringList enumStrings READ enumStrings NOTIFY enumStringsChanged)
Q_PROPERTY(QString enumStringValue READ enumStringValue WRITE setEnumStringValue NOTIFY valueChanged) Q_PROPERTY(QString enumStringValue READ enumStringValue WRITE setEnumStringValue NOTIFY valueChanged)
Q_PROPERTY(QVariantList enumValues READ enumValues CONSTANT) Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumValuesChanged)
Q_PROPERTY(QString group READ group CONSTANT) Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT) Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT) Q_PROPERTY(QVariant max READ max CONSTANT)
...@@ -81,9 +81,9 @@ public: ...@@ -81,9 +81,9 @@ public:
QVariant defaultValue (void) const; QVariant defaultValue (void) const;
bool defaultValueAvailable (void) const; bool defaultValueAvailable (void) const;
QString defaultValueString (void) const; QString defaultValueString (void) const;
int enumIndex (void) const; int enumIndex (void); // This is not const, since an unknown value can modify the enum lists
QStringList enumStrings (void) const; QStringList enumStrings (void) const;
QString enumStringValue (void) const; QString enumStringValue (void); // This is not const, since an unknown value can modify the enum lists
QVariantList enumValues (void) const; QVariantList enumValues (void) const;
QString group (void) const; QString group (void) const;
QString longDescription (void) const; QString longDescription (void) const;
...@@ -120,6 +120,9 @@ public: ...@@ -120,6 +120,9 @@ public:
void _setName(const QString& name) { _name = name; } void _setName(const QString& name) { _name = name; }
signals: signals:
void enumStringsChanged(void);
void enumValuesChanged(void);
/// QObject Property System signal for value property changes /// QObject Property System signal for value property changes
/// ///
/// This signal is only meant for use by the QT property system. It should not be connected to by client code. /// This signal is only meant for use by the QT property system. It should not be connected to by client code.
......
...@@ -260,3 +260,9 @@ void FactMetaData::setTranslators(Translator rawTranslator, Translator cookedTra ...@@ -260,3 +260,9 @@ void FactMetaData::setTranslators(Translator rawTranslator, Translator cookedTra
_rawTranslator = rawTranslator; _rawTranslator = rawTranslator;
_cookedTranslator = cookedTranslator; _cookedTranslator = cookedTranslator;
} }
void FactMetaData::addEnumInfo(const QString& name, const QVariant& value)
{
_enumStrings << name;
_enumValues << value;
}
...@@ -79,6 +79,9 @@ public: ...@@ -79,6 +79,9 @@ public:
Translator rawTranslator (void) const { return _rawTranslator; } Translator rawTranslator (void) const { return _rawTranslator; }
Translator cookedTranslator (void) const { return _cookedTranslator; } Translator cookedTranslator (void) const { return _cookedTranslator; }
/// Used to add new values to the enum lists after the meta data has been loaded
void addEnumInfo(const QString& name, const QVariant& value);
void setDecimalPlaces (int decimalPlaces) { _decimalPlaces = decimalPlaces; } void setDecimalPlaces (int decimalPlaces) { _decimalPlaces = decimalPlaces; }
void setDefaultValue (const QVariant& defaultValue); void setDefaultValue (const QVariant& defaultValue);
void setEnumInfo (const QStringList& strings, const QVariantList& values); void setEnumInfo (const QStringList& strings, const QVariantList& values);
......
...@@ -45,18 +45,18 @@ struct EnumInfo_s { ...@@ -45,18 +45,18 @@ struct EnumInfo_s {
}; };
static const struct EnumInfo_s _rgMavFrameInfo[] = { static const struct EnumInfo_s _rgMavFrameInfo[] = {
{ "MAV_FRAME_GLOBAL", MAV_FRAME_GLOBAL }, { "MAV_FRAME_GLOBAL", MAV_FRAME_GLOBAL },
{ "MAV_FRAME_LOCAL_NED", MAV_FRAME_LOCAL_NED }, { "MAV_FRAME_LOCAL_NED", MAV_FRAME_LOCAL_NED },
{ "MAV_FRAME_MISSION", MAV_FRAME_MISSION }, { "MAV_FRAME_MISSION", MAV_FRAME_MISSION },
{ "MAV_FRAME_GLOBAL_RELATIVE_ALT", MAV_FRAME_GLOBAL_RELATIVE_ALT }, { "MAV_FRAME_GLOBAL_RELATIVE_ALT", MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ "MAV_FRAME_LOCAL_ENU", MAV_FRAME_LOCAL_ENU }, { "MAV_FRAME_LOCAL_ENU", MAV_FRAME_LOCAL_ENU },
{ "MAV_FRAME_GLOBAL_INT", MAV_FRAME_GLOBAL_INT }, { "MAV_FRAME_GLOBAL_INT", MAV_FRAME_GLOBAL_INT },
{ "MAV_FRAME_GLOBAL_RELATIVE_ALT_INT", MAV_FRAME_GLOBAL_RELATIVE_ALT_INT }, { "MAV_FRAME_GLOBAL_RELATIVE_ALT_INT", MAV_FRAME_GLOBAL_RELATIVE_ALT_INT },
{ "MAV_FRAME_LOCAL_OFFSET_NED", MAV_FRAME_LOCAL_OFFSET_NED }, { "MAV_FRAME_LOCAL_OFFSET_NED", MAV_FRAME_LOCAL_OFFSET_NED },
{ "MAV_FRAME_BODY_NED", MAV_FRAME_BODY_NED }, { "MAV_FRAME_BODY_NED", MAV_FRAME_BODY_NED },
{ "MAV_FRAME_BODY_OFFSET_NED", MAV_FRAME_BODY_OFFSET_NED }, { "MAV_FRAME_BODY_OFFSET_NED", MAV_FRAME_BODY_OFFSET_NED },
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT", MAV_FRAME_GLOBAL_TERRAIN_ALT }, { "MAV_FRAME_GLOBAL_TERRAIN_ALT", MAV_FRAME_GLOBAL_TERRAIN_ALT },
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, { "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT },
}; };
QDebug operator<<(QDebug dbg, const MissionItem& missionItem) QDebug operator<<(QDebug dbg, const MissionItem& missionItem)
...@@ -514,17 +514,30 @@ void MissionItem::setParam7(double param) ...@@ -514,17 +514,30 @@ void MissionItem::setParam7(double param)
bool MissionItem::standaloneCoordinate(void) const bool MissionItem::standaloneCoordinate(void) const
{ {
return _mavCmdInfoMap[(MAV_CMD)command()]->standaloneCoordinate(); if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
return _mavCmdInfoMap[(MAV_CMD)command()]->standaloneCoordinate();
} else {
return false;
}
} }
bool MissionItem::specifiesCoordinate(void) const bool MissionItem::specifiesCoordinate(void) const
{ {
return _mavCmdInfoMap[(MAV_CMD)command()]->specifiesCoordinate(); if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
return _mavCmdInfoMap[(MAV_CMD)command()]->specifiesCoordinate();
} else {
return false;
}
} }
QString MissionItem::commandDescription(void) const QString MissionItem::commandDescription(void) const
{ {
return _mavCmdInfoMap[(MAV_CMD)command()]->description(); if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
return _mavCmdInfoMap[(MAV_CMD)command()]->description();
} else {
qWarning() << "Should not ask for command description on unknown command";
return QString();
}
} }
void MissionItem::_clearParamMetaData(void) void MissionItem::_clearParamMetaData(void)
...@@ -676,7 +689,7 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate) ...@@ -676,7 +689,7 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
bool MissionItem::friendlyEditAllowed(void) const bool MissionItem::friendlyEditAllowed(void) const
{ {
if (_mavCmdInfoMap[(MAV_CMD)command()]->friendlyEdit()) { if (_mavCmdInfoMap.contains((MAV_CMD)command()) && _mavCmdInfoMap[(MAV_CMD)command()]->friendlyEdit()) {
if (!autoContinue()) { if (!autoContinue()) {
return false; return false;
} }
...@@ -797,10 +810,12 @@ void MissionItem::setDefaultsForCommand(void) ...@@ -797,10 +810,12 @@ void MissionItem::setDefaultsForCommand(void)
// We set these global defaults first, then if there are param defaults they will get reset // We set these global defaults first, then if there are param defaults they will get reset
setParam7(defaultAltitude); setParam7(defaultAltitude);
foreach (const MavCmdParamInfo* paramInfo, _mavCmdInfoMap[(MAV_CMD)command()]->paramInfoMap()) { if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
Fact* rgParamFacts[7] = { &_param1Fact, &_param2Fact, &_param3Fact, &_param4Fact, &_param5Fact, &_param6Fact, &_param7Fact }; foreach (const MavCmdParamInfo* paramInfo, _mavCmdInfoMap[(MAV_CMD)command()]->paramInfoMap()) {
Fact* rgParamFacts[7] = { &_param1Fact, &_param2Fact, &_param3Fact, &_param4Fact, &_param5Fact, &_param6Fact, &_param7Fact };
rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue()); rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue());
}
} }
setAutoContinue(true); setAutoContinue(true);
...@@ -825,9 +840,12 @@ void MissionItem::_sendCommandChanged(void) ...@@ -825,9 +840,12 @@ void MissionItem::_sendCommandChanged(void)
QString MissionItem::commandName(void) const QString MissionItem::commandName(void) const
{ {
const MavCmdInfo* mavCmdInfo = _mavCmdInfoMap[(MAV_CMD)command()]; if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
const MavCmdInfo* mavCmdInfo = _mavCmdInfoMap[(MAV_CMD)command()];
return mavCmdInfo->friendlyName().isEmpty() ? mavCmdInfo->rawName() : mavCmdInfo->friendlyName(); return mavCmdInfo->friendlyName().isEmpty() ? mavCmdInfo->rawName() : mavCmdInfo->friendlyName();
} else {
return QString("Unknown: %1").arg(command());
}
} }
QVariant MissionItem::_degreesToRadians(const QVariant& degrees) QVariant MissionItem::_degreesToRadians(const QVariant& degrees)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment