1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-03 11:24:10 +01:00

OP-984 Some refactoring to prepare for multi PID bank GUI support.

This commit is contained in:
Fredrik Arvidsson 2014-01-01 22:49:04 +01:00
parent 99d6c9e4bd
commit b244f8a3cd
12 changed files with 582 additions and 443 deletions

View File

@ -75,14 +75,14 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
break; break;
} }
addApplySaveButtons(m_telemetry->saveTelemetryToRAM, m_telemetry->saveTelemetryToSD); addApplySaveButtons(m_telemetry->saveTelemetryToRAM, m_telemetry->saveTelemetryToSD);
addUAVObjectToWidgetRelation("HwSettings", "CC_FlexiPort", m_telemetry->cbFlexi); addWidgetBinding("HwSettings", "CC_FlexiPort", m_telemetry->cbFlexi);
addUAVObjectToWidgetRelation("HwSettings", "CC_MainPort", m_telemetry->cbTele); addWidgetBinding("HwSettings", "CC_MainPort", m_telemetry->cbTele);
addUAVObjectToWidgetRelation("HwSettings", "CC_RcvrPort", m_telemetry->cbRcvr); addWidgetBinding("HwSettings", "CC_RcvrPort", m_telemetry->cbRcvr);
addUAVObjectToWidgetRelation("HwSettings", "USB_HIDPort", m_telemetry->cbUsbHid); addWidgetBinding("HwSettings", "USB_HIDPort", m_telemetry->cbUsbHid);
addUAVObjectToWidgetRelation("HwSettings", "USB_VCPPort", m_telemetry->cbUsbVcp); addWidgetBinding("HwSettings", "USB_VCPPort", m_telemetry->cbUsbVcp);
addUAVObjectToWidgetRelation("HwSettings", "TelemetrySpeed", m_telemetry->telemetrySpeed); addWidgetBinding("HwSettings", "TelemetrySpeed", m_telemetry->telemetrySpeed);
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed); addWidgetBinding("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed);
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed); addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
enableSaveButtons(false); enableSaveButtons(false);
populateWidgets(); populateWidgets();

View File

@ -58,12 +58,12 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
// Connect the help button // Connect the help button
connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
addUAVObjectToWidgetRelation("AttitudeSettings", "ZeroDuringArming", ui->zeroGyroBiasOnArming); addWidgetBinding("AttitudeSettings", "ZeroDuringArming", ui->zeroGyroBiasOnArming);
addUAVObjectToWidgetRelation("AttitudeSettings", "AccelTau", ui->accelTauSpinbox); addWidgetBinding("AttitudeSettings", "AccelTau", ui->accelTauSpinbox);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", ui->rollBias, AttitudeSettings::BOARDROTATION_ROLL); addWidgetBinding("AttitudeSettings", "BoardRotation", ui->rollBias, AttitudeSettings::BOARDROTATION_ROLL);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH); addWidgetBinding("AttitudeSettings", "BoardRotation", ui->pitchBias, AttitudeSettings::BOARDROTATION_PITCH);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW); addWidgetBinding("AttitudeSettings", "BoardRotation", ui->yawBias, AttitudeSettings::BOARDROTATION_YAW);
addWidget(ui->zeroBias); addWidget(ui->zeroBias);
refreshWidgetsValues(); refreshWidgetsValues();
} }

View File

@ -84,11 +84,11 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
inputChannelForm *inpForm = new inputChannelForm(this, index == 0); inputChannelForm *inpForm = new inputChannelForm(this, index == 0);
ui->channelSettings->layout()->addWidget(inpForm); // Add the row to the UI ui->channelSettings->layout()->addWidget(inpForm); // Add the row to the UI
inpForm->setName(name); inpForm->setName(name);
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index); addWidgetBinding("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index);
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumber, index); addWidgetBinding("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumber, index);
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index); addWidgetBinding("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index);
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index); addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index);
addUAVObjectToWidgetRelation("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index); addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index);
addWidget(inpForm->ui->channelNumberDropdown); addWidget(inpForm->ui->channelNumberDropdown);
addWidget(inpForm->ui->channelRev); addWidget(inpForm->ui->channelRev);
addWidget(inpForm->ui->channelResponseTime); addWidget(inpForm->ui->channelResponseTime);
@ -101,7 +101,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
case ManualControlSettings::CHANNELGROUPS_ACCESSORY0: case ManualControlSettings::CHANNELGROUPS_ACCESSORY0:
case ManualControlSettings::CHANNELGROUPS_ACCESSORY1: case ManualControlSettings::CHANNELGROUPS_ACCESSORY1:
case ManualControlSettings::CHANNELGROUPS_ACCESSORY2: case ManualControlSettings::CHANNELGROUPS_ACCESSORY2:
addUAVObjectToWidgetRelation("ManualControlSettings", "ResponseTime", inpForm->ui->channelResponseTime, indexRT); addWidgetBinding("ManualControlSettings", "ResponseTime", inpForm->ui->channelResponseTime, indexRT);
++indexRT; ++indexRT;
break; break;
case ManualControlSettings::CHANNELGROUPS_THROTTLE: case ManualControlSettings::CHANNELGROUPS_THROTTLE:
@ -117,7 +117,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
++index; ++index;
} }
addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", ui->deadband, 0, 0.01f); addWidgetBinding("ManualControlSettings", "Deadband", ui->deadband, 0, 0.01f);
connect(ui->configurationWizard, SIGNAL(clicked()), this, SLOT(goToWizard())); connect(ui->configurationWizard, SIGNAL(clicked()), this, SLOT(goToWizard()));
connect(ui->stackedWidget, SIGNAL(currentChanged(int)), this, SLOT(disableWizardButton(int))); connect(ui->stackedWidget, SIGNAL(currentChanged(int)), this, SLOT(disableWizardButton(int)));
@ -128,30 +128,30 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
connect(ui->wzBack, SIGNAL(clicked()), this, SLOT(wzBack())); connect(ui->wzBack, SIGNAL(clicked()), this, SLOT(wzBack()));
ui->stackedWidget->setCurrentIndex(0); ui->stackedWidget->setCurrentIndex(0);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true); addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true); addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true); addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true); addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true); addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true); addWidgetBinding("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum); addWidgetBinding("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true); addWidgetBinding("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
addUAVObjectToWidgetRelation("StabilizationSettings", "FlightModeMap", ui->pidBankSs1, "Stabilized1", 1, true); addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs1, "Stabilized1", 1, true);
addUAVObjectToWidgetRelation("StabilizationSettings", "FlightModeMap", ui->pidBankSs2, "Stabilized2", 1, true); addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs2, "Stabilized2", 1, true);
addUAVObjectToWidgetRelation("StabilizationSettings", "FlightModeMap", ui->pidBankSs3, "Stabilized3", 1, true); addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs3, "Stabilized3", 1, true);
addUAVObjectToWidgetRelation("ManualControlSettings", "Arming", ui->armControl); addWidgetBinding("ManualControlSettings", "Arming", ui->armControl);
addUAVObjectToWidgetRelation("ManualControlSettings", "ArmedTimeout", ui->armTimeout, 0, 1000); addWidgetBinding("ManualControlSettings", "ArmedTimeout", ui->armTimeout, 0, 1000);
connect(ManualControlCommand::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveFMSlider())); connect(ManualControlCommand::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveFMSlider()));
connect(ManualControlSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updatePositionSlider())); connect(ManualControlSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updatePositionSlider()));

View File

