Commit a57b3824 authored by lm's avatar lm

Started parameter interface refactoring to adhere to MVC design pattern....

Started parameter interface refactoring to adhere to MVC design pattern. Working on getting custom widgets completely up and running
parent 9802d9fa
......@@ -157,7 +157,9 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/mission/QGCCustomWaypointAction.ui \
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui
src/ui/QGCSettingsWidget.ui \
src/ui/mission/QGCMissionDoWidget.ui \
src/ui/mission/QGCMissionConditionWidget.ui
INCLUDEPATH += src \
src/ui \
......@@ -269,7 +271,10 @@ HEADERS += src/MG.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h
src/ui/QGCSettingsWidget.h \
src/ui/mission/QGCMissionDoWidget.h \
src/ui/mission/QGCMissionConditionWidget.h \
src/uas/QGCUASParamManager.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|win32-msvc2008: {
......@@ -396,7 +401,10 @@ SOURCES += src/main.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc
src/ui/QGCSettingsWidget.cc \
src/ui/mission/QGCMissionDoWidget.cc \
src/ui/mission/QGCMissionConditionWidget.cc \
src/uas/QGCUASParamManager.cc
macx|win32-msvc2008: {
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
#include "QGCUASParamManager.h"
#include "UASInterface.h"
QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) :
QWidget(parent),
mav(uas),
transmissionListMode(false),
transmissionActive(false),
transmissionTimeout(0),
retransmissionTimeout(350),
rewriteTimeout(500),
retransmissionBurstRequestSize(2)
{
uas->setParamManager(this);
}
/**
* The .. signal is emitted
*/
void QGCUASParamManager::requestParameterListUpdate(int component)
{
}
/**
* The .. signal is emitted
*/
void QGCUASParamManager::requestParameterUpdate(int component, const QString& parameter)
{
}
#ifndef QGCUASPARAMMANAGER_H
#define QGCUASPARAMMANAGER_H
#include <QWidget>
#include <QMap>
#include <QTimer>
class UASInterface;
class QGCUASParamManager : public QWidget
{
Q_OBJECT
public:
QGCUASParamManager(UASInterface* uas, QWidget *parent = 0);
QList<QString> getParameterNames(int component) const { return parameters.value(component)->keys(); }
QList<float> getParameterValues(int component) const { return parameters.value(component)->values(); }
float getParameterValue(int component, const QString& parameter) const { return parameters.value(component)->value(parameter); }
/** @brief Request an update for the parameter list */
void requestParameterListUpdate(int component = 0);
/** @brief Request an update for this specific parameter */
void requestParameterUpdate(int component, const QString& parameter);
signals:
void parameterChanged(int component, QString parameter, float value);
void parameterChanged(int component, int parameterIndex, float value);
void parameterListUpToDate(int component);
public slots:
protected:
UASInterface* mav; ///< The MAV this widget is controlling
QMap<int, QMap<QString, float>* > changedValues; ///< Changed values
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
QVector<bool> received; ///< Successfully received parameters
QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets
QMap<int, QMap<QString, float>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list?
quint64 transmissionTimeout; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission
int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds
int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
};
#endif // QGCUASPARAMMANAGER_H
......@@ -29,7 +29,7 @@
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
startTime(QGC::groundTimeMilliseconds()),
commStatus(COMM_DISCONNECTED),
name(""),
autopilot(-1),
......@@ -73,7 +73,8 @@ yaw(0.0),
statusTimeout(new QTimer(this)),
paramsOnceRequested(false),
airframe(0),
attitudeKnown(false)
attitudeKnown(false),
paramManager(NULL)
{
color = UASInterface::getNextColor();
setBattery(LIPOLY, 3);
......
......@@ -176,6 +176,7 @@ protected: //COMMENTS FOR TEST UNIT
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else
QGCUASParamManager* paramManager; ///< Parameter manager class
public:
/** @brief Set the current battery type */
......@@ -192,6 +193,11 @@ public:
bool isAuto();
UASWaypointManager* getWaypointManager() { return &waypointManager; }
/** @brief Get reference to the param manager **/
QGCUASParamManager* getParamManager() const { return paramManager; }
// TODO Will be removed
/** @brief Set reference to the param manager **/
void setParamManager(QGCUASParamManager* manager) { paramManager = manager; }
int getSystemType();
QImage getImage();
void requestImage(); // ?
......
......@@ -41,6 +41,7 @@ This file is part of the QGROUNDCONTROL project
#include "LinkInterface.h"
#include "ProtocolInterface.h"
#include "UASWaypointManager.h"
#include "QGCUASParamManager.h"
#include "RadioCalibration/RadioCalibrationData.h"
/**
......@@ -85,6 +86,11 @@ public:
/** @brief Get reference to the waypoint manager **/
virtual UASWaypointManager* getWaypointManager(void) = 0;
/** @brief Get reference to the param manager **/
virtual QGCUASParamManager* getParamManager() const = 0;
// TODO Will be removed
/** @brief Set reference to the param manager **/
virtual void setParamManager(QGCUASParamManager* manager) = 0;
/* COMMUNICATION FLAGS */
......
......@@ -43,18 +43,8 @@ This file is part of the QGROUNDCONTROL project
* @param parent Parent widget
*/
QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
QWidget(parent),
mav(uas),
components(new QMap<int, QTreeWidgetItem*>()),
paramGroups(),
changedValues(),
parameters(),
transmissionListMode(false),
transmissionActive(false),
transmissionTimeout(0),
retransmissionTimeout(350),
rewriteTimeout(500),
retransmissionBurstRequestSize(2)
QGCUASParamManager(uas, parent),
components(new QMap<int, QTreeWidgetItem*>())
{
// Load settings
loadSettings();
......
......@@ -37,16 +37,17 @@ This file is part of the QGROUNDCONTROL project
#include <QLabel>
#include <QTimer>
#include "QGCUASParamManager.h"
#include "UASInterface.h"
/**
* @brief Widget to read/set onboard parameters
*/
class QGCParamWidget : public QWidget
class QGCParamWidget : public QGCUASParamManager
{
Q_OBJECT
public:
explicit QGCParamWidget(UASInterface* uas, QWidget *parent = 0);
QGCParamWidget(UASInterface* uas, QWidget *parent = 0);
/** @brief Get the UAS of this widget */
UASInterface* getUAS();
signals:
......@@ -85,24 +86,10 @@ public slots:
void retransmissionGuardTick();
protected:
UASInterface* mav; ///< The MAV this widget is controlling
QTreeWidget* tree; ///< The parameter tree
QLabel* statusLabel; ///< Parameter transmission label
QMap<int, QTreeWidgetItem*>* components; ///< The list of components
QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups
QMap<int, QMap<QString, float>* > changedValues; ///< Changed values
QMap<int, QMap<QString, float>* > parameters; ///< All parameters
QVector<bool> received; ///< Successfully received parameters
QMap<int, QList<int>* > transmissionMissingPackets; ///< Missing packets
QMap<int, QMap<QString, float>* > transmissionMissingWriteAckPackets; ///< Missing write ACK packets
bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list?
quint64 transmissionTimeout; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission
int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds
int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
/** @brief Activate / deactivate parameter retransmission */
void setRetransmissionGuardEnabled(bool enabled);
......
......@@ -36,19 +36,18 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
customCommand->setupUi(m_ui->customActionWidget);
// add actions
m_ui->comboBox_action->addItem(tr("Navigate"),MAV_CMD_NAV_WAYPOINT);
m_ui->comboBox_action->addItem(tr("TakeOff"),MAV_CMD_NAV_TAKEOFF);
m_ui->comboBox_action->addItem(tr("Loiter Unlim."),MAV_CMD_NAV_LOITER_UNLIM);
m_ui->comboBox_action->addItem(tr("Loiter Time"),MAV_CMD_NAV_LOITER_TIME);
m_ui->comboBox_action->addItem(tr("Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS);
m_ui->comboBox_action->addItem(tr("Ret. to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
m_ui->comboBox_action->addItem(tr("Land"),MAV_CMD_NAV_LAND);
m_ui->comboBox_action->addItem(tr("NAV: Waypoint"),MAV_CMD_NAV_WAYPOINT);
m_ui->comboBox_action->addItem(tr("NAV: TakeOff"),MAV_CMD_NAV_TAKEOFF);
m_ui->comboBox_action->addItem(tr("NAV: Loiter Unlim."),MAV_CMD_NAV_LOITER_UNLIM);
m_ui->comboBox_action->addItem(tr("NAV: Loiter Time"),MAV_CMD_NAV_LOITER_TIME);
m_ui->comboBox_action->addItem(tr("NAV: Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS);
m_ui->comboBox_action->addItem(tr("NAV: Ret. to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
m_ui->comboBox_action->addItem(tr("NAV: Land"),MAV_CMD_NAV_LAND);
m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW);
m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
// m_ui->comboBox_action->addItem(tr("Delay"), MAV_ACTION_DELAY_BEFORE_COMMAND);
// m_ui->comboBox_action->addItem(tr("Ascend/Descent"), MAV_ACTION_ASCEND_AT_RATE);
// m_ui->comboBox_action->addItem(tr("Change Mode"), MAV_ACTION_CHANGE_MODE);
// m_ui->comboBox_action->addItem(tr("Relay ON"), MAV_ACTION_RELAY_ON);
// m_ui->comboBox_action->addItem(tr("Relay OFF"), MAV_ACTION_RELAY_OFF);
// add frames
m_ui->comboBox_frame->addItem("Global",MAV_FRAME_GLOBAL);
......@@ -204,6 +203,17 @@ void WaypointView::updateActionView(int action)
m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show();
break;
case MAV_CMD_NAV_TARGET:
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->holdTimeSpinBox->show();
m_ui->customActionWidget->hide();
m_ui->autoContinue->show();
m_ui->acceptanceSpinBox->hide();
m_ui->yawSpinBox->hide();
break;
default:
break;
}
......
......@@ -7,14 +7,14 @@
<x>0</x>
<y>0</y>
<width>499</width>
<height>173</height>
<height>175</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="0">
<item row="1" column="0" colspan="4">
<widget class="QLineEdit" name="editNameLabel">
<property name="text">
<string>Informal Name..</string>
......@@ -69,24 +69,69 @@
</property>
</widget>
</item>
<item row="5" column="0" colspan="6">
<item row="5" column="0" colspan="7">
<widget class="QLabel" name="editStatusLabel">
<property name="text">
<string>TextLabel</string>
<string>Please click on refresh to update list..</string>
</property>
</widget>
</item>
<item row="3" column="0" colspan="3">
<widget class="QComboBox" name="editSelectComponentComboBox"/>
<widget class="QComboBox" name="editSelectComponentComboBox">
<property name="toolTip">
<string>Select component</string>
</property>
<property name="statusTip">
<string>Select component</string>
</property>
</widget>
</item>
<item row="5" column="6">
<widget class="QPushButton" name="editDoneButton">
<item row="3" column="4" colspan="3">
<widget class="QComboBox" name="editSelectParamComboBox">
<property name="toolTip">
<string>Select parameter</string>
</property>
<property name="statusTip">
<string>Select parameter</string>
</property>
<item>
<property name="text">
<string>Click on refresh..</string>
</property>
</item>
</widget>
</item>
<item row="2" column="7">
<widget class="QPushButton" name="writeButton">
<property name="toolTip">
<string>Transmit the current slider value to the system</string>
</property>
<property name="statusTip">
<string>Transmit the current slider value to the system</string>
</property>
<property name="text">
<string>Done</string>
<string/>
</property>
<property name="icon">
<iconset resource="../../../mavground.qrc">
<normaloff>:/images/devices/network-wireless.svg</normaloff>:/images/devices/network-wireless.svg</iconset>
</property>
</widget>
</item>
<item row="2" column="8">
<widget class="QPushButton" name="readButton">
<property name="toolTip">
<string>Read the current parameter value on the system</string>
</property>
<property name="statusTip">
<string>Read the current parameter value on the system</string>
</property>
<property name="text">
<string>R</string>
</property>
</widget>
</item>
<item row="3" column="6">
<item row="3" column="7" colspan="2">
<widget class="QPushButton" name="editRefreshParamsButton">
<property name="enabled">
<bool>true</bool>
......@@ -96,17 +141,17 @@
</property>
</widget>
</item>
<item row="3" column="4" colspan="2">
<widget class="QComboBox" name="editSelectParamComboBox">
<item>
<property name="text">
<string>Select Parameter..</string>
</property>
</item>
<item row="5" column="7" colspan="2">
<widget class="QPushButton" name="editDoneButton">
<property name="text">
<string>Done</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<resources>
<include location="../../../mavground.qrc"/>
</resources>
<connections/>
</ui>
......@@ -175,7 +175,7 @@ void QGCToolWidget::addUAS(UASInterface* uas)
void QGCToolWidget::contextMenuEvent (QContextMenuEvent* event)
{
QMenu menu(this);
//menu.addAction(addParamAction);
menu.addAction(addParamAction);
menu.addAction(addButtonAction);
menu.addAction(setTitleAction);
menu.addAction(deleteAction);
......@@ -188,7 +188,7 @@ void QGCToolWidget::createActions()
addParamAction->setStatusTip(tr("Add a parameter setting slider widget to the tool"));
connect(addParamAction, SIGNAL(triggered()), this, SLOT(addParam()));
addButtonAction = new QAction(tr("New MAV &Action Button"), this);
addButtonAction = new QAction(tr("New MAV &Command Button"), this);
addButtonAction->setStatusTip(tr("Add a new action button to the tool"));
connect(addButtonAction, SIGNAL(triggered()), this, SLOT(addAction()));
......@@ -199,6 +199,14 @@ void QGCToolWidget::createActions()
deleteAction = new QAction(tr("Delete this widget"), this);
deleteAction->setStatusTip(tr("Delete this widget permanently"));
connect(deleteAction, SIGNAL(triggered()), this, SLOT(deleteWidget()));
exportAction = new QAction(tr("Export this widget"), this);
exportAction->setStatusTip(tr("Export this widget to be reused by others"));
connect(exportAction, SIGNAL(triggered()), this, SLOT(exportWidget()));
importAction = new QAction(tr("Import widget"), this);
importAction->setStatusTip(tr("Import this widget from a file (current content will be removed)"));
connect(exportAction, SIGNAL(triggered()), this, SLOT(importWidget()));
}
QMap<QString, QGCToolWidget*>* QGCToolWidget::instances()
......@@ -249,6 +257,16 @@ void QGCToolWidget::addToolWidget(QGCToolWidgetItem* widget)
toolLayout->addWidget(widget);
}
void QGCToolWidget::exportWidget()
{
}
void QGCToolWidget::importWidget(const QString& fileName)
{
}
const QString QGCToolWidget::getTitle()
{
QDockWidget* parent = dynamic_cast<QDockWidget*>(this->parentWidget());
......
......@@ -32,6 +32,10 @@ public slots:
void addUAS(UASInterface* uas);
/** @brief Delete this widget */
void deleteWidget();
/** @brief Export this widget to a file */
void exportWidget();
/** @brief Import settings for this widget from a file */
void importWidget(const QString& fileName);
/** @brief Store all widgets of this type to QSettings */
static void storeWidgetsToSettings();
......@@ -43,6 +47,8 @@ protected:
QAction* addButtonAction;
QAction* setTitleAction;
QAction* deleteAction;
QAction* exportAction;
QAction* importAction;
QVBoxLayout* toolLayout;
UAS* mav;
QAction* mainMenuAction;
......
#include "QGCMissionConditionWidget.h"
#include "ui_QGCMissionConditionWidget.h"
QGCMissionConditionWidget::QGCMissionConditionWidget(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMissionConditionWidget)
{
ui->setupUi(this);
}
QGCMissionConditionWidget::~QGCMissionConditionWidget()
{
delete ui;
}
#ifndef QGCMISSIONCONDITIONWIDGET_H
#define QGCMISSIONCONDITIONWIDGET_H
#include <QWidget>
namespace Ui {
class QGCMissionConditionWidget;
}
class QGCMissionConditionWidget : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionConditionWidget(QWidget *parent = 0);
~QGCMissionConditionWidget();
private:
Ui::QGCMissionConditionWidget *ui;
};
#endif // QGCMISSIONCONDITIONWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionConditionWidget</class>
<widget class="QWidget" name="QGCMissionConditionWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1260</width>
<height>31</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>4</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QDoubleSpinBox" name="conditionDelayTimeSpinBox">
<property name="prefix">
<string>delay: </string>
</property>
<property name="suffix">
<string> s</string>
</property>
<property name="maximum">
<double>50000.000000000000000</double>
</property>
<property name="value">
<double>5.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionChangeAltRateSpinBox">
<property name="prefix">
<string>rate: </string>
</property>
<property name="suffix">
<string> m/s</string>
</property>
<property name="maximum">
<double>200.000000000000000</double>
</property>
<property name="value">
<double>0.500000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionChangeAltFinishAltitudeSpinBox">
<property name="prefix">
<string>finish altitude: </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-100.000000000000000</double>
</property>
<property name="maximum">
<double>1000000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionDistanceSpinBox">
<property name="prefix">
<string>distance to next wp: </string>
</property>
<property name="suffix">
<string> m/s</string>
</property>
<property name="maximum">
<double>50000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionYawAngleSpinBox">
<property name="prefix">
<string>heading: </string>
</property>
<property name="suffix">
<string>°</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionYawRateSpinBox">
<property name="prefix">
<string>turn rate: </string>
</property>
<property name="suffix">
<string>°/s</string>
</property>
<property name="maximum">
<double>1000.000000000000000</double>
</property>
<property name="value">
<double>15.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="conditionYawDirectionComboBox">
<property name="currentIndex">
<number>1</number>
</property>
<item>
<property name="text">
<string>left/counter-clockwise</string>
</property>
</item>
<item>
<property name="text">
<string>right/clockwise</string>
</property>
</item>
</widget>
</item>
<item>
<widget class="QComboBox" name="conditionYawOffsetComboBox">
<item>
<property name="text">
<string>compass direction</string>
</property>
</item>
<item>
<property name="text">
<string>offset from current heading</string>
</property>
</item>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "QGCMissionDoWidget.h"
#include "ui_QGCMissionDoWidget.h"
QGCMissionDoWidget::QGCMissionDoWidget(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMissionDoWidget)
{
ui->setupUi(this);
}
QGCMissionDoWidget::~QGCMissionDoWidget()
{
delete ui;
}
#ifndef QGCMISSIONDOWIDGET_H
#define QGCMISSIONDOWIDGET_H
#include <QWidget>
namespace Ui {
class QGCMissionDoWidget;
}
class QGCMissionDoWidget : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionDoWidget(QWidget *parent = 0);
~QGCMissionDoWidget();
private:
Ui::QGCMissionDoWidget *ui;
};
#endif // QGCMISSIONDOWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionDoWidget</class>
<widget class="QWidget" name="QGCMissionDoWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>632</width>
<height>40</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QSpinBox" name="doJumpIndexSpinBox">
<property name="geometry">
<rect>
<x>170</x>
<y>10</y>
<width>201</width>
<height>25</height>
</rect>
</property>
<property name="suffix">
<string/>
</property>
<property name="prefix">
<string>list index to jump to: </string>
</property>
<property name="maximum">
<number>5000</number>
</property>
</widget>
<widget class="QSpinBox" name="doJumpRepeatSpinBox">
<property name="geometry">
<rect>
<x>380</x>
<y>10</y>
<width>121</width>
<height>25</height>
</rect>
</property>
<property name="suffix">
<string> times</string>
</property>
<property name="prefix">
<string>repeat </string>
</property>
<property name="maximum">
<number>1000</number>
</property>
</widget>
<widget class="QComboBox" name="doSetModeComboBox">
<property name="geometry">
<rect>
<x>20</x>
<y>10</y>
<width>111</width>
<height>26</height>
</rect>
</property>
</widget>
</widget>
<resources/>
<connections/>
</ui>
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment