Commit ff9ba294 authored by Don Gagne's avatar Don Gagne

Merge pull request #1688 from DonLakeFlyer/ParameterValidation

Parameter validation
parents b788347c b6e722c6
......@@ -106,6 +106,7 @@
<file alias="QGroundControl/Controls/QGCViewMessage.qml">src/QmlControls/QGCViewMessage.qml</file>
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="ParameterEditorWidget.qml">src/ViewWidgets/ParameterEditorWidget.qml</file>
<file alias="CustomCommandWidget.qml">src/ViewWidgets/CustomCommandWidget.qml</file>
......
......@@ -116,10 +116,11 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
return;
}
QString factGroup;
FactMetaData* metaData = NULL;
int xmlState = XmlStateNone;
bool badMetaData = true;
QString factGroup;
QString errorString;
FactMetaData* metaData = NULL;
int xmlState = XmlStateNone;
bool badMetaData = true;
while (!xml.atEnd()) {
if (xml.isStartElement()) {
......@@ -221,22 +222,22 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
Q_CHECK_PTR(metaData);
if (_mapParameterName2FactMetaData.contains(name)) {
// We can't trust the meta dafa since we have dups
qCDebug(PX4ParameterLoaderLog) << "Duplicate parameter found:" << name;
qCWarning(PX4ParameterLoaderLog) << "Duplicate parameter found:" << name;
badMetaData = true;
// Reset to default meta data
_mapParameterName2FactMetaData[name] = metaData;
} else {
_mapParameterName2FactMetaData[name] = metaData;
metaData->setName(name);
metaData->setGroup(factGroup);
if (xml.attributes().hasAttribute("default")) {
bool convertOk;
QVariant varDefault = _stringToTypedVariant(strDefault, metaData->type(), &convertOk);
if (convertOk) {
if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) {
QVariant varDefault;
if (metaData->convertAndValidate(strDefault, false, varDefault, errorString)) {
metaData->setDefaultValue(varDefault);
} else {
// Non-fatal
qCDebug(PX4ParameterLoaderLog) << "Parameter meta data with bad default value, name:" << name << " type:" << type << " default:" << strDefault;
qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString;
}
}
}
......@@ -252,12 +253,14 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
if (elementName == "short_desc") {
Q_ASSERT(metaData);
QString text = xml.readElementText();
text = text.replace("\n", " ");
qCDebug(PX4ParameterLoaderLog) << "Short description:" << text;
metaData->setShortDescription(text);
} else if (elementName == "long_desc") {
Q_ASSERT(metaData);
QString text = xml.readElementText();
text = text.replace("\n", " ");
qCDebug(PX4ParameterLoaderLog) << "Long description:" << text;
metaData->setLongDescription(text);
......@@ -265,26 +268,24 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
Q_ASSERT(metaData);
QString text = xml.readElementText();
qCDebug(PX4ParameterLoaderLog) << "Min:" << text;
bool convertOk;
QVariant varMin = _stringToTypedVariant(text, metaData->type(), &convertOk);
if (convertOk) {
QVariant varMin;
if (metaData->convertAndValidate(text, true /* convertOnly */, varMin, errorString)) {
metaData->setMin(varMin);
} else {
// Non-fatal
qDebug() << "Parameter meta data with bad min value:" << text;
qCWarning(PX4ParameterLoaderLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString;
}
} else if (elementName == "max") {
Q_ASSERT(metaData);
QString text = xml.readElementText();
qCDebug(PX4ParameterLoaderLog) << "Max:" << text;
bool convertOk;
QVariant varMax = _stringToTypedVariant(text, metaData->type(), &convertOk);
if (convertOk) {
QVariant varMax;
if (metaData->convertAndValidate(text, true /* convertOnly */, varMax, errorString)) {
metaData->setMax(varMax);
} else {
// Non-fatal
qDebug() << "Parameter meta data with bad max value:" << text;
qCWarning(PX4ParameterLoaderLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString;
}
} else if (elementName == "unit") {
......@@ -302,7 +303,16 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
QString elementName = xml.name().toString();
if (elementName == "parameter") {
// Done loading this one parameter
// Done loading this parameter, validate default value
if (metaData->defaultValueAvailable()) {
QVariant var;
if (!metaData->convertAndValidate(metaData->defaultValue(), false /* convertOnly */, var, errorString)) {
qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->defaultValue() << " error:" << errorString;
}
}
// Reset for next parameter
metaData = NULL;
badMetaData = false;
xmlState = XmlStateFoundGroup;
......
......@@ -31,11 +31,12 @@ import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
FactPanel {
id: panel
QGCView {
id: rootQGCView
viewPanel: view
QGCPalette { id: palette; colorGroupEnabled: enabled }
FactPanelController { id: controller; factPanel: panel }
FactPanelController { id: controller; factPanel: rootQGCView }
property int flightLineWidth: 2 // width of lines for flight graphic
property int loiterAltitudeColumnWidth: 180 // width of loiter altitude column
......@@ -47,265 +48,271 @@ FactPanel {
property int arrowWidth: 18 // width for arrow graphic
property int firstColumnWidth: 220 // Width of first column in return home triggers area
Column {
QGCView {
id: view
anchors.fill: parent
QGCLabel {
text: "SAFETY CONFIG"
font.pixelSize: ScreenTools.largeFontPixelSize
}
Column {
anchors.fill: parent
Item { height: 20; width: 10 } // spacer
QGCLabel {
text: "SAFETY CONFIG"
font.pixelSize: ScreenTools.largeFontPixelSize
}
//-----------------------------------------------------------------
//-- Return Home Triggers
Item { height: 20; width: 10 } // spacer
QGCLabel { text: "Triggers For Return Home"; font.pixelSize: ScreenTools.mediumFontPixelSize; }
//-----------------------------------------------------------------
//-- Return Home Triggers
Item { height: 10; width: 10 } // spacer
QGCLabel { text: "Triggers For Return Home"; font.pixelSize: ScreenTools.mediumFontPixelSize; }
Rectangle {
width: parent.width
height: triggerColumn.height
color: palette.windowShade
Item { height: 10; width: 10 } // spacer
Column {
id: triggerColumn
spacing: controlVerticalSpacing
anchors.margins: shadedMargin
anchors.left: parent.left
Rectangle {
width: parent.width
height: triggerColumn.height
color: palette.windowShade
// Top margin
Item { height: 1; width: 10 }
Column {
id: triggerColumn
spacing: controlVerticalSpacing
anchors.margins: shadedMargin
anchors.left: parent.left
Row {
spacing: 10
QGCLabel { text: "RC Transmitter Signal Loss"; width: firstColumnWidth; anchors.baseline: rcLossField.baseline }
QGCLabel { text: "Return Home after"; anchors.baseline: rcLossField.baseline }
FactTextField {
id: rcLossField
fact: controller.getParameterFact(-1, "COM_RC_LOSS_T")
showUnits: true
}
}
// Top margin
Item { height: 1; width: 10 }
Row {
spacing: 10
FactCheckBox {
id: telemetryTimeoutCheckbox
anchors.baseline: telemetryLossField.baseline
width: firstColumnWidth
fact: controller.getParameterFact(-1, "COM_DL_LOSS_EN")
checkedValue: 1
uncheckedValue: 0
text: "Telemetry Signal Timeout"
Row {
spacing: 10
QGCLabel { text: "RC Transmitter Signal Loss"; width: firstColumnWidth; anchors.baseline: rcLossField.baseline }
QGCLabel { text: "Return Home after"; anchors.baseline: rcLossField.baseline }
FactTextField {
id: rcLossField
fact: controller.getParameterFact(-1, "COM_RC_LOSS_T")
showUnits: true
}
}
QGCLabel { text: "Return Home after"; anchors.baseline: telemetryLossField.baseline }
FactTextField {
id: telemetryLossField
fact: controller.getParameterFact(-1, "COM_DL_LOSS_T")
showUnits: true
enabled: telemetryTimeoutCheckbox.checked
Row {
spacing: 10
FactCheckBox {
id: telemetryTimeoutCheckbox
anchors.baseline: telemetryLossField.baseline
width: firstColumnWidth
fact: controller.getParameterFact(-1, "COM_DL_LOSS_EN")
checkedValue: 1
uncheckedValue: 0
text: "Telemetry Signal Timeout"
}
QGCLabel { text: "Return Home after"; anchors.baseline: telemetryLossField.baseline }
FactTextField {
id: telemetryLossField
fact: controller.getParameterFact(-1, "COM_DL_LOSS_T")
showUnits: true
enabled: telemetryTimeoutCheckbox.checked
}
}
}
// Bottom margin
Item { height: 1; width: 10 }
// Bottom margin
Item { height: 1; width: 10 }
}
}
}
Item { height: 20; width: 10 } // spacer
//-----------------------------------------------------------------
//-- Return Home Settings
Item { height: 20; width: 10 } // spacer
QGCLabel { text: "Return Home Settings"; font.pixelSize: ScreenTools.mediumFontPixelSize; }
//-----------------------------------------------------------------
//-- Return Home Settings
Item { height: 10; width: 10 } // spacer
QGCLabel { text: "Return Home Settings"; font.pixelSize: ScreenTools.mediumFontPixelSize; }
Rectangle {
width: parent.width
height: settingsColumn.height
color: palette.windowShade
Item { height: 10; width: 10 } // spacer
Column {
id: settingsColumn
width: parent.width
anchors.margins: shadedMargin
anchors.left: parent.left
Rectangle {
width: parent.width
height: settingsColumn.height
color: palette.windowShade
Item { height: shadedMargin; width: 10 } // top margin
Column {
id: settingsColumn
width: parent.width
anchors.margins: shadedMargin
anchors.left: parent.left
// This item is the holder for the climb alt and loiter seconds fields
Item {
width: parent.width
height: climbAltitudeColumn.height
Item { height: shadedMargin; width: 10 } // top margin
Column {
id: climbAltitudeColumn
spacing: controlVerticalSpacing
QGCLabel { text: "Climb to altitude of" }
FactTextField {
id: climbField
fact: controller.getParameterFact(-1, "RTL_RETURN_ALT")
showUnits: true
// This item is the holder for the climb alt and loiter seconds fields
Item {
width: parent.width
height: climbAltitudeColumn.height
Column {
id: climbAltitudeColumn
spacing: controlVerticalSpacing
QGCLabel { text: "Climb to altitude of" }
FactTextField {
id: climbField
fact: controller.getParameterFact(-1, "RTL_RETURN_ALT")
showUnits: true
}
}
}
Column {
x: flightGraphic.width - 200
spacing: controlVerticalSpacing
Column {
x: flightGraphic.width - 200
spacing: controlVerticalSpacing
QGCCheckBox {
id: homeLoiterCheckbox
checked: fact.value > 0
text: "Loiter at Home altitude for"
QGCCheckBox {
id: homeLoiterCheckbox
checked: fact.value > 0
text: "Loiter at Home altitude for"
property Fact fact: controller.getParameterFact(-1, "RTL_LAND_DELAY")
property Fact fact: controller.getParameterFact(-1, "RTL_LAND_DELAY")
onClicked: {
fact.value = checked ? 60 : -1
onClicked: {
fact.value = checked ? 60 : -1
}
}
}
FactTextField {
fact: controller.getParameterFact(-1, "RTL_LAND_DELAY")
showUnits: true
enabled: homeLoiterCheckbox.checked == true
FactTextField {
fact: controller.getParameterFact(-1, "RTL_LAND_DELAY")
showUnits: true
enabled: homeLoiterCheckbox.checked == true
}
}
}
}
Item { height: 20; width: 10 } // spacer
Item { height: 20; width: 10 } // spacer
// This row holds the flight graphic and the home loiter alt column
Row {
width: parent.width
spacing: 20
// This row holds the flight graphic and the home loiter alt column
Row {
width: parent.width
spacing: 20
// Flight graphic
Item {
id: flightGraphic
width: parent.width - loiterAltitudeColumnWidth
height: 200 // controls the height of the flight graphic
Rectangle {
x: planeWidth / 2
height: planeImage.y - 5
width: flightLineWidth
color: palette.button
}
Rectangle {
x: planeWidth / 2
height: flightLineWidth
width: parent.width - x
color: palette.button
}
Rectangle {
x: parent.width - flightLineWidth
height: parent.height - homeWidth - arrowToHomeSpacing
width: flightLineWidth
color: palette.button
}
// Flight graphic
Item {
id: flightGraphic
width: parent.width - loiterAltitudeColumnWidth
height: 200 // controls the height of the flight graphic
QGCColoredImage {
id: planeImage
y: parent.height - planeWidth - 40
source: "/qmlimages/SafetyComponentPlane.png"
fillMode: Image.PreserveAspectFit
width: planeWidth
height: planeWidth
smooth: true
color: palette.button
}
Rectangle {
x: planeWidth / 2
height: planeImage.y - 5
width: flightLineWidth
color: palette.button
}
Rectangle {
x: planeWidth / 2
height: flightLineWidth
width: parent.width - x
color: palette.button
}
Rectangle {
x: parent.width - flightLineWidth
height: parent.height - homeWidth - arrowToHomeSpacing
width: flightLineWidth
color: palette.button
}
QGCColoredImage {
x: planeWidth + 70
y: parent.height - height - 20
width: 80
height: parent.height / 2
source: "/qmlimages/SafetyComponentTree.svg"
fillMode: Image.Stretch
smooth: true
color: palette.windowShadeDark
}
QGCColoredImage {
id: planeImage
y: parent.height - planeWidth - 40
source: "/qmlimages/SafetyComponentPlane.png"
fillMode: Image.PreserveAspectFit
width: planeWidth
height: planeWidth
smooth: true
color: palette.button
}
QGCColoredImage {
x: planeWidth + 15
y: parent.height - height
width: 100
height: parent.height * .75
source: "/qmlimages/SafetyComponentTree.svg"
fillMode: Image.PreserveAspectFit
smooth: true
color: palette.button
}
QGCColoredImage {
x: planeWidth + 70
y: parent.height - height - 20
width: 80
height: parent.height / 2
source: "/qmlimages/SafetyComponentTree.svg"
fillMode: Image.Stretch
smooth: true
color: palette.windowShadeDark
}
QGCColoredImage {
x: parent.width - (arrowWidth/2) - 1
y: parent.height - homeWidth - arrowToHomeSpacing - 2
source: "/qmlimages/SafetyComponentArrowDown.png"
fillMode: Image.PreserveAspectFit
width: arrowWidth
height: arrowWidth
smooth: true
color: palette.button
}
QGCColoredImage {
x: planeWidth + 15
y: parent.height - height
width: 100
height: parent.height * .75
source: "/qmlimages/SafetyComponentTree.svg"
fillMode: Image.PreserveAspectFit
smooth: true
color: palette.button
}
QGCColoredImage {
x: parent.width - (arrowWidth/2) - 1
y: parent.height - homeWidth - arrowToHomeSpacing - 2
source: "/qmlimages/SafetyComponentArrowDown.png"
fillMode: Image.PreserveAspectFit
width: arrowWidth
height: arrowWidth
smooth: true
color: palette.button
}
QGCColoredImage {
id: homeImage
x: parent.width - (homeWidth / 2)
y: parent.height - homeWidth
source: "/qmlimages/SafetyComponentHome.png"
fillMode: Image.PreserveAspectFit
width: homeWidth
height: homeWidth
smooth: true
color: palette.button
QGCColoredImage {
id: homeImage
x: parent.width - (homeWidth / 2)
y: parent.height - homeWidth
source: "/qmlimages/SafetyComponentHome.png"
fillMode: Image.PreserveAspectFit
width: homeWidth
height: homeWidth
smooth: true
color: palette.button
}
}
}
Column {
spacing: controlVerticalSpacing
Column {
spacing: controlVerticalSpacing
QGCLabel {
text: "Home loiter altitude";
color: palette.text;
enabled: homeLoiterCheckbox.checked === true
}
FactTextField {
id: descendField;
fact: controller.getParameterFact(-1, "RTL_DESCEND_ALT")
enabled: homeLoiterCheckbox.checked === true
showUnits: true
QGCLabel {
text: "Home loiter altitude";
color: palette.text;
enabled: homeLoiterCheckbox.checked === true
}
FactTextField {
id: descendField;
fact: controller.getParameterFact(-1, "RTL_DESCEND_ALT")
enabled: homeLoiterCheckbox.checked === true
showUnits: true
}
}
}
}
Item { height: shadedMargin; width: 10 } // bottom margin
Item { height: shadedMargin; width: 10 } // bottom margin
}
}
}
QGCLabel {
width: parent.width
font.pixelSize: ScreenTools.mediumFontPixelSize
text: "Warning: You have an advanced safety configuration set using the NAV_RCL_OBC parameter. The above settings may not apply.";
visible: fact.value !== 0
wrapMode: Text.Wrap
QGCLabel {
width: parent.width
font.pixelSize: ScreenTools.mediumFontPixelSize
text: "Warning: You have an advanced safety configuration set using the NAV_RCL_OBC parameter. The above settings may not apply.";
visible: fact.value !== 0
wrapMode: Text.Wrap
property Fact fact: controller.getParameterFact(-1, "NAV_RCL_OBC")
}
property Fact fact: controller.getParameterFact(-1, "NAV_RCL_OBC")
}
QGCLabel {
width: parent.width
font.pixelSize: ScreenTools.mediumFontPixelSize
text: "Warning: You have an advanced safety configuration set using the NAV_DLL_OBC parameter. The above settings may not apply.";
visible: fact.value !== 0
wrapMode: Text.Wrap
QGCLabel {
width: parent.width
font.pixelSize: ScreenTools.mediumFontPixelSize
text: "Warning: You have an advanced safety configuration set using the NAV_DLL_OBC parameter. The above settings may not apply.";
visible: fact.value !== 0
wrapMode: Text.Wrap
property Fact fact: controller.getParameterFact(-1, "NAV_DLL_OBC")
property Fact fact: controller.getParameterFact(-1, "NAV_DLL_OBC")
}
}
}
} // QGCVIew
}
......@@ -51,34 +51,19 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
void Fact::setValue(const QVariant& value)
{
QVariant newValue;
switch (type()) {
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
newValue = QVariant(value.toInt());
break;
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
newValue = QVariant(value.toUInt());
break;
case FactMetaData::valueTypeFloat:
newValue = QVariant(value.toFloat());
break;
case FactMetaData::valueTypeDouble:
newValue = QVariant(value.toDouble());
break;
}
if (newValue != _value) {
_value.setValue(newValue);
emit valueChanged(_value);
emit _containerValueChanged(_value);
if (_metaData) {
QVariant typedValue;
QString errorString;
if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) {
if (typedValue != _value) {
_value.setValue(typedValue);
emit valueChanged(_value);
emit _containerValueChanged(_value);
}
}
} else {
qWarning() << "Meta data pointer missing";
}
}
......@@ -110,11 +95,15 @@ QString Fact::valueString(void) const
QVariant Fact::defaultValue(void)
{
Q_ASSERT(_metaData);
if (!_metaData->defaultValueAvailable()) {
qDebug() << "Access to unavailable default value";
if (_metaData) {
if (!_metaData->defaultValueAvailable()) {
qDebug() << "Access to unavailable default value";
}
return _metaData->defaultValue();
} else {
qWarning() << "Meta data pointer missing";
return QVariant(0);
}
return _metaData->defaultValue();
}
FactMetaData::ValueType_t Fact::type(void)
......@@ -124,38 +113,82 @@ FactMetaData::ValueType_t Fact::type(void)
QString Fact::shortDescription(void)
{
Q_ASSERT(_metaData);
return _metaData->shortDescription();
if (_metaData) {
return _metaData->shortDescription();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
}
QString Fact::longDescription(void)
{
Q_ASSERT(_metaData);
return _metaData->longDescription();
if (_metaData) {
return _metaData->longDescription();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
}
QString Fact::units(void)
{
Q_ASSERT(_metaData);
return _metaData->units();
if (_metaData) {
return _metaData->units();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
}
QVariant Fact::min(void)
{
Q_ASSERT(_metaData);
return _metaData->min();
if (_metaData) {
return _metaData->min();
} else {
qWarning() << "Meta data pointer missing";
return QVariant(0);
}
}
QVariant Fact::max(void)
{
Q_ASSERT(_metaData);
return _metaData->max();
if (_metaData) {
return _metaData->max();
} else {
qWarning() << "Meta data pointer missing";
return QVariant(0);
}
}
bool Fact::minIsDefaultForType(void)
{
if (_metaData) {
return _metaData->minIsDefaultForType();
} else {
qWarning() << "Meta data pointer missing";
return false;
}
}
bool Fact::maxIsDefaultForType(void)
{
if (_metaData) {
return _metaData->maxIsDefaultForType();
} else {
qWarning() << "Meta data pointer missing";
return false;
}
}
QString Fact::group(void)
{
Q_ASSERT(_metaData);
return _metaData->group();
if (_metaData) {
return _metaData->group();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
}
void Fact::setMetaData(FactMetaData* metaData)
......@@ -165,16 +198,40 @@ void Fact::setMetaData(FactMetaData* metaData)
bool Fact::valueEqualsDefault(void)
{
Q_ASSERT(_metaData);
if (_metaData->defaultValueAvailable()) {
return _metaData->defaultValue() == value();
if (_metaData) {
if (_metaData->defaultValueAvailable()) {
return _metaData->defaultValue() == value();
} else {
return false;
}
} else {
qWarning() << "Meta data pointer missing";
return false;
}
}
bool Fact::defaultValueAvailable(void)
{
Q_ASSERT(_metaData);
return _metaData->defaultValueAvailable();
}
\ No newline at end of file
if (_metaData) {
return _metaData->defaultValueAvailable();
} else {
qWarning() << "Meta data pointer missing";
return false;
}
}
QString Fact::validate(const QString& value, bool convertOnly)
{
if (_metaData) {
QVariant typedValue;
QString errorString;
_metaData->convertAndValidate(value, convertOnly, typedValue, errorString);
return errorString;
} else {
qWarning() << "Meta data pointer missing";
return QString("Internal error: Meta data pointer missing");
}
}
......@@ -55,9 +55,15 @@ public:
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
/// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well
Q_INVOKABLE QString validate(const QString& value, bool convertOnly);
// Property system methods
QString name(void) const;
......@@ -73,7 +79,9 @@ public:
QString longDescription(void);
QString units(void);
QVariant min(void);
bool minIsDefaultForType(void);
QVariant max(void);
bool maxIsDefaultForType(void);
QString group(void);
/// Sets the meta data associated with the Fact.
......
import QtQuick 2.2
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
QGCTextField {
property Fact fact: null
text: fact.valueString
id: _textField
property Fact fact: null
property string _validateString
text: fact.valueString
unitsLabel: fact.units
onEditingFinished: fact.value = text
onEditingFinished: {
if (qgcView) {
var errorString = fact.validate(text, false /* convertOnly */)
if (errorString == "") {
fact.value = text
} else {
_validateString = text
qgcView.showDialog(editorDialogComponent, "Invalid Parameter Value", 50, StandardButton.Save)
}
} else {
fact.value = text
fact.valueChanged(fact.value)
}
}
Component {
id: editorDialogComponent
ParameterEditorDialog {
validate: true
validateValue: _validateString
fact: _textField.fact
}
}
}
......@@ -39,7 +39,9 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent) :
_defaultValue(0),
_defaultValueAvailable(false),
_min(_minForType()),
_max(_maxForType())
_max(_maxForType()),
_minIsDefaultForType(true),
_maxIsDefaultForType(true)
{
}
......@@ -68,6 +70,7 @@ void FactMetaData::setMin(const QVariant& min)
{
if (min > _minForType()) {
_min = min;
_minIsDefaultForType = false;
} else {
qWarning() << "Attempt to set min below allowable value";
_min = _minForType();
......@@ -81,6 +84,7 @@ void FactMetaData::setMax(const QVariant& max)
_max = _maxForType();
} else {
_max = max;
_maxIsDefaultForType = false;
}
}
......@@ -133,3 +137,58 @@ QVariant FactMetaData::_maxForType(void)
// Make windows compiler happy, even switch is full cased
return QVariant();
}
bool FactMetaData::convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString)
{
bool convertOk;
errorString.clear();
switch (type()) {
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
typedValue = QVariant(value.toInt(&convertOk));
if (!convertOnly && convertOk) {
if (min() > typedValue || typedValue > max()) {
errorString = QString("Value must be within %1 and %2").arg(min().toInt()).arg(max().toInt());
}
}
break;
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
typedValue = QVariant(value.toUInt(&convertOk));
if (!convertOnly && convertOk) {
if (min() > typedValue || typedValue > max()) {
errorString = QString("Value must be within %1 and %2").arg(min().toUInt()).arg(max().toUInt());
}
}
break;
case FactMetaData::valueTypeFloat:
typedValue = QVariant(value.toFloat(&convertOk));
if (!convertOnly && convertOk) {
if (min() > typedValue || typedValue > max()) {
errorString = QString("Value must be within %1 and %2").arg(min().toFloat()).arg(max().toFloat());
}
}
break;
case FactMetaData::valueTypeDouble:
typedValue = QVariant(value.toDouble(&convertOk));
if (!convertOnly && convertOk) {
if (min() > typedValue || typedValue > max()) {
errorString = QString("Value must be within %1 and %2").arg(min().toDouble()).arg(max().toDouble());
}
}
break;
}
if (!convertOk) {
errorString = "Invalid number";
}
return convertOk && errorString.isEmpty();
}
......@@ -55,6 +55,7 @@ public:
FactMetaData(ValueType_t type, QObject* parent = NULL);
// Property accessors
QString name(void) { return _name; }
QString group(void) { return _group; }
ValueType_t type(void) { return _type; }
QVariant defaultValue(void);
......@@ -64,8 +65,11 @@ public:
QString units(void) { return _units; }
QVariant min(void) { return _min; }
QVariant max(void) { return _max; }
bool minIsDefaultForType(void) { return _minIsDefaultForType; }
bool maxIsDefaultForType(void) { return _maxIsDefaultForType; }
// Property setters
void setName(const QString& name) { _name = name; }
void setGroup(const QString& group) { _group = group; }
void setDefaultValue(const QVariant& defaultValue);
void setShortDescription(const QString& shortDescription) { _shortDescription = shortDescription; }
......@@ -73,11 +77,20 @@ public:
void setUnits(const QString& units) { _units = units; }
void setMin(const QVariant& max);
void setMax(const QVariant& max);
/// Converts the specified value, validating against meta data
/// @param value Value to convert, can be string
/// @param convertOnly true: convert to correct type only, do not validate against meta data
/// @param typeValue Converted value, correctly typed
/// @param errorString Error string if convert fails
/// @returns false: Convert failed, errorString set
bool convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString);
private:
QVariant _minForType(void);
QVariant _maxForType(void);
QString _name;
QString _group;
ValueType_t _type;
QVariant _defaultValue;
......@@ -87,6 +100,8 @@ private:
QString _units;
QVariant _min;
QVariant _max;
bool _minIsDefaultForType;
bool _maxIsDefaultForType;
};
#endif
\ No newline at end of file
......@@ -167,6 +167,11 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
if (fullLogging) {
QLoggingCategory::setFilterRules(QStringLiteral("*Log=true"));
} else {
if (_runningUnitTests) {
// We need to turn off these warnings until the firmware meta data is cleaned up
QLoggingCategory::setFilterRules(QStringLiteral("PX4ParameterLoaderLog.warning=false"));
}
// First thing we want to do is set up the qtlogging.ini file. If it doesn't already exist we copy
// it to the correct location. This way default debug builds will have logging turned off.
......
......@@ -51,88 +51,94 @@ QGCView {
ParameterEditorController { id: controller; factPanel: panel }
QGCViewPanel {
id: panel
anchors.fill: parent
Component {
id: editorDialogComponent
Component {
id: factRowsComponent
ParameterEditorDialog { fact: __editorDialogFact }
} // Component - Editor Dialog
Column {
id: factColumn
x: __leftMargin
Component {
id: factRowsComponent
QGCLabel {
height: defaultTextHeight + (ScreenTools.defaultFontPizelSize * 0.5)
text: group
verticalAlignment: Text.AlignVCenter
font.pixelSize: ScreenTools.mediumFontPixelSize
}
Column {
id: factColumn
x: __leftMargin
Rectangle {
width: parent.width
height: 1
color: __qgcPal.text
}
QGCLabel {
text: group
verticalAlignment: Text.AlignVCenter
font.pixelSize: ScreenTools.mediumFontPixelSize
}
Repeater {
model: controller.getFactsForGroup(componentId, group)
Rectangle {
width: parent.width
height: 1
color: __qgcPal.text
}
Column {
property Fact modelFact: controller.getParameterFact(componentId, modelData)
Item {
x: __leftMargin
width: parent.width
height: defaultTextHeight + (ScreenTools.defaultFontPixelSize * 0.5)
QGCLabel {
id: nameLabel
width: defaultTextWidth * (__maxParamChars + 1)
height: parent.height
verticalAlignment: Text.AlignVCenter
text: modelFact.name
}
Repeater {
model: controller.getFactsForGroup(componentId, group)
QGCLabel {
id: valueLabel
width: defaultTextWidth * 20
height: parent.height
anchors.left: nameLabel.right
verticalAlignment: Text.AlignVCenter
color: modelFact.valueEqualsDefault ? __qgcPal.text : "orange"
text: modelFact.valueString + " " + modelFact.units
}
Column {
property Fact modelFact: controller.getParameterFact(componentId, modelData)
QGCLabel {
height: parent.height
anchors.left: valueLabel.right
verticalAlignment: Text.AlignVCenter
visible: fullMode
text: modelFact.shortDescription
}
Item {
x: __leftMargin
width: parent.width
height: ScreenTools.defaultFontPixelSize * 1.75
MouseArea {
anchors.fill: parent
acceptedButtons: Qt.LeftButton
QGCLabel {
id: nameLabel
width: defaultTextWidth * (__maxParamChars + 1)
height: parent.height
verticalAlignment: Text.AlignVCenter
text: modelFact.name
}
onClicked: {
__editorDialogFact = modelFact
showDialog(editorDialogComponent, "Parameter Editor", fullMode ? 50 : -1, StandardButton.Cancel | StandardButton.Save)
}
}
QGCLabel {
id: valueLabel
width: defaultTextWidth * 20
height: parent.height
anchors.left: nameLabel.right
verticalAlignment: Text.AlignVCenter
color: modelFact.valueEqualsDefault ? __qgcPal.text : "orange"
text: modelFact.valueString + " " + modelFact.units
}
QGCLabel {
height: parent.height
anchors.left: valueLabel.right
verticalAlignment: Text.AlignVCenter
visible: fullMode
text: modelFact.shortDescription
}
Rectangle {
x: __leftMargin
width: factColumn.width - __leftMargin - __rightMargin
height: 1
color: __qgcPal.windowShade
MouseArea {
anchors.fill: parent
acceptedButtons: Qt.LeftButton
onClicked: {
__editorDialogFact = modelFact
showDialog(editorDialogComponent, "Parameter Editor", fullMode ? 50 : -1, StandardButton.Cancel | StandardButton.Save)
}
}
} // Column - Fact
} // Repeater - Facts
} // Column - Facts
} // Component - factRowsComponent
}
Rectangle {
x: __leftMargin
width: factColumn.width - __leftMargin - __rightMargin
height: 1
color: __qgcPal.windowShade
}
} // Column - Fact
} // Repeater - Facts
} // Column - Facts
} // Component - factRowsComponent
QGCViewPanel {
id: panel
anchors.fill: parent
Column {
anchors.fill: parent
......@@ -255,106 +261,5 @@ QGCView {
} // ScrollView - Facts
} // Item - Group ScrollView + Facts
} // Column - Outer
}
Component {
id: editorDialogComponent
QGCViewDialog {
id: editorDialog
ParameterEditorController { id: controller; factPanel: editorDialog }
property bool fullMode: true
function accept() {
__editorDialogFact.value = valueField.text
editorDialog.hideDialog()
}
Column {
spacing: defaultTextHeight
anchors.left: parent.left
anchors.right: parent.right
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: __editorDialogFact.shortDescription ? __editorDialogFact.shortDescription : "Description missing"
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
visible: __editorDialogFact.longDescription
text: __editorDialogFact.longDescription
}
QGCTextField {
id: valueField
text: __editorDialogFact.valueString
}
QGCLabel { text: __editorDialogFact.name }
Row {
spacing: defaultTextWidth
QGCLabel { text: "Units:" }
QGCLabel { text: __editorDialogFact.units ? __editorDialogFact.units : "none" }
}
Row {
spacing: defaultTextWidth
QGCLabel { text: "Minimum value:" }
QGCLabel { text: __editorDialogFact.min }
}
Row {
spacing: defaultTextWidth
QGCLabel { text: "Maxmimum value:" }
QGCLabel { text: __editorDialogFact.max }
}
Row {
spacing: defaultTextWidth
QGCLabel { text: "Default value:" }
QGCLabel { text: __editorDialogFact.defaultValueAvailable ? __editorDialogFact.defaultValue : "none" }
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: "Warning: Modifying parameters while vehicle is in flight can lead to vehicle instability and possible vehicle loss. " +
"Make sure you know what you are doing and double-check your values before Save!"
}
} // Column - Fact information
QGCButton {
anchors.rightMargin: defaultTextWidth
anchors.right: rcButton.left
anchors.bottom: parent.bottom
visible: __editorDialogFact.defaultValueAvailable
text: "Reset to default"
onClicked: {
__editorDialogFact.value = __editorDialogFact.defaultValue
editorDialog.hideDialog()
}
}
QGCButton {
id: rcButton
anchors.right: parent.right
anchors.bottom: parent.bottom
visible: __editorDialogFact.defaultValueAvailable
text: "Set RC to Param..."
onClicked: controller.setRCToParam(__editorDialogFact.name)
}
} // Rectangle - editorDialog
} // Component - Editor Dialog
} // QGCViewPanel
} // QGCView
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
import QtQuick 2.3
import QtQuick.Controls 1.3
import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
QGCViewDialog {
property Fact fact
property bool validate: false
property string validateValue
ParameterEditorController { id: controller; factPanel: parent }
function accept() {
var errorString = fact.validate(valueField.text, forceSave.checked)
if (errorString == "") {
fact.value = valueField.text
fact.valueChanged(fact.value)
hideDialog()
} else {
validationError.text = errorString
forceSave.visible = true
}
}
Component.onCompleted: {
if (validate) {
validationError.text = fact.validate(validateValue, false /* convertOnly */)
forceSave.visible = true
}
}
Column {
spacing: defaultTextHeight
anchors.left: parent.left
anchors.right: parent.right
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: fact.shortDescription ? fact.shortDescription : "Description missing"
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
visible: fact.longDescription
text: fact.longDescription
}
QGCTextField {
id: valueField
text: validate ? validateValue : fact.valueString
}
QGCLabel { text: fact.name }
Row {
spacing: defaultTextWidth
QGCLabel { text: "Units:" }
QGCLabel { text: fact.units ? fact.units : "none" }
}
Row {
spacing: defaultTextWidth
visible: !fact.minIsDefaultForType
QGCLabel { text: "Minimum value:" }
QGCLabel { text: fact.min }
}
Row {
spacing: defaultTextWidth
visible: !fact.maxIsDefaultForType
QGCLabel { text: "Maximum value:" }
QGCLabel { text: fact.max }
}
Row {
spacing: defaultTextWidth
QGCLabel { text: "Default value:" }
QGCLabel { text: fact.defaultValueAvailable ? fact.defaultValue : "none" }
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: "Warning: Modifying parameters while vehicle is in flight can lead to vehicle instability and possible vehicle loss. " +
"Make sure you know what you are doing and double-check your values before Save!"
}
QGCLabel {
id: validationError
width: parent.width
wrapMode: Text.WordWrap
color: "yellow"
}
QGCCheckBox {
id: forceSave
visible: false
text: "Force save (dangerous!)"
}
} // Column - Fact information
QGCButton {
id: bottomButton
anchors.rightMargin: defaultTextWidth
anchors.right: rcButton.left
anchors.bottom: parent.bottom
visible: fact.defaultValueAvailable
text: "Reset to default"
onClicked: {
fact.value = fact.defaultValue
fact.valueChanged(fact.value)
hideDialog()
}
}
QGCButton {
id: rcButton
anchors.right: parent.right
anchors.bottom: parent.bottom
text: "Set RC to Param..."
visible: !validate
onClicked: controller.setRCToParam(fact.name)
}
} // QGCViewDialog
......@@ -37,7 +37,8 @@ import QGroundControl.FactControls 1.0
FactPanel {
id: __rootItem
property bool completedSignalled: false
property var qgcView: __rootItem /// Used by Fact controls for validation dialogs
property bool completedSignalled: false
property var viewPanel
......
......@@ -14,9 +14,11 @@ SubMenuButton 1.0 SubMenuButton.qml
IndicatorButton 1.0 IndicatorButton.qml
VehicleRotationCal 1.0 VehicleRotationCal.qml
VehicleSummaryRow 1.0 VehicleSummaryRow.qml
ParameterEditor 1.0 ParameterEditor.qml
ViewWidget 1.0 ViewWidget.qml
ParameterEditor 1.0 ParameterEditor.qml
ParameterEditorDialog 1.0 ParameterEditorDialog.qml
QGCView 1.0 QGCView.qml
QGCViewPanel 1.0 QGCViewPanel.qml
QGCViewDialog 1.0 QGCViewDialog.qml
......
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