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

OP-1331 trying new approach to address input/output channel configuration grid alignment issues.

New approach is to move the individual widgets to the parent grid layout in order to have them all under the same constraints.
This wip to have feedback on other OSes.
This commit is contained in:
Philippe Renon 2014-05-10 20:40:14 +02:00
parent da3d9d61fc
commit 274c6aadad
12 changed files with 1726 additions and 1657 deletions

View File

@ -55,69 +55,67 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
{ {
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
ftw = new MyTabbedStackWidget(this, true, true); stackWidget = new MyTabbedStackWidget(this, true, true);
ftw->setIconSize(64); stackWidget->setIconSize(64);
QVBoxLayout *layout = new QVBoxLayout; QVBoxLayout *layout = new QVBoxLayout;
layout->setContentsMargins(0, 0, 0, 0); layout->setContentsMargins(0, 0, 0, 0);
layout->addWidget(ftw); layout->addWidget(stackWidget);
setLayout(layout); setLayout(layout);
// *********************
QWidget *qwd; QWidget *qwd;
QIcon *icon = new QIcon(); QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultHwSettingsWidget(this); qwd = new DefaultHwSettingsWidget(this);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); stackWidget->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigVehicleTypeWidget(this); qwd = new ConfigVehicleTypeWidget(this);
ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle")); stackWidget->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigInputWidget(this); qwd = new ConfigInputWidget(this);
ftw->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input")); stackWidget->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigOutputWidget(this); qwd = new ConfigOutputWidget(this);
ftw->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output")); stackWidget->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultAttitudeWidget(this); qwd = new DefaultAttitudeWidget(this);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); stackWidget->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigStabilizationWidget(this); qwd = new ConfigStabilizationWidget(this);
ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization")); stackWidget->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigCameraStabilizationWidget(this); qwd = new ConfigCameraStabilizationWidget(this);
ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal")); stackWidget->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigTxPIDWidget(this); qwd = new ConfigTxPIDWidget(this);
ftw->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID")); stackWidget->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID"));
stackWidget->setCurrentIndex(ConfigGadgetWidget::hardware);
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
// *********************
// Listen to autopilot connection events // Listen to autopilot connection events
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
TelemetryManager *telMngr = pm->getObject<TelemetryManager>(); TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
@ -129,9 +127,9 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
} }
help = 0; help = 0;
connect(ftw, SIGNAL(currentAboutToShow(int, bool *)), this, SLOT(tabAboutToChange(int, bool *))); connect(stackWidget, SIGNAL(currentAboutToShow(int, bool *)), this, SLOT(tabAboutToChange(int, bool *)));
// Connect to the PipXStatus object updates // Connect to the OPLinkStatus object updates
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>(); UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
oplinkStatusObj = dynamic_cast<UAVDataObject *>(objManager->getObject("OPLinkStatus")); oplinkStatusObj = dynamic_cast<UAVDataObject *>(objManager->getObject("OPLinkStatus"));
if (oplinkStatusObj != NULL) { if (oplinkStatusObj != NULL) {
@ -148,13 +146,14 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
ConfigGadgetWidget::~ConfigGadgetWidget() ConfigGadgetWidget::~ConfigGadgetWidget()
{ {
// TODO: properly delete all the tabs in ftw before exiting // TODO: properly delete all the tabs in stackWidget before exiting
delete stackWidget
} }
void ConfigGadgetWidget::startInputWizard() void ConfigGadgetWidget::startInputWizard()
{ {
ftw->setCurrentIndex(ConfigGadgetWidget::input); stackWidget->setCurrentIndex(ConfigGadgetWidget::input);
ConfigInputWidget *inputWidget = dynamic_cast<ConfigInputWidget *>(ftw->getWidget(ConfigGadgetWidget::input)); ConfigInputWidget *inputWidget = dynamic_cast<ConfigInputWidget *>(stackWidget->getWidget(ConfigGadgetWidget::input));
Q_ASSERT(inputWidget); Q_ASSERT(inputWidget);
inputWidget->startInputWizard(); inputWidget->startInputWizard();
} }
@ -166,24 +165,24 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event)
void ConfigGadgetWidget::onAutopilotDisconnect() void ConfigGadgetWidget::onAutopilotDisconnect()
{ {
int selectedIndex = ftw->currentIndex(); int selectedIndex = stackWidget->currentIndex();
QIcon *icon = new QIcon(); QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new DefaultAttitudeWidget(this); QWidget *qwd = new DefaultAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); stackWidget->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); stackWidget->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultHwSettingsWidget(this); qwd = new DefaultHwSettingsWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware); stackWidget->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); stackWidget->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
ftw->setCurrentIndex(selectedIndex); stackWidget->setCurrentIndex(selectedIndex);
emit autopilotDisconnected(); emit autopilotDisconnected();
} }
@ -196,7 +195,7 @@ void ConfigGadgetWidget::onAutopilotConnect()
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>(); UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
if (utilMngr) { if (utilMngr) {
int selectedIndex = ftw->currentIndex(); int selectedIndex = stackWidget->currentIndex();
int board = utilMngr->getBoardModel(); int board = utilMngr->getBoardModel();
if ((board & 0xff00) == 1024) { if ((board & 0xff00) == 1024) {
// CopterControl family // CopterControl family
@ -205,15 +204,15 @@ void ConfigGadgetWidget::onAutopilotConnect()
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigCCAttitudeWidget(this); QWidget *qwd = new ConfigCCAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); stackWidget->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); stackWidget->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigCCHWWidget(this); qwd = new ConfigCCHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware); stackWidget->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); stackWidget->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else if ((board & 0xff00) == 0x0900) { } else if ((board & 0xff00) == 0x0900) {
// Revolution family // Revolution family
@ -221,20 +220,20 @@ void ConfigGadgetWidget::onAutopilotConnect()
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigRevoWidget(this); QWidget *qwd = new ConfigRevoWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); stackWidget->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); stackWidget->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigRevoHWWidget(this); qwd = new ConfigRevoHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware); stackWidget->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); stackWidget->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else { } else {
// Unknown board // Unknown board
qDebug() << "Unknown board " << board; qDebug() << "Unknown board " << board;
} }
ftw->setCurrentIndex(selectedIndex); stackWidget->setCurrentIndex(selectedIndex);
} }
emit autopilotConnected(); emit autopilotConnected();
@ -244,7 +243,7 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool *proceed)
{ {
Q_UNUSED(i); Q_UNUSED(i);
*proceed = true; *proceed = true;
ConfigTaskWidget *wid = qobject_cast<ConfigTaskWidget *>(ftw->currentWidget()); ConfigTaskWidget *wid = qobject_cast<ConfigTaskWidget *>(stackWidget->currentWidget());
if (!wid) { if (!wid) {
return; return;
} }
@ -275,7 +274,7 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigPipXtremeWidget(this); QWidget *qwd = new ConfigPipXtremeWidget(this);
ftw->insertTab(ConfigGadgetWidget::oplink, qwd, *icon, QString("OPLink")); stackWidget->insertTab(ConfigGadgetWidget::oplink, qwd, *icon, QString("OPLink"));
oplinkConnected = true; oplinkConnected = true;
} }
} }
@ -284,6 +283,6 @@ void ConfigGadgetWidget::onOPLinkDisconnect()
{ {
qDebug() << "ConfigGadgetWidget onOPLinkDisconnect"; qDebug() << "ConfigGadgetWidget onOPLinkDisconnect";
oplinkTimeout->stop(); oplinkTimeout->stop();
ftw->removeTab(ConfigGadgetWidget::oplink); stackWidget->removeTab(ConfigGadgetWidget::oplink);
oplinkConnected = false; oplinkConnected = false;
} }

