Browse Source

ArduPlane pid screen visuals

QGC4.4
Michael Carpenter 12 years ago
parent
commit
f7ec760794
  1. 9
      qgroundcontrol.pro
  2. 8
      src/ui/configuration/ApmSoftwareConfig.cc
  3. 8
      src/ui/configuration/ArduCopterPidConfig.cc
  4. 9
      src/ui/configuration/ArduCopterPidConfig.h
  5. 18
      src/ui/configuration/ArduPlanePidConfig.cc
  6. 21
      src/ui/configuration/ArduPlanePidConfig.h
  7. 957
      src/ui/configuration/ArduPlanePidConfig.ui

9
qgroundcontrol.pro

@ -258,7 +258,8 @@ FORMS += src/ui/MainWindow.ui \ @@ -258,7 +258,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/configuration/AdvancedParamConfig.ui \
src/ui/configuration/ArduCopterPidConfig.ui \
src/ui/configuration/ApmPlaneLevel.ui \
src/ui/configuration/ParamWidget.ui
src/ui/configuration/ParamWidget.ui \
src/ui/configuration/ArduPlanePidConfig.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
@ -441,7 +442,8 @@ HEADERS += src/MG.h \ @@ -441,7 +442,8 @@ HEADERS += src/MG.h \
src/ui/configuration/AdvancedParamConfig.h \
src/ui/configuration/ArduCopterPidConfig.h \
src/ui/configuration/ApmPlaneLevel.h \
src/ui/configuration/ParamWidget.h
src/ui/configuration/ParamWidget.h \
src/ui/configuration/ArduPlanePidConfig.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
@ -642,7 +644,8 @@ SOURCES += src/main.cc \ @@ -642,7 +644,8 @@ SOURCES += src/main.cc \
src/ui/configuration/AdvancedParamConfig.cc \
src/ui/configuration/ArduCopterPidConfig.cc \
src/ui/configuration/ApmPlaneLevel.cc \
src/ui/configuration/ParamWidget.cc
src/ui/configuration/ParamWidget.cc \
src/ui/configuration/ArduPlanePidConfig.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc

8
src/ui/configuration/ApmSoftwareConfig.cc

@ -17,10 +17,10 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent) @@ -17,10 +17,10 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
ui.advParamListButton->setVisible(false);
ui.arduCoperPidButton->setVisible(false);
basicPidConfig = new BasicPidConfig(this);
/*basicPidConfig = new BasicPidConfig(this);
ui.stackedWidget->addWidget(basicPidConfig);
buttonToConfigWidgetMap[ui.basicPidsButton] = basicPidConfig;
connect(ui.basicPidsButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
connect(ui.basicPidsButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));*/
flightConfig = new FlightModeConfig(this);
ui.stackedWidget->addWidget(flightConfig);
@ -32,10 +32,10 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent) @@ -32,10 +32,10 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap[ui.standardParamButton] = standardParamConfig;
connect(ui.standardParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
geoFenceConfig = new GeoFenceConfig(this);
/*geoFenceConfig = new GeoFenceConfig(this);
ui.stackedWidget->addWidget(geoFenceConfig);
buttonToConfigWidgetMap[ui.geoFenceButton] = geoFenceConfig;
connect(ui.geoFenceButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
connect(ui.geoFenceButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));*/
failSafeConfig = new FailSafeConfig(this);
ui.stackedWidget->addWidget(failSafeConfig);

8
src/ui/configuration/ArduCopterPidConfig.cc

@ -1,14 +1,10 @@ @@ -1,14 +1,10 @@
#include "ArduCopterPidConfig.h"
#include "ui_ArduCopterPidConfig.h"
ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) :
QWidget(parent),
ui(new Ui::ArduCopterPidConfig)
ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui->setupUi(this);
ui.setupUi(this);
}
ArduCopterPidConfig::~ArduCopterPidConfig()
{
delete ui;
}

9
src/ui/configuration/ArduCopterPidConfig.h

@ -2,12 +2,11 @@ @@ -2,12 +2,11 @@
#define ARDUCOPTERPIDCONFIG_H
#include <QWidget>
#include "ui_ArduCopterPidConfig.h"
namespace Ui {
class ArduCopterPidConfig;
}
#include "AP2ConfigWidget.h"
class ArduCopterPidConfig : public QWidget
class ArduCopterPidConfig : public AP2ConfigWidget
{
Q_OBJECT
@ -16,7 +15,7 @@ public: @@ -16,7 +15,7 @@ public:
~ArduCopterPidConfig();
private:
Ui::ArduCopterPidConfig *ui;
Ui::ArduCopterPidConfig ui;
};
#endif // ARDUCOPTERPIDCONFIG_H

18
src/ui/configuration/ArduPlanePidConfig.cc

@ -0,0 +1,18 @@ @@ -0,0 +1,18 @@
#include "ArduPlanePidConfig.h"
ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
}
ArduPlanePidConfig::~ArduPlanePidConfig()
{
}
void ArduPlanePidconfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (parameterName == "")
{
}
}

21
src/ui/configuration/ArduPlanePidConfig.h

@ -0,0 +1,21 @@ @@ -0,0 +1,21 @@
#ifndef ARDUPLANEPIDCONFIG_H
#define ARDUPLANEPIDCONFIG_H
#include <QWidget>
#include "ui_ArduPlanePidConfig.h"
#include "AP2ConfigWidget.h"
class ArduPlanePidConfig : public AP2ConfigWidget
{
Q_OBJECT
public:
explicit ArduPlanePidConfig(QWidget *parent = 0);
~ArduPlanePidConfig();
private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
Ui::ArduPlanePidConfig ui;
};
#endif // ARDUPLANEPIDCONFIG_H

