diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index f3a61761428170e8fe7f636b0c19e9bfe05294dc..abbd3d0210a17c0094b8a566317d6abec201668b 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -165,7 +165,7 @@ QVariant Fact::cookedValue(void) const } } -QString Fact::enumStringValue(void) const +QString Fact::enumStringValue(void) { if (_metaData) { int enumIndex = this->enumIndex(); @@ -179,16 +179,23 @@ QString Fact::enumStringValue(void) const return QString(); } -int Fact::enumIndex(void) const +int Fact::enumIndex(void) { if (_metaData) { int index = 0; + foreach (QVariant enumValue, _metaData->enumValues()) { if (enumValue == rawValue()) { return 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 { qWarning() << "Meta data pointer missing"; } diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index 4acd5f70deadf8c726096e87b3ae1b43d8f69a46..f2e311c8f59eafc3d2dd3c2ca539dab4163444dd 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -52,9 +52,9 @@ public: Q_PROPERTY(QString defaultValueString READ defaultValueString CONSTANT) Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) 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(QVariantList enumValues READ enumValues CONSTANT) + Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumValuesChanged) Q_PROPERTY(QString group READ group CONSTANT) Q_PROPERTY(QString longDescription READ longDescription CONSTANT) Q_PROPERTY(QVariant max READ max CONSTANT) @@ -81,9 +81,9 @@ public: QVariant defaultValue (void) const; bool defaultValueAvailable (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; - QString enumStringValue (void) const; + QString enumStringValue (void); // This is not const, since an unknown value can modify the enum lists QVariantList enumValues (void) const; QString group (void) const; QString longDescription (void) const; @@ -120,6 +120,9 @@ public: void _setName(const QString& name) { _name = name; } signals: + void enumStringsChanged(void); + void enumValuesChanged(void); + /// 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. diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index a1c9efa6810083e11f266dfbaf29f417f0e0aab8..45a800eb4e50e00230ce6f8f22160bb5989c3304 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -260,3 +260,9 @@ void FactMetaData::setTranslators(Translator rawTranslator, Translator cookedTra _rawTranslator = rawTranslator; _cookedTranslator = cookedTranslator; } + +void FactMetaData::addEnumInfo(const QString& name, const QVariant& value) +{ + _enumStrings << name; + _enumValues << value; +} diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index b276455ec0ba8cd90af714c654c58c95f29e126b..1d2a711df1ecca6d35093cb911ddd9574c58e7d1 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -79,6 +79,9 @@ public: Translator rawTranslator (void) const { return _rawTranslator; } 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 setDefaultValue (const QVariant& defaultValue); void setEnumInfo (const QStringList& strings, const QVariantList& values); diff --git a/src/MissionManager/MissionItem.cc b/src/MissionManager/MissionItem.cc index 352864be05db746b9067212a4f110653cc9346f0..8f477f21c4ef9ac2a81b0e577715faba3fb7a353 100644 --- a/src/MissionManager/MissionItem.cc +++ b/src/MissionManager/MissionItem.cc @@ -45,18 +45,18 @@ struct EnumInfo_s { }; static const struct EnumInfo_s _rgMavFrameInfo[] = { - { "MAV_FRAME_GLOBAL", MAV_FRAME_GLOBAL }, - { "MAV_FRAME_LOCAL_NED", MAV_FRAME_LOCAL_NED }, - { "MAV_FRAME_MISSION", MAV_FRAME_MISSION }, - { "MAV_FRAME_GLOBAL_RELATIVE_ALT", MAV_FRAME_GLOBAL_RELATIVE_ALT }, - { "MAV_FRAME_LOCAL_ENU", MAV_FRAME_LOCAL_ENU }, - { "MAV_FRAME_GLOBAL_INT", MAV_FRAME_GLOBAL_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_BODY_NED", MAV_FRAME_BODY_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_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, +{ "MAV_FRAME_GLOBAL", MAV_FRAME_GLOBAL }, +{ "MAV_FRAME_LOCAL_NED", MAV_FRAME_LOCAL_NED }, +{ "MAV_FRAME_MISSION", MAV_FRAME_MISSION }, +{ "MAV_FRAME_GLOBAL_RELATIVE_ALT", MAV_FRAME_GLOBAL_RELATIVE_ALT }, +{ "MAV_FRAME_LOCAL_ENU", MAV_FRAME_LOCAL_ENU }, +{ "MAV_FRAME_GLOBAL_INT", MAV_FRAME_GLOBAL_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_BODY_NED", MAV_FRAME_BODY_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_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, }; QDebug operator<<(QDebug dbg, const MissionItem& missionItem) @@ -514,17 +514,30 @@ void MissionItem::setParam7(double param) 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 { - 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 { - 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) @@ -676,7 +689,7 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate) bool MissionItem::friendlyEditAllowed(void) const { - if (_mavCmdInfoMap[(MAV_CMD)command()]->friendlyEdit()) { + if (_mavCmdInfoMap.contains((MAV_CMD)command()) && _mavCmdInfoMap[(MAV_CMD)command()]->friendlyEdit()) { if (!autoContinue()) { return false; } @@ -797,10 +810,12 @@ void MissionItem::setDefaultsForCommand(void) // We set these global defaults first, then if there are param defaults they will get reset setParam7(defaultAltitude); - foreach (const MavCmdParamInfo* paramInfo, _mavCmdInfoMap[(MAV_CMD)command()]->paramInfoMap()) { - Fact* rgParamFacts[7] = { &_param1Fact, &_param2Fact, &_param3Fact, &_param4Fact, &_param5Fact, &_param6Fact, &_param7Fact }; + if (_mavCmdInfoMap.contains((MAV_CMD)command())) { + 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); @@ -825,9 +840,12 @@ void MissionItem::_sendCommandChanged(void) QString MissionItem::commandName(void) const { - const MavCmdInfo* mavCmdInfo = _mavCmdInfoMap[(MAV_CMD)command()]; - - return mavCmdInfo->friendlyName().isEmpty() ? mavCmdInfo->rawName() : mavCmdInfo->friendlyName(); + if (_mavCmdInfoMap.contains((MAV_CMD)command())) { + const MavCmdInfo* mavCmdInfo = _mavCmdInfoMap[(MAV_CMD)command()]; + return mavCmdInfo->friendlyName().isEmpty() ? mavCmdInfo->rawName() : mavCmdInfo->friendlyName(); + } else { + return QString("Unknown: %1").arg(command()); + } } QVariant MissionItem::_degreesToRadians(const QVariant& degrees)