Browse Source

Merge pull request #1688 from DonLakeFlyer/ParameterValidation

Parameter validation
QGC4.4
Don Gagne 10 years ago
parent
commit
ff9ba29428
  1. 1
      qgroundcontrol.qrc
  2. 54
      src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc
  3. 429
      src/AutoPilotPlugins/PX4/SafetyComponent.qml
  4. 157
      src/FactSystem/Fact.cc
  5. 8
      src/FactSystem/Fact.h
  6. 36
      src/FactSystem/FactControls/FactTextField.qml
  7. 61
      src/FactSystem/FactMetaData.cc
  8. 15
      src/FactSystem/FactMetaData.h
  9. 5
      src/QGCApplication.cc
  10. 247
      src/QmlControls/ParameterEditor.qml
  11. 164
      src/QmlControls/ParameterEditorDialog.qml
  12. 3
      src/QmlControls/QGCView.qml
  13. 4
      src/QmlControls/QGroundControl.Controls.qmldir

1
qgroundcontrol.qrc

@ -106,6 +106,7 @@
<file alias="QGroundControl/Controls/QGCViewMessage.qml">src/QmlControls/QGCViewMessage.qml</file> <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/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="ParameterEditorWidget.qml">src/ViewWidgets/ParameterEditorWidget.qml</file>
<file alias="CustomCommandWidget.qml">src/ViewWidgets/CustomCommandWidget.qml</file> <file alias="CustomCommandWidget.qml">src/ViewWidgets/CustomCommandWidget.qml</file>

54
src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc

@ -116,10 +116,11 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
return; return;
} }
QString factGroup; QString factGroup;
FactMetaData* metaData = NULL; QString errorString;
int xmlState = XmlStateNone; FactMetaData* metaData = NULL;
bool badMetaData = true; int xmlState = XmlStateNone;
bool badMetaData = true;
while (!xml.atEnd()) { while (!xml.atEnd()) {
if (xml.isStartElement()) { if (xml.isStartElement()) {
@ -221,22 +222,22 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
Q_CHECK_PTR(metaData); Q_CHECK_PTR(metaData);
if (_mapParameterName2FactMetaData.contains(name)) { if (_mapParameterName2FactMetaData.contains(name)) {
// We can't trust the meta dafa since we have dups // 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; badMetaData = true;
// Reset to default meta data // Reset to default meta data
_mapParameterName2FactMetaData[name] = metaData; _mapParameterName2FactMetaData[name] = metaData;
} else { } else {
_mapParameterName2FactMetaData[name] = metaData; _mapParameterName2FactMetaData[name] = metaData;
metaData->setName(name);
metaData->setGroup(factGroup); metaData->setGroup(factGroup);
if (xml.attributes().hasAttribute("default")) { if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) {
bool convertOk; QVariant varDefault;
QVariant varDefault = _stringToTypedVariant(strDefault, metaData->type(), &convertOk);
if (convertOk) { if (metaData->convertAndValidate(strDefault, false, varDefault, errorString)) {
metaData->setDefaultValue(varDefault); metaData->setDefaultValue(varDefault);
} else { } else {
// Non-fatal qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString;
qCDebug(PX4ParameterLoaderLog) << "Parameter meta data with bad default value, name:" << name << " type:" << type << " default:" << strDefault;
} }
} }
} }
@ -252,12 +253,14 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
if (elementName == "short_desc") { if (elementName == "short_desc") {
Q_ASSERT(metaData); Q_ASSERT(metaData);
QString text = xml.readElementText(); QString text = xml.readElementText();
text = text.replace("\n", " ");
qCDebug(PX4ParameterLoaderLog) << "Short description:" << text; qCDebug(PX4ParameterLoaderLog) << "Short description:" << text;
metaData->setShortDescription(text); metaData->setShortDescription(text);
} else if (elementName == "long_desc") { } else if (elementName == "long_desc") {
Q_ASSERT(metaData); Q_ASSERT(metaData);
QString text = xml.readElementText(); QString text = xml.readElementText();
text = text.replace("\n", " ");
qCDebug(PX4ParameterLoaderLog) << "Long description:" << text; qCDebug(PX4ParameterLoaderLog) << "Long description:" << text;
metaData->setLongDescription(text); metaData->setLongDescription(text);
@ -265,26 +268,24 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
Q_ASSERT(metaData); Q_ASSERT(metaData);
QString text = xml.readElementText(); QString text = xml.readElementText();
qCDebug(PX4ParameterLoaderLog) << "Min:" << text; qCDebug(PX4ParameterLoaderLog) << "Min:" << text;
bool convertOk;
QVariant varMin = _stringToTypedVariant(text, metaData->type(), &convertOk); QVariant varMin;
if (convertOk) { if (metaData->convertAndValidate(text, true /* convertOnly */, varMin, errorString)) {
metaData->setMin(varMin); metaData->setMin(varMin);
} else { } else {
// Non-fatal qCWarning(PX4ParameterLoaderLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString;
qDebug() << "Parameter meta data with bad min value:" << text;
} }
} else if (elementName == "max") { } else if (elementName == "max") {
Q_ASSERT(metaData); Q_ASSERT(metaData);
QString text = xml.readElementText(); QString text = xml.readElementText();
qCDebug(PX4ParameterLoaderLog) << "Max:" << text; qCDebug(PX4ParameterLoaderLog) << "Max:" << text;
bool convertOk;
QVariant varMax = _stringToTypedVariant(text, metaData->type(), &convertOk); QVariant varMax;
if (convertOk) { if (metaData->convertAndValidate(text, true /* convertOnly */, varMax, errorString)) {
metaData->setMax(varMax); metaData->setMax(varMax);
} else { } else {
// Non-fatal qCWarning(PX4ParameterLoaderLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString;
qDebug() << "Parameter meta data with bad max value:" << text;
} }
} else if (elementName == "unit") { } else if (elementName == "unit") {
@ -302,7 +303,16 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
QString elementName = xml.name().toString(); QString elementName = xml.name().toString();
if (elementName == "parameter") { 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; metaData = NULL;
badMetaData = false; badMetaData = false;
xmlState = XmlStateFoundGroup; xmlState = XmlStateFoundGroup;

429
src/AutoPilotPlugins/PX4/SafetyComponent.qml

@ -31,11 +31,12 @@ import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
FactPanel { QGCView {
id: panel id: rootQGCView
viewPanel: view
QGCPalette { id: palette; colorGroupEnabled: enabled } 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 flightLineWidth: 2 // width of lines for flight graphic
property int loiterAltitudeColumnWidth: 180 // width of loiter altitude column property int loiterAltitudeColumnWidth: 180 // width of loiter altitude column
@ -47,265 +48,271 @@ FactPanel {
property int arrowWidth: 18 // width for arrow graphic property int arrowWidth: 18 // width for arrow graphic
property int firstColumnWidth: 220 // Width of first column in return home triggers area property int firstColumnWidth: 220 // Width of first column in return home triggers area
Column { QGCView {
id: view
anchors.fill: parent anchors.fill: parent
QGCLabel { Column {
text: "SAFETY CONFIG" anchors.fill: parent
font.pixelSize: ScreenTools.largeFontPixelSize
}
Item { height: 20; width: 10 } // spacer QGCLabel {
text: "SAFETY CONFIG"
font.pixelSize: ScreenTools.largeFontPixelSize
}
//----------------------------------------------------------------- Item { height: 20; width: 10 } // spacer
//-- Return Home Triggers
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 { Item { height: 10; width: 10 } // spacer
width: parent.width
height: triggerColumn.height
color: palette.windowShade
Column { Rectangle {
id: triggerColumn width: parent.width
spacing: controlVerticalSpacing height: triggerColumn.height
anchors.margins: shadedMargin color: palette.windowShade
anchors.left: parent.left
// Top margin Column {
Item { height: 1; width: 10 } id: triggerColumn
spacing: controlVerticalSpacing
anchors.margins: shadedMargin
anchors.left: parent.left
Row { // Top margin
spacing: 10 Item { height: 1; width: 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
}
}
Row { Row {
spacing: 10 spacing: 10
FactCheckBox { QGCLabel { text: "RC Transmitter Signal Loss"; width: firstColumnWidth; anchors.baseline: rcLossField.baseline }
id: telemetryTimeoutCheckbox QGCLabel { text: "Return Home after"; anchors.baseline: rcLossField.baseline }
anchors.baseline: telemetryLossField.baseline FactTextField {
width: firstColumnWidth id: rcLossField
fact: controller.getParameterFact(-1, "COM_DL_LOSS_EN") fact: controller.getParameterFact(-1, "COM_RC_LOSS_T")
checkedValue: 1 showUnits: true
uncheckedValue: 0 }
text: "Telemetry Signal Timeout"
} }
QGCLabel { text: "Return Home after"; anchors.baseline: telemetryLossField.baseline }
FactTextField { Row {
id: telemetryLossField spacing: 10
fact: controller.getParameterFact(-1, "COM_DL_LOSS_T") FactCheckBox {
showUnits: true id: telemetryTimeoutCheckbox
enabled: telemetryTimeoutCheckbox.checked 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 // Bottom margin
Item { height: 1; width: 10 } Item { height: 1; width: 10 }
}
} }
}
Item { height: 20; width: 10 } // spacer
//----------------------------------------------------------------- Item { height: 20; width: 10 } // spacer
//-- Return Home Settings
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 { Item { height: 10; width: 10 } // spacer
width: parent.width
height: settingsColumn.height
color: palette.windowShade
Column { Rectangle {
id: settingsColumn width: parent.width
width: parent.width height: settingsColumn.height
anchors.margins: shadedMargin color: palette.windowShade
anchors.left: parent.left
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 { height: shadedMargin; width: 10 } // top margin
Item {
width: parent.width
height: climbAltitudeColumn.height
Column { // This item is the holder for the climb alt and loiter seconds fields
id: climbAltitudeColumn Item {
spacing: controlVerticalSpacing width: parent.width
height: climbAltitudeColumn.height
QGCLabel { text: "Climb to altitude of" }
FactTextField { Column {
id: climbField id: climbAltitudeColumn
fact: controller.getParameterFact(-1, "RTL_RETURN_ALT") spacing: controlVerticalSpacing
showUnits: true
QGCLabel { text: "Climb to altitude of" }
FactTextField {
id: climbField
fact: controller.getParameterFact(-1, "RTL_RETURN_ALT")
showUnits: true
}
} }
}
Column { Column {
x: flightGraphic.width - 200 x: flightGraphic.width - 200
spacing: controlVerticalSpacing spacing: controlVerticalSpacing
QGCCheckBox { QGCCheckBox {
id: homeLoiterCheckbox id: homeLoiterCheckbox
checked: fact.value > 0 checked: fact.value > 0
text: "Loiter at Home altitude for" 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: { onClicked: {
fact.value = checked ? 60 : -1 fact.value = checked ? 60 : -1
}
} }
}
FactTextField { FactTextField {
fact: controller.getParameterFact(-1, "RTL_LAND_DELAY") fact: controller.getParameterFact(-1, "RTL_LAND_DELAY")
showUnits: true showUnits: true
enabled: homeLoiterCheckbox.checked == 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 // This row holds the flight graphic and the home loiter alt column
Row { Row {
width: parent.width width: parent.width
spacing: 20 spacing: 20
// Flight graphic // Flight graphic
Item { Item {
id: flightGraphic id: flightGraphic
width: parent.width - loiterAltitudeColumnWidth width: parent.width - loiterAltitudeColumnWidth
height: 200 // controls the height of the flight graphic 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
}
QGCColoredImage { Rectangle {
id: planeImage x: planeWidth / 2
y: parent.height - planeWidth - 40 height: planeImage.y - 5
source: "/qmlimages/SafetyComponentPlane.png" width: flightLineWidth
fillMode: Image.PreserveAspectFit color: palette.button
width: planeWidth }
height: planeWidth Rectangle {
smooth: true x: planeWidth / 2
color: palette.button 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 { QGCColoredImage {
x: planeWidth + 70 id: planeImage
y: parent.height - height - 20 y: parent.height - planeWidth - 40
width: 80 source: "/qmlimages/SafetyComponentPlane.png"
height: parent.height / 2 fillMode: Image.PreserveAspectFit
source: "/qmlimages/SafetyComponentTree.svg" width: planeWidth
fillMode: Image.Stretch height: planeWidth
smooth: true smooth: true
color: palette.windowShadeDark color: palette.button
} }
QGCColoredImage { QGCColoredImage {
x: planeWidth + 15 x: planeWidth + 70
y: parent.height - height y: parent.height - height - 20
width: 100 width: 80
height: parent.height * .75 height: parent.height / 2
source: "/qmlimages/SafetyComponentTree.svg" source: "/qmlimages/SafetyComponentTree.svg"
fillMode: Image.PreserveAspectFit fillMode: Image.Stretch
smooth: true smooth: true
color: palette.button color: palette.windowShadeDark
} }
QGCColoredImage { QGCColoredImage {
x: parent.width - (arrowWidth/2) - 1 x: planeWidth + 15
y: parent.height - homeWidth - arrowToHomeSpacing - 2 y: parent.height - height
source: "/qmlimages/SafetyComponentArrowDown.png" width: 100
fillMode: Image.PreserveAspectFit height: parent.height * .75
width: arrowWidth source: "/qmlimages/SafetyComponentTree.svg"
height: arrowWidth fillMode: Image.PreserveAspectFit
smooth: true smooth: true
color: palette.button 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 { QGCColoredImage {
id: homeImage id: homeImage
x: parent.width - (homeWidth / 2) x: parent.width - (homeWidth / 2)
y: parent.height - homeWidth y: parent.height - homeWidth
source: "/qmlimages/SafetyComponentHome.png" source: "/qmlimages/SafetyComponentHome.png"
fillMode: Image.PreserveAspectFit fillMode: Image.PreserveAspectFit
width: homeWidth width: homeWidth
height: homeWidth height: homeWidth
smooth: true smooth: true
color: palette.button color: palette.button
}
} }
}
Column { Column {
spacing: controlVerticalSpacing spacing: controlVerticalSpacing
QGCLabel { QGCLabel {
text: "Home loiter altitude"; text: "Home loiter altitude";
color: palette.text; color: palette.text;
enabled: homeLoiterCheckbox.checked === true enabled: homeLoiterCheckbox.checked === true
} }
FactTextField { FactTextField {
id: descendField; id: descendField;
fact: controller.getParameterFact(-1, "RTL_DESCEND_ALT") fact: controller.getParameterFact(-1, "RTL_DESCEND_ALT")
enabled: homeLoiterCheckbox.checked === true enabled: homeLoiterCheckbox.checked === true
showUnits: true showUnits: true
}
} }
} }
}
Item { height: shadedMargin; width: 10 } // bottom margin Item { height: shadedMargin; width: 10 } // bottom margin
}
} }
}
QGCLabel { QGCLabel {
width: parent.width width: parent.width
font.pixelSize: ScreenTools.mediumFontPixelSize 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."; 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 visible: fact.value !== 0
wrapMode: Text.Wrap wrapMode: Text.Wrap
property Fact fact: controller.getParameterFact(-1, "NAV_RCL_OBC") property Fact fact: controller.getParameterFact(-1, "NAV_RCL_OBC")
} }
QGCLabel { QGCLabel {
width: parent.width width: parent.width
font.pixelSize: ScreenTools.mediumFontPixelSize 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."; 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 visible: fact.value !== 0
wrapMode: Text.Wrap wrapMode: Text.Wrap
property Fact fact: controller.getParameterFact(-1, "NAV_DLL_OBC") property Fact fact: controller.getParameterFact(-1, "NAV_DLL_OBC")
}
} }
} } // QGCVIew
} }

157
src/FactSystem/Fact.cc

@ -51,34 +51,19 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
void Fact::setValue(const QVariant& value) void Fact::setValue(const QVariant& value)
{ {
QVariant newValue; if (_metaData) {
QVariant typedValue;
switch (type()) { QString errorString;
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16: if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) {
case FactMetaData::valueTypeInt32: if (typedValue != _value) {
newValue = QVariant(value.toInt()); _value.setValue(typedValue);
break; emit valueChanged(_value);
emit _containerValueChanged(_value);
case FactMetaData::valueTypeUint8: }
case FactMetaData::valueTypeUint16: }
case FactMetaData::valueTypeUint32: } else {
newValue = QVariant(value.toUInt()); qWarning() << "Meta data pointer missing";
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);
} }
} }
@ -110,11 +95,15 @@ QString Fact::valueString(void) const
QVariant Fact::defaultValue(void) QVariant Fact::defaultValue(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
if (!_metaData->defaultValueAvailable()) { if (!_metaData->defaultValueAvailable()) {
qDebug() << "Access to unavailable default value"; 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) FactMetaData::ValueType_t Fact::type(void)
@ -124,38 +113,82 @@ FactMetaData::ValueType_t Fact::type(void)
QString Fact::shortDescription(void) QString Fact::shortDescription(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
return _metaData->shortDescription(); return _metaData->shortDescription();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
} }
QString Fact::longDescription(void) QString Fact::longDescription(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
return _metaData->longDescription(); return _metaData->longDescription();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
} }
QString Fact::units(void) QString Fact::units(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
return _metaData->units(); return _metaData->units();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
} }
QVariant Fact::min(void) QVariant Fact::min(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
return _metaData->min(); return _metaData->min();
} else {
qWarning() << "Meta data pointer missing";
return QVariant(0);
}
} }
QVariant Fact::max(void) QVariant Fact::max(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
return _metaData->max(); 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) QString Fact::group(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
return _metaData->group(); return _metaData->group();
} else {
qWarning() << "Meta data pointer missing";
return QString();
}
} }
void Fact::setMetaData(FactMetaData* metaData) void Fact::setMetaData(FactMetaData* metaData)
@ -165,16 +198,40 @@ void Fact::setMetaData(FactMetaData* metaData)
bool Fact::valueEqualsDefault(void) bool Fact::valueEqualsDefault(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
if (_metaData->defaultValueAvailable()) { if (_metaData->defaultValueAvailable()) {
return _metaData->defaultValue() == value(); return _metaData->defaultValue() == value();
} else {
return false;
}
} else { } else {
qWarning() << "Meta data pointer missing";
return false; return false;
} }
} }
bool Fact::defaultValueAvailable(void) bool Fact::defaultValueAvailable(void)
{ {
Q_ASSERT(_metaData); if (_metaData) {
return _metaData->defaultValueAvailable(); 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");
}
}

8
src/FactSystem/Fact.h

@ -55,9 +55,15 @@ public:
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT) Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT) Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT) Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(QString group READ group 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 // Property system methods
QString name(void) const; QString name(void) const;
@ -73,7 +79,9 @@ public:
QString longDescription(void); QString longDescription(void);
QString units(void); QString units(void);
QVariant min(void); QVariant min(void);
bool minIsDefaultForType(void);
QVariant max(void); QVariant max(void);
bool maxIsDefaultForType(void);
QString group(void); QString group(void);
/// Sets the meta data associated with the Fact. /// Sets the meta data associated with the Fact.

36
src/FactSystem/FactControls/FactTextField.qml

@ -1,14 +1,44 @@
import QtQuick 2.2 import QtQuick 2.2
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2 import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QGroundControl.FactSystem 1.0 import QGroundControl.FactSystem 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
QGCTextField { QGCTextField {
property Fact fact: null id: _textField
text: fact.valueString
property Fact fact: null
property string _validateString
text: fact.valueString
unitsLabel: fact.units 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
}
}
} }

61
src/FactSystem/FactMetaData.cc

@ -39,7 +39,9 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent) :
_defaultValue(0), _defaultValue(0),
_defaultValueAvailable(false), _defaultValueAvailable(false),
_min(_minForType()), _min(_minForType()),
_max(_maxForType()) _max(_maxForType()),
_minIsDefaultForType(true),
_maxIsDefaultForType(true)
{ {
} }
@ -68,6 +70,7 @@ void FactMetaData::setMin(const QVariant& min)
{ {
if (min > _minForType()) { if (min > _minForType()) {
_min = min; _min = min;
_minIsDefaultForType = false;
} else { } else {
qWarning() << "Attempt to set min below allowable value"; qWarning() << "Attempt to set min below allowable value";
_min = _minForType(); _min = _minForType();
@ -81,6 +84,7 @@ void FactMetaData::setMax(const QVariant& max)
_max = _maxForType(); _max = _maxForType();
} else { } else {
_max = max; _max = max;
_maxIsDefaultForType = false;
} }
} }
@ -133,3 +137,58 @@ QVariant FactMetaData::_maxForType(void)
// Make windows compiler happy, even switch is full cased // Make windows compiler happy, even switch is full cased
return QVariant(); 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();
}

15
src/FactSystem/FactMetaData.h

@ -55,6 +55,7 @@ public:
FactMetaData(ValueType_t type, QObject* parent = NULL); FactMetaData(ValueType_t type, QObject* parent = NULL);
// Property accessors // Property accessors
QString name(void) { return _name; }
QString group(void) { return _group; } QString group(void) { return _group; }
ValueType_t type(void) { return _type; } ValueType_t type(void) { return _type; }
QVariant defaultValue(void); QVariant defaultValue(void);
@ -64,8 +65,11 @@ public:
QString units(void) { return _units; } QString units(void) { return _units; }
QVariant min(void) { return _min; } QVariant min(void) { return _min; }
QVariant max(void) { return _max; } QVariant max(void) { return _max; }
bool minIsDefaultForType(void) { return _minIsDefaultForType; }
bool maxIsDefaultForType(void) { return _maxIsDefaultForType; }
// Property setters // Property setters
void setName(const QString& name) { _name = name; }
void setGroup(const QString& group) { _group = group; } void setGroup(const QString& group) { _group = group; }
void setDefaultValue(const QVariant& defaultValue); void setDefaultValue(const QVariant& defaultValue);
void setShortDescription(const QString& shortDescription) { _shortDescription = shortDescription; } void setShortDescription(const QString& shortDescription) { _shortDescription = shortDescription; }
@ -73,11 +77,20 @@ public:
void setUnits(const QString& units) { _units = units; } void setUnits(const QString& units) { _units = units; }
void setMin(const QVariant& max); void setMin(const QVariant& max);
void setMax(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: private:
QVariant _minForType(void); QVariant _minForType(void);
QVariant _maxForType(void); QVariant _maxForType(void);
QString _name;
QString _group; QString _group;
ValueType_t _type; ValueType_t _type;
QVariant _defaultValue; QVariant _defaultValue;
@ -87,6 +100,8 @@ private:
QString _units; QString _units;
QVariant _min; QVariant _min;
QVariant _max; QVariant _max;
bool _minIsDefaultForType;
bool _maxIsDefaultForType;
}; };
#endif #endif

5
src/QGCApplication.cc

@ -167,6 +167,11 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
if (fullLogging) { if (fullLogging) {
QLoggingCategory::setFilterRules(QStringLiteral("*Log=true")); QLoggingCategory::setFilterRules(QStringLiteral("*Log=true"));
} else { } 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 // 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. // it to the correct location. This way default debug builds will have logging turned off.

247
src/QmlControls/ParameterEditor.qml

@ -51,88 +51,94 @@ QGCView {
ParameterEditorController { id: controller; factPanel: panel } ParameterEditorController { id: controller; factPanel: panel }
QGCViewPanel { Component {
id: panel id: editorDialogComponent
anchors.fill: parent
Component { ParameterEditorDialog { fact: __editorDialogFact }
id: factRowsComponent } // Component - Editor Dialog
Column { Component {
id: factColumn id: factRowsComponent
x: __leftMargin
QGCLabel { Column {
height: defaultTextHeight + (ScreenTools.defaultFontPizelSize * 0.5) id: factColumn
text: group x: __leftMargin
verticalAlignment: Text.AlignVCenter
font.pixelSize: ScreenTools.mediumFontPixelSize
}
Rectangle { QGCLabel {
width: parent.width text: group
height: 1 verticalAlignment: Text.AlignVCenter
color: __qgcPal.text font.pixelSize: ScreenTools.mediumFontPixelSize
} }
Repeater { Rectangle {
model: controller.getFactsForGroup(componentId, group) width: parent.width
height: 1
color: __qgcPal.text
}
Column { Repeater {
property Fact modelFact: controller.getParameterFact(componentId, modelData) model: controller.getFactsForGroup(componentId, group)
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
}
QGCLabel { Column {
id: valueLabel property Fact modelFact: controller.getParameterFact(componentId, modelData)
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 { Item {
height: parent.height x: __leftMargin
anchors.left: valueLabel.right width: parent.width
verticalAlignment: Text.AlignVCenter height: ScreenTools.defaultFontPixelSize * 1.75
visible: fullMode
text: modelFact.shortDescription
}
MouseArea { QGCLabel {
anchors.fill: parent id: nameLabel
acceptedButtons: Qt.LeftButton width: defaultTextWidth * (__maxParamChars + 1)
height: parent.height
verticalAlignment: Text.AlignVCenter
text: modelFact.name
}
onClicked: { QGCLabel {
__editorDialogFact = modelFact id: valueLabel
showDialog(editorDialogComponent, "Parameter Editor", fullMode ? 50 : -1, StandardButton.Cancel | StandardButton.Save) 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 { MouseArea {
x: __leftMargin anchors.fill: parent
width: factColumn.width - __leftMargin - __rightMargin acceptedButtons: Qt.LeftButton
height: 1
color: __qgcPal.windowShade onClicked: {
__editorDialogFact = modelFact
showDialog(editorDialogComponent, "Parameter Editor", fullMode ? 50 : -1, StandardButton.Cancel | StandardButton.Save)
}
} }
} // Column - Fact }
} // Repeater - Facts
} // Column - Facts Rectangle {
} // Component - factRowsComponent 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 { Column {
anchors.fill: parent anchors.fill: parent
@ -255,106 +261,5 @@ QGCView {
} // ScrollView - Facts } // ScrollView - Facts
} // Item - Group ScrollView + Facts } // Item - Group ScrollView + Facts
} // Column - Outer } // Column - Outer
} } // QGCViewPanel
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
} // QGCView } // QGCView

164
src/QmlControls/ParameterEditorDialog.qml

@ -0,0 +1,164 @@
/*=====================================================================
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

3
src/QmlControls/QGCView.qml

@ -37,7 +37,8 @@ import QGroundControl.FactControls 1.0
FactPanel { FactPanel {
id: __rootItem id: __rootItem
property bool completedSignalled: false property var qgcView: __rootItem /// Used by Fact controls for validation dialogs
property bool completedSignalled: false
property var viewPanel property var viewPanel

4
src/QmlControls/QGroundControl.Controls.qmldir

@ -14,9 +14,11 @@ SubMenuButton 1.0 SubMenuButton.qml
IndicatorButton 1.0 IndicatorButton.qml IndicatorButton 1.0 IndicatorButton.qml
VehicleRotationCal 1.0 VehicleRotationCal.qml VehicleRotationCal 1.0 VehicleRotationCal.qml
VehicleSummaryRow 1.0 VehicleSummaryRow.qml VehicleSummaryRow 1.0 VehicleSummaryRow.qml
ParameterEditor 1.0 ParameterEditor.qml
ViewWidget 1.0 ViewWidget.qml ViewWidget 1.0 ViewWidget.qml
ParameterEditor 1.0 ParameterEditor.qml
ParameterEditorDialog 1.0 ParameterEditorDialog.qml
QGCView 1.0 QGCView.qml QGCView 1.0 QGCView.qml
QGCViewPanel 1.0 QGCViewPanel.qml QGCViewPanel 1.0 QGCViewPanel.qml
QGCViewDialog 1.0 QGCViewDialog.qml QGCViewDialog 1.0 QGCViewDialog.qml

Loading…
Cancel
Save