View File

@ -65,7 +65,6 @@ signals:
protected: protected:
void resizeEvent(QResizeEvent *event); void resizeEvent(QResizeEvent *event);
MyTabbedStackWidget *ftw;
private: private:
UAVDataObject *oplinkStatusObj; UAVDataObject *oplinkStatusObj;
@ -73,6 +72,8 @@ private:
// A timer that timesout the connction to the OPLink. // A timer that timesout the connction to the OPLink.
QTimer *oplinkTimeout; QTimer *oplinkTimeout;
bool oplinkConnected; bool oplinkConnected;
MyTabbedStackWidget *stackWidget;
}; };
#endif // CONFIGGADGETWIDGET_H #endif // CONFIGGADGETWIDGET_H

View File

@ -80,24 +80,24 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
unsigned int indexRT = 0; unsigned int indexRT = 0;
foreach(QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames()) { foreach(QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames()) {
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
InputChannelForm *inpForm = new InputChannelForm(this, index == 0); InputChannelForm *form = new InputChannelForm(this);
ui->channelSettings->layout()->addWidget(inpForm); // Add the row to the UI form->addToGrid(ui->channelLayout);
inpForm->setName(name); form->setName(name);
// The order of the following binding calls is important. Since the values will be populated // The order of the following binding calls is important. Since the values will be populated
// in reverse order of the binding order otherwise the 'Reversed' logic will floor the neutral value // in reverse order of the binding order otherwise the 'Reversed' logic will floor the neutral value
// to the max value ( which is smaller than the neutral value when reversed ) and the channel number // to the max value ( which is smaller than the neutral value when reversed ) and the channel number
// will not be set correctly. // will not be set correctly.
addWidgetBinding("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumberDropdown, index); addWidgetBinding("ManualControlSettings", "ChannelNumber", form->ui->channelNumber, index);
addWidgetBinding("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index); addWidgetBinding("ManualControlSettings", "ChannelGroups", form->ui->channelGroup, index);
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index); addWidgetBinding("ManualControlSettings", "ChannelNeutral", form->ui->channelNeutral, index);
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->neutralValue, index); addWidgetBinding("ManualControlSettings", "ChannelNeutral", form->ui->neutralValue, index);
addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index); addWidgetBinding("ManualControlSettings", "ChannelMax", form->ui->channelMax, index);
addWidgetBinding("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index); addWidgetBinding("ManualControlSettings", "ChannelMin", form->ui->channelMin, index);
addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index); addWidgetBinding("ManualControlSettings", "ChannelMax", form->ui->channelMax, index);
addWidget(inpForm->ui->channelResponseTime); addWidget(form->ui->channelResponseTime);
addWidget(inpForm->ui->channelRev); addWidget(form->ui->channelRev);
// Input filter response time fields supported for some channels only // Input filter response time fields supported for some channels only
switch (index) { switch (index) {
@ -107,13 +107,13 @@ 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:
addWidgetBinding("ManualControlSettings", "ResponseTime", inpForm->ui->channelResponseTime, indexRT); addWidgetBinding("ManualControlSettings", "ResponseTime", form->ui->channelResponseTime, indexRT);
++indexRT; ++indexRT;
break; break;
case ManualControlSettings::CHANNELGROUPS_THROTTLE: case ManualControlSettings::CHANNELGROUPS_THROTTLE:
case ManualControlSettings::CHANNELGROUPS_FLIGHTMODE: case ManualControlSettings::CHANNELGROUPS_FLIGHTMODE:
case ManualControlSettings::CHANNELGROUPS_COLLECTIVE: case ManualControlSettings::CHANNELGROUPS_COLLECTIVE:
inpForm->ui->channelResponseTime->setEnabled(false); form->ui->channelResponseTime->setEnabled(false);
break; break;
default: default:
Q_ASSERT(0); Q_ASSERT(0);

View File

@ -76,10 +76,12 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
// NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10.
// Register for ActuatorSettings changes: // Register for ActuatorSettings changes:
for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) { for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
OutputChannelForm *form = new OutputChannelForm(i, this, i == 0); OutputChannelForm *form = new OutputChannelForm(i, this);
form->addToGrid(ui->channelLayout);
connect(ui->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool))); connect(ui->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool)));
connect(form, SIGNAL(channelChanged(int, int)), this, SLOT(sendChannelTest(int, int))); connect(form, SIGNAL(channelChanged(int, int)), this, SLOT(sendChannelTest(int, int)));
ui->channelLayout->addWidget(form);
addWidget(form->ui.actuatorMin); addWidget(form->ui.actuatorMin);
addWidget(form->ui.actuatorNeutral); addWidget(form->ui.actuatorNeutral);
addWidget(form->ui.actuatorMax); addWidget(form->ui.actuatorMax);

View File

@ -174,9 +174,9 @@
<number>0</number> <number>0</number>
</property> </property>
<item> <item>
<layout class="QVBoxLayout" name="channelSettings"> <layout class="QGridLayout" name="channelLayout">
<property name="spacing"> <property name="horizontalSpacing">
<number>6</number> <number>12</number>
</property> </property>
</layout> </layout>
</item> </item>
@ -198,7 +198,7 @@
</item> </item>
<item> <item>
<layout class="QGridLayout" name="gridLayout_3"> <layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="4"> <item row="0" column="3">
<spacer name="horizontalSpacer_3"> <spacer name="horizontalSpacer_3">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -211,14 +211,14 @@
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="0" column="1"> <item row="0" column="0">
<widget class="QLabel" name="labelDeadband"> <widget class="QLabel" name="labelDeadband">
<property name="text"> <property name="text">
<string>Roll/Pitch/Yaw stick deadband</string> <string>Roll/Pitch/Yaw stick deadband</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="1">
<widget class="QDoubleSpinBox" name="deadband"> <widget class="QDoubleSpinBox" name="deadband">
<property name="toolTip"> <property name="toolTip">
<string>Stick deadband in percents of full range (0-10), zero to disable</string> <string>Stick deadband in percents of full range (0-10), zero to disable</string>
@ -234,22 +234,6 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="0">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>12</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</item> </item>
<item> <item>
@ -260,7 +244,7 @@
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
<height>40</height> <height>10</height>
</size> </size>
</property> </property>
</spacer> </spacer>
@ -369,6 +353,12 @@
</item> </item>
<item> <item>
<widget class="QPushButton" name="configurationWizard"> <widget class="QPushButton" name="configurationWizard">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>210</width> <width>210</width>
@ -413,6 +403,12 @@
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
</property> </property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>210</width> <width>210</width>
@ -546,8 +542,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>724</width> <width>772</width>
<height>497</height> <height>751</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0"> <layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0">
@ -2048,8 +2044,8 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>407</width> <width>772</width>
<height>138</height> <height>751</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
@ -2238,7 +2234,7 @@ Set to 0 to disable (recommended for soaring fixed wings).</string>
<string/> <string/>
</property> </property>
<property name="icon"> <property name="icon">
<iconset resource="../coreplugin/core.qrc"> <iconset>
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset> <normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property> </property>
<property name="iconSize"> <property name="iconSize">

View File

@ -4,13 +4,31 @@
#include "manualcontrolsettings.h" #include "manualcontrolsettings.h"
#include "gcsreceiver.h" #include "gcsreceiver.h"
InputChannelForm::InputChannelForm(QWidget *parent, bool showLegend) : InputChannelForm::InputChannelForm(QWidget *parent) : ConfigTaskWidget(parent), ui(new Ui::InputChannelForm)
ConfigTaskWidget(parent), ui(new Ui::InputChannelForm)
{ {
ui->setupUi(this); ui->setupUi(this);
connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
connect(ui->channelMax, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
connect(ui->neutralValue, SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated()));
connect(ui->channelGroup, SIGNAL(currentIndexChanged(int)), this, SLOT(groupUpdated()));
connect(ui->channelRev, SIGNAL(toggled(bool)), this, SLOT(reversedUpdated()));
disableMouseWheelEvents();
}
InputChannelForm::~InputChannelForm()
{
delete ui;
}
void InputChannelForm::addToGrid(QGridLayout *gridLayout)
{
// if we are the first row to be inserted the show the legend
bool showLegend = (gridLayout->rowCount() == 1);
// The first time through the loop, keep the legend. All other times, delete it. // The first time through the loop, keep the legend. All other times, delete it.
if (!showLegend) { if (false && !showLegend) {
QLayout *legendLayout = layout()->itemAt(0)->layout(); QLayout *legendLayout = layout()->itemAt(0)->layout();
Q_ASSERT(legendLayout); Q_ASSERT(legendLayout);
// remove every item // remove every item
@ -31,19 +49,40 @@ InputChannelForm::InputChannelForm(QWidget *parent, bool showLegend) :
delete legendLayout; delete legendLayout;
} }
connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); QGridLayout *srcLayout = dynamic_cast<QGridLayout*>(layout());
connect(ui->channelMax, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); Q_ASSERT(srcLayout);
connect(ui->neutralValue, SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated()));
connect(ui->channelGroup, SIGNAL(currentIndexChanged(int)), this, SLOT(groupUpdated()));
connect(ui->channelRev, SIGNAL(toggled(bool)), this, SLOT(reversedUpdated()));
disableMouseWheelEvents(); if (showLegend) {
Q_ASSERT(srcLayout);
int row = gridLayout->rowCount();
for(int col = 0; col < srcLayout->columnCount(); col++) {
QLayoutItem *item = srcLayout->itemAtPosition(0, col);
if (!item) {
continue;
}
QWidget *widget = item->widget();
if (widget) {
gridLayout->addWidget(widget, row, col);
continue;
}
}
} }
int row = gridLayout->rowCount();
for(int col = 0; col < srcLayout->columnCount(); col++) {
QLayoutItem *item = srcLayout->itemAtPosition(1, col);
if (!item) {
continue;
}
QWidget *widget = item->widget();
if (widget) {
gridLayout->addWidget(widget, row, col);
continue;
}
}
InputChannelForm::~InputChannelForm() //
{ setVisible(false);
delete ui;
} }
void InputChannelForm::setName(QString &name) void InputChannelForm::setName(QString &name)
@ -118,8 +157,8 @@ void InputChannelForm::reversedUpdated()
*/ */
void InputChannelForm::groupUpdated() void InputChannelForm::groupUpdated()
{ {
ui->channelNumberDropdown->clear(); ui->channelNumber->clear();
ui->channelNumberDropdown->addItem("Disabled"); ui->channelNumber->addItem("Disabled");
quint8 count = 0; quint8 count = 0;
@ -150,6 +189,6 @@ void InputChannelForm::groupUpdated()
} }
for (int i = 0; i < count; i++) { for (int i = 0; i < count; i++) {
ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i + 1))); ui->channelNumber->addItem(QString(tr("Chan %1").arg(i + 1)));
} }
} }

