diff --git a/files/images/rc_calibration.svg b/files/images/rc_calibration.svg
new file mode 100644
index 0000000000000000000000000000000000000000..92428ced8e42d5d34b60ef1e75353217cdd69fbd
--- /dev/null
+++ b/files/images/rc_calibration.svg
@@ -0,0 +1,206 @@
+
+
+
+
diff --git a/files/images/rc_stick.svg b/files/images/rc_stick.svg
new file mode 100644
index 0000000000000000000000000000000000000000..7e135e5c9eaa68a92ccc2cd090114c49be2018cc
--- /dev/null
+++ b/files/images/rc_stick.svg
@@ -0,0 +1,211 @@
+
+
+
+
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 373b9b593c25b0c041353ec0fc7e9e59f707db2a..ab1675aeb4b5087792571199afe4145b353022d7 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -88,6 +88,7 @@
files/images/contrib/slugs.png
files/styles/style-outdoor.css
files/images/patterns/lenna.jpg
+ files/images/rc_stick.svg
files/styles/Vera.ttf
diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc
index 08d82c4e6f9db801b4615d16b6e4259537680b3d..1fbc5f3760891143bc95cdb747fd282a68e2b6bc 100644
--- a/src/uas/UASManager.cc
+++ b/src/uas/UASManager.cc
@@ -290,25 +290,35 @@ void UASManager::removeUAS(QObject* uas)
if (mav) {
int listindex = systems.indexOf(mav);
- if (mav == activeUAS) {
- if (systems.count() > 1) {
+ if (mav == activeUAS)
+ {
+ if (systems.count() > 1)
+ {
// We only set a new UAS if more than one is present
- if (listindex != 0) {
+ if (listindex != 0)
+ {
// The system to be removed is not at position 1
// set position one as new active system
setActiveUAS(systems.first());
- } else {
+ }
+ else
+ {
// The system to be removed is at position 1,
// select the next system
setActiveUAS(systems.at(1));
}
- } else {
+ }
+ else
+ {
// TODO send a null pointer if no UAS is present any more
- // This has to be proberly tested however, since it might
+ // This has to be properly tested however, since it might
// crash code parts not handling null pointers correctly.
+ activeUAS = NULL;
+ // XXX Not emitting the null pointer yet
}
}
systems.removeAt(listindex);
+ emit UASDeleted(mav);
}
}
diff --git a/src/uas/UASManager.h b/src/uas/UASManager.h
index 3d31aaab19f970e11f6379f2db622f1133ba958c..6dde682b658d0db525ec627709c334accc30cbb3 100644
--- a/src/uas/UASManager.h
+++ b/src/uas/UASManager.h
@@ -258,7 +258,10 @@ protected:
signals:
+ /** A new system was created */
void UASCreated(UASInterface* UAS);
+ /** A system was deleted */
+ void UASDeleted(UASInterface* UAS);
/** @brief The UAS currently under main operator control changed */
void activeUASSet(UASInterface* UAS);
/** @brief The UAS currently under main operator control changed */
diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc
index f8e83616101b94e7aced016aef1e211d1959b1d5..1424ef9457a015541c5856d17dd43746ed414291 100644
--- a/src/ui/MainWindow.cc
+++ b/src/ui/MainWindow.cc
@@ -1214,6 +1214,12 @@ void MainWindow::UASSpecsChanged(int uas)
ui.menuUnmanned_System->setTitle(activeUAS->getUASName());
}
}
+ else
+ {
+ // Last system deleted
+ ui.menuUnmanned_System->setTitle(tr("No System"));
+ ui.menuUnmanned_System->setEnabled(false);
+ }
}
void MainWindow::UASCreated(UASInterface* uas)
@@ -1374,11 +1380,31 @@ void MainWindow::UASCreated(UASInterface* uas)
//}
if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);
+ if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true);
// Reload view state in case new widgets were added
loadViewState();
}
+void MainWindow::UASDeleted(UASInterface* uas)
+{
+ if (UASManager::instance()->getUASList().count() == 0)
+ {
+ // Last system deleted
+ ui.menuUnmanned_System->setTitle(tr("No System"));
+ ui.menuUnmanned_System->setEnabled(false);
+ }
+
+ QAction* act;
+ QList actions = ui.menuConnected_Systems->actions();
+
+ foreach (act, actions)
+ {
+ if (act->text().contains(uas->getUASName()))
+ ui.menuConnected_Systems->removeAction(act);
+ }
+}
+
/**
* Stores the current view state
*/
diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h
index 939827c792d82eb4c36304f7ed4b8fc145d3f119..828395c1797343d19aee399234e47d2af3953eb0 100644
--- a/src/ui/MainWindow.h
+++ b/src/ui/MainWindow.h
@@ -144,6 +144,8 @@ public slots:
/** @brief Add a new UAS */
void UASCreated(UASInterface* uas);
+ /** Delete an UAS */
+ void UASDeleted(UASInterface* uas);
/** @brief Update system specs of a UAS */
void UASSpecsChanged(int uas);
void startVideoCapture();
diff --git a/src/ui/QGCSettingsWidget.ui b/src/ui/QGCSettingsWidget.ui
index 19e7676a15f7e311fd1c23b00128c17d8770e244..9a89b8fe7ca65a8ae5e186c3e13fbf21fd39c1c2 100644
--- a/src/ui/QGCSettingsWidget.ui
+++ b/src/ui/QGCSettingsWidget.ui
@@ -30,7 +30,7 @@
Mute all audio output
-
+
:/files/images/status/audio-volume-muted.svg:/files/images/status/audio-volume-muted.svg
@@ -41,7 +41,7 @@
Automatically reconnect last link on application startup
-
+
:/files/images/devices/network-wireless.svg:/files/images/devices/network-wireless.svg
@@ -97,7 +97,7 @@
-
+
diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc
index 9ea63a20d23d05a59ed830b90d95e83756d8c27c..a0012c8c4f283ea2d4a20ff7ed59893d14393ef3 100644
--- a/src/ui/QGCVehicleConfig.cc
+++ b/src/ui/QGCVehicleConfig.cc
@@ -1,14 +1,302 @@
+#include
+
+#include
+
#include "QGCVehicleConfig.h"
+#include "QGC.h"
#include "ui_QGCVehicleConfig.h"
QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
QWidget(parent),
+ mav(NULL),
+ changed(true),
ui(new Ui::QGCVehicleConfig)
{
+ setObjectName("QGC_VEHICLECONFIG");
ui->setupUi(this);
+
+ requestCalibrationRC();
+ if (mav) mav->requestParameter(0, "RC_TYPE");
+
+ connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
+ connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
}
QGCVehicleConfig::~QGCVehicleConfig()
{
delete ui;
}
+
+
+void QGCVehicleConfig::toggleCalibrationRC(bool enabled)
+{
+ if (enabled)
+ {
+ startCalibrationRC();
+ }
+ else
+ {
+ stopCalibrationRC();
+ }
+}
+
+void QGCVehicleConfig::startCalibrationRC()
+{
+ ui->rcTypeComboBox->setEnabled(false);
+ resetCalibrationRC();
+}
+
+void QGCVehicleConfig::stopCalibrationRC()
+{
+ ui->rcTypeComboBox->setEnabled(true);
+}
+
+void QGCVehicleConfig::setActiveUAS(UASInterface* active)
+{
+ // Do nothing if system is the same or NULL
+ if ((active == NULL) || mav == active) return;
+
+ if (mav)
+ {
+ // Disconnect old system
+ disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
+ SLOT(remoteControlChannelRawChanged(int,float)));
+ disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
+ SLOT(parameterChanged(int,int,QString,QVariant)));
+ resetCalibrationRC();
+ }
+
+ // Connect new system
+ mav = active;
+ connect(active, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*, QString,QString)));
+}
+
+void QGCVehicleConfig::resetCalibrationRC()
+{
+ for (unsigned int i = 0; i < chanMax; ++i)
+ {
+ rcMin[i] = INT_MAX;
+ rcMax[i] = INT_MIN;
+ }
+}
+
+/**
+ * Sends the RC calibration to the vehicle and stores it in EEPROM
+ */
+void QGCVehicleConfig::writeCalibrationRC()
+{
+ if (!mav) return;
+
+ QString minTpl("RC%1_MIN");
+ QString maxTpl("RC%1_MAX");
+ QString trimTpl("RC%1_TRIM");
+ QString revTpl("RC%1_REV");
+
+ // Do not write the RC type, as these values depend on this
+ // active onboard parameter
+
+ for (unsigned int i = 0; i < chanMax; ++i)
+ {
+ mav->setParameter(0, minTpl.arg(i), rcMin[i]);
+ mav->setParameter(0, trimTpl.arg(i), rcTrim[i]);
+ mav->setParameter(0, maxTpl.arg(i), rcMax[i]);
+ mav->setParameter(0, revTpl.arg(i), (rcRev[i]) ? -1 : 1);
+ }
+
+ // Write mappings
+ mav->setParameter(0, "RC_MAP_ROLL", rcMapping[0]);
+ mav->setParameter(0, "RC_MAP_PITCH", rcMapping[1]);
+ mav->setParameter(0, "RC_MAP_THROTTLE", rcMapping[2]);
+ mav->setParameter(0, "RC_MAP_YAW", rcMapping[3]);
+ mav->setParameter(0, "RC_MAP_MODE_SW", rcMapping[4]);
+ mav->setParameter(0, "RC_MAP_AUX1", rcMapping[5]);
+ mav->setParameter(0, "RC_MAP_AUX2", rcMapping[6]);
+ mav->setParameter(0, "RC_MAP_AUX3", rcMapping[7]);
+}
+
+void QGCVehicleConfig::requestCalibrationRC()
+{
+ if (!mav) return;
+
+ QString minTpl("RC%1_MIN");
+ QString maxTpl("RC%1_MAX");
+ QString trimTpl("RC%1_TRIM");
+ QString revTpl("RC%1_REV");
+
+ // Do not request the RC type, as these values depend on this
+ // active onboard parameter
+
+ for (unsigned int i = 0; i < chanMax; ++i)
+ {
+ mav->requestParameter(0, minTpl.arg(i));
+ usleep(5000);
+ mav->requestParameter(0, trimTpl.arg(i));
+ usleep(5000);
+ mav->requestParameter(0, maxTpl.arg(i));
+ usleep(5000);
+ mav->requestParameter(0, revTpl.arg(i));
+ usleep(5000);
+ }
+}
+
+void QGCVehicleConfig::writeParameters()
+{
+ updateStatus(tr("Writing all onboard parameters."));
+ writeCalibrationRC();
+}
+
+void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val)
+{
+ if (chan < 0 || static_cast(chan) >= chanMax)
+ return;
+
+ if (chan == rcMapping[0])
+ {
+ // ROLL
+ if (rcRoll > rcTrim[chan])
+ {
+ rcRoll = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
+ }
+ else
+ {
+ rcRoll = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]);
+ }
+
+ rcRoll = qBound(-1.0f, rcRoll, 1.0f);
+ }
+ else if (chan == rcMapping[1])
+ {
+ // PITCH
+ if (rcPitch > rcTrim[chan])
+ {
+ rcPitch = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
+ }
+ else
+ {
+ rcPitch = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]);
+ }
+
+ rcPitch = qBound(-1.0f, rcPitch, 1.0f);
+ }
+ else if (chan == rcMapping[2])
+ {
+ // YAW
+ if (rcYaw > rcTrim[chan])
+ {
+ rcYaw = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
+ }
+ else
+ {
+ rcYaw = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]);
+ }
+
+ rcYaw = qBound(-1.0f, rcYaw, 1.0f);
+ }
+ else if (chan == rcMapping[3])
+ {
+ // THROTTLE
+ if (rcThrottle > rcTrim[chan])
+ {
+ rcThrottle = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
+ }
+ else
+ {
+ rcThrottle = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]);
+ }
+
+ rcThrottle = qBound(-1.0f, rcThrottle, 1.0f);
+ }
+ else if (chan == rcMapping[4])
+ {
+ // MODE SWITCH
+ if (rcMode > rcTrim[chan])
+ {
+ rcMode = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
+ }
+ else
+ {
+ rcMode = (val - rcMin[chan])/(rcTrim[chan] - rcMin[chan]);
+ }
+
+ rcMode = qBound(-1.0f, rcMode, 1.0f);
+ }
+ else if (chan == rcMapping[5])
+ {
+ // AUX1
+ rcAux1 = val;
+ }
+ else if (chan == rcMapping[6])
+ {
+ // AUX2
+ rcAux2 = val;
+ }
+ else if (chan == rcMapping[7])
+ {
+ // AUX3
+ rcAux3 = val;
+ }
+
+ changed = true;
+
+ qDebug() << "RC CHAN:" << chan << "PPM:" << val;
+}
+
+void QGCVehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+ Q_UNUSED(uas);
+ Q_UNUSED(component);
+ if (rcTypeUpdateRequested > 0 && parameterName == QString("RC_TYPE"))
+ {
+ rcTypeUpdateRequested = 0;
+ updateStatus(tr("Received RC type update, setting parameters based on model."));
+ rcType = value.toInt();
+ // Request all other parameters as well
+ requestCalibrationRC();
+ }
+}
+
+void QGCVehicleConfig::updateStatus(const QString& str)
+{
+ ui->statusLabel->setText(str);
+ ui->statusLabel->setStyleSheet("");
+}
+
+void QGCVehicleConfig::updateError(const QString& str)
+{
+ ui->statusLabel->setText(str);
+ ui->statusLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.name()));
+}
+
+void QGCVehicleConfig::setRCType(int type)
+{
+ if (!mav) return;
+
+ // XXX TODO Add handling of RC_TYPE vs non-RC_TYPE here
+
+ mav->setParameter(0, "RC_TYPE", type);
+ rcTypeUpdateRequested = QGC::groundTimeMilliseconds();
+ QTimer::singleShot(rcTypeTimeout+100, this, SLOT(checktimeOuts()));
+}
+
+void QGCVehicleConfig::checktimeOuts()
+{
+ if (rcTypeUpdateRequested > 0)
+ {
+ if (QGC::groundTimeMilliseconds() - rcTypeUpdateRequested > rcTypeTimeout)
+ {
+ updateError(tr("Setting remote control timed out - is the system connected?"));
+ }
+ }
+}
+
+void QGCVehicleConfig::updateView()
+{
+ if (changed)
+ {
+ ui->rollSlider->setValue(rcRoll);
+ ui->pitchSlider->setValue(rcPitch);
+ ui->yawSlider->setValue(rcYaw);
+ ui->throttleSlider->setValue(rcThrottle);
+ changed = false;
+ }
+}
diff --git a/src/ui/QGCVehicleConfig.h b/src/ui/QGCVehicleConfig.h
index 9be86a85e0cc839efe6ee0c07fe0ce0098b5b2a4..1d75e9af908ea49a9db6429ff7c4202fa582e2bc 100644
--- a/src/ui/QGCVehicleConfig.h
+++ b/src/ui/QGCVehicleConfig.h
@@ -3,6 +3,8 @@
#include
+#include "UASInterface.h"
+
namespace Ui {
class QGCVehicleConfig;
}
@@ -14,9 +16,66 @@ class QGCVehicleConfig : public QWidget
public:
explicit QGCVehicleConfig(QWidget *parent = 0);
~QGCVehicleConfig();
+
+public slots:
+ /** Set the MAV currently being calibrated */
+ void setActiveUAS(UASInterface* active);
+
+ /** Start the RC calibration routine */
+ void startCalibrationRC();
+ /** Stop the RC calibration routine */
+ void stopCalibrationRC();
+ /** Start/stop the RC calibration routine */
+ void toggleCalibrationRC(bool enabled);
+ /** Render the data updated */
+ void updateView();
+
+protected slots:
+ /** Reset the RC calibration */
+ void resetCalibrationRC();
+ /** Write the RC calibration */
+ void writeCalibrationRC();
+ /** Request the RC calibration */
+ void requestCalibrationRC();
+ /** Store all parameters in onboard EEPROM */
+ void writeParameters();
+ /** Receive remote control updates from MAV */
+ void remoteControlChannelRawChanged(int chan, float val);
+ /** Parameter changed onboard */
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
+ void updateStatus(const QString& str);
+ void updateError(const QString& str);
+ void setRCType(int type);
+ /** Check timeouts */
+ void checktimeOuts();
+
+protected:
+ UASInterface* mav; ///< The current MAV
+ static const unsigned int chanMax = 8; ///< Maximum number of channels
+ int rcType; ///< Type of the remote control
+ quint64 rcTypeUpdateRequested; ///< Zero if not requested, non-zero if requested
+ static const unsigned int rcTypeTimeout = 5000; ///< 5 seconds timeout, in milliseconds
+ int rcMin[chanMax]; ///< Minimum values
+ int rcMax[chanMax]; ///< Maximum values
+ int rcTrim[chanMax]; ///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle)
+ int rcMapping[chanMax]; ///< PWM to function mappings
+ bool rcRev[chanMax]; ///< Channel reverse
+ float rcRoll; ///< PPM input channel used as roll control input
+ float rcPitch; ///< PPM input channel used as pitch control input
+ float rcYaw; ///< PPM input channel used as yaw control input
+ float rcThrottle; ///< PPM input channel used as throttle control input
+ float rcMode; ///< PPM input channel used as mode switch control input
+ float rcAux1; ///< PPM input channel used as aux 1 input
+ float rcAux2; ///< PPM input channel used as aux 1 input
+ float rcAux3; ///< PPM input channel used as aux 1 input
+ bool rcCalChanged; ///< Set if the calibration changes (and needs to be written)
+ bool changed; ///< Set if any of the input data changed
private:
Ui::QGCVehicleConfig *ui;
+
+signals:
+ void visibilityChanged(bool visible);
};
#endif // QGCVEHICLECONFIG_H
diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui
index 13d41173dbdb3e8c5f2c040c4eaea28b8531433c..85ac487c498719e876d377a9f4422d87d0ec624b 100644
--- a/src/ui/QGCVehicleConfig.ui
+++ b/src/ui/QGCVehicleConfig.ui
@@ -6,209 +6,493 @@
0
0
- 499
- 451
+ 658
+ 586
Form
-
+
+
+ 6
+
+
+ 8
+
- 0
+ 6
- -
+
-
0
- Tab 1
+ RC Calibration
-
-
-
- 10
- 230
- 160
- 22
-
-
-
- Qt::Horizontal
-
-
-
-
-
- 170
- 80
- 22
- 160
-
-
-
- Qt::Vertical
-
-
-
-
-
- 220
- 230
- 160
- 22
-
-
-
- Qt::Horizontal
-
-
-
-
-
- 380
- 80
- 22
- 160
-
-
-
- Qt::Vertical
-
-
-
+
+
-
+
+
+ Qt::Vertical
+
+
+
+ -
+
+
+
+
+
+ :/files/images/rc_stick.svg
+
+
+ true
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 5
+ 5
+
+
+
+
+ -
+
+
+
+
+
+
+ -
+
+
+ 800
+
+
+ 2200
+
+
+ 1500
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ false
+
+
-
+
+ Select control mode
+
+
+
+
+ -
+
+
-
+
+ Select transmitter model
+
+
+
+
+ -
+
+
+
+ 100
+ 100
+
+
+
+
+ 50
+ 50
+
+
+
+
+ 50
+ 50
+
+
+
+
+
+
+
+ -
+
+
+
+
+
+ :/files/images/rc_stick.svg
+
+
+ true
+
+
+
+ -
+
+
+ 800
+
+
+ 2200
+
+
+ 1500
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+
+
+
+
+ -
+
+
+ 800
+
+
+ 2200
+
+
+ 1500
+
+
+ Qt::Vertical
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ -
+
+
+ 800
+
+
+ 2200
+
+
+ Qt::Vertical
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+ Start Calibration
+
+
+
+
+
+
+
+ Sensor Calibration
+
+
30
- 300
- 22
- 71
-
-
-
- Qt::Vertical
-
-
-
-
-
- 60
- 300
- 22
- 71
-
-
-
- Qt::Vertical
-
-
-
-
-
- 90
- 300
- 22
- 71
-
-
-
- Qt::Vertical
-
-
-
-
-
- 120
- 300
- 22
- 71
-
-
-
- Qt::Vertical
-
-
-
-
-
- 20
- 70
- 141
- 151
+ 20
+ 161
+ 32
- TextLabel
+ Gyro Calibration
-
+
- 220
- 70
- 151
- 141
+ 30
+ 80
+ 161
+ 32
- TextLabel
-
-
-
-
-
- 10
- 20
- 171
- 26
-
-
- -
-
- Select RC model
-
-
-
-
-
-
- 210
- 20
- 191
- 26
-
+ Accel Calibration
- -
-
- Select RC mode
-
-
-
+
- 10
- 250
- 171
- 23
+ 30
+ 140
+ 161
+ 32
-
- 24
+
+ Mag Calibration
-
+
- Tab 2
+ Multirotor Attitude Control
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ Set Gains
+
+
+
+ -
+
+
+ Load Platform Defaults
+
+
+
+ -
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
+ -
+
+
+ No pending changes
+
+
+
+ -
+
+
+ Store to EEPROM
+
+
+
-
+
+
+