@ -60,39 +60,39 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
} }
addApplySaveButtons(m_oplink->Apply, m_oplink->Save); addApplySaveButtons(m_oplink->Apply, m_oplink->Save);
addUAVObjectToWidgetRelation("OPLinkSettings", "MainPort", m_oplink->MainPort); addWidgetBinding("OPLinkSettings", "MainPort", m_oplink->MainPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort); addWidgetBinding("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "VCPPort", m_oplink->VCPPort); addWidgetBinding("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed); addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower); addWidgetBinding("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
addUAVObjectToWidgetRelation("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel); addWidgetBinding("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel); addWidgetBinding("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
addUAVObjectToWidgetRelation("OPLinkSettings", "ChannelSet", m_oplink->ChannelSet); addWidgetBinding("OPLinkSettings", "ChannelSet", m_oplink->ChannelSet);
addUAVObjectToWidgetRelation("OPLinkSettings", "CoordID", m_oplink->CoordID); addWidgetBinding("OPLinkSettings", "CoordID", m_oplink->CoordID);
addUAVObjectToWidgetRelation("OPLinkSettings", "Coordinator", m_oplink->Coordinator); addWidgetBinding("OPLinkSettings", "Coordinator", m_oplink->Coordinator);
addUAVObjectToWidgetRelation("OPLinkSettings", "OneWay", m_oplink->OneWayLink); addWidgetBinding("OPLinkSettings", "OneWay", m_oplink->OneWayLink);
addUAVObjectToWidgetRelation("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly); addWidgetBinding("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly);
addUAVObjectToWidgetRelation("OPLinkSettings", "PPM", m_oplink->PPM); addWidgetBinding("OPLinkSettings", "PPM", m_oplink->PPM);
addUAVObjectToWidgetRelation("OPLinkStatus", "DeviceID", m_oplink->DeviceID); addWidgetBinding("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxGood", m_oplink->Good); addWidgetBinding("OPLinkStatus", "RxGood", m_oplink->Good);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxCorrected", m_oplink->Corrected); addWidgetBinding("OPLinkStatus", "RxCorrected", m_oplink->Corrected);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxErrors", m_oplink->Errors); addWidgetBinding("OPLinkStatus", "RxErrors", m_oplink->Errors);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxMissed", m_oplink->Missed); addWidgetBinding("OPLinkStatus", "RxMissed", m_oplink->Missed);
addUAVObjectToWidgetRelation("OPLinkStatus", "RxFailure", m_oplink->RxFailure); addWidgetBinding("OPLinkStatus", "RxFailure", m_oplink->RxFailure);
addUAVObjectToWidgetRelation("OPLinkStatus", "UAVTalkErrors", m_oplink->UAVTalkErrors); addWidgetBinding("OPLinkStatus", "UAVTalkErrors", m_oplink->UAVTalkErrors);
addUAVObjectToWidgetRelation("OPLinkStatus", "TxDropped", m_oplink->Dropped); addWidgetBinding("OPLinkStatus", "TxDropped", m_oplink->Dropped);
addUAVObjectToWidgetRelation("OPLinkStatus", "TxResent", m_oplink->Resent); addWidgetBinding("OPLinkStatus", "TxResent", m_oplink->Resent);
addUAVObjectToWidgetRelation("OPLinkStatus", "TxFailure", m_oplink->TxFailure); addWidgetBinding("OPLinkStatus", "TxFailure", m_oplink->TxFailure);
addUAVObjectToWidgetRelation("OPLinkStatus", "Resets", m_oplink->Resets); addWidgetBinding("OPLinkStatus", "Resets", m_oplink->Resets);
addUAVObjectToWidgetRelation("OPLinkStatus", "Timeouts", m_oplink->Timeouts); addWidgetBinding("OPLinkStatus", "Timeouts", m_oplink->Timeouts);
addUAVObjectToWidgetRelation("OPLinkStatus", "RSSI", m_oplink->RSSI); addWidgetBinding("OPLinkStatus", "RSSI", m_oplink->RSSI);
addUAVObjectToWidgetRelation("OPLinkStatus", "HeapRemaining", m_oplink->FreeHeap); addWidgetBinding("OPLinkStatus", "HeapRemaining", m_oplink->FreeHeap);
addUAVObjectToWidgetRelation("OPLinkStatus", "LinkQuality", m_oplink->LinkQuality); addWidgetBinding("OPLinkStatus", "LinkQuality", m_oplink->LinkQuality);
addUAVObjectToWidgetRelation("OPLinkStatus", "RXSeq", m_oplink->RXSeq); addWidgetBinding("OPLinkStatus", "RXSeq", m_oplink->RXSeq);
addUAVObjectToWidgetRelation("OPLinkStatus", "TXSeq", m_oplink->TXSeq); addWidgetBinding("OPLinkStatus", "TXSeq", m_oplink->TXSeq);
addUAVObjectToWidgetRelation("OPLinkStatus", "RXRate", m_oplink->RXRate); addWidgetBinding("OPLinkStatus", "RXRate", m_oplink->RXRate);
addUAVObjectToWidgetRelation("OPLinkStatus", "TXRate", m_oplink->TXRate); addWidgetBinding("OPLinkStatus", "TXRate", m_oplink->TXRate);
// Connect the bind buttons // Connect the bind buttons
connect(m_oplink->Bind1, SIGNAL(clicked()), this, SLOT(bind1())); connect(m_oplink->Bind1, SIGNAL(clicked()), this, SLOT(bind1()));

View File

@ -49,21 +49,21 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD); addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
addUAVObjectToWidgetRelation("HwSettings", "RM_FlexiPort", m_ui->cbFlexi); addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
addUAVObjectToWidgetRelation("HwSettings", "RM_MainPort", m_ui->cbMain); addWidgetBinding("HwSettings", "RM_MainPort", m_ui->cbMain);
addUAVObjectToWidgetRelation("HwSettings", "RM_RcvrPort", m_ui->cbRcvr); addWidgetBinding("HwSettings", "RM_RcvrPort", m_ui->cbRcvr);
addUAVObjectToWidgetRelation("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction); addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
addUAVObjectToWidgetRelation("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction); addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed); addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
addUAVObjectToWidgetRelation("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed); addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed); addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed); addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
addUAVObjectToWidgetRelation("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed); addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed); addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed); addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp())); connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));

View File

@ -226,12 +226,12 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation())); connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation()));
addUAVObjectToWidgetRelation("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm); addWidgetBinding("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL); addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH); addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH);
addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW); addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW);
addUAVObjectToWidgetRelation("AttitudeSettings", "AccelTau", m_ui->accelTau); addWidgetBinding("AttitudeSettings", "AccelTau", m_ui->accelTau);
populateWidgets(); populateWidgets();
refreshWidgetsValues(); refreshWidgetsValues();

View File

