Commit 1bf19f54 authored by Michael Carpenter's avatar Michael Carpenter

Implementation of ArduCoptor configuration screen

parent 5796a5a8
......@@ -3,8 +3,84 @@
ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
nameToBoxMap["STB_RLL_P"] = ui.stabilPitchPSpinBox;
nameToBoxMap["STB_PIT_P"] = ui.stabilRollPSpinBox;
nameToBoxMap["STB_YAW_P"] = ui.stabilYawPSpinBox;
nameToBoxMap["HLD_LAT_P"] = ui.loiterPidPSpinBox;
nameToBoxMap["RATE_RLL_P"] = ui.rateRollPSpinBox;
nameToBoxMap["RATE_RLL_I"] = ui.rateRollISpinBox;
nameToBoxMap["RATE_RLL_D"] = ui.rateRollDSpinBox;
nameToBoxMap["RATE_RLL_IMAX"] = ui.rateRollIMAXSpinBox;
nameToBoxMap["RATE_PIT_P"] = ui.ratePitchPSpinBox;
nameToBoxMap["RATE_PIT_I"] = ui.ratePitchISpinBox;
nameToBoxMap["RATE_PIT_D"] = ui.ratePitchDSpinBox;
nameToBoxMap["RATE_PIT_IMAX"] = ui.ratePitchIMAXSpinBox;
nameToBoxMap["RATE_YAW_P"] = ui.rateYawPSpinBox;
nameToBoxMap["RATE_YAW_I"] = ui.rateYawISpinBox;
nameToBoxMap["RATE_YAW_D"] = ui.rateYawDSpinBox;
nameToBoxMap["RATE_YAW_IMAX"] = ui.rateYawIMAXSpinBox;
nameToBoxMap["LOITER_LAT_P"] = ui.rateLoiterPSpinBox;
nameToBoxMap["LOITER_LAT_I"] = ui.rateLoiterISpinBox;
nameToBoxMap["LOITER_LAT_D"] = ui.rateLoiterDSpinBox;
nameToBoxMap["LOITER_LAT_IMAX"] = ui.rateLoiterIMAXSpinBox;
nameToBoxMap["THR_ACCEL_P"] = ui.throttleAccelPSpinBox;
nameToBoxMap["THR_ACCEL_I"] = ui.throttleAccelISpinBox;
nameToBoxMap["THR_ACCEL_D"] = ui.throttleAccelDSpinBox;
nameToBoxMap["THR_ACCEL_IMAX"] = ui.throttleAccelIMAXSpinBox;
nameToBoxMap["THR_RATE_P"] = ui.throttleRatePSpinBox;
nameToBoxMap["THR_RATE_D"] = ui.throttleDateDSpinBox;
nameToBoxMap["THR_ALT_P"] = ui.altitudeHoldPSpinBox;
nameToBoxMap["WPNAV_SPEED"] = ui.wpNavLoiterSpeedSpinBox;
nameToBoxMap["WPNAV_RADIUS"] = ui.wpNavRadiusSpinBox;
nameToBoxMap["WPNAV_SPEED_DN"] = ui.wpNavSpeedDownSpinBox;
nameToBoxMap["WPNAV_LOIT_SPEED"] = ui.wpNavSpeedSpinBox;
nameToBoxMap["WPNAV_SPEED_UP"] = ui.wpNavSpeedUpSpinBox;
nameToBoxMap["TUNE_HIGH"] = ui.ch6MaxSpinBox;
nameToBoxMap["TUNE_LOW"] = ui.ch6MinSpinBox;
connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
}
ArduCopterPidConfig::~ArduCopterPidConfig()
{
}
void ArduCopterPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (nameToBoxMap.contains(parameterName))
{
nameToBoxMap[parameterName]->setValue(value.toDouble());
}
}
void ArduCopterPidConfig::writeButtonClicked()
{
if (!m_uas)
{
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
{
m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value());
}
}
void ArduCopterPidConfig::refreshButtonClicked()
{
if (!m_uas)
{
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
{
m_uas->getParamManager()->requestParameterUpdate(1,i.key());
}
}
......@@ -13,8 +13,12 @@ class ArduCopterPidConfig : public AP2ConfigWidget
public:
explicit ArduCopterPidConfig(QWidget *parent = 0);
~ArduCopterPidConfig();
private slots:
void writeButtonClicked();
void refreshButtonClicked();
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QMap<QString,QDoubleSpinBox*> nameToBoxMap;
Ui::ArduCopterPidConfig ui;
};
......
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
<width>750</width>
<height>596</height>
</rect>
</property>
<property name="windowTitle">
......@@ -26,6 +26,1035 @@
<string>&lt;h2&gt;ArduCopter Pids&lt;/h2&gt;</string>
</property>
</widget>
<widget class="QPushButton" name="writePushButton">
<property name="geometry">
<rect>
<x>120</x>
<y>540</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Write Params</string>
</property>
</widget>
<widget class="QPushButton" name="refreshPushButton">
<property name="geometry">
<rect>
<x>220</x>
<y>540</y>
<width>91</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Refresh Params</string>
</property>
</widget>
<widget class="QWidget" name="gridLayoutWidget">
<property name="geometry">
<rect>
<x>10</x>
<y>70</y>
<width>695</width>
<height>401</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="2" column="2">
<widget class="QGroupBox" name="groupBox_8">
<property name="title">
<string>Rate Yaw</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_22">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_8">
<item>
<layout class="QVBoxLayout" name="verticalLayout_23">
<item>
<widget class="QLabel" name="label_30">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_31">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_32">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_33">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_24">
<item>
<widget class="QDoubleSpinBox" name="rateYawPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateYawISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateYawDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateYawIMAXSpinBox">
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="0" column="3">
<widget class="QGroupBox" name="groupBox_4">
<property name="title">
<string>Loiter PID</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
<widget class="QLabel" name="label_14">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_8">
<item>
<widget class="QDoubleSpinBox" name="loiterPidPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="2" column="1">
<widget class="QGroupBox" name="groupBox_6">
<property name="title">
<string>Rate Pitch</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_19">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<layout class="QVBoxLayout" name="verticalLayout_11">
<item>
<widget class="QLabel" name="label_22">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_23">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_24">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_25">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_12">
<item>
<widget class="QDoubleSpinBox" name="ratePitchPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="ratePitchISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="ratePitchDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="ratePitchIMAXSpinBox">
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Stabilize Roll</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_14">
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="label_2">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QDoubleSpinBox" name="stabilRollPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="0" column="1">
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string>Stabilize Pitch</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_15">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QLabel" name="label_6">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QDoubleSpinBox" name="stabilPitchPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="2" column="0">
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
<string>Rate Roll</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_18">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QLabel" name="label_18">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_19">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_20">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_21">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_10">
<item>
<widget class="QDoubleSpinBox" name="rateRollPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateRollISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateRollDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateRollIMAXSpinBox">
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="3" column="2">
<widget class="QGroupBox" name="groupBox_10">
<property name="title">
<string>Altitude Hold</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_28">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_10">
<item>
<layout class="QVBoxLayout" name="verticalLayout_29">
<item>
<widget class="QLabel" name="label_38">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_30">
<item>
<widget class="QDoubleSpinBox" name="altitudeHoldPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="0" column="2">
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string>Stabilize Yaw</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_16">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<widget class="QLabel" name="label_10">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<widget class="QDoubleSpinBox" name="stabilYawPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="2" column="3">
<widget class="QGroupBox" name="groupBox_7">
<property name="title">
<string>Rate Loiter</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_20">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<layout class="QVBoxLayout" name="verticalLayout_13">
<item>
<widget class="QLabel" name="label_26">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_27">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_28">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_29">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_21">
<item>
<widget class="QDoubleSpinBox" name="rateLoiterPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateLoiterISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateLoiterDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="rateLoiterIMAXSpinBox">
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="1" column="0">
<widget class="QCheckBox" name="checkBox">
<property name="text">
<string>Lock Pitch and Roll Values</string>
</property>
</widget>
</item>
<item row="4" column="2">
<layout class="QVBoxLayout" name="verticalLayout_37">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_13">
<item>
<widget class="QLabel" name="label_4">
<property name="text">
<string>Ch6 Opt</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="ch6OptComboBox"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_16">
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>Min</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="ch6MinSpinBox">
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_8">
<property name="text">
<string>Max</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="ch6MaxSpinBox">
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_14">
<item>
<widget class="QLabel" name="label_5">
<property name="text">
<string>Ch7 Opt</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="ch7OptComboBox"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_15">
<item>
<widget class="QLabel" name="label_9">
<property name="text">
<string>Ch8 Opt</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="ch8OptComboBox"/>
</item>
</layout>
</item>
</layout>
</item>
<item row="3" column="0" rowspan="2">
<widget class="QGroupBox" name="groupBox_11">
<property name="title">
<string>Throttle Accel</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_31">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_11">
<item>
<layout class="QVBoxLayout" name="verticalLayout_32">
<item>
<widget class="QLabel" name="label_42">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_43">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_44">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_45">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_33">
<item>
<widget class="QDoubleSpinBox" name="throttleAccelPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="throttleAccelISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="throttleAccelDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="throttleAccelIMAXSpinBox">
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item row="3" column="1" rowspan="2">
<widget class="QGroupBox" name="groupBox_9">
<property name="title">
<string>Throttle Rate</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_25">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_9">
<item>
<layout class="QVBoxLayout" name="verticalLayout_26">
<item>
<widget class="QLabel" name="label_34">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_36">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_27">
<item>
<widget class="QDoubleSpinBox" name="throttleRatePSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="throttleDateDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item row="3" column="3" rowspan="2">
<widget class="QGroupBox" name="groupBox_12">
<property name="title">
<string>WPNav (cm's)</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_34">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<layout class="QVBoxLayout" name="verticalLayout_35">
<item>
<widget class="QLabel" name="label_46">
<property name="text">
<string>Speed</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_47">
<property name="text">
<string>Radius</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_48">
<property name="text">
<string>Speed Up</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_49">
<property name="text">
<string>speed Down</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>Loiter Speed</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_36">
<item>
<widget class="QDoubleSpinBox" name="wpNavSpeedSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="wpNavRadiusSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="wpNavSpeedUpSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="wpNavSpeedDownSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="wpNavLoiterSpeedSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</widget>
<resources/>
<connections/>
......
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