View File

@ -13,10 +13,14 @@ class InputChannelForm : public ConfigTaskWidget {
Q_OBJECT Q_OBJECT
public: public:
explicit InputChannelForm(QWidget *parent = 0, const bool showLegend = false); explicit InputChannelForm(QWidget *parent = 0);
~InputChannelForm(); ~InputChannelForm();
friend class ConfigInputWidget; friend class ConfigInputWidget;
void setName(QString &name); void setName(QString &name);
void addToGrid(QGridLayout *gridLayout);
private slots: private slots:
void minMaxUpdated(); void minMaxUpdated();
void neutralUpdated(); void neutralUpdated();

View File

@ -6,14 +6,14 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>839</width> <width>859</width>
<height>57</height> <height>51</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QGridLayout" name="gridLayout">
<property name="leftMargin"> <property name="leftMargin">
<number>0</number> <number>0</number>
</property> </property>
@ -26,12 +26,191 @@
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>0</number>
</property> </property>
<item> <property name="horizontalSpacing">
<layout class="QHBoxLayout" name="legendlLayout"> <number>12</number>
<property name="spacing">
<number>6</number>
</property> </property>
<item> <item row="1" column="9">
<widget class="QSpinBox" name="channelResponseTime">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Optional input filter response time.
Range: 0-999ms, 0 disables filter (default).
Warning: this is an expert mode feature, mostly used for aerial video
camera control (airframe yaw and camera gimbal accessory channels).
Too high values for main controls can cause undesirable effects and
even lead to crash. Use with caution.</string>
</property>
<property name="wrapping">
<bool>false</bool>
</property>
<property name="frame">
<bool>true</bool>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="maximum">
<number>999</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="channelName">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Text</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="channelNumber">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>90</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="maxVisibleItems">
<number>7</number>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="channelGroup">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QSpinBox" name="channelMin">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item row="0" column="4">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="0">
<widget class="QLabel" name="legend0"> <widget class="QLabel" name="legend0">
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
@ -77,207 +256,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="7">
<widget class="QLabel" name="legend1">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel type</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Type</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="legend2">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>90</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel number</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Number</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="legend3">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>55</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel min</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="legend4">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel neutral</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Neutral</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_4"> <spacer name="horizontalSpacer_4">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -293,56 +272,39 @@ margin:1px;</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item> <item row="1" column="4">
<widget class="QLabel" name="legend5"> <spacer name="horizontalSpacer">
<property name="enabled"> <property name="orientation">
<bool>true</bool> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="sizePolicy"> <property name="sizeType">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <enum>QSizePolicy::Fixed</enum>
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="sizeHint" stdset="0">
<size> <size>
<width>55</width> <width>10</width>
<height>20</height> <height>20</height>
</size> </size>
</property> </property>
<property name="font"> </spacer>
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel max</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item> </item>
<item> <item row="1" column="7">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="8">
<widget class="QLabel" name="legend6"> <widget class="QLabel" name="legend6">
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
@ -391,7 +353,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="9">
<widget class="QLabel" name="legend7"> <widget class="QLabel" name="legend7">
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
@ -404,7 +366,7 @@ margin:1px;</string>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>45</width> <width>50</width>
<height>20</height> <height>20</height>
</size> </size>
</property> </property>
@ -440,67 +402,154 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
</layout> <item row="0" column="6">
</item> <widget class="QLabel" name="legend5">
<item> <property name="enabled">
<layout class="QHBoxLayout" name="lineLayout" stretch="0,0,0,0,0,0,0,0,0,0"> <bool>true</bool>
<property name="spacing">
<number>6</number>
</property> </property>
<item>
<widget class="QLabel" name="channelName">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>80</width> <width>50</width>
<height>25</height> <height>20</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="font">
<size> <font>
<width>80</width> <pointsize>-1</pointsize>
<height>16777215</height> <weight>75</weight>
</size> <italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel max</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property> </property>
<property name="text"> <property name="text">
<string>Text</string> <string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="5">
<widget class="QComboBox" name="channelGroup"> <widget class="QLabel" name="legend4">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>100</width> <width>0</width>
<height>25</height> <height>20</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="font">
<size> <font>
<width>100</width> <pointsize>-1</pointsize>
<height>16777215</height> <weight>75</weight>
</size> <italic>false</italic>
<bold>true</bold>
</font>
</property> </property>
<property name="focusPolicy"> <property name="toolTip">
<enum>Qt::StrongFocus</enum> <string>Channel neutral</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Neutral</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="3">
<widget class="QComboBox" name="channelNumberDropdown"> <widget class="QLabel" name="legend3">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel min</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="legend2">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -508,40 +557,101 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>90</width> <width>90</width>
<height>25</height> <height>20</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="font">
<size> <font>
<width>90</width> <pointsize>-1</pointsize>
<height>16777215</height> <weight>75</weight>
</size> <italic>false</italic>
<bold>true</bold>
</font>
</property> </property>
<property name="focusPolicy"> <property name="toolTip">
<enum>Qt::StrongFocus</enum> <string>Channel number</string>
</property> </property>
<property name="maxVisibleItems"> <property name="styleSheet">
<number>7</number> <string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Number</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="1">
<widget class="QSpinBox" name="channelMin"> <widget class="QLabel" name="legend1">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>55</width> <width>100</width>
<height>25</height> <height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel type</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Type</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QSpinBox" name="channelMax">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>55</width> <width>16777215</width>
<height>16777215</height> <height>16777215</height>
</size> </size>
</property> </property>
@ -562,26 +672,10 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="1" column="5">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QFrame" name="frame"> <widget class="QFrame" name="frame">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -592,6 +686,12 @@ margin:1px;</string>
<height>0</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
</property> </property>
@ -600,13 +700,13 @@ margin:1px;</string>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout"> <layout class="QHBoxLayout" name="horizontalLayout">
<property name="leftMargin"> <property name="leftMargin">
<number>0</number> <number>2</number>
</property> </property>
<property name="topMargin"> <property name="topMargin">
<number>0</number> <number>0</number>
</property> </property>
<property name="rightMargin"> <property name="rightMargin">
<number>0</number> <number>2</number>
</property> </property>
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>0</number>
@ -647,6 +747,12 @@ margin:1px;</string>
<height>0</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>60</width>
<height>16777215</height>
</size>
</property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property> </property>
@ -661,63 +767,10 @@ margin:1px;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item> <item row="1" column="8">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QSpinBox" name="channelMax">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>55</width>
<height>25</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>55</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item>
<widget class="QFrame" name="frame_1"> <widget class="QFrame" name="frame_1">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -725,12 +778,12 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>75</width> <width>75</width>
<height>25</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>75</width> <width>16777215</width>
<height>16777215</height> <height>16777215</height>
</size> </size>
</property> </property>
@ -767,7 +820,7 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>20</height> <height>0</height>
</size> </size>
</property> </property>
<property name="text"> <property name="text">
@ -778,61 +831,8 @@ margin:1px;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item>
<widget class="QSpinBox" name="channelResponseTime">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>45</width>
<height>25</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>45</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Optional input filter response time.
Range: 0-999ms, 0 disables filter (default).
Warning: this is an expert mode feature, mostly used for aerial video
camera control (airframe yaw and camera gimbal accessory channels).
Too high values for main controls can cause undesirable effects and
even lead to crash. Use with caution.</string>
</property>
<property name="wrapping">
<bool>false</bool>
</property>
<property name="frame">
<bool>true</bool>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="maximum">
<number>999</number>
</property>
</widget>
</item>
</layout>
</item>
</layout> </layout>
</widget> </widget>
<tabstops>
<tabstop>channelGroup</tabstop>
<tabstop>channelNumberDropdown</tabstop>
</tabstops>
<resources/> <resources/>
<connections/> <connections/>
</ui> </ui>

View File

@ -654,19 +654,36 @@ Leave at 50Hz for fixed wing.</string>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<item> <item>
<layout class="QVBoxLayout" name="channelLayout"> <layout class="QGridLayout" name="channelLayout">
<property name="spacing"> <property name="horizontalSpacing">
<number>6</number> <number>12</number>
</property>
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property> </property>
</layout> </layout>
</item> </item>
<item> <item>
<layout class="QHBoxLayout" name="horizontalLayout_2"> <spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item> <item>
<widget class="QCheckBox" name="spinningArmed"> <widget class="QCheckBox" name="spinningArmed">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>519</width> <width>519</width>
@ -678,21 +695,6 @@ Leave at 50Hz for fixed wing.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item> <item>
<spacer name="verticalSpacer"> <spacer name="verticalSpacer">
<property name="orientation"> <property name="orientation">

View File

@ -28,30 +28,10 @@
#include "outputchannelform.h" #include "outputchannelform.h"
#include "configoutputwidget.h" #include "configoutputwidget.h"
OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const bool showLegend) : OutputChannelForm::OutputChannelForm(const int index, QWidget *parent) :
ConfigTaskWidget(parent), ui(), m_index(index), m_inChannelTest(false) ConfigTaskWidget(parent), ui(), m_index(index), m_inChannelTest(false)
{ {
ui.setupUi(this); ui.setupUi(this);
if (!showLegend) {
QLayout *legendLayout = layout()->itemAt(0)->layout();
Q_ASSERT(legendLayout);
// remove every item
while (legendLayout->count()) {
QLayoutItem *item = legendLayout->takeAt(0);
if (!item) {
continue;
}
// get widget from layout item
QWidget *widget = item->widget();
if (widget) {
delete widget;
continue;
}
}
// and finally remove and delete the legend layout
layout()->removeItem(legendLayout);
delete legendLayout;
}
// The convention for OP is Channel 1 to Channel 10. // The convention for OP is Channel 1 to Channel 10.
ui.actuatorNumber->setText(QString("%1:").arg(m_index + 1)); ui.actuatorNumber->setText(QString("%1:").arg(m_index + 1));
@ -74,6 +54,68 @@ OutputChannelForm::~OutputChannelForm()
// Do nothing // Do nothing
} }
void OutputChannelForm::addToGrid(QGridLayout *gridLayout)
{
// if we are the first row to be inserted the show the legend
bool showLegend = (gridLayout->rowCount() == 1);
if (false && !showLegend) {
QLayout *legendLayout = layout()->itemAt(0)->layout();
Q_ASSERT(legendLayout);
// remove every item
while (legendLayout->count()) {
QLayoutItem *item = legendLayout->takeAt(0);
if (!item) {
continue;
}
// get widget from layout item
QWidget *widget = item->widget();
if (widget) {
delete widget;
continue;
}
}
// and finally remove and delete the legend layout
layout()->removeItem(legendLayout);
delete legendLayout;
}
QGridLayout *srcLayout = dynamic_cast<QGridLayout*>(layout());
Q_ASSERT(srcLayout);
if (showLegend) {
Q_ASSERT(srcLayout);
int row = gridLayout->rowCount();
for(int col = 0; col < srcLayout->columnCount(); col++) {
QLayoutItem *item = srcLayout->itemAtPosition(0, col);
if (!item) {
continue;
}
QWidget *widget = item->widget();
if (widget) {
gridLayout->addWidget(widget, row, col);
continue;
}
}
}
int row = gridLayout->rowCount();
for(int col = 0; col < srcLayout->columnCount(); col++) {
QLayoutItem *item = srcLayout->itemAtPosition(1, col);
if (!item) {
continue;
}
QWidget *widget = item->widget();
if (widget) {
gridLayout->addWidget(widget, row, col);
continue;
}
}
//
setVisible(false);
}
/** /**
* Restrict UI to protect users from accidental misuse. * Restrict UI to protect users from accidental misuse.
*/ */

