Commit 7888bdb9 authored by Michael Carpenter's avatar Michael Carpenter

Addition of advanced parameters, for anything not defined in the .xml file

Configuration parameters are now split into two categories, General and
Advanced, where General parameters are anything defined in the
configuration file and Advanced are anything not defined in the
configuration file, but the autopilot still returns when requesting a
parameter list.
parent ef37f508
......@@ -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;i<toolWidgets.size();i++)
{
if (parameterName.startsWith(toolWidgets[i]->objectName()))
{
//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
......
......@@ -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
......
......@@ -886,7 +886,7 @@ p, li { white-space: pre-wrap; }
</widget>
<widget class="QWidget" name="fixedWingTab">
<attribute name="title">
<string>Hardware Specific Config</string>
<string>Advanced Config</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
......
......@@ -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)
{
......
......@@ -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();
......
......@@ -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<QGCToolWidgetItem*>* QGCToolWidget::itemList()
if (!instances) instances = new QList<QGCToolWidgetItem*>();
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()
{
......
......@@ -65,6 +65,7 @@ signals:
void titleChanged(QString);
protected:
QMap<QString,QGCToolWidgetItem*> paramToItemMap;
QList<QString> 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();
......
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