@ -51,28 +51,28 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
connect(m_txpid->Apply, SIGNAL(clicked()), this, SLOT(applySettings())); connect(m_txpid->Apply, SIGNAL(clicked()), this, SLOT(applySettings()));
connect(m_txpid->Save, SIGNAL(clicked()), this, SLOT(saveSettings())); connect(m_txpid->Save, SIGNAL(clicked()), this, SLOT(saveSettings()));
addUAVObjectToWidgetRelation("TxPIDSettings", "BankNumber", m_txpid->pidBank, 0, 1, true); addWidgetBinding("TxPIDSettings", "BankNumber", m_txpid->pidBank, 0, 1, true);
addUAVObjectToWidgetRelation("TxPIDSettings", "PIDs", m_txpid->PID1, TxPIDSettings::PIDS_INSTANCE1); addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID1, TxPIDSettings::PIDS_INSTANCE1);
addUAVObjectToWidgetRelation("TxPIDSettings", "PIDs", m_txpid->PID2, TxPIDSettings::PIDS_INSTANCE2); addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID2, TxPIDSettings::PIDS_INSTANCE2);
addUAVObjectToWidgetRelation("TxPIDSettings", "PIDs", m_txpid->PID3, TxPIDSettings::PIDS_INSTANCE3); addWidgetBinding("TxPIDSettings", "PIDs", m_txpid->PID3, TxPIDSettings::PIDS_INSTANCE3);
addUAVObjectToWidgetRelation("TxPIDSettings", "Inputs", m_txpid->Input1, TxPIDSettings::INPUTS_INSTANCE1); addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input1, TxPIDSettings::INPUTS_INSTANCE1);
addUAVObjectToWidgetRelation("TxPIDSettings", "Inputs", m_txpid->Input2, TxPIDSettings::INPUTS_INSTANCE2); addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input2, TxPIDSettings::INPUTS_INSTANCE2);
addUAVObjectToWidgetRelation("TxPIDSettings", "Inputs", m_txpid->Input3, TxPIDSettings::INPUTS_INSTANCE3); addWidgetBinding("TxPIDSettings", "Inputs", m_txpid->Input3, TxPIDSettings::INPUTS_INSTANCE3);
addUAVObjectToWidgetRelation("TxPIDSettings", "MinPID", m_txpid->MinPID1, TxPIDSettings::MINPID_INSTANCE1); addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID1, TxPIDSettings::MINPID_INSTANCE1);
addUAVObjectToWidgetRelation("TxPIDSettings", "MinPID", m_txpid->MinPID2, TxPIDSettings::MINPID_INSTANCE2); addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID2, TxPIDSettings::MINPID_INSTANCE2);
addUAVObjectToWidgetRelation("TxPIDSettings", "MinPID", m_txpid->MinPID3, TxPIDSettings::MINPID_INSTANCE3); addWidgetBinding("TxPIDSettings", "MinPID", m_txpid->MinPID3, TxPIDSettings::MINPID_INSTANCE3);
addUAVObjectToWidgetRelation("TxPIDSettings", "MaxPID", m_txpid->MaxPID1, TxPIDSettings::MAXPID_INSTANCE1); addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID1, TxPIDSettings::MAXPID_INSTANCE1);
addUAVObjectToWidgetRelation("TxPIDSettings", "MaxPID", m_txpid->MaxPID2, TxPIDSettings::MAXPID_INSTANCE2); addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID2, TxPIDSettings::MAXPID_INSTANCE2);
addUAVObjectToWidgetRelation("TxPIDSettings", "MaxPID", m_txpid->MaxPID3, TxPIDSettings::MAXPID_INSTANCE3); addWidgetBinding("TxPIDSettings", "MaxPID", m_txpid->MaxPID3, TxPIDSettings::MAXPID_INSTANCE3);
addUAVObjectToWidgetRelation("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMin, TxPIDSettings::THROTTLERANGE_MIN); addWidgetBinding("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMin, TxPIDSettings::THROTTLERANGE_MIN);
addUAVObjectToWidgetRelation("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMax, TxPIDSettings::THROTTLERANGE_MAX); addWidgetBinding("TxPIDSettings", "ThrottleRange", m_txpid->ThrottleMax, TxPIDSettings::THROTTLERANGE_MAX);
addUAVObjectToWidgetRelation("TxPIDSettings", "UpdateMode", m_txpid->UpdateMode); addWidgetBinding("TxPIDSettings", "UpdateMode", m_txpid->UpdateMode);
addWidget(m_txpid->TxPIDEnable); addWidget(m_txpid->TxPIDEnable);

View File

@ -627,7 +627,7 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>778</width> <width>796</width>
<height>659</height> <height>659</height>
</rect> </rect>
</property> </property>
@ -8752,6 +8752,35 @@ border-radius: 5;</string>
</item> </item>
</layout> </layout>
</item> </item>
<item>
<widget class="QTabWidget" name="tabWidget_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>22</height>
</size>
</property>
<property name="currentIndex">
<number>0</number>
</property>
<widget class="QWidget" name="tab">
<attribute name="title">
<string>Tab 1</string>
</attribute>
</widget>
<widget class="QWidget" name="tab_2">
<attribute name="title">
<string>Tab 2</string>
</attribute>
</widget>
</widget>
</item>
<item> <item>
<spacer name="verticalSpacer"> <spacer name="verticalSpacer">
<property name="orientation"> <property name="orientation">
@ -8867,9 +8896,9 @@ border-radius: 5;</string>
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>0</x> <x>0</x>
<y>-117</y> <y>0</y>
<width>778</width> <width>779</width>
<height>762</height> <height>684</height>
</rect> </rect>
</property> </property>
<property name="autoFillBackground"> <property name="autoFillBackground">
@ -18908,8 +18937,8 @@ border-radius: 5;</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>792</width> <width>796</width>
<height>645</height> <height>659</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_9"> <layout class="QVBoxLayout" name="verticalLayout_9">
@ -27021,8 +27050,8 @@ border-radius: 5;</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>792</width> <width>796</width>
<height>645</height> <height>659</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout_23"> <layout class="QGridLayout" name="gridLayout_23">

View File

@ -32,17 +32,17 @@
/** /**
* Constructor * Constructor
*/ */
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), isConnected(false), allowWidgetUpdates(true), smartsave(NULL), dirty(false), outOfLimitsStyle("background-color: rgb(255, 0, 0);"), timeOut(NULL) ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), m_isConnected(false), m_isWidgetUpdatesAllowed(true),
m_saveButton(NULL), m_isDirty(false), m_outOfLimitsStyle("background-color: rgb(255, 0, 0);"), m_realtimeUpdateTimer(NULL)
{ {
pm = ExtensionSystem::PluginManager::instance(); m_pluginManager = ExtensionSystem::PluginManager::instance();
objManager = pm->getObject<UAVObjectManager>(); TelemetryManager *telMngr = m_pluginManager->getObject<TelemetryManager>();
TelemetryManager *telMngr = pm->getObject<TelemetryManager>(); m_objectUtilManager = m_pluginManager->getObject<UAVObjectUtilManager>();
utilMngr = pm->getObject<UAVObjectUtilManager>();
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()), Qt::UniqueConnection); connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()), Qt::UniqueConnection);
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()), Qt::UniqueConnection); connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()), Qt::UniqueConnection);
connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected()), Qt::UniqueConnection); connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected()), Qt::UniqueConnection);
connect(telMngr, SIGNAL(disconnected()), this, SIGNAL(autoPilotDisconnected()), Qt::UniqueConnection); connect(telMngr, SIGNAL(disconnected()), this, SIGNAL(autoPilotDisconnected()), Qt::UniqueConnection);
UAVSettingsImportExportFactory *importexportplugin = pm->getObject<UAVSettingsImportExportFactory>(); UAVSettingsImportExportFactory *importexportplugin = m_pluginManager->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(invalidateObjects())); connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(invalidateObjects()));
} }
@ -52,15 +52,16 @@ ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), isConnect
*/ */
void ConfigTaskWidget::addWidget(QWidget *widget) void ConfigTaskWidget::addWidget(QWidget *widget)
{ {
addUAVObjectToWidgetRelation("", "", widget); addWidgetBinding("", "", widget);
} }
/** /**
* Add an object to the management system * Add an object to the management system
* @param objectName name of the object to add to the management system * @param objectName name of the object to add to the management system
*/ */
void ConfigTaskWidget::addUAVObject(QString objectName, QList<int> *reloadGroups) void ConfigTaskWidget::addUAVObject(QString objectName, QList<int> *reloadGroups)
{ {
addUAVObjectToWidgetRelation(objectName, "", NULL, 0, 1, false, reloadGroups); addWidgetBinding(objectName, "", NULL, 0, 1, false, reloadGroups);
} }
void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups) void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups)
@ -72,6 +73,7 @@ void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGro
} }
addUAVObject(objstr, reloadGroups); addUAVObject(objstr, reloadGroups);
} }
/** /**
* Add an UAVObject field to widget relation to the management system * Add an UAVObject field to widget relation to the management system
* @param object name of the object to add * @param object name of the object to add
@ -79,19 +81,19 @@ void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGro
* @param widget pointer to the widget whitch will display/define the field value * @param widget pointer to the widget whitch will display/define the field value
* @param index index of the field element to add to this relation * @param index index of the field element to add to this relation
*/ */
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index) void ConfigTaskWidget::addWidgetBinding(QString object, QString field, QWidget *widget, QString index)
{ {
UAVObject *obj = NULL; UAVObject *obj = NULL;
UAVObjectField *_field = NULL; UAVObjectField *_field = NULL;
obj = objManager->getObject(QString(object)); obj = getObject(QString(object));
Q_ASSERT(obj); Q_ASSERT(obj);
_field = obj->getField(QString(field)); _field = obj->getField(QString(field));
Q_ASSERT(_field); Q_ASSERT(_field);
addUAVObjectToWidgetRelation(object, field, widget, _field->getElementNames().indexOf(index)); addWidgetBinding(object, field, widget, _field->getElementNames().indexOf(index));
} }
void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index) void ConfigTaskWidget::addWidgetBinding(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index)
{ {
QString objstr; QString objstr;
QString fieldstr; QString fieldstr;
@ -102,7 +104,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
if (field) { if (field) {
fieldstr = field->getName(); fieldstr = field->getName();
} }
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index); addWidgetBinding(objstr, fieldstr, widget, index);
} }
/** /**
* Add a UAVObject field to widget relation to the management system * Add a UAVObject field to widget relation to the management system
@ -115,9 +117,9 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
* @param defaultReloadGroups default and reload groups this relation belongs to * @param defaultReloadGroups default and reload groups this relation belongs to
* @param instID instance ID of the object used on this relation * @param instID instance ID of the object used on this relation
*/ */
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID) void ConfigTaskWidget::addWidgetBinding(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{ {
UAVObject *obj = objManager->getObject(QString(object), instID); UAVObject *obj = getObject(QString(object), instID);
Q_ASSERT(obj); Q_ASSERT(obj);
UAVObjectField *_field; UAVObjectField *_field;
@ -128,10 +130,10 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
index = _field->getElementNames().indexOf(QString(element)); index = _field->getElementNames().indexOf(QString(element));
} }
} }
addUAVObjectToWidgetRelation(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID); addWidgetBinding(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID);
} }
void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID) void ConfigTaskWidget::addWidgetBinding(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{ {
QString objstr; QString objstr;
QString fieldstr; QString fieldstr;
@ -142,9 +144,10 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
if (field) { if (field) {
fieldstr = field->getName(); fieldstr = field->getName();
} }
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID); addWidgetBinding(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID);
} }
void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
void ConfigTaskWidget::addWidgetBinding(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{ {
QString objstr; QString objstr;
QString fieldstr; QString fieldstr;
@ -155,7 +158,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
if (field) { if (field) {
fieldstr = field->getName(); fieldstr = field->getName();
} }
addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID); addWidgetBinding(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID);
} }
/** /**
@ -169,45 +172,41 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie
* @param defaultReloadGroups default and reload groups this relation belongs to * @param defaultReloadGroups default and reload groups this relation belongs to
* @param instID instance ID of the object used on this relation * @param instID instance ID of the object used on this relation
*/ */
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID) void ConfigTaskWidget::addWidgetBinding(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList<int> *defaultReloadGroups, quint32 instID)
{ {
if (addShadowWidget(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID)) { if (addShadowWidgetBinding(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID)) {
return; return;
} }
UAVObject *obj = NULL; UAVObject *obj = NULL;
UAVObjectField *_field = NULL; UAVObjectField *_field = NULL;
if (!object.isEmpty()) { if (!object.isEmpty()) {
obj = objManager->getObject(QString(object), instID); obj = getObject(QString(object), instID);
Q_ASSERT(obj); Q_ASSERT(obj);
objectUpdates.insert(obj, true); m_updatedObjects.insert(obj, true);
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *))); connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *)));
connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
} }
if (!field.isEmpty() && obj) { if (!field.isEmpty() && obj) {
_field = obj->getField(QString(field)); _field = obj->getField(QString(field));
} }
objectToWidget *ow = new objectToWidget();
ow->field = _field; WidgetBinding *binding = new WidgetBinding(widget, obj, _field, index, scale, isLimited);
ow->object = obj; m_widgetBindings.append(binding);
ow->widget = widget;
ow->index = index; if (obj && m_saveButton) {
ow->scale = scale; m_saveButton->addObject((UAVDataObject *)obj);
ow->isLimited = isLimited;
objOfInterest.append(ow);
if (obj) {
if (smartsave) {
smartsave->addObject((UAVDataObject *)obj);
}
} }
if (widget == NULL) {
if (!widget) {
if (defaultReloadGroups && obj) { if (defaultReloadGroups && obj) {
foreach(int i, *defaultReloadGroups) { foreach(int i, *defaultReloadGroups) {
if (this->defaultReloadGroups.contains(i)) { if (this->m_reloadGroups.contains(i)) {
this->defaultReloadGroups.value(i)->append(ow); this->m_reloadGroups.value(i)->append(binding);
} else { } else {
this->defaultReloadGroups.insert(i, new QList<objectToWidget *>()); this->m_reloadGroups.insert(i, new QList<WidgetBinding *>());
this->defaultReloadGroups.value(i)->append(ow); this->m_reloadGroups.value(i)->append(binding);
} }
} }
} }
@ -216,31 +215,32 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
if (defaultReloadGroups) { if (defaultReloadGroups) {
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
} }
shadowsList.insert(widget, ow); m_shadowBindings.insert(widget, binding);
loadWidgetLimits(widget, _field, index, isLimited, scale); loadWidgetLimits(widget, _field, index, isLimited, scale);
} }
} }
/** /**
* destructor * destructor
*/ */
ConfigTaskWidget::~ConfigTaskWidget() ConfigTaskWidget::~ConfigTaskWidget()
{ {
if (smartsave) { if (m_saveButton) {
delete smartsave; delete m_saveButton;
} }
foreach(QList<objectToWidget *> *pointer, defaultReloadGroups.values()) { foreach(QList<WidgetBinding *> *reloadGroup, m_reloadGroups.values()) {
if (pointer) { if (reloadGroup) {
delete pointer; delete reloadGroup;
} }
} }
foreach(objectToWidget * oTw, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (oTw) { if (binding) {
delete oTw; delete binding;
} }
} }
if (timeOut) { if (m_realtimeUpdateTimer) {
delete timeOut; delete m_realtimeUpdateTimer;
timeOut = NULL; m_realtimeUpdateTimer = NULL;
} }
} }
@ -310,26 +310,26 @@ double ConfigTaskWidget::listVar(QList<double> list)
void ConfigTaskWidget::onAutopilotDisconnect() void ConfigTaskWidget::onAutopilotDisconnect()
{ {
isConnected = false; m_isConnected = false;
enableControls(false); enableControls(false);
invalidateObjects(); invalidateObjects();
} }
void ConfigTaskWidget::forceConnectedState() // dynamic widgets don't recieve the connected signal. This should be called instead. void ConfigTaskWidget::forceConnectedState() // dynamic widgets don't recieve the connected signal. This should be called instead.
{ {
isConnected = true; m_isConnected = true;
setDirty(false); setDirty(false);
} }
void ConfigTaskWidget::onAutopilotConnect() void ConfigTaskWidget::onAutopilotConnect()
{ {
if (utilMngr) { if (m_objectUtilManager) {
currentBoard = utilMngr->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE m_currentBoardId = m_objectUtilManager->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE
} }
invalidateObjects(); invalidateObjects();
isConnected = true; m_isConnected = true;
foreach(objectToWidget * ow, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
loadWidgetLimits(ow->widget, ow->field, ow->index, ow->isLimited, ow->scale); loadWidgetLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(), binding->scale());
} }
setDirty(false); setDirty(false);
enableControls(true); enableControls(true);
@ -341,14 +341,12 @@ void ConfigTaskWidget::onAutopilotConnect()
*/ */
void ConfigTaskWidget::populateWidgets() void ConfigTaskWidget::populateWidgets()
{ {
bool dirtyBack = dirty; bool dirtyBack = m_isDirty;
emit populateWidgetsRequested(); emit populateWidgetsRequested();
foreach(objectToWidget * ow, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) { if (binding->object() != NULL && binding->field() != NULL && binding->widget() != NULL) {
// do nothing setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited());
} else {
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
} }
} }
setDirty(dirtyBack); setDirty(dirtyBack);
@ -360,23 +358,20 @@ void ConfigTaskWidget::populateWidgets()
*/ */
void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj) void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj)
{ {
if (!allowWidgetUpdates) { if (!m_isWidgetUpdatesAllowed) {
return; return;
} }
bool dirtyBack = dirty; bool dirtyBack = m_isDirty;
emit refreshWidgetsValuesRequested(); emit refreshWidgetsValuesRequested();
foreach(objectToWidget * ow, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) { if (binding->object() == obj && binding->field() != NULL && binding->widget() != NULL) {
// do nothing setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited());
} else {
if (ow->object == obj || obj == NULL) {
setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited);
}
} }
} }
setDirty(dirtyBack); setDirty(dirtyBack);
} }
/** /**
* SLOT function used to update the uavobject fields from widgets with relation to * SLOT function used to update the uavobject fields from widgets with relation to
* object field added to the framework pool * object field added to the framework pool
@ -386,24 +381,26 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
{ {
emit updateObjectsFromWidgetsRequested(); emit updateObjectsFromWidgetsRequested();
foreach(objectToWidget * ow, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (ow->object == NULL || ow->field == NULL) {} else { if (binding->object() != NULL && binding->field() != NULL) {
setFieldFromWidget(ow->widget, ow->field, ow->index, ow->scale); setFieldFromWidget(binding->widget(), binding->field(), binding->index(), binding->scale());
} }
} }
} }
/** /**
* SLOT function used handle help button presses * SLOT function used handle help button presses
* Overwrite this if you need to change the default behavior * Overwrite this if you need to change the default behavior
*/ */
void ConfigTaskWidget::helpButtonPressed() void ConfigTaskWidget::helpButtonPressed()
{ {
QString url = helpButtonList.value((QPushButton *)sender(), QString()); QString url = m_helpButtons.value((QPushButton *)sender(), QString());
if (!url.isEmpty()) { if (!url.isEmpty()) {
QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode)); QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode));
} }
} }
/** /**
* Add update and save buttons to the form * Add update and save buttons to the form
* multiple buttons can be added for the same function * multiple buttons can be added for the same function
@ -412,23 +409,23 @@ void ConfigTaskWidget::helpButtonPressed()
*/ */
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save) void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
{ {
if (!smartsave) { if (!m_saveButton) {
smartsave = new smartSaveButton(this); m_saveButton = new SmartSaveButton(this);
connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); connect(m_saveButton, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty())); connect(m_saveButton, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty()));
connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates())); connect(m_saveButton, SIGNAL(beginOp()), this, SLOT(disableObjectUpdates()));
connect(smartsave, SIGNAL(endOp()), this, SLOT(enableObjUpdates())); connect(m_saveButton, SIGNAL(endOp()), this, SLOT(enableObjectUpdates()));
} }
if (update && save) { if (update && save) {
smartsave->addButtons(save, update); m_saveButton->addButtons(save, update);
} else if (update) { } else if (update) {
smartsave->addApplyButton(update); m_saveButton->addApplyButton(update);
} else if (save) { } else if (save) {
smartsave->addSaveButton(save); m_saveButton->addSaveButton(save);
} }
if (objOfInterest.count() > 0) { if (m_widgetBindings.count() > 0) {
foreach(objectToWidget * oTw, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
smartsave->addObject((UAVDataObject *)oTw->object); m_saveButton->addObject((UAVDataObject *)binding->object());
} }
} }
updateEnableControls(); updateEnableControls();
@ -441,19 +438,19 @@ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *sav
*/ */
void ConfigTaskWidget::enableControls(bool enable) void ConfigTaskWidget::enableControls(bool enable)
{ {
if (smartsave) { if (m_saveButton) {
smartsave->enableControls(enable); m_saveButton->enableControls(enable);
} }
foreach(QPushButton * button, reloadButtonList) { foreach(QPushButton * button, m_reloadButtons) {
button->setEnabled(enable); button->setEnabled(enable);
} }
foreach(objectToWidget * ow, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (ow->widget) { if (binding->widget()) {
ow->widget->setEnabled(enable); binding->widget()->setEnabled(enable);
foreach(shadow * sh, ow->shadowsList) { foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
sh->widget->setEnabled(enable); shadow->widget()->setEnabled(enable);
} }
} }
} }
@ -470,62 +467,72 @@ bool ConfigTaskWidget::shouldObjectBeSaved(UAVObject *object)
*/ */
void ConfigTaskWidget::forceShadowUpdates() void ConfigTaskWidget::forceShadowUpdates()
{ {
foreach(objectToWidget * oTw, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
foreach(shadow * sh, oTw->shadowsList) { foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale); checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(),
setWidgetFromVariant(sh->widget, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale); getVariantFromWidget(binding->widget(), binding->scale(), binding->units()), shadow->scale());
emit widgetContentsChanged((QWidget *)sh->widget); setWidgetFromVariant(shadow->widget(), getVariantFromWidget(binding->widget(), binding->scale(), binding->units()), shadow->scale());
connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); emit widgetContentsChanged(shadow->widget());
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
} }
} }
setDirty(true); setDirty(true);
} }
/** /**
* SLOT function called when one of the widgets contents added to the framework changes * SLOT function called when one of the widgets contents added to the framework changes
*/ */
void ConfigTaskWidget::widgetsContentsChanged() void ConfigTaskWidget::widgetsContentsChanged()
{ {
emit widgetContentsChanged((QWidget *)sender()); QWidget *emitter = ((QWidget *)sender());
emit widgetContentsChanged(emitter);
double scale; double scale;
objectToWidget *oTw = shadowsList.value((QWidget *)sender(), NULL); WidgetBinding *binding = m_shadowBindings.value(emitter, NULL);
if (oTw) { if (binding) {
if (oTw->widget == (QWidget *)sender()) { if (binding->widget() == emitter) {
scale = oTw->scale; scale = binding->scale();
checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), checkWidgetsLimits(emitter, binding->field(), binding->index(), binding->isLimited(),
oTw->scale, oTw->getUnits()), oTw->scale); getVariantFromWidget(emitter, binding->scale(), binding->units()), binding->scale());
} else { } else {
foreach(shadow * sh, oTw->shadowsList) { foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
if (sh->widget == (QWidget *)sender()) { if (shadow->widget() == emitter) {
scale = sh->scale; scale = shadow->scale();
checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), checkWidgetsLimits(emitter, binding->field(), binding->index(), shadow->isLimited(),
scale, oTw->getUnits()), scale); getVariantFromWidget(emitter, scale, binding->units()), scale);
} }
} }
} }
if (oTw->widget != (QWidget *)sender()) { if (binding->widget() != emitter) {
disconnectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale);
setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale); checkWidgetsLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(),
emit widgetContentsChanged((QWidget *)oTw->widget); getVariantFromWidget(emitter, scale, binding->units()), binding->scale());
connectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); setWidgetFromVariant(binding->widget(), getVariantFromWidget(emitter, scale, binding->units()), binding->scale());
emit widgetContentsChanged(binding->widget());
connectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
} }
foreach(shadow * sh, oTw->shadowsList) { foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
if (sh->widget != (QWidget *)sender()) { if (shadow->widget() != emitter) {
disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale);
setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale); checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(),
emit widgetContentsChanged((QWidget *)sh->widget); getVariantFromWidget(emitter, scale, binding->units()), shadow->scale());
connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); setWidgetFromVariant(shadow->widget(), getVariantFromWidget(emitter, scale, binding->units()), shadow->scale());
emit widgetContentsChanged(shadow->widget());
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
} }
} }
} }
if (smartsave) { if (m_saveButton) {
smartsave->resetIcons(); m_saveButton->resetIcons();
} }
setDirty(true); setDirty(true);
} }
/** /**
* SLOT function used clear the forms dirty status flag * SLOT function used clear the forms dirty status flag
*/ */
@ -539,7 +546,7 @@ void ConfigTaskWidget::clearDirty()
*/ */
void ConfigTaskWidget::setDirty(bool value) void ConfigTaskWidget::setDirty(bool value)
{ {
dirty = value; m_isDirty = value;
} }
/** /**
* Checks if the form is dirty (unsaved changes) * Checks if the form is dirty (unsaved changes)
@ -547,8 +554,8 @@ void ConfigTaskWidget::setDirty(bool value)
*/ */
bool ConfigTaskWidget::isDirty() bool ConfigTaskWidget::isDirty()
{ {
if (isConnected) { if (m_isConnected) {
return dirty; return m_isDirty;
} else { } else {
return false; return false;
} }
@ -556,49 +563,52 @@ bool ConfigTaskWidget::isDirty()
/** /**
* SLOT function used to disable widget contents changes when related object field changes * SLOT function used to disable widget contents changes when related object field changes
*/ */
void ConfigTaskWidget::disableObjUpdates() void ConfigTaskWidget::disableObjectUpdates()
{ {
allowWidgetUpdates = false; m_isWidgetUpdatesAllowed = false;
foreach(objectToWidget * obj, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (obj->object) { if (binding->object()) {
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *))); disconnect(binding->object(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)));
} }
} }
} }
/** /**
* SLOT function used to enable widget contents changes when related object field changes * SLOT function used to enable widget contents changes when related object field changes
*/ */
void ConfigTaskWidget::enableObjUpdates() void ConfigTaskWidget::enableObjectUpdates()
{ {
allowWidgetUpdates = true; m_isWidgetUpdatesAllowed = true;
foreach(objectToWidget * obj, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (obj->object) { if (binding->object()) {
connect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); connect(binding->object(), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection);
} }
} }
} }
/** /**
* Called when an uav object is updated * Called when an uav object is updated
* @param obj pointer to the object whitch has just been updated * @param obj pointer to the object whitch has just been updated
*/ */
void ConfigTaskWidget::objectUpdated(UAVObject *obj) void ConfigTaskWidget::objectUpdated(UAVObject *object)
{ {
objectUpdates[obj] = true; m_updatedObjects[object] = true;
} }
/** /**
* Checks if all objects added to the pool have already been updated * Checks if all objects added to the pool have already been updated
* @return true if all objects added to the pool have already been updated * @return true if all objects added to the pool have already been updated
*/ */
bool ConfigTaskWidget::allObjectsUpdated() bool ConfigTaskWidget::allObjectsUpdated()
{ {
qDebug() << "ConfigTaskWidge:allObjectsUpdated called"; bool result = true;
bool ret = true;
foreach(UAVObject * obj, objectUpdates.keys()) { foreach(UAVObject * object, m_updatedObjects.keys()) {
ret = ret & objectUpdates[obj]; result = result & m_updatedObjects[object];
} }
qDebug() << "Returned:" << ret; return result;
return ret;
} }
/** /**
* Adds a new help button * Adds a new help button
* @param button pointer to the help button * @param button pointer to the help button
@ -606,7 +616,7 @@ bool ConfigTaskWidget::allObjectsUpdated()
*/ */
void ConfigTaskWidget::addHelpButton(QPushButton *button, QString url) void ConfigTaskWidget::addHelpButton(QPushButton *button, QString url)
{ {
helpButtonList.insert(button, url); m_helpButtons.insert(button, url);
connect(button, SIGNAL(clicked()), this, SLOT(helpButtonPressed())); connect(button, SIGNAL(clicked()), this, SLOT(helpButtonPressed()));
} }
/** /**
@ -614,8 +624,8 @@ void ConfigTaskWidget::addHelpButton(QPushButton *button, QString url)
*/ */
void ConfigTaskWidget::invalidateObjects() void ConfigTaskWidget::invalidateObjects()
{ {
foreach(UAVObject * obj, objectUpdates.keys()) { foreach(UAVObject * obj, m_updatedObjects.keys()) {
objectUpdates[obj] = false; m_updatedObjects[obj] = false;
} }
} }
/** /**
@ -623,8 +633,8 @@ void ConfigTaskWidget::invalidateObjects()
*/ */
void ConfigTaskWidget::apply() void ConfigTaskWidget::apply()
{ {
if (smartsave) { if (m_saveButton) {
smartsave->apply(); m_saveButton->apply();
} }
} }
/** /**
@ -632,8 +642,8 @@ void ConfigTaskWidget::apply()
*/ */
void ConfigTaskWidget::save() void ConfigTaskWidget::save()
{ {
if (smartsave) { if (m_saveButton) {
smartsave->save(); m_saveButton->save();
} }
} }
/** /**
@ -642,52 +652,32 @@ void ConfigTaskWidget::save()
* This function doesn't have to be used directly, addUAVObjectToWidgetRelation will call it if a previous relation exhists. * This function doesn't have to be used directly, addUAVObjectToWidgetRelation will call it if a previous relation exhists.
* @return returns false if the shadow widget relation failed to be added (no previous relation exhisted) * @return returns false if the shadow widget relation failed to be added (no previous relation exhisted)
*/ */
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, bool ConfigTaskWidget::addShadowWidgetBinding(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,
QList<int> *defaultReloadGroups, quint32 instID) QList<int> *defaultReloadGroups, quint32 instID)
{ {
foreach(objectToWidget * oTw, objOfInterest) { foreach(WidgetBinding * binding, m_widgetBindings) {
if (!oTw->object || !oTw->widget || !oTw->field) { if (!binding->object() || !binding->widget() || !binding->field()) {
continue; continue;
} }
if (oTw->object->getName() == object && oTw->field->getName() == field && oTw->index == index && oTw->object->getInstID() == instID) { if (binding->object()->getName() == object &&
shadow *sh = NULL; binding->field()->getName() == field &&
// prefer anything else to QLabel binding->index() == index &&
if (qobject_cast<QLabel *>(oTw->widget) && !qobject_cast<QLabel *>(widget)) { binding->object()->getInstID() == instID) {
sh = new shadow;
sh->isLimited = oTw->isLimited; binding->addShadow(widget, scale, isLimited);
sh->scale = oTw->scale;
sh->widget = oTw->widget; m_shadowBindings.insert(widget, binding);
oTw->isLimited = isLimited;
oTw->scale = scale;
oTw->widget = widget;
}
// prefer QDoubleSpinBox to anything else
else if (!qobject_cast<QDoubleSpinBox *>(oTw->widget) && qobject_cast<QDoubleSpinBox *>(widget)) {
sh = new shadow;
sh->isLimited = oTw->isLimited;
sh->scale = oTw->scale;
sh->widget = oTw->widget;
oTw->isLimited = isLimited;
oTw->scale = scale;
oTw->widget = widget;
} else {
sh = new shadow;
sh->isLimited = isLimited;
sh->scale = scale;
sh->widget = widget;
}
shadowsList.insert(widget, oTw);
oTw->shadowsList.append(sh);
connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged()));
if (defaultReloadGroups) { if (defaultReloadGroups) {
addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); addWidgetToDefaultReloadGroups(widget, defaultReloadGroups);
} }
loadWidgetLimits(widget, oTw->field, oTw->index, isLimited, scale); loadWidgetLimits(widget, binding->field(), binding->index(), isLimited, scale);
return true; return true;
} }
} }
return false; return false;
} }
/** /**
* Auto loads widgets based on the Dynamic property named "objrelation" * Auto loads widgets based on the Dynamic property named "objrelation"
* Check the wiki for more information * Check the wiki for more information
@ -788,24 +778,25 @@ void ConfigTaskWidget::autoLoadWidgets()
} else { } else {
QWidget *wid = qobject_cast<QWidget *>(widget); QWidget *wid = qobject_cast<QWidget *>(widget);
if (wid) { if (wid) {
addUAVObjectToWidgetRelation(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup); addWidgetBinding(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
} }
} }
} }
} }
refreshWidgetsValues(); refreshWidgetsValues();
forceShadowUpdates(); forceShadowUpdates();
foreach(objectToWidget * ow, objOfInterest) { foreach(WidgetBinding *binding, m_widgetBindings) {
if (ow->widget) { if (binding->widget()) {
qDebug() << "Master:" << ow->widget->objectName(); qDebug() << "Binding:" << binding->widget()->objectName();
} }
foreach(shadow * sh, ow->shadowsList) { foreach(ShadowWidgetBinding *shadow, binding->shadows()) {
if (sh->widget) { if (shadow->widget()) {
qDebug() << "Child" << sh->widget->objectName(); qDebug() << " Shadow" << shadow->widget()->objectName();
} }
} }
} }
} }
/** /**
* Adds a widget to a list of default/reload groups * Adds a widget to a list of default/reload groups
* default/reload groups are groups of widgets to be set with default or reloaded (values from persistent memory) when a defined button is pressed * default/reload groups are groups of widgets to be set with default or reloaded (values from persistent memory) when a defined button is pressed
@ -814,30 +805,31 @@ void ConfigTaskWidget::autoLoadWidgets()
*/ */
void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups) void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups)
{ {
foreach(objectToWidget * oTw, objOfInterest) { foreach(WidgetBinding *binding, m_widgetBindings) {
bool addOTW = false; bool addBinding = false;
if (oTw->widget == widget) { if (binding->widget() == widget) {
addOTW = true; addBinding = true;
} else { } else {
foreach(shadow * sh, oTw->shadowsList) { foreach(ShadowWidgetBinding *shadow, binding->shadows()) {
if (sh->widget == widget) { if (shadow->widget() == widget) {
addOTW = true; addBinding = true;
} }
} }
} }
if (addOTW) { if (addBinding) {
foreach(int i, *groups) { foreach(int i, *groups) {
if (defaultReloadGroups.contains(i)) { if (m_reloadGroups.contains(i)) {
defaultReloadGroups.value(i)->append(oTw); m_reloadGroups.value(i)->append(binding);
} else { } else {
defaultReloadGroups.insert(i, new QList<objectToWidget *>()); m_reloadGroups.insert(i, new QList<WidgetBinding *>());
defaultReloadGroups.value(i)->append(oTw); m_reloadGroups.value(i)->append(binding);
} }
} }
} }
} }
} }
/** /**
* Adds a button to a default group * Adds a button to a default group
* @param button pointer to the default button * @param button pointer to the default button
@ -848,6 +840,7 @@ void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup)
button->setProperty("group", buttonGroup); button->setProperty("group", buttonGroup);
connect(button, SIGNAL(clicked()), this, SLOT(defaultButtonClicked())); connect(button, SIGNAL(clicked()), this, SLOT(defaultButtonClicked()));
} }
/** /**
* Adds a button to a reload group * Adds a button to a reload group
* @param button pointer to the reload button * @param button pointer to the reload button
@ -856,9 +849,10 @@ void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup)
void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup) void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup)
{ {
button->setProperty("group", buttonGroup); button->setProperty("group", buttonGroup);
reloadButtonList.append(button); m_reloadButtons.append(button);
connect(button, SIGNAL(clicked()), this, SLOT(reloadButtonClicked())); connect(button, SIGNAL(clicked()), this, SLOT(reloadButtonClicked()));
} }
/** /**
* Called when a default button is clicked * Called when a default button is clicked
*/ */
@ -867,40 +861,41 @@ void ConfigTaskWidget::defaultButtonClicked()
int group = sender()->property("group").toInt(); int group = sender()->property("group").toInt();
emit defaultRequested(group); emit defaultRequested(group);
QList<objectToWidget *> *list = defaultReloadGroups.value(group); QList<WidgetBinding *> *bindings = m_reloadGroups.value(group);
foreach(objectToWidget * oTw, *list) { foreach(WidgetBinding * binding, *bindings) {
if (!oTw->object || !oTw->field) { if (!binding->object() || !binding->field()) {
continue; continue;
} }
UAVDataObject *temp = ((UAVDataObject *)oTw->object)->dirtyClone(); UAVDataObject *temp = ((UAVDataObject *)binding->object())->dirtyClone();
setWidgetFromField(oTw->widget, temp->getField(oTw->field->getName()), oTw->index, oTw->scale, oTw->isLimited); setWidgetFromField(binding->widget(), temp->getField(binding->field()->getName()), binding->index(), binding->scale(), binding->isLimited());
} }
} }
/** /**
* Called when a reload button is clicked * Called when a reload button is clicked
*/ */
void ConfigTaskWidget::reloadButtonClicked() void ConfigTaskWidget::reloadButtonClicked()
{ {
if (timeOut) { if (m_realtimeUpdateTimer) {
return; return;
} }
int group = sender()->property("group").toInt(); int group = sender()->property("group").toInt();
QList<objectToWidget *> *list = defaultReloadGroups.value(group, NULL); QList<WidgetBinding *> *bindings = m_reloadGroups.value(group, NULL);
if (!list) { if (!bindings) {
return; return;
} }
ObjectPersistence *objper = dynamic_cast<ObjectPersistence *>(getObjectManager()->getObject(ObjectPersistence::NAME)); ObjectPersistence *objper = dynamic_cast<ObjectPersistence *>(getObjectManager()->getObject(ObjectPersistence::NAME));
timeOut = new QTimer(this); m_realtimeUpdateTimer = new QTimer(this);
QEventLoop *eventLoop = new QEventLoop(this); QEventLoop *eventLoop = new QEventLoop(this);
connect(timeOut, SIGNAL(timeout()), eventLoop, SLOT(quit())); connect(m_realtimeUpdateTimer, SIGNAL(timeout()), eventLoop, SLOT(quit()));
connect(objper, SIGNAL(objectUpdated(UAVObject *)), eventLoop, SLOT(quit())); connect(objper, SIGNAL(objectUpdated(UAVObject *)), eventLoop, SLOT(quit()));
QList<temphelper> temp; QList<temphelper> temp;
foreach(objectToWidget * oTw, *list) { foreach(WidgetBinding *binding, *bindings) {
if (oTw->object != NULL) { if (binding->object() != NULL) {
temphelper value; temphelper value;
value.objid = oTw->object->getObjID(); value.objid = binding->object()->getObjID();
value.objinstid = oTw->object->getInstID(); value.objinstid = binding->object()->getInstID();
if (temp.contains(value)) { if (temp.contains(value)) {
continue; continue;
} else { } else {
@ -909,28 +904,28 @@ void ConfigTaskWidget::reloadButtonClicked()
ObjectPersistence::DataFields data; ObjectPersistence::DataFields data;
data.Operation = ObjectPersistence::OPERATION_LOAD; data.Operation = ObjectPersistence::OPERATION_LOAD;
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT; data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
data.ObjectID = oTw->object->getObjID(); data.ObjectID = binding->object()->getObjID();
data.InstanceID = oTw->object->getInstID(); data.InstanceID = binding->object()->getInstID();
objper->setData(data); objper->setData(data);
objper->updated(); objper->updated();
timeOut->start(500); m_realtimeUpdateTimer->start(500);
eventLoop->exec(); eventLoop->exec();
if (timeOut->isActive()) { if (m_realtimeUpdateTimer->isActive()) {
oTw->object->requestUpdate(); binding->object()->requestUpdate();
if (oTw->widget) { if (binding->widget()) {
setWidgetFromField(oTw->widget, oTw->field, oTw->index, oTw->scale, oTw->isLimited); setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited());
} }
} }
timeOut->stop(); m_realtimeUpdateTimer->stop();
} }
} }
if (eventLoop) { if (eventLoop) {
delete eventLoop; delete eventLoop;
eventLoop = NULL; eventLoop = NULL;
} }
if (timeOut) { if (m_realtimeUpdateTimer) {
delete timeOut; delete m_realtimeUpdateTimer;
timeOut = NULL; m_realtimeUpdateTimer = NULL;
} }
} }
@ -962,6 +957,7 @@ void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget *widget, const char *f
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
} }
} }
/** /**
* Disconnects widgets "contents changed" signals to a slot * Disconnects widgets "contents changed" signals to a slot
*/ */
@ -990,6 +986,7 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char
qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className();
} }
} }
/** /**
* Sets a widget value from an UAVObject field * Sets a widget value from an UAVObject field
* @param widget pointer for the widget to set * @param widget pointer for the widget to set
@ -1013,6 +1010,7 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget *widget, UAVObjectField *field
return false; return false;
} }
} }
/** /**
* Gets a variant from a widget * Gets a variant from a widget
* @param widget pointer to the widget from where to get the value * @param widget pointer to the widget from where to get the value
@ -1043,6 +1041,7 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
return QVariant(); return QVariant();
} }
} }
/** /**
* Sets a widget from a variant * Sets a widget from a variant
* @param widget pointer for the widget to set * @param widget pointer for the widget to set
@ -1133,16 +1132,17 @@ bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field
return false; return false;
} }
} }
void ConfigTaskWidget::checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale) void ConfigTaskWidget::checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale)
{ {
if (!hasLimits) { if (!hasLimits) {
return; return;
} }
if (!field->isWithinLimits(value, index, currentBoard)) { if (!field->isWithinLimits(value, index, m_currentBoardId)) {
if (!widget->property("styleBackup").isValid()) { if (!widget->property("styleBackup").isValid()) {
widget->setProperty("styleBackup", widget->styleSheet()); widget->setProperty("styleBackup", widget->styleSheet());
} }
widget->setStyleSheet(outOfLimitsStyle); widget->setStyleSheet(m_outOfLimitsStyle);
widget->setProperty("wasOverLimits", (bool)true); widget->setProperty("wasOverLimits", (bool)true);
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) { if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
if (cb->findText(value.toString()) == -1) { if (cb->findText(value.toString()) == -1) {
@ -1189,7 +1189,7 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field,
QStringList option = field->getOptions(); QStringList option = field->getOptions();
if (hasLimits) { if (hasLimits) {
foreach(QString str, option) { foreach(QString str, option) {
if (field->isWithinLimits(str, index, currentBoard)) { if (field->isWithinLimits(str, index, m_currentBoardId)) {
cb->addItem(str); cb->addItem(str);
} }
} }
@ -1201,31 +1201,36 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field,
return; return;
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) { } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
if (field->getMaxLimit(index).isValid()) { if (field->getMaxLimit(index).isValid()) {
cb->setMaximum((double)(field->getMaxLimit(index, currentBoard).toDouble() / scale)); cb->setMaximum((double)(field->getMaxLimit(index, m_currentBoardId).toDouble() / scale));
} }
if (field->getMinLimit(index, currentBoard).isValid()) { if (field->getMinLimit(index, m_currentBoardId).isValid()) {
cb->setMinimum((double)(field->getMinLimit(index, currentBoard).toDouble() / scale)); cb->setMinimum((double)(field->getMinLimit(index, m_currentBoardId).toDouble() / scale));
} }
} else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) { } else if (QSpinBox * cb = qobject_cast<QSpinBox *>(widget)) {
if (field->getMaxLimit(index, currentBoard).isValid()) { if (field->getMaxLimit(index, m_currentBoardId).isValid()) {
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); cb->setMaximum((int)qRound(field->getMaxLimit(index, m_currentBoardId).toDouble() / scale));
} }
if (field->getMinLimit(index, currentBoard).isValid()) { if (field->getMinLimit(index, m_currentBoardId).isValid()) {
cb->setMinimum((int)qRound(field->getMinLimit(index, currentBoard).toDouble() / scale)); cb->setMinimum((int)qRound(field->getMinLimit(index, m_currentBoardId).toDouble() / scale));
} }
} else if (QSlider * cb = qobject_cast<QSlider *>(widget)) { } else if (QSlider * cb = qobject_cast<QSlider *>(widget)) {
if (field->getMaxLimit(index, currentBoard).isValid()) { if (field->getMaxLimit(index, m_currentBoardId).isValid()) {
cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); cb->setMaximum((int)qRound(field->getMaxLimit(index, m_currentBoardId).toDouble() / scale));
} }
if (field->getMinLimit(index, currentBoard).isValid()) { if (field->getMinLimit(index, m_currentBoardId).isValid()) {
cb->setMinimum((int)(field->getMinLimit(index, currentBoard).toDouble() / scale)); cb->setMinimum((int)(field->getMinLimit(index, m_currentBoardId).toDouble() / scale));
} }
} }
} }
UAVObject *ConfigTaskWidget::getObject(const QString name, quint32 instId)
{
return m_pluginManager->getObject<UAVObjectManager>()->getObject(name, instId);
}
void ConfigTaskWidget::updateEnableControls() void ConfigTaskWidget::updateEnableControls()
{ {
TelemetryManager *telMngr = pm->getObject<TelemetryManager>(); TelemetryManager *telMngr = m_pluginManager->getObject<TelemetryManager>();
Q_ASSERT(telMngr); Q_ASSERT(telMngr);
enableControls(telMngr->isConnected()); enableControls(telMngr->isConnected());
@ -1264,3 +1269,88 @@ bool ConfigTaskWidget::eventFilter(QObject *obj, QEvent *evt)
@} @}
@} @}
*/ */
WidgetBinding::WidgetBinding(QWidget *widget, UAVObject *object, UAVObjectField *field, int index, double scale, bool isLimited) :
ShadowWidgetBinding(widget, scale, isLimited)
{
m_object = object;
m_field = field;
m_index = index;
}
WidgetBinding::~WidgetBinding()
{
}
QString WidgetBinding::units() const
{
if(m_field) {
return m_field->getUnits();
}
return QString("");
}
UAVObject *WidgetBinding::object() const
{
return m_object;
}
UAVObjectField *WidgetBinding::field() const
{
return m_field;
}
int WidgetBinding::index() const
{
return m_index;
}
QList<ShadowWidgetBinding *> WidgetBinding::shadows() const
{
return m_shadows;
}
void WidgetBinding::addShadow(QWidget *widget, int scale, bool isLimited)
{
ShadowWidgetBinding *shadow = NULL;
// Prefer anything else to QLabel and prefer QDoubleSpinBox to anything else
if ((qobject_cast<QLabel *>(m_widget) && !qobject_cast<QLabel *>(widget)) ||
(!qobject_cast<QDoubleSpinBox *>(m_widget) && qobject_cast<QDoubleSpinBox *>(widget))) {
shadow = new ShadowWidgetBinding(m_widget, m_scale, m_isLimited);
m_isLimited = isLimited;
m_scale = scale;
m_widget = widget;
} else {
shadow = new ShadowWidgetBinding(widget, scale, isLimited);
}
m_shadows.append(shadow);
}
ShadowWidgetBinding::ShadowWidgetBinding(QWidget *widget, double scale, bool isLimited)
{
m_widget = widget;
m_scale = scale;
m_isLimited = isLimited;
}
ShadowWidgetBinding::~ShadowWidgetBinding()
{
}
QWidget *ShadowWidgetBinding::widget() const
{
return m_widget;
}
double ShadowWidgetBinding::scale() const
{
return m_scale;
}
bool ShadowWidgetBinding::isLimited() const
{
return m_isLimited;
}