View File

@ -35,12 +35,14 @@ class OutputChannelForm : public ConfigTaskWidget {
Q_OBJECT Q_OBJECT
public: public:
explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false); explicit OutputChannelForm(const int index, QWidget *parent = NULL);
~OutputChannelForm(); ~OutputChannelForm();
friend class ConfigOutputWidget; friend class ConfigOutputWidget;
void setAssignment(const QString &assignment); void setAssignment(const QString &assignment);
int index() const; int index() const;
void addToGrid(QGridLayout *gridLayout);
public slots: public slots:
void max(int maximum); void max(int maximum);
@ -57,7 +59,7 @@ signals:
private: private:
Ui::outputChannelForm ui; Ui::outputChannelForm ui;
/// Channel index // Channel index
int m_index; int m_index;
bool m_inChannelTest; bool m_inChannelTest;

View File

@ -7,16 +7,13 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>772</width> <width>772</width>
<height>57</height> <height>51</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QGridLayout" name="gridLayout">
<property name="spacing">
<number>6</number>
</property>
<property name="leftMargin"> <property name="leftMargin">
<number>0</number> <number>0</number>
</property> </property>
@ -29,12 +26,149 @@
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>0</number>
</property> </property>
<item> <property name="horizontalSpacing">
<layout class="QHBoxLayout" name="legendLayout">
<property name="spacing">
<number>12</number> <number>12</number>
</property> </property>
<item> <item row="0" column="1">
<widget class="QLabel" name="legend0">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>110</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Assignment</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="legend1">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="legend2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Neutral (slowest for motor)</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="5">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="0">
<widget class="QLabel" name="legend6"> <widget class="QLabel" name="legend6">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
@ -83,93 +217,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="3">
<widget class="QLabel" name="legend0">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>110</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Assignment</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="legend1">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>55</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_3"> <spacer name="horizontalSpacer_3">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -185,45 +233,8 @@ margin:1px;</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item> <item row="1" column="5">
<widget class="QLabel" name="legend2"> <spacer name="horizontalSpacer_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Neutral (slowest for motor)</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_4">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
@ -238,7 +249,91 @@ margin:1px;</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item> <item row="1" column="3">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="2">
<widget class="QSpinBox" name="actuatorMin">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PWM value, beware of not overdriving your servo.</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>0</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="actuatorNumber">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>20</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Channel Number</string>
</property>
<property name="text">
<string>0:</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="6">
<widget class="QLabel" name="legend3"> <widget class="QLabel" name="legend3">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
@ -248,7 +343,7 @@ margin:1px;</string>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>55</width> <width>50</width>
<height>20</height> <height>20</height>
</size> </size>
</property> </property>
@ -281,7 +376,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="7">
<widget class="QLabel" name="legend4"> <widget class="QLabel" name="legend4">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
@ -324,7 +419,7 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="0" column="8">
<widget class="QLabel" name="legend5"> <widget class="QLabel" name="legend5">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
@ -367,48 +462,10 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
</layout> <item row="1" column="1">
</item>
<item>
<layout class="QHBoxLayout" name="lineLayout">
<property name="spacing">
<number>12</number>
</property>
<item>
<widget class="QLabel" name="actuatorNumber">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>20</width>
<height>25</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>20</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Channel Number</string>
</property>
<property name="text">
<string>0:</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="actuatorName"> <widget class="QLabel" name="actuatorName">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -416,12 +473,12 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>110</width> <width>110</width>
<height>25</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>110</width> <width>16777215</width>
<height>16777215</height> <height>16777215</height>
</size> </size>
</property> </property>
@ -433,23 +490,23 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item row="1" column="6">
<widget class="QSpinBox" name="actuatorMin"> <widget class="QSpinBox" name="actuatorMax">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>55</width> <width>50</width>
<height>25</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>55</width> <width>16777215</width>
<height>16777215</height> <height>16777215</height>
</size> </size>
</property> </property>
@ -457,7 +514,7 @@ margin:1px;</string>
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
</property> </property>
<property name="toolTip"> <property name="toolTip">
<string>Minimum PWM value, beware of not overdriving your servo.</string> <string>Maximum PWM value, beware of not overdriving your servo.</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -465,28 +522,9 @@ margin:1px;</string>
<property name="maximum"> <property name="maximum">
<number>9999</number> <number>9999</number>
</property> </property>
<property name="value">
<number>0</number>
</property>
</widget> </widget>
</item> </item>
<item> <item row="1" column="4">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QFrame" name="frame"> <widget class="QFrame" name="frame">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred"> <sizepolicy hsizetype="Expanding" vsizetype="Preferred">
@ -502,13 +540,13 @@ margin:1px;</string>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout_3"> <layout class="QHBoxLayout" name="horizontalLayout_3">
<property name="leftMargin"> <property name="leftMargin">
<number>0</number> <number>2</number>
</property> </property>
<property name="topMargin"> <property name="topMargin">
<number>0</number> <number>0</number>
</property> </property>
<property name="rightMargin"> <property name="rightMargin">
<number>0</number> <number>2</number>
</property> </property>
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>0</number>
@ -541,20 +579,20 @@ margin:1px;</string>
<item> <item>
<widget class="QLabel" name="actuatorValue"> <widget class="QLabel" name="actuatorValue">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>24</width> <width>20</width>
<height>25</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>24</width> <width>16777215</width>
<height>16777215</height> <height>16777215</height>
</size> </size>
</property> </property>
@ -572,60 +610,10 @@ margin:1px;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item> <item row="1" column="7">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QSpinBox" name="actuatorMax">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>55</width>
<height>25</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>55</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PWM value, beware of not overdriving your servo.</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
<item>
<widget class="QFrame" name="frame_1"> <widget class="QFrame" name="frame_1">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -680,10 +668,10 @@ margin:1px;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item> <item row="1" column="8">
<widget class="QFrame" name="frame_2"> <widget class="QFrame" name="frame_2">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -691,7 +679,7 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>45</width> <width>45</width>
<height>25</height> <height>0</height>
</size> </size>
</property> </property>
<property name="frameShape"> <property name="frameShape">
@ -742,13 +730,7 @@ margin:1px;</string>
</widget> </widget>
</item> </item>
</layout> </layout>
</item>
</layout>
</widget> </widget>
<tabstops>
<tabstop>actuatorMin</tabstop>
<tabstop>actuatorMax</tabstop>
</tabstops>
<resources/> <resources/>
<connections/> <connections/>
</ui> </ui>