Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
4cd86dec
Commit
4cd86dec
authored
Jul 16, 2013
by
Bill Bonney
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'new_menus' of
https://github.com/diydrones/apm_planner
into new_menus
Conflicts: qgroundcontrol.pro
parents
75def93b
98dc9dfc
Changes
41
Hide whitespace changes
Inline
Side-by-side
Showing
41 changed files
with
5339 additions
and
319 deletions
+5339
-319
qgroundcontrol.pro
qgroundcontrol.pro
+18
-3
QGCCore.cc
src/QGCCore.cc
+1
-1
AccelCalibrationConfig.ui
src/ui/configuration/AccelCalibrationConfig.ui
+4
-4
AdvParameterList.cc
src/ui/configuration/AdvParameterList.cc
+55
-0
AdvParameterList.h
src/ui/configuration/AdvParameterList.h
+25
-0
AdvParameterList.ui
src/ui/configuration/AdvParameterList.ui
+31
-0
AdvancedParamConfig.cc
src/ui/configuration/AdvancedParamConfig.cc
+25
-1
AdvancedParamConfig.h
src/ui/configuration/AdvancedParamConfig.h
+8
-3
AdvancedParamConfig.ui
src/ui/configuration/AdvancedParamConfig.ui
+33
-15
ApmHardwareConfig.cc
src/ui/configuration/ApmHardwareConfig.cc
+34
-16
ApmHardwareConfig.h
src/ui/configuration/ApmHardwareConfig.h
+2
-0
ApmHardwareConfig.ui
src/ui/configuration/ApmHardwareConfig.ui
+20
-1
ApmPlaneLevel.cc
src/ui/configuration/ApmPlaneLevel.cc
+59
-0
ApmPlaneLevel.h
src/ui/configuration/ApmPlaneLevel.h
+23
-0
ApmPlaneLevel.ui
src/ui/configuration/ApmPlaneLevel.ui
+99
-0
ApmSoftwareConfig.cc
src/ui/configuration/ApmSoftwareConfig.cc
+398
-20
ApmSoftwareConfig.h
src/ui/configuration/ApmSoftwareConfig.h
+7
-2
ApmSoftwareConfig.ui
src/ui/configuration/ApmSoftwareConfig.ui
+190
-207
ArduCopterPidConfig.cc
src/ui/configuration/ArduCopterPidConfig.cc
+188
-6
ArduCopterPidConfig.h
src/ui/configuration/ArduCopterPidConfig.h
+12
-6
ArduCopterPidConfig.ui
src/ui/configuration/ArduCopterPidConfig.ui
+1031
-2
ArduPlanePidConfig.cc
src/ui/configuration/ArduPlanePidConfig.cc
+97
-0
ArduPlanePidConfig.h
src/ui/configuration/ArduPlanePidConfig.h
+24
-0
ArduPlanePidConfig.ui
src/ui/configuration/ArduPlanePidConfig.ui
+963
-0
ArduRoverPidConfig.cc
src/ui/configuration/ArduRoverPidConfig.cc
+78
-0
ArduRoverPidConfig.h
src/ui/configuration/ArduRoverPidConfig.h
+23
-0
ArduRoverPidConfig.ui
src/ui/configuration/ArduRoverPidConfig.ui
+732
-0
BatteryMonitorConfig.cc
src/ui/configuration/BatteryMonitorConfig.cc
+18
-0
BatteryMonitorConfig.h
src/ui/configuration/BatteryMonitorConfig.h
+2
-0
CompassConfig.cc
src/ui/configuration/CompassConfig.cc
+41
-0
CompassConfig.ui
src/ui/configuration/CompassConfig.ui
+4
-4
FailSafeConfig.cc
src/ui/configuration/FailSafeConfig.cc
+390
-1
FailSafeConfig.h
src/ui/configuration/FailSafeConfig.h
+16
-3
FailSafeConfig.ui
src/ui/configuration/FailSafeConfig.ui
+422
-2
ParamWidget.cc
src/ui/configuration/ParamWidget.cc
+79
-0
ParamWidget.h
src/ui/configuration/ParamWidget.h
+34
-0
ParamWidget.ui
src/ui/configuration/ParamWidget.ui
+78
-0
SonarConfig.ui
src/ui/configuration/SonarConfig.ui
+1
-1
StandardParamConfig.cc
src/ui/configuration/StandardParamConfig.cc
+32
-3
StandardParamConfig.h
src/ui/configuration/StandardParamConfig.h
+9
-3
StandardParamConfig.ui
src/ui/configuration/StandardParamConfig.ui
+33
-15
No files found.
qgroundcontrol.pro
View file @
4cd86dec
...
...
@@ -255,7 +255,12 @@ FORMS += src/ui/MainWindow.ui \
src
/
ui
/
configuration
/
GeoFenceConfig
.
ui
\
src
/
ui
/
configuration
/
FailSafeConfig
.
ui
\
src
/
ui
/
configuration
/
AdvancedParamConfig
.
ui
\
src
/
ui
/
configuration
/
ArduCopterPidConfig
.
ui
src
/
ui
/
configuration
/
ArduCopterPidConfig
.
ui
\
src
/
ui
/
configuration
/
ApmPlaneLevel
.
ui
\
src
/
ui
/
configuration
/
ParamWidget
.
ui
\
src
/
ui
/
configuration
/
ArduPlanePidConfig
.
ui
\
src
/
ui
/
configuration
/
AdvParameterList
.
ui
\
src
/
ui
/
configuration
/
ArduRoverPidConfig
.
ui
INCLUDEPATH
+=
src
\
src
/
ui
\
src
/
ui
/
linechart
\
...
...
@@ -437,7 +442,12 @@ HEADERS += src/MG.h \
src
/
ui
/
configuration
/
FailSafeConfig
.
h
\
src
/
ui
/
configuration
/
AdvancedParamConfig
.
h
\
src
/
ui
/
configuration
/
ArduCopterPidConfig
.
h
\
src
/
ui
/
apmtoolbar
.
h
src
/
ui
/
apmtoolbar
.
h
\
src
/
ui
/
configuration
/
ApmPlaneLevel
.
h
\
src
/
ui
/
configuration
/
ParamWidget
.
h
\
src
/
ui
/
configuration
/
ArduPlanePidConfig
.
h
\
src
/
ui
/
configuration
/
AdvParameterList
.
h
\
src
/
ui
/
configuration
/
ArduRoverPidConfig
.
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
...
...
@@ -637,7 +647,12 @@ SOURCES += src/main.cc \
src
/
ui
/
configuration
/
FailSafeConfig
.
cc
\
src
/
ui
/
configuration
/
AdvancedParamConfig
.
cc
\
src
/
ui
/
configuration
/
ArduCopterPidConfig
.
cc
\
src
/
ui
/
apmtoolbar
.
cpp
src
/
ui
/
apmtoolbar
.
cpp
\
src
/
ui
/
configuration
/
ApmPlaneLevel
.
cc
\
src
/
ui
/
configuration
/
ParamWidget
.
cc
\
src
/
ui
/
configuration
/
ArduPlanePidConfig
.
cc
\
src
/
ui
/
configuration
/
AdvParameterList
.
cc
\
src
/
ui
/
configuration
/
ArduRoverPidConfig
.
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
...
...
src/QGCCore.cc
View file @
4cd86dec
...
...
@@ -72,7 +72,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
this
->
setApplicationName
(
QGC_APPLICATION_NAME
);
this
->
setApplicationVersion
(
QGC_APPLICATION_VERSION
);
this
->
setOrganizationName
(
QLatin1String
(
"diydrones"
));
this
->
setOrganizationDomain
(
"
org
.diydrones"
);
this
->
setOrganizationDomain
(
"
com
.diydrones"
);
// Set settings format
QSettings
::
setDefaultFormat
(
QSettings
::
IniFormat
);
...
...
src/ui/configuration/AccelCalibrationConfig.ui
View file @
4cd86dec
...
...
@@ -34,8 +34,8 @@
<rect>
<x>
70
</x>
<y>
160
</y>
<width>
8
1
</width>
<height>
3
1
</height>
<width>
11
1
</width>
<height>
4
1
</height>
</rect>
</property>
<property
name=
"text"
>
...
...
@@ -48,8 +48,8 @@ Accelerometer</string>
<rect>
<x>
20
</x>
<y>
50
</y>
<width>
2
11
</width>
<height>
9
1
</height>
<width>
3
11
</width>
<height>
10
1
</height>
</rect>
</property>
<property
name=
"text"
>
...
...
src/ui/configuration/AdvParameterList.cc
0 → 100644
View file @
4cd86dec
#include "AdvParameterList.h"
AdvParameterList
::
AdvParameterList
(
QWidget
*
parent
)
:
AP2ConfigWidget
(
parent
)
{
ui
.
setupUi
(
this
);
ui
.
tableWidget
->
setColumnCount
(
4
);
ui
.
tableWidget
->
horizontalHeader
()
->
hide
();
ui
.
tableWidget
->
verticalHeader
()
->
hide
();
//ui.tableWidget->setHorizontalHeader(0);
//ui.tableWidget->setVerticalHeader(0);
ui
.
tableWidget
->
setColumnWidth
(
0
,
200
);
ui
.
tableWidget
->
setColumnWidth
(
1
,
100
);
ui
.
tableWidget
->
setColumnWidth
(
2
,
200
);
ui
.
tableWidget
->
setColumnWidth
(
3
,
800
);
}
AdvParameterList
::~
AdvParameterList
()
{
}
void
AdvParameterList
::
setParameterMetaData
(
QString
name
,
QString
humanname
,
QString
description
)
{
paramToNameMap
[
name
]
=
humanname
;
paramToDescriptionMap
[
name
]
=
description
;
}
void
AdvParameterList
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
!
paramValueMap
.
contains
(
parameterName
))
{
ui
.
tableWidget
->
setRowCount
(
ui
.
tableWidget
->
rowCount
()
+
1
);
if
(
paramToNameMap
.
contains
(
parameterName
))
{
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
0
,
new
QTableWidgetItem
(
paramToNameMap
[
parameterName
]));
}
else
{
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
0
,
new
QTableWidgetItem
(
"Unknown"
));
}
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
1
,
new
QTableWidgetItem
(
QString
::
number
(
value
.
toFloat
(),
'f'
,
2
)));
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
2
,
new
QTableWidgetItem
(
parameterName
));
if
(
paramToDescriptionMap
.
contains
(
parameterName
))
{
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
3
,
new
QTableWidgetItem
(
paramToDescriptionMap
[
parameterName
]));
}
else
{
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
3
,
new
QTableWidgetItem
(
"Unknown"
));
}
paramValueMap
[
parameterName
]
=
ui
.
tableWidget
->
item
(
ui
.
tableWidget
->
rowCount
()
-
1
,
1
);
}
paramValueMap
[
parameterName
]
->
setText
(
QString
::
number
(
value
.
toFloat
(),
'f'
,
2
));
}
src/ui/configuration/AdvParameterList.h
0 → 100644
View file @
4cd86dec
#ifndef ADVPARAMETERLIST_H
#define ADVPARAMETERLIST_H
#include <QWidget>
#include "ui_AdvParameterList.h"
#include "AP2ConfigWidget.h"
class
AdvParameterList
:
public
AP2ConfigWidget
{
Q_OBJECT
public:
explicit
AdvParameterList
(
QWidget
*
parent
=
0
);
void
setParameterMetaData
(
QString
name
,
QString
humanname
,
QString
description
);
~
AdvParameterList
();
private
slots
:
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QMap
<
QString
,
QTableWidgetItem
*>
paramValueMap
;
QMap
<
QString
,
QString
>
paramToNameMap
;
QMap
<
QString
,
QString
>
paramToDescriptionMap
;
Ui
::
AdvParameterList
ui
;
};
#endif // ADVPARAMETERLIST_H
src/ui/configuration/AdvParameterList.ui
0 → 100644
View file @
4cd86dec
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
AdvParameterList
</class>
<widget
class=
"QWidget"
name=
"AdvParameterList"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
666
</width>
<height>
497
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<item>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"text"
>
<string>
<
h2
>
Advanced Parameter List
<
/h2
>
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QTableWidget"
name=
"tableWidget"
/>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
src/ui/configuration/AdvancedParamConfig.cc
View file @
4cd86dec
#include "AdvancedParamConfig.h"
AdvancedParamConfig
::
AdvancedParamConfig
(
QWidget
*
parent
)
:
Q
Widget
(
parent
)
AdvancedParamConfig
::
AdvancedParamConfig
(
QWidget
*
parent
)
:
AP2Config
Widget
(
parent
)
{
ui
.
setupUi
(
this
);
}
...
...
@@ -9,3 +9,27 @@ AdvancedParamConfig::AdvancedParamConfig(QWidget *parent) : QWidget(parent)
AdvancedParamConfig
::~
AdvancedParamConfig
()
{
}
void
AdvancedParamConfig
::
addRange
(
QString
title
,
QString
description
,
QString
param
,
double
min
,
double
max
)
{
ParamWidget
*
widget
=
new
ParamWidget
(
ui
.
scrollAreaWidgetContents
);
paramToWidgetMap
[
param
]
=
widget
;
widget
->
setupDouble
(
title
+
"("
+
param
+
")"
,
description
,
0
,
min
,
max
);
ui
.
verticalLayout
->
addWidget
(
widget
);
widget
->
show
();
}
void
AdvancedParamConfig
::
addCombo
(
QString
title
,
QString
description
,
QString
param
,
QList
<
QPair
<
int
,
QString
>
>
valuelist
)
{
ParamWidget
*
widget
=
new
ParamWidget
(
ui
.
scrollAreaWidgetContents
);
paramToWidgetMap
[
param
]
=
widget
;
widget
->
setupCombo
(
title
+
"("
+
param
+
")"
,
description
,
valuelist
);
ui
.
verticalLayout
->
addWidget
(
widget
);
widget
->
show
();
}
void
AdvancedParamConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
paramToWidgetMap
.
contains
(
parameterName
))
{
paramToWidgetMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
}
}
src/ui/configuration/AdvancedParamConfig.h
View file @
4cd86dec
...
...
@@ -3,16 +3,21 @@
#include <QWidget>
#include "ui_AdvancedParamConfig.h"
class
AdvancedParamConfig
:
public
QWidget
#include "AP2ConfigWidget.h"
#include "ParamWidget.h"
class
AdvancedParamConfig
:
public
AP2ConfigWidget
{
Q_OBJECT
public:
explicit
AdvancedParamConfig
(
QWidget
*
parent
=
0
);
~
AdvancedParamConfig
();
void
addRange
(
QString
title
,
QString
description
,
QString
param
,
double
min
,
double
max
);
void
addCombo
(
QString
title
,
QString
description
,
QString
param
,
QList
<
QPair
<
int
,
QString
>
>
valuelist
);
private
slots
:
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QMap
<
QString
,
ParamWidget
*>
paramToWidgetMap
;
Ui
::
AdvancedParamConfig
ui
;
};
...
...
src/ui/configuration/AdvancedParamConfig.ui
View file @
4cd86dec
...
...
@@ -6,26 +6,44 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
400
</width>
<height>
300
</height>
<width>
725
</width>
<height>
632
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"geometry"
>
<rect>
<x>
10
</x>
<y>
10
</y>
<width>
181
</width>
<height>
31
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
<
h2
>
Advanced Params
<
/h2
>
</string>
</property>
</widget>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_3"
>
<item>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"text"
>
<string>
<
h2
>
Advanced Params
<
/h2
>
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QScrollArea"
name=
"scrollArea"
>
<property
name=
"widgetResizable"
>
<bool>
true
</bool>
</property>
<widget
class=
"QWidget"
name=
"scrollAreaWidgetContents"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
705
</width>
<height>
585
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_2"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
/>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
...
...
src/ui/configuration/ApmHardwareConfig.cc
View file @
4cd86dec
...
...
@@ -30,35 +30,28 @@ This file is part of the QGROUNDCONTROL project
*/
#include "ApmHardwareConfig.h"
ApmHardwareConfig
::
ApmHardwareConfig
(
QWidget
*
parent
)
:
QWidget
(
parent
)
{
ui
.
setupUi
(
this
);
//ui.firmwareButton->setVisible(valse);
ui
.
manditoryHardware
->
setVisible
(
false
);
ui
.
frameTypeButton
->
setVisible
(
false
);
ui
.
compassButton
->
setVisible
(
false
);
ui
.
accelCalibrateButton
->
setVisible
(
false
);
ui
.
arduPlaneLevelButton
->
setVisible
(
false
);
ui
.
radioCalibrateButton
->
setVisible
(
false
);
ui
.
optionalHardwareButton
->
setVisible
(
false
);
//ui.radio3DRButton->setVisible(false);
ui
.
batteryMonitorButton
->
setVisible
(
false
);
ui
.
sonarButton
->
setVisible
(
false
);
ui
.
airspeedButton
->
setVisible
(
false
);
ui
.
opticalFlowButton
->
setVisible
(
false
);
ui
.
osdButton
->
setVisible
(
false
);
ui
.
cameraGimbalButton
->
setVisible
(
false
);
//ui.antennaTrackerButton->setVisible(false);
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
frameTypeButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
compassButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
accelCalibrateButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
radioCalibrateButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
radio3DRButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
batteryMonitorButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
sonarButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
airspeedButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
opticalFlowButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
osdButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
cameraGimbalButton
,
SLOT
(
setShown
(
bool
)));
...
...
@@ -87,6 +80,11 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap
[
ui
.
accelCalibrateButton
]
=
accelConfig
;
connect
(
ui
.
accelCalibrateButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
planeLevel
=
new
ApmPlaneLevel
(
this
);
ui
.
stackedWidget
->
addWidget
(
planeLevel
);
buttonToConfigWidgetMap
[
ui
.
arduPlaneLevelButton
]
=
planeLevel
;
connect
(
ui
.
arduPlaneLevelButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
radioConfig
=
new
RadioCalibrationConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
radioConfig
);
buttonToConfigWidgetMap
[
ui
.
radioCalibrateButton
]
=
radioConfig
;
...
...
@@ -133,8 +131,6 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap
[
ui
.
antennaTrackerButton
]
=
antennaTrackerConfig
;
connect
(
ui
.
antennaTrackerButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
if
(
UASManager
::
instance
()
->
getActiveUAS
())
{
...
...
@@ -159,11 +155,33 @@ void ApmHardwareConfig::activeUASSet(UASInterface *uas)
{
return
;
}
if
(
uas
->
getSystemType
()
==
MAV_TYPE_FIXED_WING
)
{
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
compassButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
arduPlaneLevelButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
radioCalibrateButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
optionalHardwareButton
,
SIGNAL
(
toggled
(
bool
)),
ui
.
airspeedButton
,
SLOT
(
setShown
(
bool
)));
}
else
if
(
uas
->
getSystemType
()
==
MAV_TYPE_QUADROTOR
)
{
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
frameTypeButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
compassButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
accelCalibrateButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
radioCalibrateButton
,
SLOT
(
setShown
(
bool
)));
}
else
if
(
uas
->
getSystemType
()
==
MAV_TYPE_GROUND_ROVER
)
{
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
compassButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
radioCalibrateButton
,
SLOT
(
setShown
(
bool
)));
}
else
{
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
compassButton
,
SLOT
(
setShown
(
bool
)));
connect
(
ui
.
manditoryHardware
,
SIGNAL
(
toggled
(
bool
)),
ui
.
radioCalibrateButton
,
SLOT
(
setShown
(
bool
)));
}
ui
.
firmwareButton
->
setVisible
(
true
);
ui
.
manditoryHardware
->
setVisible
(
true
);
ui
.
manditoryHardware
->
setChecked
(
fals
e
);
ui
.
manditoryHardware
->
setChecked
(
tru
e
);
ui
.
optionalHardwareButton
->
setVisible
(
true
);
ui
.
optionalHardwareButton
->
setChecked
(
false
);
ui
.
radio3DRButton
->
setVisible
(
false
);
ui
.
antennaTrackerButton
->
setVisible
(
false
);
ui
.
optionalHardwareButton
->
setChecked
(
true
);
}
src/ui/configuration/ApmHardwareConfig.h
View file @
4cd86dec
...
...
@@ -48,6 +48,7 @@ This file is part of the QGROUNDCONTROL project
#include "OsdConfig.h"
#include "CameraGimbalConfig.h"
#include "AntennaTrackerConfig.h"
#include "ApmPlaneLevel.h"
class
ApmHardwareConfig
:
public
QWidget
{
...
...
@@ -70,6 +71,7 @@ private:
OsdConfig
*
osdConfig
;
CameraGimbalConfig
*
cameraGimbalConfig
;
AntennaTrackerConfig
*
antennaTrackerConfig
;
ApmPlaneLevel
*
planeLevel
;
private
slots
:
void
activeUASSet
(
UASInterface
*
uas
);
void
activateStackedWidget
();
...
...
src/ui/configuration/ApmHardwareConfig.ui
View file @
4cd86dec
...
...
@@ -43,7 +43,7 @@
<x>
0
</x>
<y>
0
</y>
<width>
156
</width>
<height>
6
35
</height>
<height>
6
76
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_12"
>
...
...
@@ -129,6 +129,25 @@
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"arduPlaneLevelButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"layoutDirection"
>
<enum>
Qt::LeftToRight
</enum>
</property>
<property
name=
"autoFillBackground"
>
<bool>
false
</bool>
</property>
<property
name=
"text"
>
<string>
ArduPlane Level
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"radioCalibrateButton"
>
<property
name=
"minimumSize"
>
...
...
src/ui/configuration/ApmPlaneLevel.cc
0 → 100644
View file @
4cd86dec
#include "ApmPlaneLevel.h"
#include <QMessageBox>
ApmPlaneLevel
::
ApmPlaneLevel
(
QWidget
*
parent
)
:
AP2ConfigWidget
(
parent
)
{
ui
.
setupUi
(
this
);
connect
(
ui
.
levelPushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
levelClicked
()));
connect
(
ui
.
manualLevelCheckBox
,
SIGNAL
(
toggled
(
bool
)),
this
,
SLOT
(
manualCheckBoxToggled
(
bool
)));
}
ApmPlaneLevel
::~
ApmPlaneLevel
()
{
}
void
ApmPlaneLevel
::
levelClicked
()
{
QMessageBox
::
information
(
0
,
"Warning"
,
"Be sure the plane is completly level, then click ok"
);
MAV_CMD
command
=
MAV_CMD_PREFLIGHT_CALIBRATION
;
int
confirm
=
0
;
float
param1
=
1
;
float
param2
=
0
;
float
param3
=
1
;
float
param4
=
0
;
float
param5
=
0
;
float
param6
=
0
;
float
param7
=
0
;
int
component
=
1
;
m_uas
->
executeCommand
(
command
,
confirm
,
param1
,
param2
,
param3
,
param4
,
param5
,
param6
,
param7
,
component
);
QMessageBox
::
information
(
0
,
"Warning"
,
"Leveling completed"
);
}
void
ApmPlaneLevel
::
manualCheckBoxToggled
(
bool
checked
)
{
if
(
!
m_uas
)
{
return
;
}
if
(
checked
)
{
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"MANUAL_LEVEL"
,
1
);
}
else
{
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"MANUAL_LEVEL"
,
0
);
}
}
void
ApmPlaneLevel
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
parameterName
==
"MANUAL_LEVEL"
)
{
if
(
value
.
toInt
()
==
1
)
{
ui
.
manualLevelCheckBox
->
setChecked
(
true
);
}
else
{
ui
.
manualLevelCheckBox
->
setChecked
(
false
);
}
}
}
src/ui/configuration/ApmPlaneLevel.h
0 → 100644
View file @
4cd86dec
#ifndef APMPLANELEVEL_H
#define APMPLANELEVEL_H
#include <QWidget>
#include "ui_ApmPlaneLevel.h"
#include "AP2ConfigWidget.h"
class
ApmPlaneLevel
:
public
AP2ConfigWidget
{
Q_OBJECT
public:
explicit
ApmPlaneLevel
(
QWidget
*
parent
=
0
);
~
ApmPlaneLevel
();
private
slots
:
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
void
levelClicked
();
void
manualCheckBoxToggled
(
bool
checked
);
private:
Ui
::
ApmPlaneLevel
ui
;
};
#endif // APMPLANELEVEL_H
src/ui/configuration/ApmPlaneLevel.ui
0 → 100644
View file @
4cd86dec
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
ApmPlaneLevel
</class>
<widget
class=
"QWidget"
name=
"ApmPlaneLevel"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
400
</width>
<height>
300
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"geometry"
>
<rect>
<x>
10
</x>
<y>
10
</y>
<width>
141
</width>
<height>
31
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
<
h2
>
ArduPlane Level
<
/h2
>
</string>
</property>
</widget>
<widget
class=
"QLabel"
name=
"label_2"
>
<property
name=
"geometry"
>
<rect>
<x>
50
</x>
<y>
70
</y>
<width>
271
</width>
<height>
41
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
By Default your plane will autolevel on every boot.
To disable this action you need to turn on manual
level and perform a level to calibrate the accel offsets.
</string>
</property>
</widget>
<widget
class=
"QLabel"
name=
"label_3"
>
<property
name=
"geometry"
>
<rect>
<x>
50
</x>
<y>
150
</y>
<width>
291
</width>
<height>
16
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
Level your plane and click Level to set default accel offsets
</string>
</property>
</widget>
<widget
class=
"QPushButton"
name=
"levelPushButton"
>
<property
name=
"geometry"
>
<rect>
<x>
160
</x>
<y>
180
</y>
<width>
75
</width>
<height>
23
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
Level
</string>
</property>
</widget>
<widget
class=
"QGroupBox"
name=
"groupBox"
>
<property
name=
"geometry"
>
<rect>
<x>
120
</x>
<y>
230
</y>
<width>
151
</width>
<height>
51
</height>
</rect>
</property>
<property
name=
"title"
>
<string>
For advanced users ONLY
</string>
</property>
<widget
class=
"QCheckBox"
name=
"manualLevelCheckBox"
>
<property
name=
"geometry"
>
<rect>
<x>
30
</x>
<y>
20
</y>
<width>
91
</width>
<height>
17
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
Manual Level
</string>
</property>
</widget>
</widget>
</widget>
<resources/>
<connections/>
</ui>
src/ui/configuration/ApmSoftwareConfig.cc
View file @
4cd86dec
#include "ApmSoftwareConfig.h"
#include <QXmlStreamReader>
#include <QDir>
#include <QFile>
ApmSoftwareConfig
::
ApmSoftwareConfig
(
QWidget
*
parent
)
:
QWidget
(
parent
)
{
ui
.
setupUi
(
this
);
ui
.
basicPidsButton
->
setVisible
(
false
);
ui
.
flightModesButton
->
setVisible
(
false
);
ui
.
standardParamButton
->
setVisible
(
false
);
ui
.
geoFenceButton
->
setVisible
(
false
);
ui
.
failSafeButton
->
setVisible
(
false
);
ui
.
advancedParamButton
->
setVisible
(
false
);
ui
.
advParamListButton
->
setVisible
(
false
);
ui
.
arduCoperPidButton
->
setVisible
(
false
);
basicPidConfig
=
new
BasicPidConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
basicPidConfig
);
buttonToConfigWidgetMap
[
ui
.
basicPidsButton
]
=
basicPidConfig
;
connect
(
ui
.
basicPidsButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
ui
.
arduCopterPidButton
->
setVisible
(
false
);
ui
.
arduRoverPidButton
->
setVisible
(
false
);
ui
.
arduPlanePidButton
->
setVisible
(
false
);
flightConfig
=
new
FlightModeConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
flightConfig
);
...
...
@@ -29,11 +27,6 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap
[
ui
.
standardParamButton
]
=
standardParamConfig
;
connect
(
ui
.
standardParamButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
geoFenceConfig
=
new
GeoFenceConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
geoFenceConfig
);
buttonToConfigWidgetMap
[
ui
.
geoFenceButton
]
=
geoFenceConfig
;
connect
(
ui
.
geoFenceButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
failSafeConfig
=
new
FailSafeConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
failSafeConfig
);
buttonToConfigWidgetMap
[
ui
.
failSafeButton
]
=
failSafeConfig
;
...
...
@@ -44,10 +37,25 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap
[
ui
.
advancedParamButton
]
=
advancedParamConfig
;
connect
(
ui
.
advancedParamButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
arduCoperPidConfig
=
new
ArduCopterPidConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
arduCoperPidConfig
);
buttonToConfigWidgetMap
[
ui
.
arduCoperPidButton
]
=
arduCoperPidConfig
;
connect
(
ui
.
arduCoperPidButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
advParameterList
=
new
AdvParameterList
(
this
);
ui
.
stackedWidget
->
addWidget
(
advParameterList
);
buttonToConfigWidgetMap
[
ui
.
advParamListButton
]
=
advParameterList
;
connect
(
ui
.
advParamListButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
arduCopterPidConfig
=
new
ArduCopterPidConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
arduCopterPidConfig
);
buttonToConfigWidgetMap
[
ui
.
arduCopterPidButton
]
=
arduCopterPidConfig
;
connect
(
ui
.
arduCopterPidButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
arduPlanePidConfig
=
new
ArduPlanePidConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
arduPlanePidConfig
);
buttonToConfigWidgetMap
[
ui
.
arduPlanePidButton
]
=
arduPlanePidConfig
;
connect
(
ui
.
arduPlanePidButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
arduRoverPidConfig
=
new
ArduRoverPidConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
arduRoverPidConfig
);
buttonToConfigWidgetMap
[
ui
.
arduRoverPidButton
]
=
arduRoverPidConfig
;
connect
(
ui
.
arduRoverPidButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
if
(
UASManager
::
instance
()
->
getActiveUAS
())
...
...
@@ -73,13 +81,383 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
return
;
}
ui
.
basicPidsButton
->
setVisible
(
true
);
ui
.
flightModesButton
->
setVisible
(
true
);
ui
.
standardParamButton
->
setVisible
(
true
);
ui
.
geoFenceButton
->
setVisible
(
true
);
ui
.
failSafeButton
->
setVisible
(
true
);
ui
.
advancedParamButton
->
setVisible
(
true
);
ui
.
advParamListButton
->
setVisible
(
true
);
ui
.
arduCoperPidButton
->
setVisible
(
true
);
if
(
uas
->
getSystemType
()
==
MAV_TYPE_FIXED_WING
)
{
ui
.
arduPlanePidButton
->
setVisible
(
true
);
ui
.
arduCopterPidButton
->
setVisible
(
false
);
ui
.
arduRoverPidButton
->
setVisible
(
false
);
}
else
if
(
uas
->
getSystemType
()
==
MAV_TYPE_QUADROTOR
)
{
ui
.
arduCopterPidButton
->
setVisible
(
true
);
ui
.
arduPlanePidButton
->
setVisible
(
false
);
ui
.
arduRoverPidButton
->
setVisible
(
false
);
}
else
if
(
uas
->
getSystemType
()
==
MAV_TYPE_GROUND_ROVER
)
{
ui
.
arduRoverPidButton
->
setVisible
(
true
);
ui
.
arduCopterPidButton
->
setVisible
(
false
);
ui
.
arduPlanePidButton
->
setVisible
(
false
);
}
QDir
autopilotdir
(
qApp
->
applicationDirPath
()
+
"/files/"
+
uas
->
getAutopilotTypeName
().
toLower
());
QFile
xmlfile
(
autopilotdir
.
absolutePath
()
+
"/arduplane.pdef.xml"
);
if
(
xmlfile
.
exists
()
&&
!
xmlfile
.
open
(
QIODevice
::
ReadOnly
))
{
return
;
}
QXmlStreamReader
xml
(
xmlfile
.
readAll
());
xmlfile
.
close
();
//TODO: Testing to ensure that incorrectly formated XML won't break this.
//Also, move this into the Param Manager, as it should handle all metadata.
while
(
!
xml
.
atEnd
())
{
if
(
xml
.
isStartElement
()
&&
xml
.
name
()
==
"paramfile"
)
{
xml
.
readNext
();
while
((
xml
.
name
()
!=
"paramfile"
)
&&
!
xml
.
atEnd
())
{
QString
valuetype
=
""
;
if
(
xml
.
isStartElement
()
&&
(
xml
.
name
()
==
"vehicles"
||
xml
.
name
()
==
"libraries"
))
//Enter into the vehicles loop
{
valuetype
=
xml
.
name
().
toString
();
xml
.
readNext
();
while
((
xml
.
name
()
!=
valuetype
)
&&
!
xml
.
atEnd
())
{
if
(
xml
.
isStartElement
()
&&
xml
.
name
()
==
"parameters"
)
//This is a parameter block
{
QString
parametersname
=
""
;
if
(
xml
.
attributes
().
hasAttribute
(
"name"
))
{
parametersname
=
xml
.
attributes
().
value
(
"name"
).
toString
();
}
QVariantMap
genset
;
QVariantMap
advset
;
QString
setname
=
parametersname
;
xml
.
readNext
();
int
genarraycount
=
0
;
int
advarraycount
=
0
;
while
((
xml
.
name
()
!=
"parameters"
)
&&
!
xml
.
atEnd
())
{
if
(
xml
.
isStartElement
()
&&
xml
.
name
()
==
"param"
)
{
QString
humanname
=
xml
.
attributes
().
value
(
"humanName"
).
toString
();
QString
name
=
xml
.
attributes
().
value
(
"name"
).
toString
();
QString
tab
=
xml
.
attributes
().
value
(
"user"
).
toString
();
if
(
tab
==
"Advanced"
)
{
advset
[
"title"
]
=
parametersname
;
}
else
{
genset
[
"title"
]
=
parametersname
;
}
if
(
name
.
contains
(
":"
))
{
name
=
name
.
split
(
":"
)[
1
];
}
QString
docs
=
xml
.
attributes
().
value
(
"documentation"
).
toString
();
//paramTooltips[name] = name + " - " + docs;
int
type
=
-
1
;
//Type of item
QMap
<
QString
,
QString
>
fieldmap
;
QMap
<
QString
,
QString
>
valuemap
;
xml
.
readNext
();
while
((
xml
.
name
()
!=
"param"
)
&&
!
xml
.
atEnd
())
{
if
(
xml
.
isStartElement
()
&&
xml
.
name
()
==
"values"
)
{
type
=
1
;
//1 is a combobox
if
(
tab
==
"Advanced"
)
{
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"TYPE"
]
=
"COMBO"
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_DESCRIPTION"
]
=
humanname
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_PARAMID"
]
=
name
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_COMPONENTID"
]
=
1
;
}
else
{
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"TYPE"
]
=
"COMBO"
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_DESCRIPTION"
]
=
humanname
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_PARAMID"
]
=
name
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_COMPONENTID"
]
=
1
;
}
int
paramcount
=
0
;
xml
.
readNext
();
while
((
xml
.
name
()
!=
"values"
)
&&
!
xml
.
atEnd
())
{
if
(
xml
.
isStartElement
()
&&
xml
.
name
()
==
"value"
)
{
QString
code
=
xml
.
attributes
().
value
(
"code"
).
toString
();
QString
arg
=
xml
.
readElementText
();
valuemap
[
code
]
=
arg
;
if
(
tab
==
"Advanced"
)
{
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_ITEM_"
+
QString
::
number
(
paramcount
)
+
"_TEXT"
]
=
arg
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_ITEM_"
+
QString
::
number
(
paramcount
)
+
"_VAL"
]
=
code
.
toInt
();
}
else
{
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_ITEM_"
+
QString
::
number
(
paramcount
)
+
"_TEXT"
]
=
arg
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_ITEM_"
+
QString
::
number
(
paramcount
)
+
"_VAL"
]
=
code
.
toInt
();
}
paramcount
++
;
}
xml
.
readNext
();
}
if
(
tab
==
"Advanced"
)
{
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_COUNT"
]
=
paramcount
;
}
else
{
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_COMBOBOX_COUNT"
]
=
paramcount
;
}
}
if
(
xml
.
isStartElement
()
&&
xml
.
name
()
==
"field"
)
{
type
=
2
;
//2 is a slider
QString
fieldtype
=
xml
.
attributes
().
value
(
"name"
).
toString
();
QString
text
=
xml
.
readElementText
();
fieldmap
[
fieldtype
]
=
text
;
}
xml
.
readNext
();
}
if
(
type
==
-
1
)
{
//Nothing inside! Assume it's a value, give it a default range.
type
=
2
;
QString
fieldtype
=
"Range"
;
QString
text
=
"0 100"
;
//TODO: Determine a better way of figuring out default ranges.
fieldmap
[
fieldtype
]
=
text
;
}
if
(
type
==
2
)
{
if
(
tab
==
"Advanced"
)
{
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"TYPE"
]
=
"SLIDER"
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_DESCRIPTION"
]
=
humanname
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_PARAMID"
]
=
name
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_COMPONENTID"
]
=
1
;
}
else
{
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"TYPE"
]
=
"SLIDER"
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_DESCRIPTION"
]
=
humanname
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_PARAMID"
]
=
name
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_COMPONENTID"
]
=
1
;
}
if
(
fieldmap
.
contains
(
"Range"
))
{
float
min
=
0
;
float
max
=
0
;
//Some range fields list "0-10" and some list "0 10". Handle both.
if
(
fieldmap
[
"Range"
].
split
(
" "
).
size
()
>
1
)
{
min
=
fieldmap
[
"Range"
].
split
(
" "
)[
0
].
trimmed
().
toFloat
();
max
=
fieldmap
[
"Range"
].
split
(
" "
)[
1
].
trimmed
().
toFloat
();
}
else
if
(
fieldmap
[
"Range"
].
split
(
"-"
).
size
()
>
1
)
{
min
=
fieldmap
[
"Range"
].
split
(
"-"
)[
0
].
trimmed
().
toFloat
();
max
=
fieldmap
[
"Range"
].
split
(
"-"
)[
1
].
trimmed
().
toFloat
();
}
if
(
tab
==
"Advanced"
)
{
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_MIN"
]
=
min
;
advset
[
setname
+
"
\\
"
+
QString
::
number
(
advarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_MAX"
]
=
max
;
}
else
{
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_MIN"
]
=
min
;
genset
[
setname
+
"
\\
"
+
QString
::
number
(
genarraycount
)
+
"
\\
"
+
"QGC_PARAM_SLIDER_MAX"
]
=
max
;
}
}
}
if
(
tab
==
"Advanced"
)
{
advarraycount
++
;
advset
[
"count"
]
=
advarraycount
;
}
else
{
genarraycount
++
;
genset
[
"count"
]
=
genarraycount
;
}
//Right here we have a single param in memory
name
;
docs
;
valuemap
;
fieldmap
;
//standardParamConfig
if
(
valuemap
.
size
()
>
0
)
{
QList
<
QPair
<
int
,
QString
>
>
valuelist
;
for
(
QMap
<
QString
,
QString
>::
const_iterator
i
=
valuemap
.
constBegin
();
i
!=
valuemap
.
constEnd
();
i
++
)
{
valuelist
.
append
(
QPair
<
int
,
QString
>
(
i
.
key
().
toInt
(),
i
.
value
()));
}
if
(
tab
==
"Standard"
)
{
standardParamConfig
->
addCombo
(
humanname
,
docs
,
name
,
valuelist
);
}
else
if
(
tab
==
"Advanced"
)
{
advancedParamConfig
->
addCombo
(
humanname
,
docs
,
name
,
valuelist
);
}
advParameterList
->
setParameterMetaData
(
name
,
humanname
,
docs
);
}
else
if
(
fieldmap
.
size
()
>
0
)
{
float
min
=
0
;
float
max
=
100
;
if
(
fieldmap
.
contains
(
"Range"
))
{
float
min
=
0
;
float
max
=
0
;
//Some range fields list "0-10" and some list "0 10". Handle both.
if
(
fieldmap
[
"Range"
].
split
(
" "
).
size
()
>
1
)
{
min
=
fieldmap
[
"Range"
].
split
(
" "
)[
0
].
trimmed
().
toFloat
();
max
=
fieldmap
[
"Range"
].
split
(
" "
)[
1
].
trimmed
().
toFloat
();
}
else
if
(
fieldmap
[
"Range"
].
split
(
"-"
).
size
()
>
1
)
{
min
=
fieldmap
[
"Range"
].
split
(
"-"
)[
0
].
trimmed
().
toFloat
();
max
=
fieldmap
[
"Range"
].
split
(
"-"
)[
1
].
trimmed
().
toFloat
();
}
}
if
(
tab
==
"Standard"
)
{
standardParamConfig
->
addRange
(
humanname
,
docs
,
name
,
min
,
max
);
}
else
if
(
tab
==
"Advanced"
)
{
advancedParamConfig
->
addRange
(
humanname
,
docs
,
name
,
max
,
min
);
}
advParameterList
->
setParameterMetaData
(
name
,
humanname
,
docs
);
}
}
xml
.
readNext
();
}
if
(
genarraycount
>
0
)
{
/*
tool = new QGCToolWidget("", this);
tool->addUAS(mav);
tool->setTitle(parametersname);
tool->setObjectName(parametersname);
tool->setSettings(genset);
QList<QString> paramlist = tool->getParamList();
for (int i=0;i<paramlist.size();i++)
{
//Based on the airframe, we add the parameter to different categories.
if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
{
systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
}
else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
{
systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
}
else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
{
systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
}
else
{
libParamToWidgetMap->insert(paramlist[i],tool);
}
}
toolWidgets.append(tool);
QGroupBox *box = new QGroupBox(this);
box->setTitle(tool->objectName());
box->setLayout(new QVBoxLayout());
box->layout()->addWidget(tool);
if (valuetype == "vehicles")
{
ui->leftGeneralLayout->addWidget(box);
}
else if (valuetype == "libraries")
{
ui->rightGeneralLayout->addWidget(box);
}
box->hide();
toolToBoxMap[tool] = box;*/
}
if
(
advarraycount
>
0
)
{
/*
tool = new QGCToolWidget("", this);
tool->addUAS(mav);
tool->setTitle(parametersname);
tool->setObjectName(parametersname);
tool->setSettings(advset);
QList<QString> paramlist = tool->getParamList();
for (int i=0;i<paramlist.size();i++)
{
//Based on the airframe, we add the parameter to different categories.
if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
{
systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
}
else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
{
systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
}
else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
{
systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
}
else
{
libParamToWidgetMap->insert(paramlist[i],tool);
}
}
toolWidgets.append(tool);
QGroupBox *box = new QGroupBox(this);
box->setTitle(tool->objectName());
box->setLayout(new QVBoxLayout());
box->layout()->addWidget(tool);
if (valuetype == "vehicles")
{
ui->leftAdvancedLayout->addWidget(box);
}
else if (valuetype == "libraries")
{
ui->rightAdvancedLayout->addWidget(box);
}
box->hide();
toolToBoxMap[tool] = box;*/
}
}
xml
.
readNext
();
}
}
xml
.
readNext
();
}
}
xml
.
readNext
();
}
}
src/ui/configuration/ApmSoftwareConfig.h
View file @
4cd86dec
...
...
@@ -10,7 +10,9 @@
#include "FailSafeConfig.h"
#include "AdvancedParamConfig.h"
#include "ArduCopterPidConfig.h"
#include "ArduPlanePidConfig.h"
#include "ArduRoverPidConfig.h"
#include "AdvParameterList.h"
#include "UASInterface.h"
#include "UASManager.h"
...
...
@@ -32,7 +34,10 @@ private:
GeoFenceConfig
*
geoFenceConfig
;
FailSafeConfig
*
failSafeConfig
;
AdvancedParamConfig
*
advancedParamConfig
;
ArduCopterPidConfig
*
arduCoperPidConfig
;
ArduCopterPidConfig
*
arduCopterPidConfig
;
ArduPlanePidConfig
*
arduPlanePidConfig
;
ArduRoverPidConfig
*
arduRoverPidConfig
;
AdvParameterList
*
advParameterList
;
QMap
<
QObject
*
,
QWidget
*>
buttonToConfigWidgetMap
;
};
...
...
src/ui/configuration/ApmSoftwareConfig.ui
View file @
4cd86dec
...
...
@@ -6,221 +6,204 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
718
</width>
<height>
531
</height>
<width>
853
</width>
<height>
619
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<widget
class=
"QScrollArea"
name=
"scrollArea_6"
>
<property
name=
"geometry"
>
<rect>
<x>
20
</x>
<y>
10
</y>
<width>
175
</width>
<height>
531
</height>
</rect>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
175
</width>
<height>
0
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
175
</width>
<height>
16777215
</height>
</size>
</property>
<property
name=
"widgetResizable"
>
<bool>
true
</bool>
</property>
<widget
class=
"QWidget"
name=
"scrollAreaWidgetContents_3"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
173
</width>
<height>
529
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_12"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"navBarLayout"
>
<property
name=
"sizeConstraint"
>
<enum>
QLayout::SetMinAndMaxSize
</enum>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<item>
<widget
class=
"QScrollArea"
name=
"scrollArea_6"
>
<property
name=
"minimumSize"
>
<size>
<width>
175
</width>
<height>
0
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
175
</width>
<height>
16777215
</height>
</size>
</property>
<property
name=
"widgetResizable"
>
<bool>
true
</bool>
</property>
<widget
class=
"QWidget"
name=
"scrollAreaWidgetContents_3"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
173
</width>
<height>
599
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_12"
>
<item>
<widget
class=
"QPushButton"
name=
"plannerConfigButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
100
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
APM Planner 2.0 Config
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"basicPidsButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Basic Pids
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"flightModesButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Flight Modes
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"standardParamButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Standard Params
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"geoFenceButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
GeoFence
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"failSafeButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
FailSafe
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"advancedParamButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Advanced Params
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"advParamListButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Adv Parameter List
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"arduCoperPidButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
ArduCoper Pids
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</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>
<layout
class=
"QVBoxLayout"
name=
"navBarLayout"
>
<property
name=
"sizeConstraint"
>
<enum>
QLayout::SetMinAndMaxSize
</enum>
</property>
<item>
<widget
class=
"QPushButton"
name=
"plannerConfigButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
100
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
APM Planner 2.0 Config
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"flightModesButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Flight Modes
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"standardParamButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Standard Params
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"failSafeButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
FailSafe
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"advancedParamButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Advanced Params
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"advParamListButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Adv Parameter List
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"arduCopterPidButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
ArduCopter Pids
</string>
</property>
<property
name=
"checkable"
>
<bool>
false
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"arduPlanePidButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
ArduPlane Pids
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QPushButton"
name=
"arduRoverPidButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
35
</height>
</size>
</property>
<property
name=
"text"
>
<string>
ArduRover Pids
</string>
</property>
</widget>
</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>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
<widget
class=
"QStackedWidget"
name=
"stackedWidget"
>
<property
name=
"geometry"
>
<rect>
<x>
220
</x>
<y>
20
</y>
<width>
471
</width>
<height>
491
</height>
</rect>
</property>
</widget>
</widget>
</widget>
</item>
<item>
<widget
class=
"QStackedWidget"
name=
"stackedWidget"
/>
</item>
</layout>
</widget>
<resources/>
<connections/>
...
...
src/ui/configuration/ArduCopterPidConfig.cc
View file @
4cd86dec
#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
);
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
()));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
0
,
"CH6_NONE"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
1
,
"CH6_STABILIZE_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
2
,
"CH6_STABILIZE_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
3
,
"CH6_YAW_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
24
,
"CH6_YAW_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
4
,
"CH6_RATE_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
5
,
"CH6_RATE_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
6
,
"CH6_YAW_RATE_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
26
,
"CH6_YAW_RATE_KD"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
7
,
"CH6_THROTTLE_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
9
,
"CH6_RELAY"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
10
,
"CH6_WP_SPEED"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
12
,
"CH6_LOITER_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
13
,
"CH6_HELI_EXTERNAL_GYRO"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
14
,
"CH6_THR_HOLD_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
17
,
"CH6_OPTFLOW_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
18
,
"CH6_OPTFLOW_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
19
,
"CH6_OPTFLOW_KD"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
21
,
"CH6_RATE_KD"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
22
,
"CH6_LOITER_RATE_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
23
,
"CH6_LOITER_RATE_KD"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
25
,
"CH6_ACRO_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
27
,
"CH6_LOITER_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
28
,
"CH6_LOITER_RATE_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
29
,
"CH6_STABILIZE_KD"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
30
,
"CH6_AHRS_YAW_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
31
,
"CH6_AHRS_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
32
,
"CH6_INAV_TC"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
33
,
"CH6_THROTTLE_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
34
,
"CH6_THR_ACCEL_KP"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
35
,
"CH6_THR_ACCEL_KI"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
36
,
"CH6_THR_ACCEL_KD"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
38
,
"CH6_DECLINATION"
));
ch6ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
39
,
"CH6_CIRCLE_RATE"
));
for
(
int
i
=
0
;
i
<
ch6ValueToTextList
.
size
();
i
++
)
{
ui
.
ch6OptComboBox
->
addItem
(
ch6ValueToTextList
[
i
].
second
);
}
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
0
,
"Do nothing"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
2
,
"Flip"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
3
,
"Simple mode"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
4
,
"RTL"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
5
,
"Save Trim"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
7
,
"Save WP"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
8
,
"Multi Mode"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
9
,
"Camera Trigger"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
10
,
"Sonar"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
11
,
"Fence"
));
ch7ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
12
,
"ResetToArmedYaw"
));
for
(
int
i
=
0
;
i
<
ch7ValueToTextList
.
size
();
i
++
)
{
ui
.
ch7OptComboBox
->
addItem
(
ch7ValueToTextList
[
i
].
second
);
}
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
0
,
"Do nothing"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
2
,
"Flip"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
3
,
"Simple mode"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
4
,
"RTL"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
5
,
"Save Trim"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
7
,
"Save WP"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
8
,
"Multi Mode"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
9
,
"Camera Trigger"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
10
,
"Sonar"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
11
,
"Fence"
));
ch8ValueToTextList
.
append
(
QPair
<
int
,
QString
>
(
12
,
"ResetToArmedYaw"
));
for
(
int
i
=
0
;
i
<
ch8ValueToTextList
.
size
();
i
++
)
{
ui
.
ch8OptComboBox
->
addItem
(
ch8ValueToTextList
[
i
].
second
);
}
}
ArduCopterPidConfig
::~
ArduCopterPidConfig
()
{
delete
ui
;
}
void
ArduCopterPidConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
nameToBoxMap
.
contains
(
parameterName
))
{
nameToBoxMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
}
else
if
(
parameterName
==
"TUNE"
)
{
for
(
int
i
=
0
;
i
<
ch6ValueToTextList
.
size
();
i
++
)
{
if
(
ch6ValueToTextList
[
i
].
first
==
value
.
toInt
())
{
ui
.
ch6OptComboBox
->
setCurrentIndex
(
i
);
}
}
}
else
if
(
parameterName
==
"CH7_OPT"
)
{
for
(
int
i
=
0
;
i
<
ch7ValueToTextList
.
size
();
i
++
)
{
if
(
ch7ValueToTextList
[
i
].
first
==
value
.
toInt
())
{
ui
.
ch7OptComboBox
->
setCurrentIndex
(
i
);
}
}
}
else
if
(
parameterName
==
"CH8_OPT"
)
{
for
(
int
i
=
0
;
i
<
ch8ValueToTextList
.
size
();
i
++
)
{
if
(
ch8ValueToTextList
[
i
].
first
==
value
.
toInt
())
{
ui
.
ch8OptComboBox
->
setCurrentIndex
(
i
);
}
}
}
}
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
());
}
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"TUNE"
,
ch8ValueToTextList
[
ui
.
ch6OptComboBox
->
currentIndex
()].
first
);
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"CH7_OPT"
,
ch7ValueToTextList
[
ui
.
ch7OptComboBox
->
currentIndex
()].
first
);
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"CH8_OPT"
,
ch8ValueToTextList
[
ui
.
ch8OptComboBox
->
currentIndex
()].
first
);
}
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
());
}
m_uas
->
getParamManager
()
->
requestParameterUpdate
(
1
,
"TUNE"
);
m_uas
->
getParamManager
()
->
requestParameterUpdate
(
1
,
"CH7_OPT"
);
m_uas
->
getParamManager
()
->
requestParameterUpdate
(
1
,
"CH8_OPT"
);
}
src/ui/configuration/ArduCopterPidConfig.h
View file @
4cd86dec
...
...
@@ -2,21 +2,27 @@
#define ARDUCOPTERPIDCONFIG_H
#include <QWidget>
#include "ui_ArduCopterPidConfig.h"
namespace
Ui
{
class
ArduCopterPidConfig
;
}
#include "AP2ConfigWidget.h"
class
ArduCopterPidConfig
:
public
Q
Widget
class
ArduCopterPidConfig
:
public
AP2Config
Widget
{
Q_OBJECT
public:
explicit
ArduCopterPidConfig
(
QWidget
*
parent
=
0
);
~
ArduCopterPidConfig
();
private
slots
:
void
writeButtonClicked
();
void
refreshButtonClicked
();
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
Ui
::
ArduCopterPidConfig
*
ui
;
QList
<
QPair
<
int
,
QString
>
>
ch6ValueToTextList
;
QList
<
QPair
<
int
,
QString
>
>
ch7ValueToTextList
;
QList
<
QPair
<
int
,
QString
>
>
ch8ValueToTextList
;
QMap
<
QString
,
QDoubleSpinBox
*>
nameToBoxMap
;
Ui
::
ArduCopterPidConfig
ui
;
};
#endif // ARDUCOPTERPIDCONFIG_H
src/ui/configuration/ArduCopterPidConfig.ui
View file @
4cd86dec
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
40
0
</width>
<height>
300
</height>
<width>
75
0
</width>
<height>
596
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -26,6 +26,1035 @@
<string>
<
h2
>
ArduCopter Pids
<
/h2
>
</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/>
...
...
src/ui/configuration/ArduPlanePidConfig.cc
0 → 100644
View file @
4cd86dec
#include "ArduPlanePidConfig.h"
ArduPlanePidConfig
::
ArduPlanePidConfig
(
QWidget
*
parent
)
:
AP2ConfigWidget
(
parent
)
{
ui
.
setupUi
(
this
);
nameToBoxMap
[
"RLL2SRV_P"
]
=
ui
.
servoRollPSpinBox
;
nameToBoxMap
[
"RLL2SRV_I"
]
=
ui
.
servoRollISpinBox
;
nameToBoxMap
[
"RLL2SRV_D"
]
=
ui
.
servoRollDSpinBox
;
nameToBoxMap
[
"RLL2SRV_IMAX"
]
=
ui
.
servoRollIMAXSpinBox
;
nameToBoxMap
[
"PTCH2SRV_P"
]
=
ui
.
servoPitchPSpinBox
;
nameToBoxMap
[
"PTCH2SRV_I"
]
=
ui
.
servoPitchISpinBox
;
nameToBoxMap
[
"PTCH2SRV_D"
]
=
ui
.
servoPitchDSpinBox
;
nameToBoxMap
[
"PTCH2SRV_IMAX"
]
=
ui
.
servoPitchIMAXSpinBox
;
nameToBoxMap
[
"YW2SRV_P"
]
=
ui
.
servoYawPSpinBox
;
nameToBoxMap
[
"YW2SRV_I"
]
=
ui
.
servoYawISpinBox
;
nameToBoxMap
[
"YW2SRV_D"
]
=
ui
.
servoYawDSpinBox
;
nameToBoxMap
[
"YW2SRV_IMAX"
]
=
ui
.
servoYawIMAXSpinBox
;
nameToBoxMap
[
"ALT2PTCH_P"
]
=
ui
.
navAltPSpinBox
;
nameToBoxMap
[
"ALT2PTCH_I"
]
=
ui
.
navAltISpinBox
;
nameToBoxMap
[
"ALT2PTCH_D"
]
=
ui
.
navAltDSpinBox
;
nameToBoxMap
[
"ALT2PTCH_IMAX"
]
=
ui
.
navAltIMAXSpinBox
;
nameToBoxMap
[
"ARSP2PTCH_P"
]
=
ui
.
navASPSpinBox
;
nameToBoxMap
[
"ARSP2PTCH_I"
]
=
ui
.
navASISpinBox
;
nameToBoxMap
[
"ARSP2PTCH_D"
]
=
ui
.
navASDSpinBox
;
nameToBoxMap
[
"ARSP2PTCH_IMAX"
]
=
ui
.
navASIMAXSpinBox
;
nameToBoxMap
[
"ENRGY2THR_P"
]
=
ui
.
energyPSpinBox
;
nameToBoxMap
[
"ENRGY2THR_I"
]
=
ui
.
energyISpinBox
;
nameToBoxMap
[
"ENRGY2THR_D"
]
=
ui
.
energyDSpinBox
;
nameToBoxMap
[
"ENRGY2THR_IMAX"
]
=
ui
.
energyIMAXSpinBox
;
nameToBoxMap
[
"KFF_PTCH2THR"
]
=
ui
.
otherPitchCompSpinBox
;
nameToBoxMap
[
"KFF_PTCHCOMP"
]
=
ui
.
otherPtTSpinBox
;
nameToBoxMap
[
"KFF_RDDRMIX"
]
=
ui
.
otherRudderMixSpinBox
;
nameToBoxMap
[
"TRIM_THROTTLE"
]
=
ui
.
throttleCruiseSpinBox
;
nameToBoxMap
[
"THR_FS_VALUE"
]
=
ui
.
throttleFSSpinBox
;
nameToBoxMap
[
"THR_MAX"
]
=
ui
.
throttleMaxSpinBox
;
nameToBoxMap
[
"THR_MIN"
]
=
ui
.
throttleMinSpinBox
;
nameToBoxMap
[
"TRIM_ARSPD_CM"
]
=
ui
.
airspeedCruiseSpinBox
;
nameToBoxMap
[
"ARSPD_FBW_MAX"
]
=
ui
.
airspeedFBWMaxSpinBox
;
nameToBoxMap
[
"ARSPD_FBW_MIN"
]
=
ui
.
airspeedFBWMinSpinBox
;
nameToBoxMap
[
"ARSPD_RATIO"
]
=
ui
.
airspeedRatioSpinBox
;
nameToBoxMap
[
"NAVL1_DAMPING"
]
=
ui
.
l1DampingSpinBox
;
nameToBoxMap
[
"NAVL1_PERIOD"
]
=
ui
.
l1PeriodSpinBox
;
nameToBoxMap
[
"LIM_ROLL_CD"
]
=
ui
.
navBankMaxSpinBox
;
nameToBoxMap
[
"LIM_PITCH_MAX"
]
=
ui
.
navPitchMaxSpinBox
;
nameToBoxMap
[
"LIM_PITCH_MIN"
]
=
ui
.
navPitchMinSpinBox
;
connect
(
ui
.
writePushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
writeButtonClicked
()));
connect
(
ui
.
refreshPushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
refreshButtonClicked
()));
}
ArduPlanePidConfig
::~
ArduPlanePidConfig
()
{
}
void
ArduPlanePidConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
nameToBoxMap
.
contains
(
parameterName
))
{
nameToBoxMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
}
}
void
ArduPlanePidConfig
::
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
ArduPlanePidConfig
::
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
());
}
}
src/ui/configuration/ArduPlanePidConfig.h
0 → 100644
View file @
4cd86dec
#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
);
void
writeButtonClicked
();
void
refreshButtonClicked
();
private:
QMap
<
QString
,
QDoubleSpinBox
*>
nameToBoxMap
;
Ui
::
ArduPlanePidConfig
ui
;
};
#endif // ARDUPLANEPIDCONFIG_H
src/ui/configuration/ArduPlanePidConfig.ui
0 → 100644
View file @
4cd86dec
<?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=
"servoRollIMAXSpinBox"
>
<property
name=
"maximum"
>
<double>
10000.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>
10000.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>
10000.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>
10000.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>
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>
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>
10000.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=
"minimum"
>
<double>
-10000.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
10000.000000000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"navPitchMinSpinBox"
>
<property
name=
"decimals"
>
<number>
3
</number>
</property>
<property
name=
"maximum"
>
<double>
10000.000000000000000
</double>
</property>
<property
name=
"value"
>
<double>
0.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>
src/ui/configuration/ArduRoverPidConfig.cc
0 → 100644
View file @
4cd86dec
#include "ArduRoverPidConfig.h"
ArduRoverPidConfig
::
ArduRoverPidConfig
(
QWidget
*
parent
)
:
AP2ConfigWidget
(
parent
)
{
ui
.
setupUi
(
this
);
nameToBoxMap
[
"STEER2SRV_P"
]
=
ui
.
steer2ServoPSpinBox
;
nameToBoxMap
[
"STEER2SRV_I"
]
=
ui
.
steer2ServoISpinBox
;
nameToBoxMap
[
"STEER2SRV_D"
]
=
ui
.
steer2ServoDSpinBox
;
nameToBoxMap
[
"STEER2SRV_IMAX"
]
=
ui
.
steer2ServoIMAXSpinBox
;
nameToBoxMap
[
"XTRK_ANGLE_CD"
]
=
ui
.
xtrackEntryAngleSpinBox
;
nameToBoxMap
[
"XTRK_GAIN_SC"
]
=
ui
.
xtrackGainSpinBox
;
nameToBoxMap
[
"CRUISE_THROTTLE"
]
=
ui
.
throttleCruiseSpinBox
;
nameToBoxMap
[
"THR_MIN"
]
=
ui
.
throttleMinSpinBox
;
nameToBoxMap
[
"THR_MAX"
]
=
ui
.
throttleMaxSpinBox
;
nameToBoxMap
[
"FS_THR_VALUE"
]
=
ui
.
throttleFSSpinBox
;
nameToBoxMap
[
"HDNG2STEER_P"
]
=
ui
.
heading2SteerPSpinBox
;
nameToBoxMap
[
"HDNG2STEER_I"
]
=
ui
.
heading2SteerISpinBox
;
nameToBoxMap
[
"HDNG2STEER_D"
]
=
ui
.
heading2SteerDSpinBox
;
nameToBoxMap
[
"HDNG2STEER_IMAX"
]
=
ui
.
heading2SteerIMAXSpinBox
;
nameToBoxMap
[
"SPEED2THR_P"
]
=
ui
.
speed2ThrottlePSpinBox
;
nameToBoxMap
[
"SPEED2THR_I"
]
=
ui
.
speed2ThrottleISpinBox
;
nameToBoxMap
[
"SPEED2THR_D"
]
=
ui
.
speed2ThrottleDSpinBox
;
nameToBoxMap
[
"SPEED2THR_IMAX"
]
=
ui
.
speed2ThrottleIMAXSpinBox
;
nameToBoxMap
[
"CRUISE_SPEED"
]
=
ui
.
roverCruiseSpinBox
;
nameToBoxMap
[
"SPEED_TURN_GAIN"
]
=
ui
.
roverTurnSpeedSpinBox
;
nameToBoxMap
[
"SPEED_TURN_DIST"
]
=
ui
.
roverTurnDistSpinBox
;
nameToBoxMap
[
"WP_RADIUS"
]
=
ui
.
roverWPRadiusSpinBox
;
nameToBoxMap
[
"SONAR_TRIGGER_CM"
]
=
ui
.
sonarTriggerSpinBox
;
nameToBoxMap
[
"SONAR_TURN_ANGLE"
]
=
ui
.
sonarTurnAngleSpinBox
;
nameToBoxMap
[
"SONAR_TURN_TIME"
]
=
ui
.
sonarTurnTimeSpinBox
;
nameToBoxMap
[
"SONAR_DEBOUNCE"
]
=
ui
.
sonaeDebounceSpinBox
;
connect
(
ui
.
writePushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
writeButtonClicked
()));
connect
(
ui
.
refreshPushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
refreshButtonClicked
()));
}
ArduRoverPidConfig
::~
ArduRoverPidConfig
()
{
}
void
ArduRoverPidConfig
::
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
ArduRoverPidConfig
::
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
());
}
}
void
ArduRoverPidConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
nameToBoxMap
.
contains
(
parameterName
))
{
nameToBoxMap
[
parameterName
]
->
setValue
(
value
.
toFloat
());
}
}
src/ui/configuration/ArduRoverPidConfig.h
0 → 100644
View file @
4cd86dec
#ifndef ARDUROVERPIDCONFIG_H
#define ARDUROVERPIDCONFIG_H
#include <QWidget>
#include "ui_ArduRoverPidConfig.h"
#include "AP2ConfigWidget.h"
class
ArduRoverPidConfig
:
public
AP2ConfigWidget
{
Q_OBJECT
public:
explicit
ArduRoverPidConfig
(
QWidget
*
parent
=
0
);
~
ArduRoverPidConfig
();
private
slots
:
void
writeButtonClicked
();
void
refreshButtonClicked
();
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QMap
<
QString
,
QDoubleSpinBox
*>
nameToBoxMap
;
Ui
::
ArduRoverPidConfig
ui
;
};
#endif // ARDUROVERPIDCONFIG_H
src/ui/configuration/ArduRoverPidConfig.ui
0 → 100644
View file @
4cd86dec
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
ArduRoverPidConfig
</class>
<widget
class=
"QWidget"
name=
"ArduRoverPidConfig"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
626
</width>
<height>
607
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"geometry"
>
<rect>
<x>
10
</x>
<y>
10
</y>
<width>
151
</width>
<height>
21
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
<
h2
>
ArduRover Pids
<
/h2
>
</string>
</property>
</widget>
<widget
class=
"QWidget"
name=
"gridLayoutWidget"
>
<property
name=
"geometry"
>
<rect>
<x>
60
</x>
<y>
90
</y>
<width>
504
</width>
<height>
419
</height>
</rect>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QGroupBox"
name=
"groupBox_5"
>
<property
name=
"title"
>
<string>
Steer 2 Servo
</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=
"steer2ServoPSpinBox"
>
<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=
"steer2ServoISpinBox"
>
<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=
"steer2ServoDSpinBox"
>
<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=
"steer2ServoIMAXSpinBox"
>
<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=
"1"
>
<widget
class=
"QGroupBox"
name=
"groupBox_7"
>
<property
name=
"title"
>
<string>
Speed 2 Throttle
</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_14"
>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"speed2ThrottlePSpinBox"
>
<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=
"speed2ThrottleISpinBox"
>
<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=
"speed2ThrottleDSpinBox"
>
<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=
"speed2ThrottleIMAXSpinBox"
>
<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=
"QGroupBox"
name=
"groupBox_9"
>
<property
name=
"title"
>
<string>
Heading 2 Steer
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_22"
>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_9"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_17"
>
<item>
<widget
class=
"QLabel"
name=
"label_34"
>
<property
name=
"text"
>
<string>
P
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_35"
>
<property
name=
"text"
>
<string>
I
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_36"
>
<property
name=
"text"
>
<string>
D
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_37"
>
<property
name=
"text"
>
<string>
INT_MAX
</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_23"
>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"heading2SteerPSpinBox"
>
<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=
"heading2SteerISpinBox"
>
<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=
"heading2SteerDSpinBox"
>
<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=
"heading2SteerIMAXSpinBox"
>
<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_10"
>
<property
name=
"title"
>
<string>
Throttle 0-100%
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_24"
>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_10"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_25"
>
<item>
<widget
class=
"QLabel"
name=
"label_38"
>
<property
name=
"text"
>
<string>
Cruise
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_39"
>
<property
name=
"text"
>
<string>
Min
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_40"
>
<property
name=
"text"
>
<string>
Max
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_41"
>
<property
name=
"text"
>
<string>
FS Value
</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_26"
>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"throttleCruiseSpinBox"
>
<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=
"throttleMinSpinBox"
>
<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=
"throttleMaxSpinBox"
>
<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=
"throttleFSSpinBox"
>
<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_11"
>
<property
name=
"title"
>
<string>
Xtrack Pids
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_27"
>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_11"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_28"
>
<item>
<widget
class=
"QLabel"
name=
"label_42"
>
<property
name=
"text"
>
<string>
Gain (cm)
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_43"
>
<property
name=
"text"
>
<string>
Entry Angle
</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_29"
>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"xtrackGainSpinBox"
>
<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=
"xtrackEntryAngleSpinBox"
>
<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=
"2"
column=
"1"
>
<widget
class=
"QGroupBox"
name=
"groupBox_8"
>
<property
name=
"title"
>
<string>
Sonar
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_21"
>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_8"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_15"
>
<item>
<widget
class=
"QLabel"
name=
"label_30"
>
<property
name=
"text"
>
<string>
Trigger cm
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_31"
>
<property
name=
"text"
>
<string>
Turn Angle
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_32"
>
<property
name=
"text"
>
<string>
Turn Time
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_33"
>
<property
name=
"text"
>
<string>
Debounce
</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_16"
>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"sonarTriggerSpinBox"
>
<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=
"sonarTurnAngleSpinBox"
>
<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=
"sonarTurnTimeSpinBox"
>
<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=
"sonaeDebounceSpinBox"
>
<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=
"2"
>
<widget
class=
"QGroupBox"
name=
"groupBox_6"
>
<property
name=
"title"
>
<string>
Rover
</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>
Cruise Speed
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_23"
>
<property
name=
"text"
>
<string>
Turn Speed
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_24"
>
<property
name=
"text"
>
<string>
Turn Dist
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_25"
>
<property
name=
"text"
>
<string>
WP Radius
</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_12"
>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"roverCruiseSpinBox"
>
<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=
"roverTurnSpeedSpinBox"
>
<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=
"roverTurnDistSpinBox"
>
<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=
"roverWPRadiusSpinBox"
>
<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
class=
"QPushButton"
name=
"refreshPushButton"
>
<property
name=
"geometry"
>
<rect>
<x>
300
</x>
<y>
540
</y>
<width>
91
</width>
<height>
23
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
Refresh Params
</string>
</property>
</widget>
<widget
class=
"QPushButton"
name=
"writePushButton"
>
<property
name=
"geometry"
>
<rect>
<x>
200
</x>
<y>
540
</y>
<width>
75
</width>
<height>
23
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
Write Params
</string>
</property>
</widget>
</widget>
<resources/>
<connections/>
</ui>
src/ui/configuration/BatteryMonitorConfig.cc
View file @
4cd86dec
...
...
@@ -32,6 +32,16 @@ BatteryMonitorConfig::BatteryMonitorConfig(QWidget *parent) : AP2ConfigWidget(pa
}
void
BatteryMonitorConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
!
uas
)
{
return
;
}
connect
(
uas
,
SIGNAL
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)),
this
,
SLOT
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)));
AP2ConfigWidget
::
activeUASSet
(
uas
);
}
void
BatteryMonitorConfig
::
calcDividerSet
()
{
if
(
!
m_uas
)
...
...
@@ -222,6 +232,14 @@ void BatteryMonitorConfig::apmVerCurrentIndexChanged(int index)
BatteryMonitorConfig
::~
BatteryMonitorConfig
()
{
}
void
BatteryMonitorConfig
::
batteryChanged
(
UASInterface
*
uas
,
double
voltage
,
double
current
,
double
percent
,
int
seconds
)
{
ui
.
calcVoltsLineEdit
->
setText
(
QString
::
number
(
voltage
,
'f'
,
2
));
if
(
ui
.
measuredVoltsLineEdit
->
text
()
==
""
)
{
ui
.
measuredVoltsLineEdit
->
setText
(
ui
.
calcVoltsLineEdit
->
text
());
}
}
void
BatteryMonitorConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
...
...
src/ui/configuration/BatteryMonitorConfig.h
View file @
4cd86dec
...
...
@@ -20,6 +20,8 @@ private slots:
void
calcDividerSet
();
void
ampsPerVoltSet
();
void
batteryCapacitySet
();
void
activeUASSet
(
UASInterface
*
uas
);
void
batteryChanged
(
UASInterface
*
uas
,
double
voltage
,
double
current
,
double
percent
,
int
seconds
);
private:
Ui
::
BatteryMonitorConfig
ui
;
};
...
...
src/ui/configuration/CompassConfig.cc
View file @
4cd86dec
...
...
@@ -16,6 +16,33 @@ CompassConfig::CompassConfig(QWidget *parent) : QWidget(parent)
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
activeUASSet
(
UASManager
::
instance
()
->
getActiveUAS
());
ui
.
orientationComboBox
->
addItem
(
"ROTATION_NONE"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_45"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_90"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_135"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_180"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_225"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_270"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_315"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_180"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_180_YAW_45"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_180_YAW_90"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_180_YAW_135"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_PITCH_180"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_180_YAW_225"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_180_YAW_270"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_180_YAW_315"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_90"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_90_YAW_45"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_90_YAW_90"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_90_YAW_135"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_270"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_270_YAW_45"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_270_YAW_90"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_ROLL_270_YAW_135"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_PITCH_90"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_PITCH_270"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_MAX"
);
}
CompassConfig
::~
CompassConfig
()
{
...
...
@@ -39,12 +66,14 @@ void CompassConfig::parameterChanged(int uas, int component, QString parameterNa
ui
.
enableCheckBox
->
setChecked
(
false
);
ui
.
autoDecCheckBox
->
setEnabled
(
false
);
ui
.
declinationLineEdit
->
setEnabled
(
false
);
ui
.
orientationComboBox
->
setEnabled
(
false
);
}
else
{
ui
.
enableCheckBox
->
setChecked
(
true
);
ui
.
autoDecCheckBox
->
setEnabled
(
true
);
ui
.
declinationLineEdit
->
setEnabled
(
true
);
ui
.
orientationComboBox
->
setEnabled
(
true
);
}
ui
.
enableCheckBox
->
setEnabled
(
true
);
}
...
...
@@ -63,6 +92,12 @@ void CompassConfig::parameterChanged(int uas, int component, QString parameterNa
{
ui
.
declinationLineEdit
->
setText
(
QString
::
number
(
value
.
toDouble
()));
}
else
if
(
parameterName
==
"COMPASS_ORIENT"
)
{
disconnect
(
ui
.
orientationComboBox
,
SIGNAL
(
currentIndexChanged
(
int
)),
this
,
SLOT
(
orientationComboChanged
(
int
)));
ui
.
orientationComboBox
->
setCurrentIndex
(
value
.
toInt
());
connect
(
ui
.
orientationComboBox
,
SIGNAL
(
currentIndexChanged
(
int
)),
this
,
SLOT
(
orientationComboChanged
(
int
)));
}
}
void
CompassConfig
::
enableClicked
(
bool
enabled
)
...
...
@@ -104,5 +139,11 @@ void CompassConfig::autoDecClicked(bool enabled)
void
CompassConfig
::
orientationComboChanged
(
int
index
)
{
//COMPASS_ORIENT
if
(
!
m_uas
)
{
return
;
}
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"COMPASS_ORIENT"
,
index
);
}
src/ui/configuration/CompassConfig.ui
View file @
4cd86dec
...
...
@@ -55,9 +55,9 @@
<widget
class=
"QPushButton"
name=
"pushButton"
>
<property
name=
"geometry"
>
<rect>
<x>
30
0
</x>
<x>
29
0
</x>
<y>
180
</y>
<width>
9
1
</width>
<width>
10
1
</width>
<height>
23
</height>
</rect>
</property>
...
...
@@ -70,7 +70,7 @@
<rect>
<x>
390
</x>
<y>
180
</y>
<width>
9
1
</width>
<width>
10
1
</width>
<height>
23
</height>
</rect>
</property>
...
...
@@ -118,7 +118,7 @@
<rect>
<x>
10
</x>
<y>
70
</y>
<width>
2
0
1
</width>
<width>
2
1
1
</width>
<height>
111
</height>
</rect>
</property>
...
...
src/ui/configuration/FailSafeConfig.cc
View file @
4cd86dec
#include "FailSafeConfig.h"
FailSafeConfig
::
FailSafeConfig
(
QWidget
*
parent
)
:
Q
Widget
(
parent
)
FailSafeConfig
::
FailSafeConfig
(
QWidget
*
parent
)
:
AP2Config
Widget
(
parent
)
{
ui
.
setupUi
(
this
);
ui
.
radio1In
->
setName
(
"Radio 1"
);
ui
.
radio1In
->
setMin
(
800
);
ui
.
radio1In
->
setMax
(
2200
);
ui
.
radio1In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio2In
->
setName
(
"Radio 2"
);
ui
.
radio2In
->
setMin
(
800
);
ui
.
radio2In
->
setMax
(
2200
);
ui
.
radio2In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio3In
->
setName
(
"Radio 3"
);
ui
.
radio3In
->
setMin
(
800
);
ui
.
radio3In
->
setMax
(
2200
);
ui
.
radio3In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio4In
->
setName
(
"Radio 4"
);
ui
.
radio4In
->
setMin
(
800
);
ui
.
radio4In
->
setMax
(
2200
);
ui
.
radio4In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio5In
->
setName
(
"Radio 5"
);
ui
.
radio5In
->
setMin
(
800
);
ui
.
radio5In
->
setMax
(
2200
);
ui
.
radio5In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio6In
->
setName
(
"Radio 6"
);
ui
.
radio6In
->
setMin
(
800
);
ui
.
radio6In
->
setMax
(
2200
);
ui
.
radio6In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio7In
->
setName
(
"Radio 7"
);
ui
.
radio7In
->
setMin
(
800
);
ui
.
radio7In
->
setMax
(
2200
);
ui
.
radio7In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio8In
->
setName
(
"Radio 8"
);
ui
.
radio8In
->
setMin
(
800
);
ui
.
radio8In
->
setMax
(
2200
);
ui
.
radio8In
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio1Out
->
setName
(
"Radio 1"
);
ui
.
radio1Out
->
setMin
(
800
);
ui
.
radio1Out
->
setMax
(
2200
);
ui
.
radio1Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio2Out
->
setName
(
"Radio 2"
);
ui
.
radio2Out
->
setMin
(
800
);
ui
.
radio2Out
->
setMax
(
2200
);
ui
.
radio2Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio3Out
->
setName
(
"Radio 3"
);
ui
.
radio3Out
->
setMin
(
800
);
ui
.
radio3Out
->
setMax
(
2200
);
ui
.
radio3Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio4Out
->
setName
(
"Radio 4"
);
ui
.
radio4Out
->
setMin
(
800
);
ui
.
radio4Out
->
setMax
(
2200
);
ui
.
radio4Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio5Out
->
setName
(
"Radio 5"
);
ui
.
radio5Out
->
setMin
(
800
);
ui
.
radio5Out
->
setMax
(
2200
);
ui
.
radio5Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio6Out
->
setName
(
"Radio 6"
);
ui
.
radio6Out
->
setMin
(
800
);
ui
.
radio6Out
->
setMax
(
2200
);
ui
.
radio6Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio7Out
->
setName
(
"Radio 7"
);
ui
.
radio7Out
->
setMin
(
800
);
ui
.
radio7Out
->
setMax
(
2200
);
ui
.
radio7Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
radio8Out
->
setName
(
"Radio 8"
);
ui
.
radio8Out
->
setMin
(
800
);
ui
.
radio8Out
->
setMax
(
2200
);
ui
.
radio8Out
->
setOrientation
(
Qt
::
Horizontal
);
ui
.
throttleFailSafeComboBox
->
addItem
(
"Disable"
);
ui
.
throttleFailSafeComboBox
->
addItem
(
"Enabled - Always TRL"
);
ui
.
throttleFailSafeComboBox
->
addItem
(
"Enabled - Continue in auto"
);
connect
(
ui
.
batteryFailCheckBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
batteryFailChecked
(
bool
)));
connect
(
ui
.
fsLongCheckBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
fsLongClicked
(
bool
)));
connect
(
ui
.
fsShortCheckBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
fsShortClicked
(
bool
)));
connect
(
ui
.
gcsCheckBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
gcsChecked
(
bool
)));
connect
(
ui
.
throttleActionCheckBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
throttleActionChecked
(
bool
)));
connect
(
ui
.
throttleCheckBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
throttleChecked
(
bool
)));
connect
(
ui
.
throttlePwmSpinBox
,
SIGNAL
(
editingFinished
()),
this
,
SLOT
(
throttlePwmChanged
()));
connect
(
ui
.
throttleFailSafeComboBox
,
SIGNAL
(
currentIndexChanged
(
int
)),
this
,
SLOT
(
throttleFailSafeChanged
(
int
)));
}
void
FailSafeConfig
::
gcsChecked
(
bool
checked
)
{
if
(
!
m_uas
)
{
return
;
}
if
(
checked
)
{
m_uas
->
setParameter
(
1
,
"FS_GCS_ENABL"
,
1
);
}
else
{
m_uas
->
setParameter
(
1
,
"FS_GCS_ENABL"
,
0
);
}
}
void
FailSafeConfig
::
throttleActionChecked
(
bool
checked
)
{
if
(
!
m_uas
)
{
return
;
}
if
(
checked
)
{
m_uas
->
setParameter
(
1
,
"THR_FS_ACTION"
,
1
);
}
else
{
m_uas
->
setParameter
(
1
,
"THR_FS_ACTION"
,
0
);
}
}
void
FailSafeConfig
::
throttleChecked
(
bool
checked
)
{
if
(
!
m_uas
)
{
return
;
}
if
(
checked
)
{
m_uas
->
setParameter
(
1
,
"THR_FAILSAFE"
,
1
);
}
else
{
m_uas
->
setParameter
(
1
,
"THR_FAILSAFE"
,
0
);
}
}
void
FailSafeConfig
::
throttlePwmChanged
()
{
if
(
!
m_uas
)
{
return
;
}
m_uas
->
setParameter
(
1
,
"THR_FS_VALUE"
,
ui
.
throttlePwmSpinBox
->
value
());
}
void
FailSafeConfig
::
throttleFailSafeChanged
(
int
index
)
{
if
(
!
m_uas
)
{
return
;
}
m_uas
->
setParameter
(
1
,
"FS_THR_ENABLE"
,
index
);
}
void
FailSafeConfig
::
fsLongClicked
(
bool
checked
)
{
if
(
!
m_uas
)
{
return
;
}
if
(
checked
)
{
m_uas
->
setParameter
(
1
,
"FS_LONG_ACTN"
,
1
);
}
else
{
m_uas
->
setParameter
(
1
,
"FS_LONG_ACTN"
,
0
);
}
}
void
FailSafeConfig
::
fsShortClicked
(
bool
checked
)
{
if
(
!
m_uas
)
{
return
;
}
if
(
checked
)
{
m_uas
->
setParameter
(
1
,
"FS_SHORT_ACTN"
,
1
);
}
else
{
m_uas
->
setParameter
(
1
,
"FS_SHORT_ACTN"
,
0
);
}
}
void
FailSafeConfig
::
batteryFailChecked
(
bool
checked
)
{
if
(
!
m_uas
)
{
return
;
}
if
(
checked
)
{
m_uas
->
setParameter
(
1
,
"FS_BATT_ENABLE"
,
1
);
}
else
{
m_uas
->
setParameter
(
1
,
"FS_BATT_ENABLE"
,
0
);
}
}
FailSafeConfig
::~
FailSafeConfig
()
{
}
void
FailSafeConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
AP2ConfigWidget
::
activeUASSet
(
uas
);
connect
(
uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanges
(
int
,
float
)));
connect
(
uas
,
SIGNAL
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)));
connect
(
uas
,
SIGNAL
(
armingChanged
(
bool
)),
this
,
SLOT
(
armingChanged
(
bool
)));
if
(
uas
->
getSystemType
()
==
MAV_TYPE_FIXED_WING
)
{
ui
.
batteryFailCheckBox
->
setVisible
(
false
);
ui
.
throttleFailSafeComboBox
->
setVisible
(
false
);
ui
.
batteryVoltSpinBox
->
setVisible
(
false
);
ui
.
label_6
->
setVisible
(
false
);
ui
.
throttlePwmSpinBox
->
setVisible
(
true
);
//Both
ui
.
throttleCheckBox
->
setVisible
(
true
);
ui
.
throttleActionCheckBox
->
setVisible
(
true
);
ui
.
gcsCheckBox
->
setVisible
(
true
);
ui
.
fsLongCheckBox
->
setVisible
(
true
);
ui
.
fsShortCheckBox
->
setVisible
(
true
);
}
else
if
(
uas
->
getSystemType
()
==
MAV_TYPE_QUADROTOR
)
{
ui
.
batteryFailCheckBox
->
setVisible
(
true
);
ui
.
throttleFailSafeComboBox
->
setVisible
(
true
);
ui
.
batteryVoltSpinBox
->
setVisible
(
true
);
ui
.
label_6
->
setVisible
(
true
);
ui
.
throttlePwmSpinBox
->
setVisible
(
true
);
//Both
ui
.
throttleCheckBox
->
setVisible
(
false
);
ui
.
throttleActionCheckBox
->
setVisible
(
false
);
ui
.
gcsCheckBox
->
setVisible
(
false
);
ui
.
fsLongCheckBox
->
setVisible
(
false
);
ui
.
fsShortCheckBox
->
setVisible
(
false
);
}
else
{
//Show all, just in case
ui
.
batteryFailCheckBox
->
setVisible
(
true
);
ui
.
throttleFailSafeComboBox
->
setVisible
(
true
);
ui
.
batteryVoltSpinBox
->
setVisible
(
true
);
ui
.
throttlePwmSpinBox
->
setVisible
(
true
);
//Both
ui
.
throttleCheckBox
->
setVisible
(
true
);
ui
.
throttleActionCheckBox
->
setVisible
(
true
);
ui
.
gcsCheckBox
->
setVisible
(
true
);
ui
.
fsLongCheckBox
->
setVisible
(
true
);
ui
.
fsShortCheckBox
->
setVisible
(
true
);
}
}
void
FailSafeConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
//Arducopter
if
(
parameterName
==
"FS_THR_ENABLE"
)
{
ui
.
throttleFailSafeComboBox
->
setCurrentIndex
(
value
.
toInt
());
}
else
if
(
parameterName
==
"FS_THR_VALUE"
)
{
ui
.
throttlePwmSpinBox
->
setValue
(
value
.
toFloat
());
}
else
if
(
parameterName
==
"FS_BATT_ENABLE"
)
{
if
(
value
.
toInt
()
==
0
)
{
ui
.
batteryFailCheckBox
->
setChecked
(
false
);
}
else
{
ui
.
batteryFailCheckBox
->
setChecked
(
true
);
}
}
else
if
(
parameterName
==
"LOW_VOLT"
)
{
ui
.
batteryVoltSpinBox
->
setValue
(
value
.
toFloat
());
}
//Arduplane
else
if
(
parameterName
==
"THR_FAILSAFE"
)
{
if
(
value
.
toInt
()
==
0
)
{
ui
.
throttleCheckBox
->
setChecked
(
false
);
}
else
{
ui
.
throttleCheckBox
->
setChecked
(
true
);
}
}
else
if
(
parameterName
==
"THR_FS_VALUE"
)
{
ui
.
throttlePwmSpinBox
->
setValue
(
value
.
toFloat
());
}
else
if
(
parameterName
==
"THR_FS_ACTION"
)
{
if
(
value
.
toInt
()
==
0
)
{
ui
.
throttleActionCheckBox
->
setChecked
(
false
);
}
else
{
ui
.
throttleActionCheckBox
->
setChecked
(
true
);
}
}
else
if
(
parameterName
==
"FS_GCS_ENABL"
)
{
if
(
value
.
toInt
()
==
0
)
{
ui
.
gcsCheckBox
->
setChecked
(
false
);
}
else
{
ui
.
gcsCheckBox
->
setChecked
(
true
);
}
}
else
if
(
parameterName
==
"FS_SHORT_ACTN"
)
{
if
(
value
.
toInt
()
==
0
)
{
ui
.
fsShortCheckBox
->
setChecked
(
false
);
}
else
{
ui
.
fsShortCheckBox
->
setChecked
(
true
);
}
}
else
if
(
parameterName
==
"FS_LONG_ACTN"
)
{
if
(
value
.
toInt
()
==
0
)
{
ui
.
fsLongCheckBox
->
setChecked
(
false
);
}
else
{
ui
.
fsLongCheckBox
->
setChecked
(
true
);
}
}
}
void
FailSafeConfig
::
armingChanged
(
bool
armed
)
{
if
(
armed
)
{
ui
.
armedLabel
->
setText
(
"<h1>ARMED</h1>"
);
}
else
{
ui
.
armedLabel
->
setText
(
"<h1>DISARMED</h1>"
);
}
}
void
FailSafeConfig
::
remoteControlChannelRawChanges
(
int
chan
,
float
value
)
{
if
(
chan
==
0
)
{
ui
.
radio1In
->
setValue
(
value
);
}
else
if
(
chan
==
1
)
{
ui
.
radio2In
->
setValue
(
value
);
}
else
if
(
chan
==
2
)
{
ui
.
radio3In
->
setValue
(
value
);
}
else
if
(
chan
==
3
)
{
ui
.
radio4In
->
setValue
(
value
);
}
else
if
(
chan
==
4
)
{
ui
.
radio5In
->
setValue
(
value
);
}
else
if
(
chan
==
5
)
{
ui
.
radio6In
->
setValue
(
value
);
}
else
if
(
chan
==
6
)
{
ui
.
radio7In
->
setValue
(
value
);
}
else
if
(
chan
==
7
)
{
ui
.
radio8In
->
setValue
(
value
);
}
}
void
FailSafeConfig
::
hilActuatorsChanged
(
uint64_t
time
,
float
act1
,
float
act2
,
float
act3
,
float
act4
,
float
act5
,
float
act6
,
float
act7
,
float
act8
)
{
ui
.
radio1Out
->
setValue
(
act1
);
ui
.
radio2Out
->
setValue
(
act2
);
ui
.
radio3Out
->
setValue
(
act3
);
ui
.
radio4Out
->
setValue
(
act4
);
ui
.
radio5Out
->
setValue
(
act5
);
ui
.
radio6Out
->
setValue
(
act6
);
ui
.
radio7Out
->
setValue
(
act7
);
ui
.
radio8Out
->
setValue
(
act8
);
}
src/ui/configuration/FailSafeConfig.h
View file @
4cd86dec
...
...
@@ -3,15 +3,28 @@
#include <QWidget>
#include "ui_FailSafeConfig.h"
class
FailSafeConfig
:
public
Q
Widget
#include "AP2ConfigWidget.h"
class
FailSafeConfig
:
public
AP2Config
Widget
{
Q_OBJECT
public:
explicit
FailSafeConfig
(
QWidget
*
parent
=
0
);
~
FailSafeConfig
();
private
slots
:
void
activeUASSet
(
UASInterface
*
uas
);
void
remoteControlChannelRawChanges
(
int
chan
,
float
value
);
void
hilActuatorsChanged
(
uint64_t
time
,
float
act1
,
float
act2
,
float
act3
,
float
act4
,
float
act5
,
float
act6
,
float
act7
,
float
act8
);
void
armingChanged
(
bool
armed
);
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
void
batteryFailChecked
(
bool
checked
);
void
fsLongClicked
(
bool
checked
);
void
fsShortClicked
(
bool
checked
);
void
gcsChecked
(
bool
checked
);
void
throttleActionChecked
(
bool
checked
);
void
throttleChecked
(
bool
checked
);
void
throttlePwmChanged
();
void
throttleFailSafeChanged
(
int
index
);
private:
Ui
::
FailSafeConfig
ui
;
};
...
...
src/ui/configuration/FailSafeConfig.ui
View file @
4cd86dec
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
400
</width>
<height>
300
</height>
<width>
822
</width>
<height>
536
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -26,7 +26,427 @@
<string>
<
h2
>
Fail Safe
<
/h2
>
</string>
</property>
</widget>
<widget
class=
"QWidget"
name=
"verticalLayoutWidget"
>
<property
name=
"geometry"
>
<rect>
<x>
20
</x>
<y>
70
</y>
<width>
252
</width>
<height>
441
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio1In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio2In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio3In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio4In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio5In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio6In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio7In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio8In"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget
class=
"QWidget"
name=
"verticalLayoutWidget_2"
>
<property
name=
"geometry"
>
<rect>
<x>
300
</x>
<y>
70
</y>
<width>
252
</width>
<height>
441
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_2"
>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio1Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio2Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio3Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio4Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio5Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio6Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio7Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio8Out"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget
class=
"QGroupBox"
name=
"groupBox"
>
<property
name=
"geometry"
>
<rect>
<x>
570
</x>
<y>
60
</y>
<width>
181
</width>
<height>
181
</height>
</rect>
</property>
<property
name=
"title"
>
<string>
Status
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_3"
>
<item>
<widget
class=
"QLabel"
name=
"modeLabel"
>
<property
name=
"text"
>
<string>
TextLabel
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"armedLabel"
>
<property
name=
"text"
>
<string>
TextLabel
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"gpsLabel"
>
<property
name=
"text"
>
<string>
TextLabel
</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget
class=
"QGroupBox"
name=
"groupBox_2"
>
<property
name=
"geometry"
>
<rect>
<x>
570
</x>
<y>
250
</y>
<width>
161
</width>
<height>
261
</height>
</rect>
</property>
<property
name=
"title"
>
<string>
Failsafe Options
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_4"
>
<item>
<widget
class=
"QCheckBox"
name=
"throttleCheckBox"
>
<property
name=
"text"
>
<string>
Throttle FailSafe
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QComboBox"
name=
"throttleFailSafeComboBox"
/>
</item>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_2"
>
<item>
<widget
class=
"QLabel"
name=
"label_5"
>
<property
name=
"text"
>
<string>
FS Pwm
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QSpinBox"
name=
"throttlePwmSpinBox"
>
<property
name=
"maximum"
>
<number>
3000
</number>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget
class=
"QCheckBox"
name=
"throttleActionCheckBox"
>
<property
name=
"text"
>
<string>
Throttle FailSafe Action
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QCheckBox"
name=
"gcsCheckBox"
>
<property
name=
"text"
>
<string>
GCS FailSafe
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QCheckBox"
name=
"fsShortCheckBox"
>
<property
name=
"text"
>
<string>
FailSafe Short (1 sec)
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QCheckBox"
name=
"fsLongCheckBox"
>
<property
name=
"text"
>
<string>
FailSafe Long (20 sec)
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QCheckBox"
name=
"batteryFailCheckBox"
>
<property
name=
"text"
>
<string>
Battery Failsafe
</string>
</property>
</widget>
</item>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<item>
<widget
class=
"QLabel"
name=
"label_6"
>
<property
name=
"text"
>
<string>
Low Battery
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"batteryVoltSpinBox"
>
<property
name=
"maximum"
>
<double>
100.000000000000000
</double>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
<customwidgets>
<customwidget>
<class>
QGCRadioChannelDisplay
</class>
<extends>
QWidget
</extends>
<header>
ui/designer/QGCRadioChannelDisplay.h
</header>
<container>
1
</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
src/ui/configuration/ParamWidget.cc
0 → 100644
View file @
4cd86dec
#include "ParamWidget.h"
ParamWidget
::
ParamWidget
(
QWidget
*
parent
)
:
QWidget
(
parent
)
{
ui
.
setupUi
(
this
);
}
ParamWidget
::~
ParamWidget
()
{
}
void
ParamWidget
::
setupInt
(
QString
title
,
QString
description
,
int
value
,
int
min
,
int
max
)
{
type
=
INT
;
ui
.
titleLabel
->
setText
(
"<h3>"
+
title
+
"</h3>"
);
ui
.
descriptionLabel
->
setText
(
description
);
ui
.
valueComboBox
->
hide
();
ui
.
valueSlider
->
show
();
ui
.
intSpinBox
->
show
();
ui
.
doubleSpinBox
->
hide
();
m_min
=
min
;
m_max
=
max
;
}
void
ParamWidget
::
setupDouble
(
QString
title
,
QString
description
,
double
value
,
double
min
,
double
max
)
{
type
=
DOUBLE
;
ui
.
titleLabel
->
setText
(
"<h3>"
+
title
+
"</h3>"
);
ui
.
descriptionLabel
->
setText
(
description
);
ui
.
valueComboBox
->
hide
();
ui
.
valueSlider
->
show
();
ui
.
intSpinBox
->
hide
();
ui
.
doubleSpinBox
->
show
();
m_min
=
min
;
m_max
=
max
;
}
void
ParamWidget
::
setupCombo
(
QString
title
,
QString
description
,
QList
<
QPair
<
int
,
QString
>
>
list
)
{
type
=
COMBO
;
ui
.
titleLabel
->
setText
(
"<h3>"
+
title
+
"</h3>"
);
ui
.
descriptionLabel
->
setText
(
description
);
ui
.
valueComboBox
->
show
();
ui
.
valueSlider
->
hide
();
ui
.
intSpinBox
->
hide
();
ui
.
doubleSpinBox
->
hide
();
m_valueList
=
list
;
ui
.
valueComboBox
->
clear
();
for
(
int
i
=
0
;
i
<
m_valueList
.
size
();
i
++
)
{
ui
.
valueComboBox
->
addItem
(
m_valueList
[
i
].
second
);
}
}
void
ParamWidget
::
setValue
(
double
value
)
{
if
(
type
==
INT
)
{
ui
.
intSpinBox
->
setValue
(
value
);
ui
.
valueSlider
->
setValue
(((
value
+
m_min
)
/
(
m_max
+
m_min
))
*
100.0
);
}
else
if
(
type
==
DOUBLE
)
{
ui
.
doubleSpinBox
->
setValue
(
value
);
ui
.
valueSlider
->
setValue
(((
value
+
m_min
)
/
(
m_max
+
m_min
))
*
100.0
);
}
else
if
(
type
==
COMBO
)
{
for
(
int
i
=
0
;
i
<
m_valueList
.
size
();
i
++
)
{
if
((
int
)
value
==
m_valueList
[
i
].
first
)
{
ui
.
valueComboBox
->
setCurrentIndex
(
i
);
return
;
}
}
}
}
src/ui/configuration/ParamWidget.h
0 → 100644
View file @
4cd86dec
#ifndef PARAMWIDGET_H
#define PARAMWIDGET_H
#include <QWidget>
#include "ui_ParamWidget.h"
class
ParamWidget
:
public
QWidget
{
Q_OBJECT
public:
explicit
ParamWidget
(
QWidget
*
parent
=
0
);
~
ParamWidget
();
void
setupInt
(
QString
title
,
QString
description
,
int
value
,
int
min
,
int
max
);
void
setupDouble
(
QString
title
,
QString
description
,
double
value
,
double
min
,
double
max
);
void
setupCombo
(
QString
title
,
QString
description
,
QList
<
QPair
<
int
,
QString
>
>
list
);
void
setValue
(
double
value
);
private:
enum
VIEWTYPE
{
INT
,
DOUBLE
,
COMBO
};
double
m_min
;
double
m_max
;
double
m_dvalue
;
int
m_ivalue
;
VIEWTYPE
type
;
QList
<
QPair
<
int
,
QString
>
>
m_valueList
;
Ui
::
ParamWidget
ui
;
};
#endif // PARAMWIDGET_H
src/ui/configuration/ParamWidget.ui
0 → 100644
View file @
4cd86dec
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
ParamWidget
</class>
<widget
class=
"QWidget"
name=
"ParamWidget"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
619
</width>
<height>
207
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_2"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<item>
<widget
class=
"QLabel"
name=
"titleLabel"
>
<property
name=
"text"
>
<string>
TextLabel
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"descriptionLabel"
>
<property
name=
"text"
>
<string>
TextLabel
</string>
</property>
<property
name=
"wordWrap"
>
<bool>
true
</bool>
</property>
</widget>
</item>
<item>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<item>
<widget
class=
"QSpinBox"
name=
"intSpinBox"
/>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"doubleSpinBox"
/>
</item>
<item>
<widget
class=
"QSlider"
name=
"valueSlider"
>
<property
name=
"maximum"
>
<number>
100
</number>
</property>
<property
name=
"orientation"
>
<enum>
Qt::Horizontal
</enum>
</property>
</widget>
</item>
<item>
<widget
class=
"QComboBox"
name=
"valueComboBox"
/>
</item>
</layout>
</item>
</layout>
</item>
<item>
<spacer
name=
"horizontalSpacer"
>
<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>
</widget>
<resources/>
<connections/>
</ui>
src/ui/configuration/SonarConfig.ui
View file @
4cd86dec
...
...
@@ -58,7 +58,7 @@
</rect>
</property>
<property
name=
"text"
>
<string>
CheckBox
</string>
<string>
Enable
</string>
</property>
</widget>
<widget
class=
"QComboBox"
name=
"sonarTypeComboBox"
>
...
...
src/ui/configuration/StandardParamConfig.cc
View file @
4cd86dec
#include "StandardParamConfig.h"
#include "ParamWidget.h"
StandardParamConfig
::
StandardParamConfig
(
QWidget
*
parent
)
:
AP2ConfigWidget
(
parent
)
{
ui
.
setupUi
(
this
);
}
StandardParamConfig
::~
StandardParamConfig
()
{
}
StandardParamConfig
::
StandardParamConfig
(
QWidget
*
parent
)
:
QWidget
(
parent
)
void
StandardParamConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
ui
.
setupUi
(
this
);
AP2ConfigWidget
::
activeUASSet
(
uas
);
}
void
StandardParamConfig
::
addRange
(
QString
title
,
QString
description
,
QString
param
,
double
min
,
double
max
)
{
ParamWidget
*
widget
=
new
ParamWidget
(
ui
.
scrollAreaWidgetContents
);
paramToWidgetMap
[
param
]
=
widget
;
widget
->
setupDouble
(
title
+
"("
+
param
+
")"
,
description
,
0
,
min
,
max
);
ui
.
verticalLayout
->
addWidget
(
widget
);
widget
->
show
();
}
StandardParamConfig
::~
StandardParamConfig
()
void
StandardParamConfig
::
addCombo
(
QString
title
,
QString
description
,
QString
param
,
QList
<
QPair
<
int
,
QString
>
>
valuelist
)
{
ParamWidget
*
widget
=
new
ParamWidget
(
ui
.
scrollAreaWidgetContents
);
paramToWidgetMap
[
param
]
=
widget
;
widget
->
setupCombo
(
title
+
"("
+
param
+
")"
,
description
,
valuelist
);
ui
.
verticalLayout
->
addWidget
(
widget
);
widget
->
show
();
}
void
StandardParamConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
paramToWidgetMap
.
contains
(
parameterName
))
{
paramToWidgetMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
}
}
src/ui/configuration/StandardParamConfig.h
View file @
4cd86dec
...
...
@@ -3,16 +3,22 @@
#include <QWidget>
#include "ui_StandardParamConfig.h"
class
StandardParamConfig
:
public
QWidget
#include "AP2ConfigWidget.h"
#include "ParamWidget.h"
class
StandardParamConfig
:
public
AP2ConfigWidget
{
Q_OBJECT
public:
explicit
StandardParamConfig
(
QWidget
*
parent
=
0
);
~
StandardParamConfig
();
void
addRange
(
QString
title
,
QString
description
,
QString
param
,
double
min
,
double
max
);
void
addCombo
(
QString
title
,
QString
description
,
QString
param
,
QList
<
QPair
<
int
,
QString
>
>
valuelist
);
private
slots
:
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QMap
<
QString
,
ParamWidget
*>
paramToWidgetMap
;
void
activeUASSet
(
UASInterface
*
uas
);
Ui
::
StandardParamConfig
ui
;
};
...
...
src/ui/configuration/StandardParamConfig.ui
View file @
4cd86dec
...
...
@@ -6,26 +6,44 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
400
</width>
<height>
300
</height>
<width>
651
</width>
<height>
552
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"geometry"
>
<rect>
<x>
20
</x>
<y>
20
</y>
<width>
201
</width>
<height>
41
</height>
</rect>
</property>
<property
name=
"text"
>
<string>
<
h2
>
Standard Params
<
/h2
>
</string>
</property>
</widget>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_3"
>
<item>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"text"
>
<string>
<
h2
>
Standard Params
<
/h2
>
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QScrollArea"
name=
"scrollArea"
>
<property
name=
"widgetResizable"
>
<bool>
true
</bool>
</property>
<widget
class=
"QWidget"
name=
"scrollAreaWidgetContents"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
631
</width>
<height>
505
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_2"
>
<item>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
/>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment