diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index 98b03b46fb054df5409f385a183084a682beb483..1c07f656ec70421b60b96e33cdbffdd83fc7e3c0 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -34,6 +34,7 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : calibrationEnabled(false), ui(new Ui::QGCVehicleConfig) { + doneLoadingConfig = false; setObjectName("QGC_VEHICLECONFIG"); ui->setupUi(this); @@ -322,6 +323,7 @@ void QGCVehicleConfig::loadConfig() if (!xmlfile.open(QIODevice::ReadOnly)) { loadQgcConfig(); + doneLoadingConfig = true; return; } @@ -491,6 +493,8 @@ void QGCVehicleConfig::loadConfig() mav->getParamManager()->setParamInfo(paramTooltips); } emit configReady(); + doneLoadingConfig = true; + mav->requestParameters(); } void QGCVehicleConfig::setActiveUAS(UASInterface* active) @@ -761,7 +765,10 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete { Q_UNUSED(uas); Q_UNUSED(component); - + if (!doneLoadingConfig) + { + return; + } if (paramToWidgetMap.contains(parameterName)) { paramToWidgetMap[parameterName]->setParameterValue(uas,component,parameterName,value); @@ -777,7 +784,49 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete } else { + bool found = false; qDebug() << "Param with no widget:" << parameterName; + for (int i=0;iobjectName())) + { + //It should be grouped with this one. + qDebug() << parameterName << toolWidgets[i]->objectName(); + toolWidgets[i]->addParam(uas,component,parameterName,value); + paramToWidgetMap[parameterName] = toolWidgets[i]; + found = true; + break; + } + } + if (!found) + { + QGCToolWidget *tool = new QGCToolWidget("", this); + QString tooltitle = parameterName; + if (parameterName.split("_").size() > 1) + { + tooltitle = parameterName.split("_")[0] + "_"; + } + tool->setTitle(tooltitle); + tool->setObjectName(tooltitle); + //tool->setSettings(set); + tool->addParam(uas,component,parameterName,value); + paramToWidgetMap[parameterName] = tool; + toolWidgets.append(tool); + QGroupBox *box = new QGroupBox(this); + box->setTitle(tool->objectName()); + box->setLayout(new QVBoxLayout()); + box->layout()->addWidget(tool); + + if (ui->leftHWSpecificLayout->count() > ui->rightHWSpecificLayout->count()) + { + ui->rightHWSpecificLayout->addWidget(box); + } + else + { + ui->leftHWSpecificLayout->addWidget(box); + } + toolToBoxMap[tool] = box; + } } // Channel calibration values diff --git a/src/ui/QGCVehicleConfig.h b/src/ui/QGCVehicleConfig.h index 6674b153db8404d213f0fb9c8ad594943258cd1c..928ab67c8a88eeb5eb5b67894c146f079f11e0c8 100644 --- a/src/ui/QGCVehicleConfig.h +++ b/src/ui/QGCVehicleConfig.h @@ -144,6 +144,7 @@ protected slots: void updateInvertedCheckboxes(int index); protected: + bool doneLoadingConfig; UASInterface* mav; ///< The current MAV static const unsigned int chanMax = 8; ///< Maximum number of channels unsigned int chanCount; ///< Actual channels diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui index ffc5ea3d4bf69794023a8fe09bce340e5463fe37..07e0f2b4e6d4465713e4c1097c4b5c9b96e01940 100644 --- a/src/ui/QGCVehicleConfig.ui +++ b/src/ui/QGCVehicleConfig.ui @@ -886,7 +886,7 @@ p, li { white-space: pre-wrap; } - Hardware Specific Config + Advanced Config diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index c6cd4fc3238e637aa926120b48666241c22a9d7c..288476eab57174c38a00622b62f43847894ad35a 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -309,6 +309,10 @@ void QGCParamSlider::setSliderValue(int sliderValue) void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, QVariant value) { Q_UNUSED(paramCount); + if (ui->nameLabel->text() == "Name") + { + ui->nameLabel->setText(parameterName); + } // Check if this component and parameter are part of the list bool found = false; for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i) @@ -449,6 +453,13 @@ void QGCParamSlider::readSettings(const QString& pre,const QVariantMap& settings // Get param value after settings have been loaded //requestParameter(); } +void QGCParamSlider::setParamMinMax(double min, double max) +{ + parameterMin = min; + parameterMax = max; + ui->editMinSpinBox->setValue(min); + ui->editMaxSpinBox->setValue(max); +} void QGCParamSlider::readSettings(const QSettings& settings) { diff --git a/src/ui/designer/QGCParamSlider.h b/src/ui/designer/QGCParamSlider.h index fe6fae4d2663a151cf7b54e7e38612ffa172f98c..a785e32f3b3a530dff2b741a52d01c78cf6f5b92 100644 --- a/src/ui/designer/QGCParamSlider.h +++ b/src/ui/designer/QGCParamSlider.h @@ -45,6 +45,8 @@ public slots: /** @brief Show tool tip of calling element */ void showTooltip(); + void setParamMinMax(double min, double max); + protected slots: /** @brief Request the parameter of this widget from the MAV */ void requestParameter(); diff --git a/src/ui/designer/QGCToolWidget.cc b/src/ui/designer/QGCToolWidget.cc index b9f005fd3e3819cf4796d70c94cbdfda3f4ac019..5237dc6e8980000a444369c9f75e5bfaa30c825e 100644 --- a/src/ui/designer/QGCToolWidget.cc +++ b/src/ui/designer/QGCToolWidget.cc @@ -203,6 +203,12 @@ void QGCToolWidget::setParameterValue(int uas, int component, QString parameterN //int size = settings.beginReadArray("QGC_TOOL_WIDGET_ITEMS"); int size = settingsMap["count"].toInt(); //qDebug() << "CHILDREN SIZE:" << size; + if (paramToItemMap.contains(parameterName)) + { + //slider->setParameterValue(uas,component,0,-1,paramname,value); + //paramToItemMap[parameterName]->set + return; + } for (int j = 0; j < size; j++) { @@ -220,6 +226,7 @@ void QGCToolWidget::setParameterValue(int uas, int component, QString parameterN if (checkparam == parameterName) { item = new QGCParamSlider(this); + paramToItemMap[parameterName] = item; addToolWidget(item); item->readSettings(widgetName + "\\" + QString::number(j) + "\\",settingsMap); @@ -236,6 +243,7 @@ void QGCToolWidget::setParameterValue(int uas, int component, QString parameterN item = new QGCComboBox(this); addToolWidget(item); item->readSettings(widgetName + "\\" + QString::number(j) + "\\",settingsMap); + paramToItemMap[parameterName] = item; return; } @@ -501,6 +509,22 @@ QList* QGCToolWidget::itemList() if (!instances) instances = new QList(); return instances; } +void QGCToolWidget::addParam(int uas,int component,QString paramname,QVariant value) +{ + QGCParamSlider* slider = new QGCParamSlider(this); + connect(slider, SIGNAL(destroyed()), this, SLOT(storeSettings())); + if (ui->hintLabel) + { + ui->hintLabel->deleteLater(); + ui->hintLabel = NULL; + } + toolLayout->addWidget(slider); + slider->setActiveUAS(mav); + slider->setParamMinMax(0,100); + slider->setParameterValue(uas,component,0,-1,paramname,value); + + +} void QGCToolWidget::addParam() { diff --git a/src/ui/designer/QGCToolWidget.h b/src/ui/designer/QGCToolWidget.h index ef8fb922ffa10b892e4721f6c63cc274fe7bab80..ab07c8ba4d873252aded2fb22fc2ea5dcaa4e916 100644 --- a/src/ui/designer/QGCToolWidget.h +++ b/src/ui/designer/QGCToolWidget.h @@ -65,6 +65,7 @@ signals: void titleChanged(QString); protected: + QMap paramToItemMap; QList paramList; QVariantMap settingsMap; QAction* addParamAction; @@ -90,6 +91,7 @@ protected: void hideEvent(QHideEvent* event); public slots: void setTitle(QString title); + void addParam(int uas,int component,QString paramname,QVariant value); protected slots: void addParam(); void addCommand();