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
160e0014
Commit
160e0014
authored
Sep 24, 2012
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
HIL and Joystick input
parent
b3f6fe78
Changes
10
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
358 additions
and
82 deletions
+358
-82
QGCFlightGearLink.cc
src/comm/QGCFlightGearLink.cc
+5
-0
QGCFlightGearLink.h
src/comm/QGCFlightGearLink.h
+6
-0
QGCHilLink.h
src/comm/QGCHilLink.h
+6
-0
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+46
-31
QGCXPlaneLink.h
src/comm/QGCXPlaneLink.h
+16
-0
JoystickInput.cc
src/input/JoystickInput.cc
+40
-3
JoystickInput.h
src/input/JoystickInput.h
+82
-0
UAS.cc
src/uas/UAS.cc
+3
-3
JoystickWidget.cc
src/ui/JoystickWidget.cc
+11
-0
JoystickWidget.ui
src/ui/JoystickWidget.ui
+143
-45
No files found.
src/comm/QGCFlightGearLink.cc
View file @
160e0014
...
...
@@ -503,6 +503,11 @@ QString QGCFlightGearLink::getName()
return
name
;
}
QString
QGCFlightGearLink
::
getRemoteHost
()
{
return
QString
(
"%1:%2"
).
arg
(
currentHost
.
toString
(),
currentPort
);
}
void
QGCFlightGearLink
::
setName
(
QString
name
)
{
this
->
name
=
name
;
...
...
src/comm/QGCFlightGearLink.h
View file @
160e0014
...
...
@@ -63,6 +63,12 @@ public:
*/
QString
getName
();
/**
* @brief Get remote host and port
* @return string in format <host>:<port>
*/
QString
getRemoteHost
();
void
run
();
public
slots
:
...
...
src/comm/QGCHilLink.h
View file @
160e0014
...
...
@@ -19,6 +19,12 @@ public:
*/
virtual
QString
getName
()
=
0
;
/**
* @brief Get remote host and port
* @return string in format <host>:<port>
*/
virtual
QString
getRemoteHost
()
=
0
;
public
slots
:
virtual
void
setPort
(
int
port
)
=
0
;
/** @brief Add a new host to broadcast messages to */
...
...
src/comm/QGCXPlaneLink.cc
View file @
160e0014
...
...
@@ -51,15 +51,38 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress
this
->
connectState
=
false
;
this
->
name
=
tr
(
"X-Plane Link (localPort:%1)"
).
arg
(
localPort
);
setRemoteHost
(
remoteHost
);
loadSettings
();
}
QGCXPlaneLink
::~
QGCXPlaneLink
()
{
storeSettings
();
// if(connectState) {
// disconnectSimulation();
// }
}
void
QGCXPlaneLink
::
loadSettings
()
{
// Load defaults from settings
QSettings
settings
;
settings
.
sync
();
settings
.
beginGroup
(
"QGC_XPLANE_LINK"
);
setRemoteHost
(
settings
.
value
(
"REMOTE_HOST"
,
QString
(
"%1:%2"
).
arg
(
remoteHost
.
toString
(),
remotePort
)).
toString
());
settings
.
endGroup
();
}
void
QGCXPlaneLink
::
storeSettings
()
{
// Store settings
QSettings
settings
;
settings
.
beginGroup
(
"QGC_XPLANE_LINK"
);
settings
.
setValue
(
"REMOTE_HOST"
,
QString
(
"%1:%2"
).
arg
(
remoteHost
.
toString
(),
remotePort
));
settings
.
endGroup
();
settings
.
sync
();
}
/**
* @brief Runs the thread
*
...
...
@@ -102,62 +125,54 @@ void QGCXPlaneLink::processError(QProcess::ProcessError err)
}
}
QString
QGCXPlaneLink
::
getRemoteHost
()
{
return
QString
(
"%1:%2"
).
arg
(
remoteHost
.
toString
(),
remotePort
);
}
/**
* @param
localHost Hostname in standard formatting, e.g. locallocalH
ost:14551 or 192.168.1.1:14551
* @param
newHost Hostname in standard formatting, e.g. localh
ost:14551 or 192.168.1.1:14551
*/
void
QGCXPlaneLink
::
setRemoteHost
(
const
QString
&
local
Host
)
void
QGCXPlaneLink
::
setRemoteHost
(
const
QString
&
new
Host
)
{
if
(
local
Host
.
contains
(
":"
))
if
(
new
Host
.
contains
(
":"
))
{
//qDebug() << "HOST: " <<
local
Host.split(":").first();
QHostInfo
info
=
QHostInfo
::
fromName
(
local
Host
.
split
(
":"
).
first
());
//qDebug() << "HOST: " <<
new
Host.split(":").first();
QHostInfo
info
=
QHostInfo
::
fromName
(
new
Host
.
split
(
":"
).
first
());
if
(
info
.
error
()
==
QHostInfo
::
NoError
)
{
// Add
local
Host
QList
<
QHostAddress
>
local
HostAddresses
=
info
.
addresses
();
// Add
new
Host
QList
<
QHostAddress
>
new
HostAddresses
=
info
.
addresses
();
QHostAddress
address
;
for
(
int
i
=
0
;
i
<
local
HostAddresses
.
size
();
i
++
)
for
(
int
i
=
0
;
i
<
new
HostAddresses
.
size
();
i
++
)
{
// Exclude loopback IPv4 and all IPv6 addresses
if
(
!
local
HostAddresses
.
at
(
i
).
toString
().
contains
(
":"
))
if
(
!
new
HostAddresses
.
at
(
i
).
toString
().
contains
(
":"
))
{
address
=
local
HostAddresses
.
at
(
i
);
address
=
new
HostAddresses
.
at
(
i
);
}
}
remoteHost
=
address
;
//qDebug() << "Address:" << address.toString();
// Set localPort according to user input
remotePort
=
local
Host
.
split
(
":"
).
last
().
toInt
();
remotePort
=
new
Host
.
split
(
":"
).
last
().
toInt
();
}
}
else
{
QHostInfo
info
=
QHostInfo
::
fromName
(
local
Host
);
QHostInfo
info
=
QHostInfo
::
fromName
(
new
Host
);
if
(
info
.
error
()
==
QHostInfo
::
NoError
)
{
// Add
local
Host
// Add
new
Host
remoteHost
=
info
.
addresses
().
first
();
}
}
// // Send request to send correct data
//#pragma pack(push, 1)
// struct payload {
// char b[5];
// int index;
// float f[8];
// } p;
//#pragma pack(pop)
// p.b[0] = 'D';
// p.b[1] = 'A';
// p.b[2] = 'T';
// p.b[3] = 'A';
// p.b[4] = '\0';
// p.f[0]
// writeBytes((const char*)&p, sizeof(p));
if
(
isConnected
())
{
disconnectSimulation
();
connectSimulation
();
}
}
void
QGCXPlaneLink
::
updateControls
(
uint64_t
time
,
float
rollAilerons
,
float
pitchElevator
,
float
yawRudder
,
float
throttle
,
uint8_t
systemMode
,
uint8_t
navMode
)
...
...
src/comm/QGCXPlaneLink.h
View file @
160e0014
...
...
@@ -52,6 +52,16 @@ public:
QGCXPlaneLink
(
UASInterface
*
mav
,
QString
remoteHost
=
QString
(
"127.0.0.1:49000"
),
QHostAddress
localHost
=
QHostAddress
::
Any
,
quint16
localPort
=
49005
);
~
QGCXPlaneLink
();
/**
* @brief Load X-Plane HIL settings
*/
void
loadSettings
();
/**
* @brief Store X-Plane HIL settings
*/
void
storeSettings
();
bool
isConnected
();
qint64
bytesAvailable
();
int
getPort
()
const
{
...
...
@@ -65,6 +75,12 @@ public:
void
run
();
/**
* @brief Get remote host and port
* @return string in format <host>:<port>
*/
QString
getRemoteHost
();
public
slots
:
// void setAddress(QString address);
void
setPort
(
int
port
);
...
...
src/input/JoystickInput.cc
View file @
160e0014
...
...
@@ -18,6 +18,7 @@
#include "UASManager.h"
#include "QGC.h"
#include <QMutexLocker>
#include <QSettings>
/**
* The coordinate frame of the joystick axis is the aeronautical frame like shown on this image:
...
...
@@ -34,8 +35,13 @@ JoystickInput::JoystickInput() :
xAxis
(
0
),
yAxis
(
1
),
yawAxis
(
3
),
autoButtonMapping
(
-
1
),
manualButtonMapping
(
-
1
),
stabilizeButtonMapping
(
-
1
),
joystickName
(
tr
(
"Unitinialized"
))
{
loadSettings
();
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
calibrationPositive
[
i
]
=
sdlJoystickMax
;
calibrationNegative
[
i
]
=
sdlJoystickMin
;
...
...
@@ -49,9 +55,40 @@ JoystickInput::JoystickInput() :
JoystickInput
::~
JoystickInput
()
{
storeSettings
();
done
=
true
;
QGC
::
SLEEP
::
usleep
(
50000
);
this
->
deleteLater
();
}
void
JoystickInput
::
loadSettings
()
{
// Load defaults from settings
QSettings
settings
;
settings
.
sync
();
settings
.
beginGroup
(
"QGC_JOYSTICK_INPUT"
);
xAxis
=
(
settings
.
value
(
"X_AXIS_MAPPING"
,
xAxis
).
toInt
());
yAxis
=
(
settings
.
value
(
"Y_AXIS_MAPPING"
,
yAxis
).
toInt
());
thrustAxis
=
(
settings
.
value
(
"THRUST_AXIS_MAPPING"
,
thrustAxis
).
toInt
());
yawAxis
=
(
settings
.
value
(
"YAW_AXIS_MAPPING"
,
yawAxis
).
toInt
());
autoButtonMapping
=
(
settings
.
value
(
"AUTO_BUTTON_MAPPING"
,
autoButtonMapping
).
toInt
());
stabilizeButtonMapping
=
(
settings
.
value
(
"STABILIZE_BUTTON_MAPPING"
,
stabilizeButtonMapping
).
toInt
());
manualButtonMapping
=
(
settings
.
value
(
"MANUAL_BUTTON_MAPPING"
,
manualButtonMapping
).
toInt
());
settings
.
endGroup
();
}
void
JoystickInput
::
storeSettings
()
{
// Store settings
QSettings
settings
;
settings
.
beginGroup
(
"QGC_JOYSTICK_INPUT"
);
settings
.
setValue
(
"X_AXIS_MAPPING"
,
xAxis
);
settings
.
setValue
(
"Y_AXIS_MAPPING"
,
yAxis
);
settings
.
setValue
(
"THRUST_AXIS_MAPPING"
,
thrustAxis
);
settings
.
setValue
(
"YAW_AXIS_MAPPING"
,
yawAxis
);
settings
.
setValue
(
"AUTO_BUTTON_MAPPING"
,
autoButtonMapping
);
settings
.
setValue
(
"STABILIZE_BUTTON_MAPPING"
,
stabilizeButtonMapping
);
settings
.
setValue
(
"MANUAL_BUTTON_MAPPING"
,
manualButtonMapping
);
settings
.
endGroup
();
settings
.
sync
();
}
...
...
@@ -95,7 +132,7 @@ void JoystickInput::init()
// Wait for joysticks if none is connected
while
(
numJoysticks
==
0
)
{
QGC
::
SLEEP
::
msleep
(
8
00
);
QGC
::
SLEEP
::
msleep
(
4
00
);
// INITIALIZE SDL Joystick support
if
(
SDL_InitSubSystem
(
SDL_INIT_JOYSTICK
|
SDL_INIT_NOPARACHUTE
)
<
0
)
{
...
...
src/input/JoystickInput.h
View file @
160e0014
...
...
@@ -58,6 +58,51 @@ public:
const
QString
&
getName
();
/**
* @brief Load joystick settings
*/
void
loadSettings
();
/**
* @brief Store joystick settings
*/
void
storeSettings
();
int
getMappingThrustAxis
()
{
return
thrustAxis
;
}
int
getMappingXAxis
()
{
return
xAxis
;
}
int
getMappingYAxis
()
{
return
yAxis
;
}
int
getMappingYawAxis
()
{
return
yawAxis
;
}
int
getMappingAutoButton
()
{
return
autoButtonMapping
;
}
int
getMappingManualButton
()
{
return
manualButtonMapping
;
}
int
getMappingStabilizeButton
()
{
return
stabilizeButtonMapping
;
}
const
double
sdlJoystickMin
;
const
double
sdlJoystickMax
;
...
...
@@ -76,6 +121,9 @@ protected:
int
xAxis
;
int
yAxis
;
int
yawAxis
;
int
autoButtonMapping
;
int
manualButtonMapping
;
int
stabilizeButtonMapping
;
SDL_Event
event
;
QString
joystickName
;
...
...
@@ -149,6 +197,40 @@ signals:
public
slots
:
void
setActiveUAS
(
UASInterface
*
uas
);
void
setMappingThrustAxis
(
int
mapping
)
{
thrustAxis
=
mapping
;
}
void
setMappingXAxis
(
int
mapping
)
{
xAxis
=
mapping
;
}
void
setMappingYAxis
(
int
mapping
)
{
yAxis
=
mapping
;
}
void
setMappingYawAxis
(
int
mapping
)
{
yawAxis
=
mapping
;
}
void
setMappingAutoButton
(
int
mapping
)
{
autoButtonMapping
=
mapping
;
}
void
setMappingManualButton
(
int
mapping
)
{
manualButtonMapping
=
mapping
;
}
void
setMappingStabilizeButton
(
int
mapping
)
{
stabilizeButtonMapping
=
mapping
;
}
};
#endif // _JOYSTICKINPUT_H_
src/uas/UAS.cc
View file @
160e0014
...
...
@@ -2393,9 +2393,9 @@ void UAS::disarmSystem()
void
UAS
::
setManualControlCommands
(
double
roll
,
double
pitch
,
double
yaw
,
double
thrust
)
{
// Scale values
double
rollPitchScaling
=
0.2
f
;
double
yawScaling
=
0.5
f
;
double
thrustScaling
=
1.0
f
;
double
rollPitchScaling
=
0.2
f
*
1000.0
f
;
double
yawScaling
=
0.5
f
*
1000.0
f
;
double
thrustScaling
=
1.0
f
*
1000.0
f
;
manualRollAngle
=
roll
*
rollPitchScaling
;
manualPitchAngle
=
pitch
*
rollPitchScaling
;
...
...
src/ui/JoystickWidget.cc
View file @
160e0014
...
...
@@ -9,8 +9,19 @@ JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) :
m_ui
->
setupUi
(
this
);
this
->
joystick
=
joystick
;
m_ui
->
rollMapSpinBox
->
setValue
(
joystick
->
getMappingXAxis
());
m_ui
->
pitchMapSpinBox
->
setValue
(
joystick
->
getMappingYAxis
());
m_ui
->
yawMapSpinBox
->
setValue
(
joystick
->
getMappingYawAxis
());
m_ui
->
throttleMapSpinBox
->
setValue
(
joystick
->
getMappingThrustAxis
());
m_ui
->
autoMapSpinBox
->
setValue
(
joystick
->
getMappingAutoButton
());
connect
(
this
->
joystick
,
SIGNAL
(
joystickChanged
(
double
,
double
,
double
,
double
,
int
,
int
)),
this
,
SLOT
(
updateJoystick
(
double
,
double
,
double
,
double
,
int
,
int
)));
connect
(
this
->
joystick
,
SIGNAL
(
buttonPressed
(
int
)),
this
,
SLOT
(
pressKey
(
int
)));
connect
(
m_ui
->
rollMapSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
->
joystick
,
SLOT
(
setMappingXAxis
(
int
)));
connect
(
m_ui
->
pitchMapSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
->
joystick
,
SLOT
(
setMappingYAxis
(
int
)));
connect
(
m_ui
->
yawMapSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
->
joystick
,
SLOT
(
setMappingYawAxis
(
int
)));
connect
(
m_ui
->
throttleMapSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
->
joystick
,
SLOT
(
setMappingThrustAxis
(
int
)));
connect
(
m_ui
->
autoMapSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
this
->
joystick
,
SLOT
(
setMappingAutoButton
(
int
)));
// Display the widget
this
->
window
()
->
setWindowTitle
(
tr
(
"Joystick Settings"
));
...
...
src/ui/JoystickWidget.ui
View file @
160e0014
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
396
</width>
<height>
3
23
</height>
<width>
654
</width>
<height>
3
76
</height>
</rect>
</property>
<property
name=
"minimumSize"
>
...
...
@@ -19,13 +19,57 @@
<property
name=
"windowTitle"
>
<string>
Dialog
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout_2"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_2"
columnstretch=
"10,10,1,5"
>
<property
name=
"margin"
>
<number>
8
</number>
</property>
<property
name=
"spacing"
>
<number>
8
</number>
</property>
<item
row=
"1"
column=
"1"
colspan=
"2"
>
<widget
class=
"QLabel"
name=
"statusLabel"
>
<property
name=
"text"
>
<string>
No joystick detecte yet.. waiting
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QGroupBox"
name=
"groupBox_3"
>
<property
name=
"maximumSize"
>
<size>
<width>
60
</width>
<height>
16777215
</height>
</size>
</property>
<property
name=
"title"
>
<string>
Throttle
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_2"
>
<property
name=
"spacing"
>
<number>
0
</number>
</property>
<property
name=
"margin"
>
<number>
2
</number>
</property>
<item>
<widget
class=
"QProgressBar"
name=
"thrust"
>
<property
name=
"minimumSize"
>
<size>
<width>
40
</width>
<height>
20
</height>
</size>
</property>
<property
name=
"value"
>
<number>
0
</number>
</property>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QGroupBox"
name=
"groupBox_2"
>
<property
name=
"title"
>
...
...
@@ -85,6 +129,9 @@
<property
name=
"text"
>
<string>
Y
</string>
</property>
<property
name=
"alignment"
>
<set>
Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter
</set>
</property>
</widget>
</item>
<item
row=
"4"
column=
"0"
>
...
...
@@ -138,47 +185,6 @@
</layout>
</widget>
</item>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QGroupBox"
name=
"groupBox_3"
>
<property
name=
"maximumSize"
>
<size>
<width>
60
</width>
<height>
16777215
</height>
</size>
</property>
<property
name=
"title"
>
<string>
Throttle
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_2"
>
<property
name=
"margin"
>
<number>
2
</number>
</property>
<item>
<widget
class=
"QProgressBar"
name=
"thrust"
>
<property
name=
"minimumSize"
>
<size>
<width>
40
</width>
<height>
20
</height>
</size>
</property>
<property
name=
"value"
>
<number>
0
</number>
</property>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item
row=
"1"
column=
"1"
colspan=
"2"
>
<widget
class=
"QLabel"
name=
"statusLabel"
>
<property
name=
"text"
>
<string>
No joystick - connect and restart QGroundControl
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"0"
rowspan=
"3"
>
<widget
class=
"QGroupBox"
name=
"groupBox"
>
<property
name=
"maximumSize"
>
...
...
@@ -357,7 +363,7 @@
</layout>
</widget>
</item>
<item
row=
"
2"
column=
"1"
colspan=
"2
"
>
<item
row=
"
1"
column=
"3
"
>
<widget
class=
"QDialogButtonBox"
name=
"buttonBox"
>
<property
name=
"orientation"
>
<enum>
Qt::Horizontal
</enum>
...
...
@@ -367,6 +373,98 @@
</property>
</widget>
</item>
<item
row=
"0"
column=
"3"
>
<widget
class=
"QGroupBox"
name=
"groupBox_4"
>
<property
name=
"title"
>
<string>
Mappings
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout_3"
columnstretch=
"30,10"
>
<item
row=
"3"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_6"
>
<property
name=
"text"
>
<string>
Throttle
</string>
</property>
</widget>
</item>
<item
row=
"5"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_8"
>
<property
name=
"text"
>
<string>
Stabilized Button
</string>
</property>
</widget>
</item>
<item
row=
"4"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_7"
>
<property
name=
"text"
>
<string>
Auto Button
</string>
</property>
</widget>
</item>
<item
row=
"6"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_9"
>
<property
name=
"text"
>
<string>
Manual Button
</string>
</property>
</widget>
</item>
<item
row=
"1"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_4"
>
<property
name=
"text"
>
<string>
Pitch Axis
</string>
</property>
</widget>
</item>
<item
row=
"2"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_5"
>
<property
name=
"text"
>
<string>
Yaw Axis
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_3"
>
<property
name=
"text"
>
<string>
Roll Axis
</string>
</property>
</widget>
</item>
<item
row=
"7"
column=
"0"
colspan=
"2"
>
<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>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QSpinBox"
name=
"rollMapSpinBox"
/>
</item>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QSpinBox"
name=
"pitchMapSpinBox"
/>
</item>
<item
row=
"2"
column=
"1"
>
<widget
class=
"QSpinBox"
name=
"yawMapSpinBox"
/>
</item>
<item
row=
"3"
column=
"1"
>
<widget
class=
"QSpinBox"
name=
"throttleMapSpinBox"
/>
</item>
<item
row=
"4"
column=
"1"
>
<widget
class=
"QSpinBox"
name=
"autoMapSpinBox"
/>
</item>
<item
row=
"5"
column=
"1"
>
<widget
class=
"QSpinBox"
name=
"stabilizedMapSpinBox"
/>
</item>
<item
row=
"6"
column=
"1"
>
<widget
class=
"QSpinBox"
name=
"manualMapSpinBox"
/>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources/>
...
...
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