Commit 8dd3148d authored by Don Gagne's avatar Don Gagne

Merge pull request #2481 from DonLakeFlyer/AutoTranslation

Automatic raw->cooked translation based on units meta data
parents de276119 1e613594
...@@ -80,7 +80,7 @@ void Fact::forceSetRawValue(const QVariant& value) ...@@ -80,7 +80,7 @@ void Fact::forceSetRawValue(const QVariant& value)
QVariant typedValue; QVariant typedValue;
QString errorString; QString errorString;
if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) { if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
_rawValue.setValue(typedValue); _rawValue.setValue(typedValue);
emit valueChanged(cookedValue()); emit valueChanged(cookedValue());
emit _containerRawValueChanged(rawValue()); emit _containerRawValueChanged(rawValue());
...@@ -96,7 +96,7 @@ void Fact::setRawValue(const QVariant& value) ...@@ -96,7 +96,7 @@ void Fact::setRawValue(const QVariant& value)
QVariant typedValue; QVariant typedValue;
QString errorString; QString errorString;
if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) { if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
if (typedValue != _rawValue) { if (typedValue != _rawValue) {
_rawValue.setValue(typedValue); _rawValue.setValue(typedValue);
emit valueChanged(cookedValue()); emit valueChanged(cookedValue());
...@@ -242,27 +242,45 @@ QString Fact::_variantToString(const QVariant& variant) const ...@@ -242,27 +242,45 @@ QString Fact::_variantToString(const QVariant& variant) const
return valueString; return valueString;
} }
QString Fact::valueString(void) const QString Fact::rawValueString(void) const
{
return _variantToString(rawValue());
}
QString Fact::cookedValueString(void) const
{ {
return _variantToString(cookedValue()); return _variantToString(cookedValue());
} }
QVariant Fact::defaultValue(void) const QVariant Fact::rawDefaultValue(void) const
{
if (_metaData) {
if (!_metaData->defaultValueAvailable()) {
qDebug() << "Access to unavailable default value";
}
return _metaData->rawDefaultValue();
} else {
qWarning() << "Meta data pointer missing";
return QVariant(0);
}
}
QVariant Fact::cookedDefaultValue(void) const
{ {
if (_metaData) { if (_metaData) {
if (!_metaData->defaultValueAvailable()) { if (!_metaData->defaultValueAvailable()) {
qDebug() << "Access to unavailable default value"; qDebug() << "Access to unavailable default value";
} }
return _metaData->defaultValue(); return _metaData->cookedDefaultValue();
} else { } else {
qWarning() << "Meta data pointer missing"; qWarning() << "Meta data pointer missing";
return QVariant(0); return QVariant(0);
} }
} }
QString Fact::defaultValueString(void) const QString Fact::cookedDefaultValueString(void) const
{ {
return _variantToString(defaultValue()); return _variantToString(cookedDefaultValue());
} }
FactMetaData::ValueType_t Fact::type(void) const FactMetaData::ValueType_t Fact::type(void) const
...@@ -290,44 +308,74 @@ QString Fact::longDescription(void) const ...@@ -290,44 +308,74 @@ QString Fact::longDescription(void) const
} }
} }
QString Fact::units(void) const QString Fact::rawUnits(void) const
{
if (_metaData) {
return _metaData->rawUnits();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
}
QString Fact::cookedUnits(void) const
{ {
if (_metaData) { if (_metaData) {
return _metaData->units(); return _metaData->cookedUnits();
} else { } else {
qWarning() << "Meta data pointer missing"; qWarning() << "Meta data pointer missing";
return QString(); return QString();
} }
} }
QVariant Fact::min(void) const QVariant Fact::rawMin(void) const
{ {
if (_metaData) { if (_metaData) {
return _metaData->min(); return _metaData->rawMin();
} else { } else {
qWarning() << "Meta data pointer missing"; qWarning() << "Meta data pointer missing";
return QVariant(0); return QVariant(0);
} }
} }
QString Fact::minString(void) const QVariant Fact::cookedMin(void) const
{ {
return _variantToString(min()); if (_metaData) {
return _metaData->cookedMin();
} else {
qWarning() << "Meta data pointer missing";
return QVariant(0);
}
} }
QVariant Fact::max(void) const QString Fact::cookedMinString(void) const
{
return _variantToString(cookedMin());
}
QVariant Fact::rawMax(void) const
{ {
if (_metaData) { if (_metaData) {
return _metaData->max(); return _metaData->rawMax();
} else { } else {
qWarning() << "Meta data pointer missing"; qWarning() << "Meta data pointer missing";
return QVariant(0); return QVariant(0);
} }
} }
QString Fact::maxString(void) const QVariant Fact::cookedMax(void) const
{ {
return _variantToString(max()); if (_metaData) {
return _metaData->cookedMax();
} else {
qWarning() << "Meta data pointer missing";
return QVariant(0);
}
}
QString Fact::cookedMaxString(void) const
{
return _variantToString(cookedMax());
} }
bool Fact::minIsDefaultForType(void) const bool Fact::minIsDefaultForType(void) const
...@@ -372,6 +420,8 @@ QString Fact::group(void) const ...@@ -372,6 +420,8 @@ QString Fact::group(void) const
void Fact::setMetaData(FactMetaData* metaData) void Fact::setMetaData(FactMetaData* metaData)
{ {
// FIXME: Hack to stuff enums into APM parameters, wating on real APM metadata
static QStringList apmFlightModeParamList; static QStringList apmFlightModeParamList;
static QStringList apmFlightModeEnumStrings; static QStringList apmFlightModeEnumStrings;
static QVariantList apmFlightModeEnumValues; static QVariantList apmFlightModeEnumValues;
...@@ -380,8 +430,6 @@ void Fact::setMetaData(FactMetaData* metaData) ...@@ -380,8 +430,6 @@ void Fact::setMetaData(FactMetaData* metaData)
static QStringList apmChannelOptEnumStrings; static QStringList apmChannelOptEnumStrings;
static QVariantList apmChannelOptEnumValues; static QVariantList apmChannelOptEnumValues;
// FIXME: Hack to stuff enums into APM parameters, wating on real APM metadata
if (apmFlightModeEnumStrings.count() == 0) { if (apmFlightModeEnumStrings.count() == 0) {
apmFlightModeParamList << "FLTMODE1" << "FLTMODE2" << "FLTMODE3" << "FLTMODE4" << "FLTMODE5" << "FLTMODE6"; apmFlightModeParamList << "FLTMODE1" << "FLTMODE2" << "FLTMODE3" << "FLTMODE4" << "FLTMODE5" << "FLTMODE6";
apmFlightModeEnumStrings << "Stabilize" << "Acro" << "AltHold" << "Auto" << "Guided" << "Loiter" << "RTL" << "Circle" apmFlightModeEnumStrings << "Stabilize" << "Acro" << "AltHold" << "Auto" << "Guided" << "Loiter" << "RTL" << "Circle"
...@@ -415,7 +463,7 @@ bool Fact::valueEqualsDefault(void) const ...@@ -415,7 +463,7 @@ bool Fact::valueEqualsDefault(void) const
{ {
if (_metaData) { if (_metaData) {
if (_metaData->defaultValueAvailable()) { if (_metaData->defaultValueAvailable()) {
return _metaData->defaultValue() == rawValue(); return _metaData->rawDefaultValue() == rawValue();
} else { } else {
return false; return false;
} }
...@@ -435,14 +483,13 @@ bool Fact::defaultValueAvailable(void) const ...@@ -435,14 +483,13 @@ bool Fact::defaultValueAvailable(void) const
} }
} }
QString Fact::validate(const QString& value, bool convertOnly) QString Fact::validate(const QString& cookedValue, bool convertOnly)
{ {
if (_metaData) { if (_metaData) {
QVariant typedValue; QVariant typedValue;
QString errorString; QString errorString;
_metaData->convertAndValidate(value, convertOnly, typedValue, errorString); _metaData->convertAndValidateCooked(cookedValue, convertOnly, typedValue, errorString);
return errorString; return errorString;
} else { } else {
......
...@@ -48,8 +48,8 @@ public: ...@@ -48,8 +48,8 @@ public:
Q_PROPERTY(int componentId READ componentId CONSTANT) Q_PROPERTY(int componentId READ componentId CONSTANT)
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT) Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT) Q_PROPERTY(QVariant defaultValue READ cookedDefaultValue CONSTANT)
Q_PROPERTY(QString defaultValueString READ defaultValueString CONSTANT) Q_PROPERTY(QString defaultValueString READ cookedDefaultValueString 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 NOTIFY enumStringsChanged) Q_PROPERTY(QStringList enumStrings READ enumStrings NOTIFY enumStringsChanged)
...@@ -57,48 +57,53 @@ public: ...@@ -57,48 +57,53 @@ public:
Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumValuesChanged) 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 cookedMax CONSTANT)
Q_PROPERTY(QString maxString READ maxString CONSTANT) Q_PROPERTY(QString maxString READ cookedMaxString CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT) Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT) Q_PROPERTY(QVariant min READ cookedMin CONSTANT)
Q_PROPERTY(QString minString READ minString CONSTANT) Q_PROPERTY(QString minString READ cookedMinString CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT) Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT) Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT) Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
Q_PROPERTY(QString units READ units CONSTANT) Q_PROPERTY(QString units READ cookedUnits CONSTANT)
Q_PROPERTY(QVariant value READ cookedValue WRITE setCookedValue NOTIFY valueChanged) Q_PROPERTY(QVariant value READ cookedValue WRITE setCookedValue NOTIFY valueChanged)
Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) Q_PROPERTY(QVariant valueString READ cookedValueString NOTIFY valueChanged)
/// Convert and validate value /// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well /// @param convertOnly true: validate type conversion only, false: validate against meta data as well
Q_INVOKABLE QString validate(const QString& value, bool convertOnly); Q_INVOKABLE QString validate(const QString& cookedValue, bool convertOnly);
QVariant cookedValue (void) const; /// Value after translation QVariant cookedValue (void) const; /// Value after translation
QVariant rawValue (void) const { return _rawValue; } /// value prior to translation, careful
int componentId (void) const; int componentId (void) const;
int decimalPlaces (void) const; int decimalPlaces (void) const;
QVariant defaultValue (void) const; QVariant rawDefaultValue (void) const;
QVariant cookedDefaultValue (void) const;
bool defaultValueAvailable (void) const; bool defaultValueAvailable (void) const;
QString defaultValueString (void) const; QString cookedDefaultValueString(void) const;
int enumIndex (void); // This is not const, since an unknown value can modify the enum lists 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); // This is not const, since an unknown value can modify the enum lists 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;
QVariant max (void) const; QVariant rawMax (void) const;
QString maxString (void) const; QVariant cookedMax (void) const;
QString cookedMaxString (void) const;
bool maxIsDefaultForType (void) const; bool maxIsDefaultForType (void) const;
QVariant min (void) const; QVariant rawMin (void) const;
QString minString (void) const; QVariant cookedMin (void) const;
QString cookedMinString (void) const;
bool minIsDefaultForType (void) const; bool minIsDefaultForType (void) const;
QString name (void) const; QString name (void) const;
QVariant rawValue (void) const { return _rawValue; } /// value prior to translation, careful
QString shortDescription (void) const; QString shortDescription (void) const;
FactMetaData::ValueType_t type (void) const; FactMetaData::ValueType_t type (void) const;
QString units (void) const; QString cookedUnits (void) const;
QString valueString (void) const; QString rawUnits (void) const;
QString rawValueString (void) const;
QString cookedValueString (void) const;
bool valueEqualsDefault (void) const; bool valueEqualsDefault (void) const;
void setRawValue (const QVariant& value); void setRawValue (const QVariant& value);
......
This diff is collapsed.
...@@ -61,20 +61,24 @@ public: ...@@ -61,20 +61,24 @@ public:
const FactMetaData& operator=(const FactMetaData& other); const FactMetaData& operator=(const FactMetaData& other);
int decimalPlaces (void) const { return _decimalPlaces; } int decimalPlaces (void) const { return _decimalPlaces; }
QVariant defaultValue (void) const; QVariant rawDefaultValue (void) const;
QVariant cookedDefaultValue (void) const { return _rawTranslator(rawDefaultValue()); }
bool defaultValueAvailable (void) const { return _defaultValueAvailable; } bool defaultValueAvailable (void) const { return _defaultValueAvailable; }
QStringList enumStrings (void) const { return _enumStrings; } QStringList enumStrings (void) const { return _enumStrings; }
QVariantList enumValues (void) const { return _enumValues; } QVariantList enumValues (void) const { return _enumValues; }
QString group (void) const { return _group; } QString group (void) const { return _group; }
QString longDescription (void) const { return _longDescription;} QString longDescription (void) const { return _longDescription;}
QVariant max (void) const { return _max; } QVariant rawMax (void) const { return _rawMax; }
QVariant cookedMax (void) const { return _rawTranslator(_rawMax); }
bool maxIsDefaultForType (void) const { return _maxIsDefaultForType; } bool maxIsDefaultForType (void) const { return _maxIsDefaultForType; }
QVariant min (void) const { return _min; } QVariant rawMin (void) const { return _rawMin; }
QVariant cookedMin (void) const { return _rawTranslator(_rawMin); }
bool minIsDefaultForType (void) const { return _minIsDefaultForType; } bool minIsDefaultForType (void) const { return _minIsDefaultForType; }
QString name (void) const { return _name; } QString name (void) const { return _name; }
QString shortDescription (void) const { return _shortDescription; } QString shortDescription (void) const { return _shortDescription; }
ValueType_t type (void) const { return _type; } ValueType_t type (void) const { return _type; }
QString units (void) const { return _units; } QString rawUnits (void) const { return _rawUnits; }
QString cookedUnits (void) const { return _cookedUnits; }
Translator rawTranslator (void) const { return _rawTranslator; } Translator rawTranslator (void) const { return _rawTranslator; }
Translator cookedTranslator (void) const { return _cookedTranslator; } Translator cookedTranslator (void) const { return _cookedTranslator; }
...@@ -83,50 +87,71 @@ public: ...@@ -83,50 +87,71 @@ public:
void addEnumInfo(const QString& name, const QVariant& value); 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 setRawDefaultValue (const QVariant& rawDefaultValue);
void setEnumInfo (const QStringList& strings, const QVariantList& values); void setEnumInfo (const QStringList& strings, const QVariantList& values);
void setGroup (const QString& group) { _group = group; } void setGroup (const QString& group) { _group = group; }
void setLongDescription (const QString& longDescription) { _longDescription = longDescription;} void setLongDescription (const QString& longDescription) { _longDescription = longDescription;}
void setMax (const QVariant& max); void setRawMax (const QVariant& rawMax);
void setMin (const QVariant& max); void setRawMin (const QVariant& rawMin);
void setName (const QString& name) { _name = name; } void setName (const QString& name) { _name = name; }
void setShortDescription(const QString& shortDescription) { _shortDescription = shortDescription; } void setShortDescription(const QString& shortDescription) { _shortDescription = shortDescription; }
void setUnits (const QString& units) { _units = units; } void setRawUnits (const QString& rawUnits);
void setTranslators(Translator rawTranslator, Translator cookedTranslator); void setTranslators(Translator rawTranslator, Translator cookedTranslator);
static QVariant defaultTranslator(const QVariant& from) { return from; }
/// Converts the specified value, validating against meta data /// Converts the specified raw value, validating against meta data
/// @param value Value to convert, can be string /// @param rawValue Value to convert, can be string
/// @param convertOnly true: convert to correct type only, do not validate against meta data /// @param convertOnly true: convert to correct type only, do not validate against meta data
/// @param typeValue Converted value, correctly typed /// @param typeValue Converted value, correctly typed
/// @param errorString Error string if convert fails /// @param errorString Error string if convert fails, values are cooked values since user visible
/// @returns false: Convert failed, errorString set /// @returns false: Convert failed, errorString set
bool convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString); bool convertAndValidateRaw(const QVariant& rawValue, bool convertOnly, QVariant& typedValue, QString& errorString);
/// Same as convertAndValidateRaw except for cookedValue input
bool convertAndValidateCooked(const QVariant& cookedValue, bool convertOnly, QVariant& typedValue, QString& errorString);
static const int defaultDecimalPlaces = 3; static const int defaultDecimalPlaces = 3;
private: private:
QVariant _minForType(void) const; QVariant _minForType(void) const;
QVariant _maxForType(void) const; QVariant _maxForType(void) const;
void _setBuiltInTranslator(void);
// Built in translators
static QVariant _defaultTranslator(const QVariant& from) { return from; }
static QVariant _degreesToRadians(const QVariant& degrees);
static QVariant _radiansToDegrees(const QVariant& radians);
static QVariant _centiDegreesToDegrees(const QVariant& centiDegrees);
static QVariant _degreesToCentiDegrees(const QVariant& degrees);
ValueType_t _type; // must be first for correct constructor init ValueType_t _type; // must be first for correct constructor init
int _decimalPlaces; int _decimalPlaces;
QVariant _defaultValue; QVariant _rawDefaultValue;
bool _defaultValueAvailable; bool _defaultValueAvailable;
QStringList _enumStrings; QStringList _enumStrings;
QVariantList _enumValues; QVariantList _enumValues;
QString _group; QString _group;
QString _longDescription; QString _longDescription;
QVariant _max; QVariant _rawMax;
bool _maxIsDefaultForType; bool _maxIsDefaultForType;
QVariant _min; QVariant _rawMin;
bool _minIsDefaultForType; bool _minIsDefaultForType;
QString _name; QString _name;
QString _shortDescription; QString _shortDescription;
QString _units; QString _rawUnits;
QString _cookedUnits;
Translator _rawTranslator; Translator _rawTranslator;
Translator _cookedTranslator; Translator _cookedTranslator;
struct BuiltInTranslation_s {
const char* rawUnits;
const char* cookedUnits;
Translator rawTranslator;
Translator cookedTranslator;
};
static const BuiltInTranslation_s _rgBuildInTranslations[];
}; };
#endif #endif
...@@ -721,7 +721,7 @@ void ParameterLoader::writeParametersToStream(QTextStream &stream) ...@@ -721,7 +721,7 @@ void ParameterLoader::writeParametersToStream(QTextStream &stream)
Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>(); Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
Q_ASSERT(fact); Q_ASSERT(fact);
stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->valueString() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n"; stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueString() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
} }
} }
......
...@@ -434,14 +434,14 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) ...@@ -434,14 +434,14 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
} }
if (!rawMetaData->units.isEmpty()) { if (!rawMetaData->units.isEmpty()) {
metaData->setUnits(rawMetaData->units); metaData->setRawUnits(rawMetaData->units);
} }
if (!rawMetaData->min.isEmpty()) { if (!rawMetaData->min.isEmpty()) {
QVariant varMin; QVariant varMin;
QString errorString; QString errorString;
if (metaData->convertAndValidate(rawMetaData->min, false /* validate as well */, varMin, errorString)) { if (metaData->convertAndValidateRaw(rawMetaData->min, false /* validate as well */, varMin, errorString)) {
metaData->setMin(varMin); metaData->setRawMin(varMin);
} else { } else {
qCDebug(APMParameterMetaDataLog) << "Invalid min value, name:" << metaData->name() qCDebug(APMParameterMetaDataLog) << "Invalid min value, name:" << metaData->name()
<< " type:" << metaData->type() << " min:" << rawMetaData->min << " type:" << metaData->type() << " min:" << rawMetaData->min
...@@ -452,8 +452,8 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) ...@@ -452,8 +452,8 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
if (!rawMetaData->max.isEmpty()) { if (!rawMetaData->max.isEmpty()) {
QVariant varMax; QVariant varMax;
QString errorString; QString errorString;
if (metaData->convertAndValidate(rawMetaData->max, false /* validate as well */, varMax, errorString)) { if (metaData->convertAndValidateRaw(rawMetaData->max, false /* validate as well */, varMax, errorString)) {
metaData->setMax(varMax); metaData->setRawMax(varMax);
} else { } else {
qCDebug(APMParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:" qCDebug(APMParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:"
<< metaData->type() << " max:" << rawMetaData->max << metaData->type() << " max:" << rawMetaData->max
...@@ -470,7 +470,7 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) ...@@ -470,7 +470,7 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
QString errorString; QString errorString;
QPair<QString, QString> enumPair = rawMetaData->values[i]; QPair<QString, QString> enumPair = rawMetaData->values[i];
if (metaData->convertAndValidate(enumPair.first, false /* validate */, enumValue, errorString)) { if (metaData->convertAndValidateRaw(enumPair.first, false /* validate */, enumValue, errorString)) {
enumValues << enumValue; enumValues << enumValue;
enumStrings << enumPair.second; enumStrings << enumPair.second;
} else { } else {
......
...@@ -239,8 +239,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) ...@@ -239,8 +239,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) { if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) {
QVariant varDefault; QVariant varDefault;
if (metaData->convertAndValidate(strDefault, false, varDefault, errorString)) { if (metaData->convertAndValidateRaw(strDefault, false, varDefault, errorString)) {
metaData->setDefaultValue(varDefault); metaData->setRawDefaultValue(varDefault);
} else { } else {
qCWarning(PX4ParameterMetaDataLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString; qCWarning(PX4ParameterMetaDataLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString;
} }
...@@ -275,8 +275,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) ...@@ -275,8 +275,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
qCDebug(PX4ParameterMetaDataLog) << "Min:" << text; qCDebug(PX4ParameterMetaDataLog) << "Min:" << text;
QVariant varMin; QVariant varMin;
if (metaData->convertAndValidate(text, true /* convertOnly */, varMin, errorString)) { if (metaData->convertAndValidateRaw(text, true /* convertOnly */, varMin, errorString)) {
metaData->setMin(varMin); metaData->setRawMin(varMin);
} else { } else {
qCWarning(PX4ParameterMetaDataLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString; qCWarning(PX4ParameterMetaDataLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString;
} }
...@@ -287,8 +287,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) ...@@ -287,8 +287,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
qCDebug(PX4ParameterMetaDataLog) << "Max:" << text; qCDebug(PX4ParameterMetaDataLog) << "Max:" << text;
QVariant varMax; QVariant varMax;
if (metaData->convertAndValidate(text, true /* convertOnly */, varMax, errorString)) { if (metaData->convertAndValidateRaw(text, true /* convertOnly */, varMax, errorString)) {
metaData->setMax(varMax); metaData->setRawMax(varMax);
} else { } else {
qCWarning(PX4ParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString; qCWarning(PX4ParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString;
} }
...@@ -297,7 +297,7 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) ...@@ -297,7 +297,7 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
Q_ASSERT(metaData); Q_ASSERT(metaData);
QString text = xml.readElementText(); QString text = xml.readElementText();
qCDebug(PX4ParameterMetaDataLog) << "Unit:" << text; qCDebug(PX4ParameterMetaDataLog) << "Unit:" << text;
metaData->setUnits(text); metaData->setRawUnits(text);
} else if (elementName == "decimal") { } else if (elementName == "decimal") {
Q_ASSERT(metaData); Q_ASSERT(metaData);
...@@ -325,8 +325,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) ...@@ -325,8 +325,8 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
if (metaData->defaultValueAvailable()) { if (metaData->defaultValueAvailable()) {
QVariant var; QVariant var;
if (!metaData->convertAndValidate(metaData->defaultValue(), false /* convertOnly */, var, errorString)) { if (!metaData->convertAndValidateRaw(metaData->rawDefaultValue(), false /* convertOnly */, var, errorString)) {
qCWarning(PX4ParameterMetaDataLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->defaultValue() << " error:" << errorString; qCWarning(PX4ParameterMetaDataLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->rawDefaultValue() << " error:" << errorString;
} }
} }
......
...@@ -113,7 +113,7 @@ ...@@ -113,7 +113,7 @@
}, },
"param4": { "param4": {
"label": "Heading:", "label": "Heading:",
"units": "degreesConvert", "units": "radians",
"default": 0.0, "default": 0.0,
"decimalPlaces": 2 "decimalPlaces": 2
} }
...@@ -128,13 +128,13 @@ ...@@ -128,13 +128,13 @@
"category": "Basic", "category": "Basic",
"param1": { "param1": {
"label": "Pitch:", "label": "Pitch:",
"units": "degreesConvert", "units": "radians",
"default": 0.26179939, "default": 0.26179939,
"decimalPlaces": 2 "decimalPlaces": 2
}, },
"param4": { "param4": {
"label": "Heading:", "label": "Heading:",
"units": "degreesConvert", "units": "radians",
"default": 0.0, "default": 0.0,
"decimalPlaces": 2 "decimalPlaces": 2
} }
......
...@@ -58,9 +58,6 @@ const QString MissionCommands::_specifiesCoordinateJsonKey (QStringLiteral("spe ...@@ -58,9 +58,6 @@ const QString MissionCommands::_specifiesCoordinateJsonKey (QStringLiteral("spe
const QString MissionCommands::_unitsJsonKey (QStringLiteral("units")); const QString MissionCommands::_unitsJsonKey (QStringLiteral("units"));
const QString MissionCommands::_versionJsonKey (QStringLiteral("version")); const QString MissionCommands::_versionJsonKey (QStringLiteral("version"));
const QString MissionCommands::_degreesConvertUnits (QStringLiteral("degreesConvert"));
const QString MissionCommands::_degreesUnits (QStringLiteral("degrees"));
MissionCommands::MissionCommands(QGCApplication* app) MissionCommands::MissionCommands(QGCApplication* app)
: QGCTool(app) : QGCTool(app)
{ {
......
...@@ -139,9 +139,6 @@ public: ...@@ -139,9 +139,6 @@ public:
// Overrides from QGCTool // Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox); virtual void setToolbox(QGCToolbox* toolbox);
static const QString _degreesUnits;
static const QString _degreesConvertUnits;
signals: signals:
private: private:
......
...@@ -309,7 +309,7 @@ void MissionItem::_setupMetaData(void) ...@@ -309,7 +309,7 @@ void MissionItem::_setupMetaData(void)
if (!_altitudeMetaData) { if (!_altitudeMetaData) {
_altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble); _altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
_altitudeMetaData->setUnits("meters"); _altitudeMetaData->setRawUnits("meters");
_altitudeMetaData->setDecimalPlaces(3); _altitudeMetaData->setDecimalPlaces(3);
enumStrings.clear(); enumStrings.clear();
...@@ -336,11 +336,11 @@ void MissionItem::_setupMetaData(void) ...@@ -336,11 +336,11 @@ void MissionItem::_setupMetaData(void)
_frameMetaData->setEnumInfo(enumStrings, enumValues); _frameMetaData->setEnumInfo(enumStrings, enumValues);
_latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble); _latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
_latitudeMetaData->setUnits("deg"); _latitudeMetaData->setRawUnits("deg");
_latitudeMetaData->setDecimalPlaces(7); _latitudeMetaData->setDecimalPlaces(7);
_longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble); _longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
_longitudeMetaData->setUnits("deg"); _longitudeMetaData->setRawUnits("deg");
_longitudeMetaData->setDecimalPlaces(7); _longitudeMetaData->setDecimalPlaces(7);
} }
...@@ -516,18 +516,14 @@ QString MissionItem::commandDescription(void) const ...@@ -516,18 +516,14 @@ QString MissionItem::commandDescription(void) const
void MissionItem::_clearParamMetaData(void) void MissionItem::_clearParamMetaData(void)
{ {
_param1MetaData.setUnits(""); _param1MetaData.setRawUnits("");
_param1MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param1MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param1MetaData.setTranslators(FactMetaData::defaultTranslator, FactMetaData::defaultTranslator); _param2MetaData.setRawUnits("");
_param2MetaData.setUnits("");
_param2MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param2MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param2MetaData.setTranslators(FactMetaData::defaultTranslator, FactMetaData::defaultTranslator); _param3MetaData.setRawUnits("");
_param3MetaData.setUnits("");
_param3MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param3MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param3MetaData.setTranslators(FactMetaData::defaultTranslator, FactMetaData::defaultTranslator); _param4MetaData.setRawUnits("");
_param4MetaData.setUnits("");
_param4MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces); _param4MetaData.setDecimalPlaces(FactMetaData::defaultDecimalPlaces);
_param4MetaData.setTranslators(FactMetaData::defaultTranslator, FactMetaData::defaultTranslator);
} }
QmlObjectListModel* MissionItem::textFieldFacts(void) QmlObjectListModel* MissionItem::textFieldFacts(void)
...@@ -575,12 +571,7 @@ QmlObjectListModel* MissionItem::textFieldFacts(void) ...@@ -575,12 +571,7 @@ QmlObjectListModel* MissionItem::textFieldFacts(void)
paramFact->_setName(paramInfo->label()); paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces()); paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues()); paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues());
if (paramInfo->units() == MissionCommands::_degreesConvertUnits) { paramMetaData->setRawUnits(paramInfo->units());
paramMetaData->setTranslators(_radiansToDegrees, _degreesToRadians);
paramMetaData->setUnits(MissionCommands::_degreesUnits);
} else {
paramMetaData->setUnits(paramInfo->units());
}
paramFact->setMetaData(paramMetaData); paramFact->setMetaData(paramMetaData);
model->append(paramFact); model->append(paramFact);
} }
...@@ -634,12 +625,7 @@ QmlObjectListModel* MissionItem::comboboxFacts(void) ...@@ -634,12 +625,7 @@ QmlObjectListModel* MissionItem::comboboxFacts(void)
paramFact->_setName(paramInfo->label()); paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces()); paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues()); paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues());
if (paramInfo->units() == MissionCommands::_degreesConvertUnits) { paramMetaData->setRawUnits(paramInfo->units());
paramMetaData->setTranslators(_radiansToDegrees, _degreesToRadians);
paramMetaData->setUnits(MissionCommands::_degreesUnits);
} else {
paramMetaData->setUnits(paramInfo->units());
}
paramFact->setMetaData(paramMetaData); paramFact->setMetaData(paramMetaData);
model->append(paramFact); model->append(paramFact);
} }
...@@ -804,16 +790,6 @@ QString MissionItem::commandName(void) const ...@@ -804,16 +790,6 @@ QString MissionItem::commandName(void) const
} }
} }
QVariant MissionItem::_degreesToRadians(const QVariant& degrees)
{
return QVariant(degrees.toDouble() * (M_PI / 180.0));
}
QVariant MissionItem::_radiansToDegrees(const QVariant& radians)
{
return QVariant(radians.toDouble() * (180 / M_PI));
}
void MissionItem::_sendFriendlyEditAllowedChanged(void) void MissionItem::_sendFriendlyEditAllowedChanged(void)
{ {
emit friendlyEditAllowedChanged(friendlyEditAllowed()); emit friendlyEditAllowedChanged(friendlyEditAllowed());
......
...@@ -211,9 +211,6 @@ private: ...@@ -211,9 +211,6 @@ private:
void _connectSignals(void); void _connectSignals(void);
void _setupMetaData(void); void _setupMetaData(void);
static QVariant _degreesToRadians(const QVariant& degrees);
static QVariant _radiansToDegrees(const QVariant& radians);
private: private:
bool _rawEdit; bool _rawEdit;
bool _dirty; bool _dirty;
......
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