From 714a00981236e3ec40814518c28a629b117f35f5 Mon Sep 17 00:00:00 2001 From: tstellanova Date: Tue, 6 Aug 2013 10:25:33 -0700 Subject: [PATCH] move parameter meta info into param data model --- src/uas/QGCUASParamManager.cc | 8 +- src/uas/QGCUASParamManager.h | 12 +-- src/uas/UASParameterDataModel.cc | 144 ++++++++++++++++++++++++++++- src/uas/UASParameterDataModel.h | 29 +++++- src/ui/QGCPX4VehicleConfig.cc | 4 +- src/ui/QGCParamWidget.cc | 146 ++++-------------------------- src/ui/QGCParamWidget.h | 17 +--- src/ui/QGCVehicleConfig.cc | 4 +- src/ui/designer/QGCComboBox.cc | 31 +++---- src/ui/designer/QGCParamSlider.cc | 30 ++---- 10 files changed, 225 insertions(+), 200 deletions(-) diff --git a/src/uas/QGCUASParamManager.cc b/src/uas/QGCUASParamManager.cc index af62e3916..06774ec25 100644 --- a/src/uas/QGCUASParamManager.cc +++ b/src/uas/QGCUASParamManager.cc @@ -11,8 +11,8 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) : rewriteTimeout(500), retransmissionBurstRequestSize(5) { - uas->setParamManager(this); paramDataModel = uas->getParamDataModel(); + uas->setParamManager(this); } @@ -82,6 +82,12 @@ void QGCUASParamManager::setParameterStatusMsg(const QString& msg) parameterStatusMsg = msg; } +void QGCUASParamManager::setParamDescriptions(const QMap& paramInfo) { + paramDataModel->setParamDescriptions(paramInfo); +} + + + void QGCUASParamManager::retransmissionGuardTick() { if (transmissionActive) { diff --git a/src/uas/QGCUASParamManager.h b/src/uas/QGCUASParamManager.h index f16be9f7b..2a0165959 100644 --- a/src/uas/QGCUASParamManager.h +++ b/src/uas/QGCUASParamManager.h @@ -17,20 +17,14 @@ public: virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const; - virtual bool isParamMinKnown(const QString& param) = 0; - virtual bool isParamMaxKnown(const QString& param) = 0; - virtual bool isParamDefaultKnown(const QString& param) = 0; - virtual double getParamMin(const QString& param) = 0; - virtual double getParamMax(const QString& param) = 0; - virtual double getParamDefault(const QString& param) = 0; - virtual QString getParamInfo(const QString& param) = 0; - virtual void setParamInfo(const QMap& param) = 0; - /** @brief Request an update for the parameter list */ void requestParameterListUpdate(int component = 0); /** @brief Request an update for this specific parameter */ virtual void requestParameterUpdate(int component, const QString& parameter) = 0; + /** @brief Provide tooltips / user-visible descriptions for parameters */ + virtual void setParamDescriptions(const QMap& paramDescs); + protected: /** @brief Check for missing parameters */ virtual void retransmissionGuardTick(); diff --git a/src/uas/UASParameterDataModel.cc b/src/uas/UASParameterDataModel.cc index 3269efd18..d678385dc 100644 --- a/src/uas/UASParameterDataModel.cc +++ b/src/uas/UASParameterDataModel.cc @@ -152,7 +152,7 @@ void UASParameterDataModel::forgetAllOnboardParameters() onboardParameters.clear(); } -void UASParameterDataModel::readUpdateParametersFromStream(QTextStream& stream) +void UASParameterDataModel::readUpdateParametersFromStream( QTextStream& stream) { bool userWarned = false; @@ -228,7 +228,7 @@ void UASParameterDataModel::readUpdateParametersFromStream(QTextStream& stream) } -void UASParameterDataModel::writeOnboardParametersToStream(QTextStream& stream, const QString& name) +void UASParameterDataModel::writeOnboardParametersToStream( QTextStream &stream, const QString& name) { stream << "# Onboard parameters for system " << name << "\n"; stream << "#\n"; @@ -272,3 +272,143 @@ void UASParameterDataModel::writeOnboardParametersToStream(QTextStream& stream, } } } + + +void UASParameterDataModel::loadParamMetaInfoFromStream(QTextStream& stream) +{ + + // First line is header + // there might be more lines, but the first + // line is assumed to be at least header + QString header = stream.readLine(); + + // Ignore top-level comment lines + while (header.startsWith('#') || header.startsWith('/') + || header.startsWith('=') || header.startsWith('^')) + { + header = stream.readLine(); + } + + bool charRead = false; + QString separator = ""; + QList sepCandidates; + sepCandidates << '\t'; + sepCandidates << ','; + sepCandidates << ';'; + //sepCandidates << ' '; + sepCandidates << '~'; + sepCandidates << '|'; + + // Iterate until separator is found + // or full header is parsed + for (int i = 0; i < header.length(); i++) + { + if (sepCandidates.contains(header.at(i))) + { + // Separator found + if (charRead) + { + separator += header[i]; + } + } + else + { + // Char found + charRead = true; + // If the separator is not empty, this char + // has been read after a separator, so detection + // is now complete + if (separator != "") break; + } + } + + bool stripFirstSeparator = false; + bool stripLastSeparator = false; + + // Figure out if the lines start with the separator (e.g. wiki syntax) + if (header.startsWith(separator)) stripFirstSeparator = true; + + // Figure out if the lines end with the separator (e.g. wiki syntax) + if (header.endsWith(separator)) stripLastSeparator = true; + + QString out = separator; + out.replace("\t", ""); + //qDebug() << " Separator: \"" << out << "\""; + //qDebug() << "READING CSV:" << header; + + + // Read data + while (!stream.atEnd()) + { + QString line = stream.readLine(); + + //qDebug() << "LINE PRE-STRIP" << line; + + // Strip separtors if necessary + if (stripFirstSeparator) line.remove(0, separator.length()); + if (stripLastSeparator) line.remove(line.length()-separator.length(), line.length()-1); + + //qDebug() << "LINE POST-STRIP" << line; + + // Keep empty parts here - we still have to act on them + QStringList parts = line.split(separator, QString::KeepEmptyParts); + + // Each line is: + // variable name, Min, Max, Default, Multiplier, Enabled (0 = no, 1 = yes), Comment + + + // Fill in min, max and default values + if (parts.count() > 1) + { + // min + paramMin.insert(parts.at(0).trimmed(), parts.at(1).toDouble()); + } + if (parts.count() > 2) + { + // max + paramMax.insert(parts.at(0).trimmed(), parts.at(2).toDouble()); + } + if (parts.count() > 3) + { + // default + paramDefault.insert(parts.at(0).trimmed(), parts.at(3).toDouble()); + } + // IGNORING 4 and 5 for now + if (parts.count() > 6) + { + // tooltip + paramDescriptions.insert(parts.at(0).trimmed(), parts.at(6).trimmed()); + qDebug() << "PARAM META:" << parts.at(0).trimmed(); + } + } +} + + void UASParameterDataModel::setParamDescriptions(const QMap& paramInfo) +{ + if (paramInfo.isEmpty()) { + qDebug() << __FILE__ << ":" << __LINE__ << "setParamDescriptions with empty"; + } + + paramDescriptions = paramInfo; +} + +bool UASParameterDataModel::isValueGreaterThanParamMax(const QString& paramName, double dblVal) +{ + if (paramMax.contains(paramName)) { + if (dblVal > paramMax.value(paramName)) + return true; + } + + return false; +} + +bool UASParameterDataModel::isValueLessThanParamMin(const QString& paramName, double dblVal) +{ + if (paramMin.contains(paramName)) { + if (dblVal < paramMin.value(paramName)) + return true; + } + + return false; + } + diff --git a/src/uas/UASParameterDataModel.h b/src/uas/UASParameterDataModel.h index e38e06c8c..0f89ed436 100644 --- a/src/uas/UASParameterDataModel.h +++ b/src/uas/UASParameterDataModel.h @@ -14,6 +14,21 @@ public: explicit UASParameterDataModel(QObject *parent = 0); + //Parameter meta info + bool isParamMinKnown(const QString& param) { return paramMin.contains(param); } + virtual bool isValueLessThanParamMin(const QString& param, double dblVal); + + bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); } + virtual bool isValueGreaterThanParamMax(const QString& param, double dblVal); + + bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); } + double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); } + double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); } + double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); } + virtual QString getParamDescription(const QString& param) { return paramDescriptions.value(param, ""); } + virtual void setParamDescriptions(const QMap& paramInfo); + + virtual void addComponent(int componentId); /** @brief Write a new pending parameter value that may be eventually sent to the UAS */ @@ -59,8 +74,10 @@ public: } - virtual void writeOnboardParametersToStream(QTextStream& stream, const QString& uasName); - virtual void readUpdateParametersFromStream(QTextStream& stream); + virtual void writeOnboardParametersToStream(QTextStream &stream, const QString& uasName); + virtual void readUpdateParametersFromStream(QTextStream &stream); + + virtual void loadParamMetaInfoFromStream(QTextStream& stream); void setUASID(int anId) { this->uasId = anId; } @@ -74,6 +91,14 @@ protected: QMap* > pendingParameters; ///< Changed values that have not yet been transmitted to the UAS, by component ID QMap* > onboardParameters; ///< All parameters confirmed to be stored onboard the UAS, by component ID + // Tooltip data structures + QMap paramDescriptions; ///< Tooltip values + + // Min / Default / Max data structures + QMap paramMin; ///< Minimum param values + QMap paramDefault; ///< Default param values + QMap paramMax; ///< Minimum param values + }; diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index 3ea93d914..f43f20a88 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -793,7 +793,7 @@ void QGCPX4VehicleConfig::loadConfig() xml.readNext(); } - mav->getParamManager()->setParamInfo(paramTooltips); + mav->getParamManager()->setParamDescriptions(paramTooltips); doneLoadingConfig = true; mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished. } @@ -892,7 +892,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) if (!paramTooltips.isEmpty()) { - mav->getParamManager()->setParamInfo(paramTooltips); + mav->getParamManager()->setParamDescriptions(paramTooltips); } qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName(); diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index 1cb641fdd..7b6f33301 100644 --- a/src/ui/QGCParamWidget.cc +++ b/src/ui/QGCParamWidget.cc @@ -55,9 +55,9 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : loadSettings(); // Load default values and tooltips - QString hey(uas->getAutopilotTypeName()); - QString hey2(uas->getSystemTypeName()); - loadParameterInfoCSV(hey, hey2); + QString autoPilotName(uas->getAutopilotTypeName()); + QString sysTypeName(uas->getSystemTypeName()); + loadParamMetaInfoCSV(autoPilotName, sysTypeName); // Create tree widget tree = new QTreeWidget(this); @@ -169,15 +169,9 @@ void QGCParamWidget::loadSettings() } -void QGCParamWidget::setParamInfo(const QMap& paramInfo) { - if (paramInfo.isEmpty()) { - qDebug() << __FILE__ << ":" << __LINE__ << "setParamInfo with empty"; - } - paramToolTips = paramInfo; -} -void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QString& airframe) +void QGCParamWidget::loadParamMetaInfoCSV(const QString& autopilot, const QString& airframe) { Q_UNUSED(airframe); @@ -198,116 +192,11 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin return; } - // Extract header - // Read in values - // Find all keys QTextStream in(¶mMetaFile); + paramDataModel->loadParamMetaInfoFromStream(in); + paramMetaFile.close(); - // First line is header - // there might be more lines, but the first - // line is assumed to be at least header - QString header = in.readLine(); - - // Ignore top-level comment lines - while (header.startsWith('#') || header.startsWith('/') - || header.startsWith('=') || header.startsWith('^')) - { - header = in.readLine(); - } - - bool charRead = false; - QString separator = ""; - QList sepCandidates; - sepCandidates << '\t'; - sepCandidates << ','; - sepCandidates << ';'; - //sepCandidates << ' '; - sepCandidates << '~'; - sepCandidates << '|'; - - // Iterate until separator is found - // or full header is parsed - for (int i = 0; i < header.length(); i++) - { - if (sepCandidates.contains(header.at(i))) - { - // Separator found - if (charRead) - { - separator += header[i]; - } - } - else - { - // Char found - charRead = true; - // If the separator is not empty, this char - // has been read after a separator, so detection - // is now complete - if (separator != "") break; - } - } - - bool stripFirstSeparator = false; - bool stripLastSeparator = false; - - // Figure out if the lines start with the separator (e.g. wiki syntax) - if (header.startsWith(separator)) stripFirstSeparator = true; - - // Figure out if the lines end with the separator (e.g. wiki syntax) - if (header.endsWith(separator)) stripLastSeparator = true; - - QString out = separator; - out.replace("\t", ""); - //qDebug() << " Separator: \"" << out << "\""; - //qDebug() << "READING CSV:" << header; - - - // Read data - while (!in.atEnd()) - { - QString line = in.readLine(); - - //qDebug() << "LINE PRE-STRIP" << line; - - // Strip separtors if necessary - if (stripFirstSeparator) line.remove(0, separator.length()); - if (stripLastSeparator) line.remove(line.length()-separator.length(), line.length()-1); - - //qDebug() << "LINE POST-STRIP" << line; - - // Keep empty parts here - we still have to act on them - QStringList parts = line.split(separator, QString::KeepEmptyParts); - - // Each line is: - // variable name, Min, Max, Default, Multiplier, Enabled (0 = no, 1 = yes), Comment - - - // Fill in min, max and default values - if (parts.count() > 1) - { - // min - paramMin.insert(parts.at(0).trimmed(), parts.at(1).toDouble()); - } - if (parts.count() > 2) - { - // max - paramMax.insert(parts.at(0).trimmed(), parts.at(2).toDouble()); - } - if (parts.count() > 3) - { - // default - paramDefault.insert(parts.at(0).trimmed(), parts.at(3).toDouble()); - } - // IGNORING 4 and 5 for now - if (parts.count() > 6) - { - // tooltip - paramToolTips.insert(parts.at(0).trimmed(), parts.at(6).trimmed()); - qDebug() << "PARAM META:" << parts.at(0).trimmed(); - } - } } /** @@ -628,15 +517,15 @@ void QGCParamWidget::receivedParameterUpdate(int uas, int component, QString par parameterItem->setBackground(0, Qt::NoBrush); parameterItem->setBackground(1, Qt::NoBrush); // Add tooltip + QString paramDesc = paramDataModel->getParamDescription(parameterName); QString tooltipFormat; - if (paramDefault.contains(parameterName)) - { + if (paramDataModel->isParamDefaultKnown(parameterName)) { tooltipFormat = tr("Default: %1, %2"); - tooltipFormat = tooltipFormat.arg(paramDefault.value(parameterName, 0.0f)).arg(paramToolTips.value(parameterName, "")); + double paramDefValue = paramDataModel->getParamDefault(parameterName); + tooltipFormat = tooltipFormat.arg(paramDefValue).arg(paramDesc); } - else - { - tooltipFormat = paramToolTips.value(parameterName, ""); + else { + tooltipFormat = paramDesc; } parameterItem->setToolTip(0, tooltipFormat); parameterItem->setToolTip(1, tooltipFormat); @@ -837,14 +726,17 @@ void QGCParamWidget::writeParameters() */ void QGCParamWidget::setParameter(int component, QString parameterName, QVariant value) { + if (parameterName.isEmpty()) { + return; + } + double dblValue = value.toDouble(); - if (paramMin.contains(parameterName) && dblValue < paramMin.value(parameterName)) - { + + if (paramDataModel->isValueLessThanParamMin(parameterName,dblValue)) { statusLabel->setText(tr("REJ. %1, %2 < min").arg(parameterName).arg(dblValue)); return; } - if (paramMax.contains(parameterName) && dblValue > paramMax.value(parameterName)) - { + if (paramDataModel->isValueGreaterThanParamMax(parameterName,dblValue)) { statusLabel->setText(tr("REJ. %1, %2 > max").arg(parameterName).arg(dblValue)); return; } diff --git a/src/ui/QGCParamWidget.h b/src/ui/QGCParamWidget.h index c49f5a55c..9b34813b0 100644 --- a/src/ui/QGCParamWidget.h +++ b/src/ui/QGCParamWidget.h @@ -51,14 +51,6 @@ public: /** @brief Get the UAS of this widget */ UASInterface* getUAS(); - bool isParamMinKnown(const QString& param) { return paramMin.contains(param); } - bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); } - bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); } - double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); } - double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); } - double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); } - QString getParamInfo(const QString& param) { return paramToolTips.value(param, ""); } - void setParamInfo(const QMap& paramInfo); protected: virtual void setParameterStatusMsg(const QString& msg); @@ -104,18 +96,13 @@ protected: QMap* components; ///< The list of components QMap* > paramGroups; ///< Parameter groups - // Tooltip data structures - QMap paramToolTips; ///< Tooltip values - // Min / Default / Max data structures - QMap paramMin; ///< Minimum param values - QMap paramDefault; ///< Default param values - QMap paramMax; ///< Minimum param values + /** @brief Load settings */ void loadSettings(); /** @brief Load meta information from CSV */ - void loadParameterInfoCSV(const QString& autopilot, const QString& airframe); + void loadParamMetaInfoCSV(const QString& autopilot, const QString& airframe); }; #endif // QGCPARAMWIDGET_H diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index d94076dbd..dd2c769a7 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -786,7 +786,7 @@ void QGCVehicleConfig::loadConfig() xml.readNext(); } - mav->getParamManager()->setParamInfo(paramTooltips); + mav->getParamManager()->setParamDescriptions(paramTooltips); doneLoadingConfig = true; mav->requestParameters(); //Config is finished, lets do a parameter request to ensure none are missed if someone else started requesting before we were finished. } @@ -888,7 +888,7 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) if (!paramTooltips.isEmpty()) { - mav->getParamManager()->setParamInfo(paramTooltips); + mav->getParamManager()->setParamDescriptions(paramTooltips); } qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName(); diff --git a/src/ui/designer/QGCComboBox.cc b/src/ui/designer/QGCComboBox.cc index 21d86f679..91f9dfc21 100644 --- a/src/ui/designer/QGCComboBox.cc +++ b/src/ui/designer/QGCComboBox.cc @@ -108,15 +108,14 @@ void QGCComboBox::setActiveUAS(UASInterface* activeUas) // Update current param value //requestParameter(); // Set param info - QString text = uas->getParamManager()->getParamInfo(parameterName); - if (text != "") - { + + QString text = uas->getParamDataModel()->getParamDescription(parameterName); + if (!text.isEmpty()) { ui->infoLabel->setToolTip(text); ui->infoLabel->show(); } // Force-uncheck and hide label if no description is available - if (ui->editInfoCheckBox->isChecked()) - { + if (ui->editInfoCheckBox->isChecked()) { showInfo((text.length() > 0)); } } @@ -147,27 +146,21 @@ void QGCComboBox::selectParameter(int paramIndex) parameterName = ui->editSelectParamComboBox->itemText(paramIndex); // Update min and max values if available - if (uas) - { - if (uas->getParamManager()) - { - // Current value - //uas->getParamManager()->requestParameterUpdate(component, parameterName); - + if (uas) { + UASParameterDataModel* dataModel = uas->getParamDataModel(); + if (dataModel) { // Minimum - if (uas->getParamManager()->isParamMinKnown(parameterName)) - { - parameterMin = uas->getParamManager()->getParamMin(parameterName); + if (dataModel->isParamMinKnown(parameterName)) { + parameterMin = dataModel->getParamMin(parameterName); } // Maximum - if (uas->getParamManager()->isParamMaxKnown(parameterName)) - { - parameterMax = uas->getParamManager()->getParamMax(parameterName); + if (dataModel->isParamMaxKnown(parameterName)) { + parameterMax = dataModel->getParamMax(parameterName); } // Description - QString text = uas->getParamManager()->getParamInfo(parameterName); + QString text = dataModel->getParamDescription(parameterName); //ui->infoLabel->setText(text); showInfo(!(text.length() > 0)); } diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index 6733c5790..7f7675942 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -102,8 +102,8 @@ void QGCParamSlider::setActiveUAS(UASInterface* activeUas) uas = activeUas; } - QString text = uas->getParamManager()->getParamInfo(parameterName); - if (text != "") { + QString text = uas->getParamDataModel()->getParamDescription(parameterName); + if (!text.isEmpty()) { ui->infoLabel->setToolTip(text); ui->infoLabel->show(); } @@ -176,32 +176,20 @@ void QGCParamSlider::selectParameter(int paramIndex) parameterName = ui->editSelectParamComboBox->itemText(paramIndex); // Update min and max values if available - if (uas) - { - if (uas->getParamManager()) - { - // Current value - //uas->getParamManager()->requestParameterUpdate(component, parameterName); - + if (uas) { + UASParameterDataModel* dataModel = uas->getParamDataModel(); + if (dataModel) { // Minimum - if (uas->getParamManager()->isParamMinKnown(parameterName)) - { - parameterMin = uas->getParamManager()->getParamMin(parameterName); + if (dataModel->isParamMinKnown(parameterName)) { + parameterMin = dataModel->getParamMin(parameterName); ui->editMinSpinBox->setValue(parameterMin); } // Maximum - if (uas->getParamManager()->isParamMaxKnown(parameterName)) - { - parameterMax = uas->getParamManager()->getParamMax(parameterName); + if (dataModel->isParamMaxKnown(parameterName)) { + parameterMax = dataModel->getParamMax(parameterName); ui->editMaxSpinBox->setValue(parameterMax); } - - // Description - //QString text = uas->getParamManager()->getParamInfo(parameterName); - //ui->infoLabel->setText(text); - - //showInfo(!(text.length() > 0)); } } } -- 2.22.0