View File

@ -27,7 +27,6 @@
#ifndef CONFIGTASKWIDGET_H #ifndef CONFIGTASKWIDGET_H
#define CONFIGTASKWIDGET_H #define CONFIGTASKWIDGET_H
#include "extensionsystem/pluginmanager.h" #include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h" #include "uavobjectmanager.h"
#include "uavobject.h" #include "uavobject.h"
@ -48,32 +47,46 @@
#include <QUrl> #include <QUrl>
#include <QEvent> #include <QEvent>
class ShadowWidgetBinding : public QObject {
Q_OBJECT
public:
ShadowWidgetBinding(QWidget* widget, double scale, bool isLimited);
~ShadowWidgetBinding();
QWidget *widget() const;
double scale() const;
bool isLimited() const;
protected:
QWidget *m_widget;
double m_scale;
bool m_isLimited;
};
class WidgetBinding : public ShadowWidgetBinding {
Q_OBJECT
public:
WidgetBinding(QWidget* widget, UAVObject* object, UAVObjectField* field, int index, double scale, bool isLimited);
~WidgetBinding();
QString units() const;
UAVObject *object() const;
UAVObjectField *field() const;
int index() const;
QList<ShadowWidgetBinding *> shadows() const;
void addShadow(QWidget* widget, int scale, bool isLimited);
private:
UAVObject *m_object;
UAVObjectField *m_field;
int m_index;
QList<ShadowWidgetBinding *> m_shadows;
};
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget { class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget {
Q_OBJECT Q_OBJECT
public: public:
struct shadow {
QWidget *widget;
double scale;
bool isLimited;
};
struct objectToWidget {
UAVObject *object;
UAVObjectField *field;
QWidget *widget;
int index;
double scale;
bool isLimited;
QList<shadow *> shadowsList;
QString getUnits() const
{
if (field) {
return field->getUnits();
}
return QString("");
}
};
struct temphelper { struct temphelper {
quint32 objid; quint32 objid;
quint32 objinstid; quint32 objinstid;
@ -111,25 +124,24 @@ public:
void addWidget(QWidget *widget); void addWidget(QWidget *widget);
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0); void addWidgetBinding(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *m_reloadGroups = 0, quint32 instID = 0);
void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0); void addWidgetBinding(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *m_reloadGroups = 0, quint32 instID = 0);
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0); void addWidgetBinding(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited = false, QList<int> *m_reloadGroups = 0, quint32 instID = 0);
void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited = false, QList<int> *defaultReloadGroups = 0, quint32 instID = 0); void addWidgetBinding(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited = false, QList<int> *m_reloadGroups = 0, quint32 instID = 0);
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index); void addWidgetBinding(QString object, QString field, QWidget *widget, QString index);
void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index); void addWidgetBinding(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index);
// BUTTONS//
void addApplySaveButtons(QPushButton *update, QPushButton *save); void addApplySaveButtons(QPushButton *update, QPushButton *save);
void addReloadButton(QPushButton *button, int buttonGroup); void addReloadButton(QPushButton *button, int buttonGroup);
void addDefaultButton(QPushButton *button, int buttonGroup); void addDefaultButton(QPushButton *button, int buttonGroup);
//////////
void addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups); void addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> *groups);
bool addShadowWidget(QWidget *masterWidget, QWidget *shadowWidget, double shadowScale = 1, bool shadowIsLimited = false); bool addShadowWidgetBinding(QWidget *masterWidget, QWidget *shadowWidget, double shadowScale = 1, bool shadowIsLimited = false);
bool addShadowWidget(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList<int> *defaultReloadGroups = NULL, quint32 instID = 0); bool addShadowWidgetBinding(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false,
QList<int> *m_reloadGroups = NULL, quint32 instID = 0);
void autoLoadWidgets(); void autoLoadWidgets();
@ -139,18 +151,20 @@ public:
bool allObjectsUpdated(); bool allObjectsUpdated();
void setOutOfLimitsStyle(QString style) void setOutOfLimitsStyle(QString style)
{ {
outOfLimitsStyle = style; m_outOfLimitsStyle = style;
} }
void addHelpButton(QPushButton *button, QString url); void addHelpButton(QPushButton *button, QString url);
void forceShadowUpdates(); void forceShadowUpdates();
void forceConnectedState(); void forceConnectedState();
virtual bool shouldObjectBeSaved(UAVObject *object); virtual bool shouldObjectBeSaved(UAVObject *object);
public slots: public slots:
void onAutopilotDisconnect(); void onAutopilotDisconnect();
void onAutopilotConnect(); void onAutopilotConnect();
void invalidateObjects(); void invalidateObjects();
void apply(); void apply();
void save(); void save();
signals: signals:
// fired when a widgets contents changes // fired when a widgets contents changes
void widgetContentsChanged(QWidget *widget); void widgetContentsChanged(QWidget *widget);
@ -165,40 +179,46 @@ signals:
// fired when the autopilot disconnects // fired when the autopilot disconnects
void autoPilotDisconnected(); void autoPilotDisconnected();
void defaultRequested(int group); void defaultRequested(int group);
private slots: private slots:
void objectUpdated(UAVObject *); void objectUpdated(UAVObject *object);
void defaultButtonClicked(); void defaultButtonClicked();
void reloadButtonClicked(); void reloadButtonClicked();
private: private:
int currentBoard; int m_currentBoardId;
bool isConnected; bool m_isConnected;
bool allowWidgetUpdates; bool m_isWidgetUpdatesAllowed;
QStringList objectsList; QStringList m_objects;
QList <objectToWidget *> objOfInterest; QList <WidgetBinding *> m_widgetBindings;
ExtensionSystem::PluginManager *pm; ExtensionSystem::PluginManager *m_pluginManager;
UAVObjectManager *objManager; UAVObjectUtilManager *m_objectUtilManager;
UAVObjectUtilManager *utilMngr; SmartSaveButton *m_saveButton;
smartSaveButton *smartsave; QMap<UAVObject *, bool> m_updatedObjects;
QMap<UAVObject *, bool> objectUpdates; QMap<int, QList<WidgetBinding *> *> m_reloadGroups;
QMap<int, QList<objectToWidget *> *> defaultReloadGroups; QMap<QWidget *, WidgetBinding *> m_shadowBindings;
QMap<QWidget *, objectToWidget *> shadowsList; QMap<QPushButton *, QString> m_helpButtons;
QMap<QPushButton *, QString> helpButtonList; QList<QPushButton *> m_reloadButtons;
QList<QPushButton *> reloadButtonList; bool m_isDirty;
bool dirty; QString m_outOfLimitsStyle;
QTimer *m_realtimeUpdateTimer;
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale); 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, QString units);
QVariant getVariantFromWidget(QWidget *widget, double scale, const QString units);
bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units); bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units);
bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale); bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale);
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function); void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
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);
QString outOfLimitsStyle; virtual UAVObject* getObject(const QString name, quint32 instId = 0);
QTimer *timeOut;
protected slots: protected slots:
virtual void disableObjUpdates(); virtual void disableObjectUpdates();
virtual void enableObjUpdates(); virtual void enableObjectUpdates();
virtual void clearDirty(); virtual void clearDirty();
virtual void widgetsContentsChanged(); virtual void widgetsContentsChanged();
virtual void populateWidgets(); virtual void populateWidgets();

