Commit b3e13a6f authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4575 from DonLakeFlyer/StringFact

FactSystem: String support
parents 0faac4c4 80ee708c
......@@ -16,12 +16,14 @@ QGCTextField {
showUnits: true
showHelp: true
property Fact fact: null
property Fact fact: null
property string _validateString
property bool _factIsString: fact ? fact.type === FactMetaData.valueTypeString : false
// At this point all Facts are numeric
inputMethodHints: ScreenTools.isiOS ?
Qt.ImhNone : // iOS numeric keyboard has not done button, we can't use it
inputMethodHints: (_factIsString || ScreenTools.isiOS) ?
Qt.ImhNone : // iOS numeric keyboard has no done button, we can't use it
Qt.ImhFormattedNumbersOnly // Forces use of virtual numeric keyboard
onEditingFinished: {
......
......@@ -7,12 +7,6 @@
*
****************************************************************************/
/// @file
/// @brief Object which exposes a FactMetaData
///
/// @author Don Gagne <don@thegagnes.com>
#include "FactMetaData.h"
#include "SettingsManager.h"
#include "JsonHelper.h"
......@@ -157,7 +151,7 @@ QVariant FactMetaData::rawDefaultValue(void) const
void FactMetaData::setRawDefaultValue(const QVariant& rawDefaultValue)
{
if (_rawMin <= rawDefaultValue && rawDefaultValue <= _rawMax) {
if (_type == valueTypeString || (_rawMin <= rawDefaultValue && rawDefaultValue <= _rawMax)) {
_rawDefaultValue = rawDefaultValue;
_defaultValueAvailable = true;
} else {
......@@ -208,6 +202,8 @@ QVariant FactMetaData::_minForType(void) const
return QVariant(-std::numeric_limits<float>::max());
case valueTypeDouble:
return QVariant(-std::numeric_limits<double>::max());
case valueTypeString:
return QVariant();
}
// Make windows compiler happy, even switch is full cased
......@@ -233,6 +229,8 @@ QVariant FactMetaData::_maxForType(void) const
return QVariant(std::numeric_limits<float>::max());
case valueTypeDouble:
return QVariant(std::numeric_limits<double>::max());
case valueTypeString:
return QVariant();
}
// Make windows compiler happy, even switch is full cased
......@@ -285,6 +283,10 @@ bool FactMetaData::convertAndValidateRaw(const QVariant& rawValue, bool convertO
}
}
break;
case FactMetaData::valueTypeString:
convertOk = true;
typedValue = QVariant(rawValue.toString());
break;
}
if (!convertOk) {
......@@ -340,6 +342,10 @@ bool FactMetaData::convertAndValidateCooked(const QVariant& cookedValue, bool co
}
}
break;
case FactMetaData::valueTypeString:
convertOk = true;
typedValue = QVariant(cookedValue.toString());
break;
}
if (!convertOk) {
......@@ -556,7 +562,8 @@ FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString,
<< QStringLiteral("Uint32")
<< QStringLiteral("Int32")
<< QStringLiteral("Float")
<< QStringLiteral("Double");
<< QStringLiteral("Double")
<< QStringLiteral("String");
knownTypes << valueTypeUint8
<< valueTypeInt8
......@@ -565,7 +572,8 @@ FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString,
<< valueTypeUint32
<< valueTypeInt32
<< valueTypeFloat
<< valueTypeDouble;
<< valueTypeDouble
<< valueTypeString;
for (int i=0; i<knownTypeStrings.count(); i++) {
if (knownTypeStrings[i].compare(typeString, Qt::CaseInsensitive) == 0) {
......@@ -599,7 +607,7 @@ size_t FactMetaData::typeToSize(ValueType_t type)
default:
qWarning() << "Unsupported fact value type" << type;
return 4;
return 0;
}
}
......@@ -766,8 +774,8 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
// Validate key types
QStringList keys;
QList<QJsonValue::Type> types;
keys << _nameJsonKey << _decimalPlacesJsonKey << _typeJsonKey << _shortDescriptionJsonKey << _longDescriptionJsonKey << _unitsJsonKey << _defaultValueJsonKey << _minJsonKey << _maxJsonKey;
types << QJsonValue::String << QJsonValue::Double << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Double << QJsonValue::Double;
keys << _nameJsonKey << _decimalPlacesJsonKey << _typeJsonKey << _shortDescriptionJsonKey << _longDescriptionJsonKey << _unitsJsonKey << _minJsonKey << _maxJsonKey;
types << QJsonValue::String << QJsonValue::Double << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Double;
if (!JsonHelper::validateKeyTypes(json, keys, types, errorString)) {
qWarning() << errorString;
return new FactMetaData(valueTypeUint32, metaDataParent);
......@@ -811,7 +819,7 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
metaData->setRawUnits(json[_unitsJsonKey].toString());
}
if (json.contains(_defaultValueJsonKey)) {
metaData->setRawDefaultValue(json[_defaultValueJsonKey].toDouble());
metaData->setRawDefaultValue(json[_defaultValueJsonKey]);
}
if (json.contains(_minJsonKey)) {
metaData->setRawMin(json[_minJsonKey].toDouble());
......
......@@ -37,9 +37,12 @@ public:
valueTypeUint32,
valueTypeInt32,
valueTypeFloat,
valueTypeDouble
valueTypeDouble,
valueTypeString
} ValueType_t;
Q_ENUM(ValueType_t)
typedef QVariant (*Translator)(const QVariant& from);
FactMetaData(QObject* parent = NULL);
......
......@@ -30,6 +30,7 @@ void FactSystem::setToolbox(QGCToolbox *toolbox)
QGCTool::setToolbox(toolbox);
qmlRegisterType<Fact> (_factSystemQmlUri, 1, 0, "Fact");
qmlRegisterType<FactMetaData> (_factSystemQmlUri, 1, 0, "FactMetaData");
qmlRegisterType<FactPanelController>(_factSystemQmlUri, 1, 0, "FactPanelController");
qmlRegisterUncreatableType<FactGroup>(_factSystemQmlUri, 1, 0, "FactGroup", "ReferenceOnly");
......
......@@ -39,22 +39,26 @@ QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string,
int convertTo = QVariant::Int; // keep compiler warning happy
switch (type) {
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
convertTo = QVariant::UInt;
break;
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
convertTo = QVariant::Int;
break;
case FactMetaData::valueTypeFloat:
convertTo = QMetaType::Float;
break;
case FactMetaData::valueTypeDouble:
convertTo = QVariant::Double;
break;
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
convertTo = QVariant::UInt;
break;
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
convertTo = QVariant::Int;
break;
case FactMetaData::valueTypeFloat:
convertTo = QMetaType::Float;
break;
case FactMetaData::valueTypeDouble:
convertTo = QVariant::Double;
break;
case FactMetaData::valueTypeString:
qWarning() << "Internal Error: No support for string parameters";
convertTo = QVariant::String;
break;
}
*convertOk = var.convert(convertTo);
......
......@@ -39,22 +39,26 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
int convertTo = QVariant::Int; // keep compiler warning happy
switch (type) {
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
convertTo = QVariant::UInt;
break;
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
convertTo = QVariant::Int;
break;
case FactMetaData::valueTypeFloat:
convertTo = QMetaType::Float;
break;
case FactMetaData::valueTypeDouble:
convertTo = QVariant::Double;
break;
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
convertTo = QVariant::UInt;
break;
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
convertTo = QVariant::Int;
break;
case FactMetaData::valueTypeFloat:
convertTo = QMetaType::Float;
break;
case FactMetaData::valueTypeDouble:
convertTo = QVariant::Double;
break;
case FactMetaData::valueTypeString:
qWarning() << "Internal Error: No support for string parameters";
convertTo = QVariant::String;
break;
}
*convertOk = var.convert(convertTo);
......
......@@ -21,7 +21,6 @@ static const char* kQmlGlobalKeyName = "QGCQml";
const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey = "VirtualTabletJoystick";
const char* QGroundControlQmlGlobal::_baseFontPointSizeKey = "BaseDeviceFontPointSize";
const char* QGroundControlQmlGlobal::_missionAutoLoadDirKey = "MissionAutoLoadDir";
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
: QGCTool(app)
......@@ -227,15 +226,3 @@ bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPo
return QLineF(line1A, line1B).intersect(QLineF(line2A, line2B), &intersectPoint) == QLineF::BoundedIntersection &&
intersectPoint != line1A && intersectPoint != line1B;
}
QString QGroundControlQmlGlobal::missionAutoLoadDir(void)
{
QSettings settings;
return settings.value(_missionAutoLoadDirKey).toString();
}
void QGroundControlQmlGlobal::setMissionAutoLoadDir(const QString& missionAutoLoadDir)
{
QSettings settings;
settings.setValue(_missionAutoLoadDirKey, missionAutoLoadDir);
}
......@@ -61,7 +61,6 @@ public:
Q_PROPERTY(bool isSaveLogPromptNotArmed READ isSaveLogPromptNotArmed WRITE setIsSaveLogPromptNotArmed NOTIFY isSaveLogPromptNotArmedChanged)
Q_PROPERTY(bool virtualTabletJoystick READ virtualTabletJoystick WRITE setVirtualTabletJoystick NOTIFY virtualTabletJoystickChanged)
Q_PROPERTY(qreal baseFontPointSize READ baseFontPointSize WRITE setBaseFontPointSize NOTIFY baseFontPointSizeChanged)
Q_PROPERTY(QString missionAutoLoadDir READ missionAutoLoadDir WRITE setMissionAutoLoadDir NOTIFY missionAutoLoadDirChanged STORED false)
//-------------------------------------------------------------------------
// MavLink Protocol
......@@ -127,6 +126,8 @@ public:
Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2);
Q_INVOKABLE QString urlToLocalFile(QUrl url) { return url.toLocalFile(); }
// Property accesors
FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
......@@ -174,9 +175,6 @@ public:
QString qgcVersion(void) const { return qgcApp()->applicationVersion(); }
static QString missionAutoLoadDir(void);
static void setMissionAutoLoadDir(const QString& missionAutoLoadDir);
// Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox);
......@@ -192,7 +190,6 @@ signals:
void mavlinkSystemIDChanged (int id);
void flightMapPositionChanged (QGeoCoordinate flightMapPosition);
void flightMapZoomChanged (double flightMapZoom);
void missionAutoLoadDirChanged (QString missionAutoLoadDir);
private:
FlightMapSettings* _flightMapSettings;
......@@ -214,7 +211,6 @@ private:
static const char* _virtualTabletJoystickKey;
static const char* _baseFontPointSizeKey;
static const char* _missionAutoLoadDirKey;
};
#endif
......@@ -21,6 +21,7 @@ const char* SettingsManager::areaUnitsSettingsName = "Are
const char* SettingsManager::speedUnitsSettingsName = "SpeedUnits";
const char* SettingsManager::batteryPercentRemainingAnnounceSettingsName = "batteryPercentRemainingAnnounce";
const char* SettingsManager::defaultMissionItemAltitudeSettingsName = "DefaultMissionItemAltitude";
const char* SettingsManager::missionAutoLoadDirSettingsName = "MissionAutoLoadDir";
SettingsManager::SettingsManager(QGCApplication* app)
: QGCTool(app)
......@@ -33,6 +34,7 @@ SettingsManager::SettingsManager(QGCApplication* app)
, _speedUnitsFact(NULL)
, _batteryPercentRemainingAnnounceFact(NULL)
, _defaultMissionItemAltitudeFact(NULL)
, _missionAutoLoadDirFact(NULL)
{
}
......@@ -103,6 +105,15 @@ Fact* SettingsManager::defaultMissionItemAltitude(void)
return _defaultMissionItemAltitudeFact;
}
Fact* SettingsManager::missionAutoLoadDir(void)
{
if (!_missionAutoLoadDirFact) {
_missionAutoLoadDirFact = _createSettingsFact(missionAutoLoadDirSettingsName);
}
return _missionAutoLoadDirFact;
}
Fact* SettingsManager::distanceUnits(void)
{
if (!_distanceUnitsFact) {
......
......@@ -54,25 +54,27 @@ public:
Q_ENUMS(AreaUnits)
Q_ENUMS(SpeedUnits)
Q_PROPERTY(Fact* offlineEditingFirmwareType READ offlineEditingFirmwareType CONSTANT)
Q_PROPERTY(Fact* offlineEditingVehicleType READ offlineEditingVehicleType CONSTANT)
Q_PROPERTY(Fact* offlineEditingCruiseSpeed READ offlineEditingCruiseSpeed CONSTANT)
Q_PROPERTY(Fact* offlineEditingHoverSpeed READ offlineEditingHoverSpeed CONSTANT)
Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT)
Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT)
Q_PROPERTY(Fact* speedUnits READ speedUnits CONSTANT)
Q_PROPERTY(Fact* batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT)
Q_PROPERTY(Fact* defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT)
Fact* offlineEditingFirmwareType (void);
Fact* offlineEditingVehicleType (void);
Fact* offlineEditingCruiseSpeed (void);
Fact* offlineEditingHoverSpeed (void);
Fact* distanceUnits (void);
Fact* areaUnits (void);
Fact* speedUnits (void);
Fact* batteryPercentRemainingAnnounce(void);
Fact* defaultMissionItemAltitude (void);
Q_PROPERTY(Fact* offlineEditingFirmwareType READ offlineEditingFirmwareType CONSTANT)
Q_PROPERTY(Fact* offlineEditingVehicleType READ offlineEditingVehicleType CONSTANT)
Q_PROPERTY(Fact* offlineEditingCruiseSpeed READ offlineEditingCruiseSpeed CONSTANT)
Q_PROPERTY(Fact* offlineEditingHoverSpeed READ offlineEditingHoverSpeed CONSTANT)
Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT)
Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT)
Q_PROPERTY(Fact* speedUnits READ speedUnits CONSTANT)
Q_PROPERTY(Fact* batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT)
Q_PROPERTY(Fact* defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT)
Q_PROPERTY(Fact* missionAutoLoadDir READ missionAutoLoadDir CONSTANT)
Fact* offlineEditingFirmwareType (void);
Fact* offlineEditingVehicleType (void);
Fact* offlineEditingCruiseSpeed (void);
Fact* offlineEditingHoverSpeed (void);
Fact* distanceUnits (void);
Fact* areaUnits (void);
Fact* speedUnits (void);
Fact* batteryPercentRemainingAnnounce (void);
Fact* defaultMissionItemAltitude (void);
Fact* missionAutoLoadDir (void);
// Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox);
......@@ -86,13 +88,8 @@ public:
static const char* speedUnitsSettingsName;
static const char* batteryPercentRemainingAnnounceSettingsName;
static const char* defaultMissionItemAltitudeSettingsName;
static const char* missionAutoLoadDirSettingsName;
public slots:
signals:
private slots:
private:
SettingsFact* _createSettingsFact(const QString& name);
......@@ -107,6 +104,7 @@ private:
SettingsFact* _speedUnitsFact;
SettingsFact* _batteryPercentRemainingAnnounceFact;
SettingsFact* _defaultMissionItemAltitudeFact;
SettingsFact* _missionAutoLoadDirFact;
};
#endif
......@@ -54,5 +54,12 @@
"min": 0.0,
"units": "meters",
"decimalPlaces": 2
},
{
"name": "MissionAutoLoadDir",
"shortDescription": "Mission auto load directory",
"longDescription": "The directory from which missions will be automaticallu loaded onto a vehicle when it connects.",
"type": "string",
"defaultValue": ""
}
]
......@@ -1579,7 +1579,7 @@ void Vehicle::_parametersReady(bool parametersReady)
{
if (parametersReady && !_missionManagerInitialRequestSent) {
_missionManagerInitialRequestSent = true;
QString missionAutoLoadDirPath = QGroundControlQmlGlobal::missionAutoLoadDir();
QString missionAutoLoadDirPath = _settingsManager->missionAutoLoadDir()->rawValue().toString();
if (missionAutoLoadDirPath.isEmpty()) {
_missionManager->requestMissionItems();
} else {
......
......@@ -33,6 +33,7 @@ QGCView {
anchors.margins: ScreenTools.defaultFontPixelWidth
property Fact _percentRemainingAnnounce: QGroundControl.settingsManager.batteryPercentRemainingAnnounce
property Fact _autoLoadDir: QGroundControl.settingsManager.missionAutoLoadDir
property real _labelWidth: ScreenTools.defaultFontPixelWidth * 15
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
......@@ -331,30 +332,41 @@ QGCView {
}
}
//-----------------------------------------------------------------
//-- AutoLoad
//-- Mission AutoLoad
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCCheckBox {
id: autoLoadCheckbox
anchors.verticalCenter: parent.verticalCenter
text: qsTr("AutoLoad mission directory:")
checked: QGroundControl.missionAutoLoadDir != ""
checked: _autoLoadDir.valueString
onClicked: {
autoLoadDir.enabled = checked
if (!checked) {
QGroundControl.missionAutoLoadDir = ""
autoLoadDir.text = ""
if (checked) {
_autoLoadDir.rawValue = QGroundControl.urlToLocalFile(autoloadDirPicker.shortcuts.home)
} else {
_autoLoadDir.rawValue = ""
}
}
}
QGCTextField {
id: autoLoadDir
FactTextField {
id: autoLoadDirField
width: _editFieldWidth
enabled: autoLoadCheckbox.checked
anchors.verticalCenter: parent.verticalCenter
text: QGroundControl.missionAutoLoadDir
onEditingFinished: QGroundControl.missionAutoLoadDir = text
fact: _autoLoadDir
}
QGCButton {
text: qsTr("Browse")
onClicked: autoloadDirPicker.visible = true
FileDialog {
id: autoloadDirPicker
title: qsTr("Choose the location of mission file.")
folder: shortcuts.home
selectFolder: true
onAccepted: _autoLoadDir.rawValue = QGroundControl.urlToLocalFile(autoloadDirPicker.fileUrl)
}
}
}
//-----------------------------------------------------------------
......@@ -561,7 +573,7 @@ QGCView {
readOnly: true
text: QGroundControl.videoManager.videoSavePath
}
Button {
QGCButton {
text: "Browse"
onClicked: fileDialog.visible = true
}
......
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