Commit b42f062d authored by lm's avatar lm

Fixed dynamic param widget! Now ready to use!

parent 272965d8
...@@ -22,6 +22,9 @@ public: ...@@ -22,6 +22,9 @@ public:
/** @brief Request an update for this specific parameter */ /** @brief Request an update for this specific parameter */
void requestParameterUpdate(int component, const QString& parameter); void requestParameterUpdate(int component, const QString& parameter);
/** @brief Request list of parameters from MAV */
virtual void requestParameterList() = 0;
signals: signals:
void parameterChanged(int component, QString parameter, float value); void parameterChanged(int component, QString parameter, float value);
void parameterChanged(int component, int parameterIndex, float value); void parameterChanged(int component, int parameterIndex, float value);
......
...@@ -16,9 +16,18 @@ ...@@ -16,9 +16,18 @@
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout">
<item row="1" column="0" colspan="2"> <item row="1" column="0" colspan="2">
<widget class="QLabel" name="nameLabel"> <widget class="QLabel" name="nameLabel">
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="text"> <property name="text">
<string>Description</string> <string>Description</string>
</property> </property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget> </widget>
</item> </item>
<item row="2" column="0"> <item row="2" column="0">
...@@ -54,6 +63,12 @@ ...@@ -54,6 +63,12 @@
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QPushButton" name="actionButton"> <widget class="QPushButton" name="actionButton">
<property name="minimumSize">
<size>
<width>30</width>
<height>0</height>
</size>
</property>
<property name="text"> <property name="text">
<string>Button name</string> <string>Button name</string>
</property> </property>
......
...@@ -5,6 +5,7 @@ ...@@ -5,6 +5,7 @@
#include "QGCParamSlider.h" #include "QGCParamSlider.h"
#include "ui_QGCParamSlider.h" #include "ui_QGCParamSlider.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UASManager.h"
QGCParamSlider::QGCParamSlider(QWidget *parent) : QGCParamSlider::QGCParamSlider(QWidget *parent) :
...@@ -15,24 +16,37 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) : ...@@ -15,24 +16,37 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
parameterMin(0.0f), parameterMin(0.0f),
parameterMax(0.0f), parameterMax(0.0f),
component(0), component(0),
parameterIndex(-1),
ui(new Ui::QGCParamSlider) ui(new Ui::QGCParamSlider)
{ {
ui->setupUi(this); ui->setupUi(this);
uas = NULL;
scaledInt = ui->valueSlider->maximum() - ui->valueSlider->minimum(); scaledInt = ui->valueSlider->maximum() - ui->valueSlider->minimum();
ui->editDoneButton->show(); ui->editDoneButton->hide();
ui->editMaxLabel->show(); ui->editMaxLabel->hide();
ui->editMinLabel->show(); ui->editMinLabel->hide();
ui->editNameLabel->show(); ui->editNameLabel->hide();
ui->editInstructionsLabel->show(); ui->editInstructionsLabel->hide();
ui->editRefreshParamsButton->show(); ui->editRefreshParamsButton->hide();
ui->editSelectParamComboBox->show(); ui->editSelectParamComboBox->hide();
ui->editSelectComponentComboBox->show(); ui->editSelectComponentComboBox->hide();
ui->editStatusLabel->show(); ui->editStatusLabel->hide();
ui->editMinSpinBox->show(); ui->editMinSpinBox->hide();
ui->editMaxSpinBox->show(); ui->editMaxSpinBox->hide();
connect(ui->editDoneButton, SIGNAL(clicked()), this, SLOT(endEditMode())); connect(ui->editDoneButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
// Sending actions
connect(ui->writeButton, SIGNAL(clicked()), this, SLOT(sendParameter()));
connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectComponent(int)));
connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectParameter(int)));
connect(ui->valueSlider, SIGNAL(valueChanged(int)), this, SLOT(setSliderValue(int)));
connect(ui->editNameLabel, SIGNAL(textChanged(QString)), ui->nameLabel, SLOT(setText(QString)));
connect(ui->readButton, SIGNAL(clicked()), this, SLOT(requestParameter()));
// Set the current UAS if present
setActiveUAS(UASManager::instance()->getActiveUAS());
} }
QGCParamSlider::~QGCParamSlider() QGCParamSlider::~QGCParamSlider()
...@@ -40,6 +54,42 @@ QGCParamSlider::~QGCParamSlider() ...@@ -40,6 +54,42 @@ QGCParamSlider::~QGCParamSlider()
delete ui; delete ui;
} }
void QGCParamSlider::setActiveUAS(UASInterface* activeUas)
{
if (activeUas)
{
if (uas)
{
disconnect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,float)), this, SLOT(setParameterValue(int,int,int,int,QString,float)));
disconnect(ui->editRefreshParamsButton, SIGNAL(clicked()), uas->getParamManager(), SLOT(requestParameterList()));
}
// Connect buttons and signals
connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,float)), this, SLOT(setParameterValue(int,int,int,int,QString,float)), Qt::UniqueConnection);
connect(ui->editRefreshParamsButton, SIGNAL(clicked()), activeUas->getParamManager(), SLOT(requestParameterList()), Qt::UniqueConnection);
uas = activeUas;
}
}
void QGCParamSlider::requestParameter()
{
if (parameterIndex != -1)
{
uas->requestParameter(this->component, this->parameterIndex);
}
}
void QGCParamSlider::selectComponent(int componentIndex)
{
this->component = ui->editSelectComponentComboBox->itemData(componentIndex).toInt();
}
void QGCParamSlider::selectParameter(int paramIndex)
{
parameterName = ui->editSelectParamComboBox->itemText(paramIndex);
parameterIndex = ui->editSelectParamComboBox->itemData(paramIndex).toInt();
}
void QGCParamSlider::startEditMode() void QGCParamSlider::startEditMode()
{ {
ui->editDoneButton->show(); ui->editDoneButton->show();
...@@ -53,11 +103,23 @@ void QGCParamSlider::startEditMode() ...@@ -53,11 +103,23 @@ void QGCParamSlider::startEditMode()
ui->editStatusLabel->show(); ui->editStatusLabel->show();
ui->editMinSpinBox->show(); ui->editMinSpinBox->show();
ui->editMaxSpinBox->show(); ui->editMaxSpinBox->show();
ui->writeButton->hide();
ui->readButton->hide();
isInEditMode = true; isInEditMode = true;
} }
void QGCParamSlider::endEditMode() void QGCParamSlider::endEditMode()
{ {
// Store component id
selectComponent(ui->editSelectComponentComboBox->currentIndex());
// Store parameter name and id
selectParameter(ui->editSelectParamComboBox->currentIndex());
// Min/max
parameterMin = ui->editMinSpinBox->value();
parameterMax = ui->editMaxSpinBox->value();
ui->editDoneButton->hide(); ui->editDoneButton->hide();
ui->editMaxLabel->hide(); ui->editMaxLabel->hide();
ui->editMinLabel->hide(); ui->editMinLabel->hide();
...@@ -69,6 +131,8 @@ void QGCParamSlider::endEditMode() ...@@ -69,6 +131,8 @@ void QGCParamSlider::endEditMode()
ui->editStatusLabel->hide(); ui->editStatusLabel->hide();
ui->editMinSpinBox->hide(); ui->editMinSpinBox->hide();
ui->editMaxSpinBox->hide(); ui->editMaxSpinBox->hide();
ui->writeButton->show();
ui->readButton->show();
isInEditMode = false; isInEditMode = false;
emit editingFinished(); emit editingFinished();
} }
...@@ -77,6 +141,7 @@ void QGCParamSlider::sendParameter() ...@@ -77,6 +141,7 @@ void QGCParamSlider::sendParameter()
{ {
if (QGCToolWidgetItem::uas) if (QGCToolWidgetItem::uas)
{ {
qDebug() << "SENDING" << component << parameterName << parameterValue;
QGCToolWidgetItem::uas->setParameter(component, parameterName, parameterValue); QGCToolWidgetItem::uas->setParameter(component, parameterName, parameterValue);
} }
else else
...@@ -89,7 +154,7 @@ void QGCParamSlider::setSliderValue(int sliderValue) ...@@ -89,7 +154,7 @@ void QGCParamSlider::setSliderValue(int sliderValue)
{ {
parameterValue = scaledIntToFloat(sliderValue); parameterValue = scaledIntToFloat(sliderValue);
QString unit(""); QString unit("");
ui->valueLabel->setText(QString("%1 %2").arg(parameterValue, 0, 'f', 3).arg(unit)); ui->valueLabel->setText(QString("%1 %2").arg(parameterValue, 6, 'f', 6, ' ').arg(unit));
} }
/** /**
...@@ -98,8 +163,39 @@ void QGCParamSlider::setSliderValue(int sliderValue) ...@@ -98,8 +163,39 @@ void QGCParamSlider::setSliderValue(int sliderValue)
* @brief parameterName Key/name of the parameter * @brief parameterName Key/name of the parameter
* @brief value Value of the parameter * @brief value Value of the parameter
*/ */
void QGCParamSlider::setParameterValue(int uas, int component, QString parameterName, float value) void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, float value)
{ {
Q_UNUSED(paramCount);
// Check if this component and parameter are part of the list
bool found = false;
for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i)
{
if (component == ui->editSelectComponentComboBox->itemData(i).toInt())
{
found = true;
}
}
if (!found)
{
ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(component), component);
}
// Parameter checking
found = false;
for (int i = 0; i < ui->editSelectParamComboBox->count(); ++i)
{
if (parameterName == ui->editSelectParamComboBox->itemText(i))
{
found = true;
}
}
if (!found)
{
ui->editSelectParamComboBox->addItem(parameterName, paramIndex);
}
Q_UNUSED(uas); Q_UNUSED(uas);
if (component == this->component && parameterName == this->parameterName) if (component == this->component && parameterName == this->parameterName)
{ {
...@@ -124,12 +220,16 @@ void QGCParamSlider::changeEvent(QEvent *e) ...@@ -124,12 +220,16 @@ void QGCParamSlider::changeEvent(QEvent *e)
float QGCParamSlider::scaledIntToFloat(int sliderValue) float QGCParamSlider::scaledIntToFloat(int sliderValue)
{ {
return (((double)sliderValue)/scaledInt)*(parameterMax - parameterMin); float result = (((double)sliderValue)/(double)scaledInt)*(ui->editMaxSpinBox->value() - ui->editMinSpinBox->value());
qDebug() << "INT TO FLOAT: CONVERTED" << sliderValue << "TO" << result;
return result;
} }
int QGCParamSlider::floatToScaledInt(float value) int QGCParamSlider::floatToScaledInt(float value)
{ {
return ((value - parameterMin)/(parameterMax - parameterMin))*scaledInt; int result = ((value - ui->editMinSpinBox->value())/(ui->editMaxSpinBox->value() - ui->editMinSpinBox->value()))*scaledInt;
qDebug() << "FLOAT TO INT: CONVERTED" << value << "TO" << result << "SCALEDINT" << scaledInt;
return result;
} }
void QGCParamSlider::writeSettings(QSettings& settings) void QGCParamSlider::writeSettings(QSettings& settings)
...@@ -137,8 +237,9 @@ void QGCParamSlider::writeSettings(QSettings& settings) ...@@ -137,8 +237,9 @@ void QGCParamSlider::writeSettings(QSettings& settings)
settings.setValue("TYPE", "SLIDER"); settings.setValue("TYPE", "SLIDER");
settings.setValue("QGC_PARAM_SLIDER_DESCRIPTION", ui->nameLabel->text()); settings.setValue("QGC_PARAM_SLIDER_DESCRIPTION", ui->nameLabel->text());
//settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text()); //settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text());
settings.setValue("QGC_PARAM_SLIDER_PARAMID", ui->editSelectParamComboBox->currentText()); settings.setValue("QGC_PARAM_SLIDER_PARAMID", parameterName);
settings.setValue("QGC_PARAM_SLIDER_COMPONENTID", ui->editSelectComponentComboBox->currentText()); settings.setValue("QGC_PARAM_SLIDER_PARAMINDEX", parameterIndex);
settings.setValue("QGC_PARAM_SLIDER_COMPONENTID", component);
settings.setValue("QGC_PARAM_SLIDER_MIN", ui->editMinSpinBox->value()); settings.setValue("QGC_PARAM_SLIDER_MIN", ui->editMinSpinBox->value());
settings.setValue("QGC_PARAM_SLIDER_MAX", ui->editMaxSpinBox->value()); settings.setValue("QGC_PARAM_SLIDER_MAX", ui->editMaxSpinBox->value());
settings.sync(); settings.sync();
...@@ -147,9 +248,11 @@ void QGCParamSlider::writeSettings(QSettings& settings) ...@@ -147,9 +248,11 @@ void QGCParamSlider::writeSettings(QSettings& settings)
void QGCParamSlider::readSettings(const QSettings& settings) void QGCParamSlider::readSettings(const QSettings& settings)
{ {
ui->nameLabel->setText(settings.value("QGC_PARAM_SLIDER_DESCRIPTION").toString()); ui->nameLabel->setText(settings.value("QGC_PARAM_SLIDER_DESCRIPTION").toString());
ui->editNameLabel->setText(settings.value("QGC_PARAM_SLIDER_DESCRIPTION").toString());
//settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text()); //settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text());
ui->editSelectParamComboBox->setEditText(settings.value("QGC_PARAM_SLIDER_PARAMID").toString()); parameterIndex = settings.value("QGC_PARAM_SLIDER_PARAMINDEX", parameterIndex).toInt();
ui->editSelectComponentComboBox->setEditText(settings.value("QGC_PARAM_SLIDER_COMPONENTID").toString()); ui->editSelectParamComboBox->addItem(settings.value("QGC_PARAM_SLIDER_PARAMID").toString(), parameterIndex);
ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(settings.value("QGC_PARAM_SLIDER_COMPONENTID").toInt()), settings.value("QGC_PARAM_SLIDER_COMPONENTID").toInt());
ui->editMinSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MIN").toFloat()); ui->editMinSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MIN").toFloat());
ui->editMaxSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MAX").toFloat()); ui->editMaxSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MAX").toFloat());
qDebug() << "DONE READING SETTINGS"; qDebug() << "DONE READING SETTINGS";
......
...@@ -27,9 +27,16 @@ public slots: ...@@ -27,9 +27,16 @@ public slots:
/** @brief Set the slider value as parameter value */ /** @brief Set the slider value as parameter value */
void setSliderValue(int sliderValue); void setSliderValue(int sliderValue);
/** @brief Update the UI with the new parameter value */ /** @brief Update the UI with the new parameter value */
void setParameterValue(int uas, int component, QString parameterName, float value); void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, float value);
void writeSettings(QSettings& settings); void writeSettings(QSettings& settings);
void readSettings(const QSettings& settings); void readSettings(const QSettings& settings);
void setActiveUAS(UASInterface *uas);
void selectComponent(int componentIndex);
void selectParameter(int paramIndex);
protected slots:
/** @brief Request the parameter of this widget from the MAV */
void requestParameter();
protected: protected:
QString parameterName; ///< Key/Name of the parameter QString parameterName; ///< Key/Name of the parameter
...@@ -38,6 +45,7 @@ protected: ...@@ -38,6 +45,7 @@ protected:
float parameterMin; float parameterMin;
float parameterMax; float parameterMax;
int component; ///< ID of the MAV component to address int component; ///< ID of the MAV component to address
int parameterIndex;
double scaledInt; double scaledInt;
void changeEvent(QEvent *e); void changeEvent(QEvent *e);
......
...@@ -6,77 +6,103 @@ ...@@ -6,77 +6,103 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>499</width> <width>606</width>
<height>175</height> <height>179</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout" columnstretch="100,0,0,0,0,0,0,0,0,0">
<item row="1" column="0" colspan="4"> <item row="1" column="1" colspan="4">
<widget class="QLineEdit" name="editNameLabel"> <widget class="QLineEdit" name="editNameLabel">
<property name="text"> <property name="text">
<string>Informal Name..</string> <string>Informal Name..</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="4"> <item row="1" column="5">
<widget class="QLabel" name="editMinLabel"> <widget class="QLabel" name="editMinLabel">
<property name="text"> <property name="text">
<string>Min</string> <string>Min</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="6"> <item row="1" column="7">
<widget class="QLabel" name="editMaxLabel"> <widget class="QLabel" name="editMaxLabel">
<property name="text"> <property name="text">
<string>Max</string> <string>Max</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="0"> <item row="2" column="1">
<widget class="QLabel" name="nameLabel"> <widget class="QLabel" name="nameLabel">
<property name="text"> <property name="text">
<string>Name</string> <string>Name</string>
</property> </property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget> </widget>
</item> </item>
<item row="2" column="1"> <item row="2" column="2">
<widget class="QLabel" name="valueLabel"> <widget class="QLabel" name="valueLabel">
<property name="text"> <property name="text">
<string>0.00</string> <string>0.00</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="3" colspan="2"> <item row="2" column="4" colspan="2">
<widget class="QDoubleSpinBox" name="editMinSpinBox"/> <widget class="QDoubleSpinBox" name="editMinSpinBox">
<property name="minimum">
<double>-999999999.000000000000000</double>
</property>
<property name="maximum">
<double>999999999.000000000000000</double>
</property>
</widget>
</item> </item>
<item row="2" column="5"> <item row="2" column="6">
<widget class="QSlider" name="valueSlider"> <widget class="QSlider" name="valueSlider">
<property name="maximumSize">
<size>
<width>300</width>
<height>16777215</height>
</size>
</property>
<property name="maximum">
<number>1000000</number>
</property>
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="6"> <item row="2" column="7">
<widget class="QDoubleSpinBox" name="editMaxSpinBox"/> <widget class="QDoubleSpinBox" name="editMaxSpinBox">
<property name="minimum">
<double>-999999999.000000000000000</double>
</property>
<property name="maximum">
<double>999999999.000000000000000</double>
</property>
</widget>
</item> </item>
<item row="0" column="0" colspan="7"> <item row="0" column="1" colspan="7">
<widget class="QLabel" name="editInstructionsLabel"> <widget class="QLabel" name="editInstructionsLabel">
<property name="text"> <property name="text">
<string>Please configure the parameter slider now:</string> <string>Please configure the parameter slider now:</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="0" colspan="7"> <item row="5" column="1" colspan="7">
<widget class="QLabel" name="editStatusLabel"> <widget class="QLabel" name="editStatusLabel">
<property name="text"> <property name="text">
<string>Please click on refresh to update list..</string> <string>Please click first on refresh to update selection menus..</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="0" colspan="3"> <item row="3" column="1" colspan="3">
<widget class="QComboBox" name="editSelectComponentComboBox"> <widget class="QComboBox" name="editSelectComponentComboBox">
<property name="toolTip"> <property name="toolTip">
<string>Select component</string> <string>Select component</string>
...@@ -86,7 +112,7 @@ ...@@ -86,7 +112,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="4" colspan="3"> <item row="3" column="5" colspan="3">
<widget class="QComboBox" name="editSelectParamComboBox"> <widget class="QComboBox" name="editSelectParamComboBox">
<property name="toolTip"> <property name="toolTip">
<string>Select parameter</string> <string>Select parameter</string>
...@@ -94,14 +120,9 @@ ...@@ -94,14 +120,9 @@
<property name="statusTip"> <property name="statusTip">
<string>Select parameter</string> <string>Select parameter</string>
</property> </property>
<item>
<property name="text">
<string>Click on refresh..</string>
</property>
</item>
</widget> </widget>
</item> </item>
<item row="2" column="7"> <item row="2" column="8">
<widget class="QPushButton" name="writeButton"> <widget class="QPushButton" name="writeButton">
<property name="toolTip"> <property name="toolTip">
<string>Transmit the current slider value to the system</string> <string>Transmit the current slider value to the system</string>
...@@ -118,7 +139,7 @@ ...@@ -118,7 +139,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="8"> <item row="2" column="9">
<widget class="QPushButton" name="readButton"> <widget class="QPushButton" name="readButton">
<property name="toolTip"> <property name="toolTip">
<string>Read the current parameter value on the system</string> <string>Read the current parameter value on the system</string>
...@@ -131,7 +152,7 @@ ...@@ -131,7 +152,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="7" colspan="2"> <item row="3" column="8" colspan="2">
<widget class="QPushButton" name="editRefreshParamsButton"> <widget class="QPushButton" name="editRefreshParamsButton">
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
...@@ -141,13 +162,29 @@ ...@@ -141,13 +162,29 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="7" colspan="2"> <item row="5" column="8" colspan="2">
<widget class="QPushButton" name="editDoneButton"> <widget class="QPushButton" name="editDoneButton">
<property name="text"> <property name="text">
<string>Done</string> <string>Done</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="3">
<widget class="QDoubleSpinBox" name="valueSpinBox"/>
</item>
<item row="2" column="0">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</widget> </widget>
<resources> <resources>
......
...@@ -105,6 +105,11 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent) ...@@ -105,6 +105,11 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent)
item = new QGCActionButton(newWidgets.at(i)); item = new QGCActionButton(newWidgets.at(i));
qDebug() << "CREATED BUTTON"; qDebug() << "CREATED BUTTON";
} }
else if (type == "SLIDER")
{
item = new QGCParamSlider(newWidgets.at(i));
qDebug() << "CREATED PARAM SLIDER";
}
if (item) if (item)
{ {
......
...@@ -14,6 +14,9 @@ ...@@ -14,6 +14,9 @@
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QVBoxLayout" name="toolLayout"> <layout class="QVBoxLayout" name="toolLayout">
<property name="spacing">
<number>6</number>
</property>
<item> <item>
<widget class="QLabel" name="hintLabel"> <widget class="QLabel" name="hintLabel">
<property name="text"> <property name="text">
......
...@@ -22,7 +22,7 @@ public slots: ...@@ -22,7 +22,7 @@ public slots:
virtual void setComponent(int comp) {_component = comp;} virtual void setComponent(int comp) {_component = comp;}
virtual void writeSettings(QSettings& settings) = 0; virtual void writeSettings(QSettings& settings) = 0;
virtual void readSettings(const QSettings& settings) = 0; virtual void readSettings(const QSettings& settings) = 0;
void setActiveUAS(UASInterface *uas); virtual void setActiveUAS(UASInterface *uas);
signals: signals:
void editingFinished(); void editingFinished();
......
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