mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-02 10:24:11 +01:00
OP-984 Added backing store for values when switching between uavos.
This commit is contained in:
parent
a3c03b0244
commit
088197ac69
@ -41,19 +41,25 @@
|
|||||||
#include <extensionsystem/pluginmanager.h>
|
#include <extensionsystem/pluginmanager.h>
|
||||||
#include <coreplugin/generalsettings.h>
|
#include <coreplugin/generalsettings.h>
|
||||||
#include "altitudeholdsettings.h"
|
#include "altitudeholdsettings.h"
|
||||||
|
#include "stabilizationsettings.h"
|
||||||
|
|
||||||
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent),
|
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent),
|
||||||
boardModel(0), m_currentPIDBank(0)
|
boardModel(0), m_pidBankCount(0), m_currentPIDBank(0)
|
||||||
{
|
{
|
||||||
ui = new Ui_StabilizationWidget();
|
ui = new Ui_StabilizationWidget();
|
||||||
ui->setupUi(this);
|
ui->setupUi(this);
|
||||||
|
|
||||||
|
StabilizationSettings* stabSettings = qobject_cast<StabilizationSettings*>(getObject("StabilizationSettings"));
|
||||||
|
Q_ASSERT(stabSettings);
|
||||||
|
|
||||||
|
m_pidBankCount = stabSettings->getField("FlightModeMap")->getOptions().count();
|
||||||
|
|
||||||
// Set up fake tab widget stuff for pid banks support
|
// Set up fake tab widget stuff for pid banks support
|
||||||
m_pidTabBars.append(ui->basicPIDBankTabBar);
|
m_pidTabBars.append(ui->basicPIDBankTabBar);
|
||||||
m_pidTabBars.append(ui->advancedPIDBankTabBar);
|
m_pidTabBars.append(ui->advancedPIDBankTabBar);
|
||||||
m_pidTabBars.append(ui->expertPIDBankTabBar);
|
m_pidTabBars.append(ui->expertPIDBankTabBar);
|
||||||
foreach(QTabBar * tabBar, m_pidTabBars) {
|
foreach(QTabBar * tabBar, m_pidTabBars) {
|
||||||
for (int i = 0; i < PID_BANKS; i++) {
|
for (int i = 0; i < m_pidBankCount; i++) {
|
||||||
tabBar->addTab(tr("PID Bank %1").arg(i + 1));
|
tabBar->addTab(tr("PID Bank %1").arg(i + 1));
|
||||||
tabBar->setTabData(i, QString("StabilizationSettingsBank%1").arg(i + 1));
|
tabBar->setTabData(i, QString("StabilizationSettingsBank%1").arg(i + 1));
|
||||||
}
|
}
|
||||||
@ -61,7 +67,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
|||||||
connect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int)));
|
connect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int)));
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int i = 0; i < PID_BANKS; i++) {
|
for (int i = 0; i < m_pidBankCount; i++) {
|
||||||
if(i > 0) {
|
if(i > 0) {
|
||||||
m_stabilizationObjectsString.append(",");
|
m_stabilizationObjectsString.append(",");
|
||||||
}
|
}
|
||||||
|
@ -54,8 +54,7 @@ private:
|
|||||||
// Milliseconds between automatic 'Instant Updates'
|
// Milliseconds between automatic 'Instant Updates'
|
||||||
static const int AUTOMATIC_UPDATE_RATE = 500;
|
static const int AUTOMATIC_UPDATE_RATE = 500;
|
||||||
|
|
||||||
static const int PID_BANKS = 3;
|
int m_pidBankCount;
|
||||||
|
|
||||||
int boardModel;
|
int boardModel;
|
||||||
int m_currentPIDBank;
|
int m_currentPIDBank;
|
||||||
protected:
|
protected:
|
||||||
|
@ -129,7 +129,6 @@ HEADERS += mainwindow.h \
|
|||||||
uavgadgetdecorator.h \
|
uavgadgetdecorator.h \
|
||||||
workspacesettings.h \
|
workspacesettings.h \
|
||||||
uavconfiginfo.h \
|
uavconfiginfo.h \
|
||||||
authorsdialog.h \
|
|
||||||
iconfigurableplugin.h \
|
iconfigurableplugin.h \
|
||||||
aboutdialog.h
|
aboutdialog.h
|
||||||
|
|
||||||
|
@ -278,7 +278,7 @@ void ConfigTaskWidget::onAutopilotConnect()
|
|||||||
|
|
||||||
void ConfigTaskWidget::populateWidgets()
|
void ConfigTaskWidget::populateWidgets()
|
||||||
{
|
{
|
||||||
bool dirtyBack = m_isDirty;
|
bool dirtyBack = isDirty();
|
||||||
emit populateWidgetsRequested();
|
emit populateWidgetsRequested();
|
||||||
|
|
||||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||||
@ -295,7 +295,7 @@ void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool dirtyBack = m_isDirty;
|
bool dirtyBack = isDirty();
|
||||||
emit refreshWidgetsValuesRequested();
|
emit refreshWidgetsValuesRequested();
|
||||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject.values(obj)) {
|
foreach(WidgetBinding * binding, m_widgetBindingsPerObject.values(obj)) {
|
||||||
if (binding->isEnabled() && binding->field() != NULL && binding->widget() != NULL) {
|
if (binding->isEnabled() && binding->field() != NULL && binding->widget() != NULL) {
|
||||||
@ -310,8 +310,9 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
|
|||||||
emit updateObjectsFromWidgetsRequested();
|
emit updateObjectsFromWidgetsRequested();
|
||||||
|
|
||||||
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
|
||||||
if (binding->isEnabled() && binding->object() != NULL && binding->field() != NULL) {
|
if (binding->object() != NULL && binding->field() != NULL) {
|
||||||
setFieldFromWidget(binding->widget(), binding->field(), binding->index(), binding->scale());
|
binding->updateObjectFieldFromValue();
|
||||||
|
//setFieldFromWidget(binding->widget(), binding->field(), binding->index(), binding->scale());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -399,6 +400,7 @@ void ConfigTaskWidget::widgetsContentsChanged()
|
|||||||
QWidget *emitter = ((QWidget *)sender());
|
QWidget *emitter = ((QWidget *)sender());
|
||||||
emit widgetContentsChanged(emitter);
|
emit widgetContentsChanged(emitter);
|
||||||
double scale;
|
double scale;
|
||||||
|
QVariant value;
|
||||||
foreach(WidgetBinding *binding ,m_widgetBindingsPerWidget.values(emitter)) {
|
foreach(WidgetBinding *binding ,m_widgetBindingsPerWidget.values(emitter)) {
|
||||||
|
|
||||||
if (binding && binding->isEnabled()) {
|
if (binding && binding->isEnabled()) {
|
||||||
@ -415,12 +417,15 @@ void ConfigTaskWidget::widgetsContentsChanged()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
value = getVariantFromWidget(emitter, scale, binding->units());
|
||||||
|
binding->setValue(value);
|
||||||
|
|
||||||
if (binding->widget() != emitter) {
|
if (binding->widget() != emitter) {
|
||||||
disconnectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
|
disconnectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
|
||||||
|
|
||||||
checkWidgetsLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(),
|
checkWidgetsLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(),
|
||||||
getVariantFromWidget(emitter, scale, binding->units()), binding->scale());
|
value, binding->scale());
|
||||||
setWidgetFromVariant(binding->widget(), getVariantFromWidget(emitter, scale, binding->units()), binding->scale());
|
setWidgetFromVariant(binding->widget(), value, binding->scale());
|
||||||
emit widgetContentsChanged(binding->widget());
|
emit widgetContentsChanged(binding->widget());
|
||||||
|
|
||||||
connectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
|
connectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
|
||||||
@ -430,8 +435,8 @@ void ConfigTaskWidget::widgetsContentsChanged()
|
|||||||
disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
||||||
|
|
||||||
checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(),
|
checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(),
|
||||||
getVariantFromWidget(emitter, scale, binding->units()), shadow->scale());
|
value, shadow->scale());
|
||||||
setWidgetFromVariant(shadow->widget(), getVariantFromWidget(emitter, scale, binding->units()), shadow->scale());
|
setWidgetFromVariant(shadow->widget(), value, shadow->scale());
|
||||||
emit widgetContentsChanged(shadow->widget());
|
emit widgetContentsChanged(shadow->widget());
|
||||||
|
|
||||||
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
|
||||||
@ -828,22 +833,6 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ConfigTaskWidget::setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale)
|
|
||||||
{
|
|
||||||
if (!widget || !field) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
QVariant ret = getVariantFromWidget(widget, scale, field->getUnits());
|
|
||||||
if (ret.isValid()) {
|
|
||||||
field->setValue(ret, index);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
{
|
|
||||||
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units)
|
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units)
|
||||||
{
|
{
|
||||||
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
|
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
|
||||||
@ -1139,6 +1128,7 @@ bool WidgetBinding::matches(QString objectName, QString fieldName, int index, qu
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool WidgetBinding::isEnabled() const
|
bool WidgetBinding::isEnabled() const
|
||||||
{
|
{
|
||||||
return m_isEnabled;
|
return m_isEnabled;
|
||||||
@ -1149,6 +1139,25 @@ void WidgetBinding::setIsEnabled(bool isEnabled)
|
|||||||
m_isEnabled = isEnabled;
|
m_isEnabled = isEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
QVariant WidgetBinding::value() const
|
||||||
|
{
|
||||||
|
return m_value;
|
||||||
|
}
|
||||||
|
|
||||||
|
void WidgetBinding::setValue(const QVariant &value)
|
||||||
|
{
|
||||||
|
m_value = value;
|
||||||
|
if(m_object && m_field) {
|
||||||
|
qDebug() << "WidgetBinding" << m_object->getName() << ":" << m_field->getName() << "value =" << value.toString();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void WidgetBinding::updateObjectFieldFromValue()
|
||||||
|
{
|
||||||
|
if (m_value.isValid()) {
|
||||||
|
m_field->setValue(m_value, m_index);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
ShadowWidgetBinding::ShadowWidgetBinding(QWidget *widget, double scale, bool isLimited)
|
ShadowWidgetBinding::ShadowWidgetBinding(QWidget *widget, double scale, bool isLimited)
|
||||||
{
|
{
|
||||||
|
@ -80,12 +80,18 @@ public:
|
|||||||
bool isEnabled() const;
|
bool isEnabled() const;
|
||||||
void setIsEnabled(bool isEnabled);
|
void setIsEnabled(bool isEnabled);
|
||||||
|
|
||||||
|
QVariant value() const;
|
||||||
|
void setValue(const QVariant &value);
|
||||||
|
|
||||||
|
void updateObjectFieldFromValue();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
UAVObject *m_object;
|
UAVObject *m_object;
|
||||||
UAVObjectField *m_field;
|
UAVObjectField *m_field;
|
||||||
int m_index;
|
int m_index;
|
||||||
bool m_isEnabled;
|
bool m_isEnabled;
|
||||||
QList<ShadowWidgetBinding *> m_shadows;
|
QList<ShadowWidgetBinding *> m_shadows;
|
||||||
|
QVariant m_value;
|
||||||
};
|
};
|
||||||
|
|
||||||
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget {
|
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget {
|
||||||
@ -214,7 +220,6 @@ private:
|
|||||||
QString m_outOfLimitsStyle;
|
QString m_outOfLimitsStyle;
|
||||||
QTimer *m_realtimeUpdateTimer;
|
QTimer *m_realtimeUpdateTimer;
|
||||||
|
|
||||||
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale);
|
|
||||||
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits);
|
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits);
|
||||||
|
|
||||||
QVariant getVariantFromWidget(QWidget *widget, double scale, const QString units);
|
QVariant getVariantFromWidget(QWidget *widget, double scale, const QString units);
|
||||||
@ -225,7 +230,6 @@ private:
|
|||||||
void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function);
|
void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function);
|
||||||
|
|
||||||
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale);
|
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale);
|
||||||
virtual UAVObject *getObject(const QString name, quint32 instId = 0);
|
|
||||||
|
|
||||||
int fieldIndexFromElementName(QString objectName, QString fieldName, QString elementName);
|
int fieldIndexFromElementName(QString objectName, QString fieldName, QString elementName);
|
||||||
|
|
||||||
@ -245,7 +249,7 @@ protected slots:
|
|||||||
protected:
|
protected:
|
||||||
virtual void enableControls(bool enable);
|
virtual void enableControls(bool enable);
|
||||||
virtual QString mapObjectName(const QString objectName);
|
virtual QString mapObjectName(const QString objectName);
|
||||||
|
virtual UAVObject *getObject(const QString name, quint32 instId = 0);
|
||||||
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale);
|
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale);
|
||||||
void updateEnableControls();
|
void updateEnableControls();
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user