View File

@ -27,27 +27,27 @@
#include "smartsavebutton.h" #include "smartsavebutton.h"
#include "configtaskwidget.h" #include "configtaskwidget.h"
smartSaveButton::smartSaveButton(ConfigTaskWidget *configTaskWidget) : configWidget(configTaskWidget) SmartSaveButton::SmartSaveButton(ConfigTaskWidget *configTaskWidget) : configWidget(configTaskWidget)
{} {}
void smartSaveButton::addButtons(QPushButton *save, QPushButton *apply) void SmartSaveButton::addButtons(QPushButton *save, QPushButton *apply)
{ {
buttonList.insert(save, save_button); buttonList.insert(save, save_button);
buttonList.insert(apply, apply_button); buttonList.insert(apply, apply_button);
connect(save, SIGNAL(clicked()), this, SLOT(processClick())); connect(save, SIGNAL(clicked()), this, SLOT(processClick()));
connect(apply, SIGNAL(clicked()), this, SLOT(processClick())); connect(apply, SIGNAL(clicked()), this, SLOT(processClick()));
} }
void smartSaveButton::addApplyButton(QPushButton *apply) void SmartSaveButton::addApplyButton(QPushButton *apply)
{ {
buttonList.insert(apply, apply_button); buttonList.insert(apply, apply_button);
connect(apply, SIGNAL(clicked()), this, SLOT(processClick())); connect(apply, SIGNAL(clicked()), this, SLOT(processClick()));
} }
void smartSaveButton::addSaveButton(QPushButton *save) void SmartSaveButton::addSaveButton(QPushButton *save)
{ {
buttonList.insert(save, save_button); buttonList.insert(save, save_button);
connect(save, SIGNAL(clicked()), this, SLOT(processClick())); connect(save, SIGNAL(clicked()), this, SLOT(processClick()));
} }
void smartSaveButton::processClick() void SmartSaveButton::processClick()
{ {
emit beginOp(); emit beginOp();
bool save = false; bool save = false;
@ -62,7 +62,7 @@ void smartSaveButton::processClick()
processOperation(button, save); processOperation(button, save);
} }
void smartSaveButton::processOperation(QPushButton *button, bool save) void SmartSaveButton::processOperation(QPushButton *button, bool save)
{ {
emit preProcessOperations(); emit preProcessOperations();
@ -157,33 +157,33 @@ void smartSaveButton::processOperation(QPushButton *button, bool save)
emit endOp(); emit endOp();
} }
void smartSaveButton::setObjects(QList<UAVDataObject *> list) void SmartSaveButton::setObjects(QList<UAVDataObject *> list)
{ {
objects = list; objects = list;
} }
void smartSaveButton::addObject(UAVDataObject *obj) void SmartSaveButton::addObject(UAVDataObject *obj)
{ {
Q_ASSERT(obj); Q_ASSERT(obj);
if (!objects.contains(obj)) { if (!objects.contains(obj)) {
objects.append(obj); objects.append(obj);
} }
} }
void smartSaveButton::removeObject(UAVDataObject *obj) void SmartSaveButton::removeObject(UAVDataObject *obj)
{ {
if (objects.contains(obj)) { if (objects.contains(obj)) {
objects.removeAll(obj); objects.removeAll(obj);
} }
} }
void smartSaveButton::removeAllObjects() void SmartSaveButton::removeAllObjects()
{ {
objects.clear(); objects.clear();
} }
void smartSaveButton::clearObjects() void SmartSaveButton::clearObjects()
{ {
objects.clear(); objects.clear();
} }
void smartSaveButton::transaction_finished(UAVObject *obj, bool result) void SmartSaveButton::transaction_finished(UAVObject *obj, bool result)
{ {
if (current_object == obj) { if (current_object == obj) {
up_result = result; up_result = result;
@ -191,32 +191,32 @@ void smartSaveButton::transaction_finished(UAVObject *obj, bool result)
} }
} }
void smartSaveButton::saving_finished(int id, bool result) void SmartSaveButton::saving_finished(int id, bool result)
{ {
if (id == current_objectID) { if (id == (int)current_objectID) {
sv_result = result; sv_result = result;
loop.quit(); loop.quit();
} }
} }
void smartSaveButton::enableControls(bool value) void SmartSaveButton::enableControls(bool value)
{ {
foreach(QPushButton * button, buttonList.keys()) foreach(QPushButton * button, buttonList.keys())
button->setEnabled(value); button->setEnabled(value);
} }
void smartSaveButton::resetIcons() void SmartSaveButton::resetIcons()
{ {
foreach(QPushButton * button, buttonList.keys()) foreach(QPushButton * button, buttonList.keys())
button->setIcon(QIcon()); button->setIcon(QIcon());
} }
void smartSaveButton::apply() void SmartSaveButton::apply()
{ {
processOperation(NULL, false); processOperation(NULL, false);
} }
void smartSaveButton::save() void SmartSaveButton::save()
{ {
processOperation(NULL, true); processOperation(NULL, true);
} }

View File

@ -40,13 +40,13 @@
class ConfigTaskWidget; class ConfigTaskWidget;
class smartSaveButton : public QObject { class SmartSaveButton : public QObject {
enum buttonTypeEnum { save_button, apply_button }; enum buttonTypeEnum { save_button, apply_button };
public: public:
Q_OBJECT Q_OBJECT
public: public:
smartSaveButton(ConfigTaskWidget *configTaskWidget); SmartSaveButton(ConfigTaskWidget *configTaskWidget);
void addButtons(QPushButton *save, QPushButton *apply); void addButtons(QPushButton *save, QPushButton *apply);
void setObjects(QList<UAVDataObject *>); void setObjects(QList<UAVDataObject *>);
void addObject(UAVDataObject *); void addObject(UAVDataObject *);