957
src/ui/configuration/ArduPlanePidConfig.ui

@ -0,0 +1,957 @@ @@ -0,0 +1,957 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ArduPlanePidConfig</class>
<widget class="QWidget" name="ArduPlanePidConfig">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>733</width>
<height>641</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QWidget" name="gridLayoutWidget">
<property name="geometry">
<rect>
<x>20</x>
<y>10</y>
<width>681</width>
<height>581</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string>L1 Control - Turn Control</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_29">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_11">
<item>
<layout class="QVBoxLayout" name="verticalLayout_27">
<item>
<widget class="QLabel" name="label_41">
<property name="text">
<string>Period</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_42">
<property name="text">
<string>Damping</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_28">
<item>
<widget class="QDoubleSpinBox" name="l1PeriodSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="l1DampingSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.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="0" column="0">
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Servo Roll Pid</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>
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_4">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QDoubleSpinBox" name="servoRollPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoRollISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoRollDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoIMAXSpinBox">
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="1" column="2">
<widget class="QGroupBox" name="groupBox_6">
<property name="title">
<string>Nav Pitch Alt Pid</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_18">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<layout class="QVBoxLayout" name="verticalLayout_11">
<item>
<widget class="QLabel" name="label_21">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_22">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_23">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_24">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_12">
<item>
<widget class="QDoubleSpinBox" name="navAltPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navAltISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navAltDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navAltIMAXSpinBox">
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="1" column="1">
<widget class="QGroupBox" name="groupBox_4">
<property name="title">
<string>Nav Pitch AS Pid</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QLabel" name="label_17">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_18">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_19">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_20">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_10">
<item>
<widget class="QDoubleSpinBox" name="navASPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navASISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navASDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navASIMAXSpinBox">
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="0" column="2">
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
<string>Servo Yaw Pid</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_9">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_10">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_11">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_12">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<widget class="QDoubleSpinBox" name="servoYawPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoYawISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoYawDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoYawIMAXSpinBox">
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="2" column="2">
<widget class="QGroupBox" name="groupBox_7">
<property name="title">
<string>Throttle 0-100%</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_31">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<layout class="QVBoxLayout" name="verticalLayout_19">
<item>
<widget class="QLabel" name="label_25">
<property name="text">
<string>Cruise</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_26">
<property name="text">
<string>Min</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_27">
<property name="text">
<string>Max</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_28">
<property name="text">
<string>FS Value</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_20">
<item>
<widget class="QDoubleSpinBox" name="throttleCruiseSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="throttleMinSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="throttleMaxSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="throttleFSSpinBox">
<property name="maximum">
<double>100.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>Servo Pitch Pid</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_5">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_6">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_8">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QDoubleSpinBox" name="servoPitchPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoPitchISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoPitchDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="servoPitchIMAXSpinBox">
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="3" column="2">
<widget class="QGroupBox" name="groupBox_8">
<property name="title">
<string>Aiespeed m/s</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_32">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_10">
<item>
<layout class="QVBoxLayout" name="verticalLayout_25">
<item>
<widget class="QLabel" name="label_37">
<property name="text">
<string>Cruise</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_38">
<property name="text">
<string>FBW min</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_39">
<property name="text">
<string>FBW max</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_40">
<property name="text">
<string>Ratio</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_26">
<item>
<widget class="QDoubleSpinBox" name="airspeedCruiseSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="airspeedFBWMinSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="airspeedFBWMaxSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="airspeedRatioSpinBox">
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="2" column="1">
<widget class="QGroupBox" name="groupBox_9">
<property name="title">
<string>Other Mix's</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_30">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_8">
<item>
<layout class="QVBoxLayout" name="verticalLayout_21">
<item>
<widget class="QLabel" name="label_29">
<property name="text">
<string>P to T</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_30">
<property name="text">
<string>Pitch Comp</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_31">
<property name="text">
<string>Rudder Mix</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_22">
<item>
<widget class="QDoubleSpinBox" name="otherPtTSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="otherPitchCompSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="otherRudderMixSpinBox">
<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="3" column="1">
<widget class="QGroupBox" name="groupBox_10">
<property name="title">
<string>Navigation Angles</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_33">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_9">
<item>
<layout class="QVBoxLayout" name="verticalLayout_23">
<item>
<widget class="QLabel" name="label_33">
<property name="text">
<string>Bank Max</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_34">
<property name="text">
<string>Pitch Max</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_35">
<property name="text">
<string>Pitch Min</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_24">
<item>
<widget class="QDoubleSpinBox" name="navBankMaxSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navPitchMaxSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="navPitchMinSpinBox">
<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_11">
<property name="title">
<string>Energy/Alt Pid</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
<widget class="QLabel" name="label_13">
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_14">
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_15">
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_16">
<property name="text">
<string>INT_MAX</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_8">
<item>
<widget class="QDoubleSpinBox" name="energyPSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="energyISpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="energyDSpinBox">
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="energyIMAXSpinBox">
<property name="maximum">
<double>100.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<widget class="QPushButton" name="writePushButton">
<property name="geometry">
<rect>
<x>260</x>
<y>600</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>350</x>
<y>600</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Refresh Params</string>
</property>
</widget>
</widget>
<resources/>
<connections/>
</ui>
Loading…
Cancel
Save