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
47d59fa9
Commit
47d59fa9
authored
Nov 24, 2012
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Firmware upgrade app, XPlane link improvements, better RC calibration
parent
16f28ff7
Changes
14
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
14 changed files
with
447 additions
and
245 deletions
+447
-245
PX4FirmwareUpgradeWorker.cc
src/PX4FirmwareUpgradeWorker.cc
+48
-16
PX4FirmwareUpgradeWorker.h
src/PX4FirmwareUpgradeWorker.h
+19
-4
QUpgradeApp.cc
src/apps/qupgrade/QUpgradeApp.cc
+12
-4
QUpgradeMainWindow.cc
src/apps/qupgrade/QUpgradeMainWindow.cc
+0
-4
QUpgradeMainWindow.h
src/apps/qupgrade/QUpgradeMainWindow.h
+0
-2
QUpgradeMainWindow.ui
src/apps/qupgrade/QUpgradeMainWindow.ui
+1
-9
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+17
-4
QGCXPlaneLink.h
src/comm/QGCXPlaneLink.h
+3
-0
PX4FirmwareUpgrader.cc
src/ui/PX4FirmwareUpgrader.cc
+16
-1
QGCHilConfiguration.cc
src/ui/QGCHilConfiguration.cc
+8
-2
QGCHilConfiguration.ui
src/ui/QGCHilConfiguration.ui
+15
-38
QGCVehicleConfig.cc
src/ui/QGCVehicleConfig.cc
+201
-133
QGCVehicleConfig.h
src/ui/QGCVehicleConfig.h
+75
-3
QGCVehicleConfig.ui
src/ui/QGCVehicleConfig.ui
+32
-25
No files found.
src/PX4FirmwareUpgradeWorker.cc
View file @
47d59fa9
#include <QJsonDocument>
#include <QFile>
#include "PX4FirmwareUpgradeWorker.h"
#include <SerialLink.h>
...
...
@@ -49,21 +52,28 @@ PX4FirmwareUpgradeWorker* PX4FirmwareUpgradeWorker::putWorkerInThread(QObject *p
// Starts an event loop, and emits workerThread->started()
workerThread
->
start
();
return
worker
;
}
bool
PX4FirmwareUpgradeWorker
::
startContinousScan
()
void
PX4FirmwareUpgradeWorker
::
startContinousScan
()
{
while
(
true
)
{
if
(
detect
())
{
break
;
}
exitThread
=
false
;
while
(
!
exitThread
)
{
// if (detect()) {
// break;
// }
QGC
::
SLEEP
::
msleep
(
20
);
}
return
true
;
if
(
exitThread
)
{
link
->
disconnect
();
delete
link
;
exit
(
0
);
}
}
bool
PX4FirmwareUpgradeWorker
::
detect
()
void
PX4FirmwareUpgradeWorker
::
detect
()
{
if
(
!
link
)
{
...
...
@@ -80,7 +90,7 @@ bool PX4FirmwareUpgradeWorker::detect()
// Ignore known wrong link names
if
(
ports
->
at
(
i
).
contains
(
"Bluetooth"
))
{
continue
;
//
continue;
}
link
->
setPortName
(
ports
->
at
(
i
));
...
...
@@ -101,12 +111,6 @@ bool PX4FirmwareUpgradeWorker::detect()
break
;
}
if
(
insync
)
{
return
true
;
}
else
{
return
false
;
}
//ui.portName->setCurrentIndex(ui.baudRate->findText(QString("%1").arg(this->link->getPortName())));
// Set port
...
...
@@ -119,11 +123,15 @@ void PX4FirmwareUpgradeWorker::receiveBytes(LinkInterface* link, QByteArray b)
{
for
(
int
position
=
0
;
position
<
b
.
size
();
position
++
)
{
qDebug
()
<<
"BYTES"
;
qDebug
()
<<
std
::
hex
<<
(
char
)(
b
[
position
]);
qDebug
()
<<
(
char
)(
b
[
position
]);
if
(((
const
char
)
b
[
position
])
==
INSYNC
)
{
qDebug
()
<<
"SYNC"
;
insync
=
true
;
}
if
(
insync
&&
((
const
char
)
b
[
position
])
==
OK
)
{
emit
detectionStatusChanged
(
"Found PX4 board"
);
}
}
...
...
@@ -131,7 +139,31 @@ void PX4FirmwareUpgradeWorker::receiveBytes(LinkInterface* link, QByteArray b)
printf
(
"
\n
"
);
}
bool
PX4FirmwareUpgradeWorker
::
upgrade
(
const
QString
&
filename
)
void
PX4FirmwareUpgradeWorker
::
loadFirmware
(
const
QString
&
filename
)
{
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"LOADING FW"
;
QFile
f
(
filename
);
if
(
f
.
open
(
QIODevice
::
ReadOnly
))
{
QByteArray
buf
=
f
.
readAll
();
f
.
close
();
firmware
=
QJsonDocument
::
fromBinaryData
(
buf
);
if
(
firmware
.
isNull
())
{
emit
upgradeStatusChanged
(
tr
(
"Failed decoding file %1"
).
arg
(
filename
));
}
else
{
emit
upgradeStatusChanged
(
tr
(
"Ready to flash %1"
).
arg
(
filename
));
}
}
else
{
emit
upgradeStatusChanged
(
tr
(
"Failed opening file %1"
).
arg
(
filename
));
}
}
void
PX4FirmwareUpgradeWorker
::
upgrade
()
{
emit
upgradeStatusChanged
(
tr
(
"Starting firmware upgrade.."
));
}
void
PX4FirmwareUpgradeWorker
::
abort
()
{
exitThread
=
true
;
}
src/PX4FirmwareUpgradeWorker.h
View file @
47d59fa9
...
...
@@ -2,6 +2,7 @@
#define PX4FIRMWAREUPGRADEWORKER_H
#include <QObject>
#include <QJsonDocument>
#include <SerialLink.h>
...
...
@@ -24,7 +25,7 @@ public slots:
* @brief Continously scan for bootloaders
* @return
*/
bool
startContinousScan
();
void
startContinousScan
();
/**
* @brief Detect connected PX4 bootloaders
...
...
@@ -34,14 +35,19 @@ public slots:
*
* @return true if found on one link, false else
*/
bool
detect
();
void
detect
();
/**
* @brief Upgrade the firmware using the currently connected link
* @param filename file name / path of the firmware file
* @return true if upgrade succeeds, false else
*/
bool
upgrade
(
const
QString
&
filename
);
void
upgrade
();
/**
* @brief Load firmware from disk into memory
* @param filename
*/
void
loadFirmware
(
const
QString
&
filename
);
/**
* @brief Receive bytes from a link
...
...
@@ -50,9 +56,18 @@ public slots:
*/
void
receiveBytes
(
LinkInterface
*
link
,
QByteArray
b
);
/**
* @brief Abort upgrade worker
*/
void
abort
();
protected:
bool
exitThread
;
private:
SerialLink
*
link
;
bool
insync
;
QJsonDocument
firmware
;
};
#endif // PX4FIRMWAREUPGRADEWORKER_H
src/apps/qupgrade/QUpgradeApp.cc
View file @
47d59fa9
...
...
@@ -72,13 +72,21 @@ QUpgradeApp::QUpgradeApp(int &argc, char* argv[]) : QApplication(argc, argv)
// Create main window
QUpgradeMainWindow
*
window
=
new
QUpgradeMainWindow
();
PX4FirmwareUpgrader
*
upgrader
=
new
PX4FirmwareUpgrader
(
window
);
window
->
setCentralWidget
(
upgrader
);
// Get PX4 upgrade widget and instantiate worker thread
PX4FirmwareUpgradeWorker
*
worker
=
PX4FirmwareUpgradeWorker
::
putWorkerInThread
(
this
);
connect
(
worker
,
SIGNAL
(
detectionStatusChanged
(
QString
)),
window
->
firmwareUpgrader
(),
SLOT
(
setDetectionStatusText
(
QString
)));
connect
(
worker
,
SIGNAL
(
upgradeStatusChanged
(
QString
)),
window
->
firmwareUpgrader
(),
SLOT
(
setFlashStatusText
(
QString
)));
connect
(
worker
,
SIGNAL
(
upgradeProgressChanged
(
int
)),
window
->
firmwareUpgrader
(),
SLOT
(
setFlashProgress
(
int
)));
connect
(
worker
,
SIGNAL
(
validPortFound
(
QString
)),
window
->
firmwareUpgrader
(),
SLOT
(
setPortName
(
QString
)));
connect
(
worker
,
SIGNAL
(
detectionStatusChanged
(
QString
)),
upgrader
,
SLOT
(
setDetectionStatusText
(
QString
)),
Qt
::
QueuedConnection
);
connect
(
worker
,
SIGNAL
(
upgradeStatusChanged
(
QString
)),
upgrader
,
SLOT
(
setFlashStatusText
(
QString
)),
Qt
::
QueuedConnection
);
connect
(
worker
,
SIGNAL
(
upgradeProgressChanged
(
int
)),
upgrader
,
SLOT
(
setFlashProgress
(
int
)),
Qt
::
QueuedConnection
);
connect
(
worker
,
SIGNAL
(
validPortFound
(
QString
)),
upgrader
,
SLOT
(
setPortName
(
QString
)));
connect
(
upgrader
,
SIGNAL
(
firmwareFileNameSet
(
QString
)),
worker
,
SLOT
(
loadFirmware
(
QString
)),
Qt
::
QueuedConnection
);
connect
(
upgrader
,
SIGNAL
(
upgrade
()),
worker
,
SLOT
(
upgrade
()),
Qt
::
QueuedConnection
);
connect
(
this
,
SIGNAL
(
lastWindowClosed
()),
worker
,
SLOT
(
abort
()),
Qt
::
QueuedConnection
);
worker
->
loadFirmware
(
"abc"
);
window
->
setWindowTitle
(
applicationName
()
+
" "
+
applicationVersion
());
window
->
show
();
...
...
src/apps/qupgrade/QUpgradeMainWindow.cc
View file @
47d59fa9
...
...
@@ -42,10 +42,6 @@ QUpgradeMainWindow::QUpgradeMainWindow(QWidget *parent) :
ui
->
setupUi
(
this
);
}
PX4FirmwareUpgrader
*
QUpgradeMainWindow
::
firmwareUpgrader
()
{
return
ui
->
centralwidget
;
}
QUpgradeMainWindow
::~
QUpgradeMainWindow
()
{
delete
ui
;
...
...
src/apps/qupgrade/QUpgradeMainWindow.h
View file @
47d59fa9
...
...
@@ -48,8 +48,6 @@ public:
explicit
QUpgradeMainWindow
(
QWidget
*
parent
=
0
);
~
QUpgradeMainWindow
();
PX4FirmwareUpgrader
*
firmwareUpgrader
();
public
slots
:
protected:
...
...
src/apps/qupgrade/QUpgradeMainWindow.ui
View file @
47d59fa9
...
...
@@ -13,7 +13,7 @@
<property
name=
"windowTitle"
>
<string>
MainWindow
</string>
</property>
<widget
class=
"
PX4FirmwareUpgrader
"
name=
"centralwidget"
>
<widget
class=
"
QWidget
"
name=
"centralwidget"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
rowstretch=
"0"
/>
</widget>
<widget
class=
"QMenuBar"
name=
"menubar"
>
...
...
@@ -28,14 +28,6 @@
</widget>
<widget
class=
"QStatusBar"
name=
"statusbar"
/>
</widget>
<customwidgets>
<customwidget>
<class>
PX4FirmwareUpgrader
</class>
<extends>
QWidget
</extends>
<header
location=
"global"
>
PX4FirmwareUpgrader.h
</header>
<container>
1
</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
src/comm/QGCXPlaneLink.cc
View file @
47d59fa9
...
...
@@ -49,7 +49,10 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress
terraSync
(
NULL
),
airframeID
(
QGCXPlaneLink
::
AIRFRAME_UNKNOWN
),
xPlaneConnected
(
false
),
xPlaneVersion
(
0
)
xPlaneVersion
(
0
),
simUpdateLast
(
QGC
::
groundTimeMilliseconds
()),
simUpdateLastText
(
QGC
::
groundTimeMilliseconds
()),
simUpdateHz
(
0
)
{
this
->
localHost
=
localHost
;
this
->
localPort
=
localPort
/*+mav->getUASID()*/
;
...
...
@@ -374,7 +377,7 @@ void QGCXPlaneLink::readBytes()
// Only emit updates on attitude message
bool
emitUpdate
=
false
;
const
qint64
maxLength
=
65536
;
const
qint64
maxLength
=
1000
;
char
data
[
maxLength
];
QHostAddress
sender
;
quint16
senderPort
;
...
...
@@ -509,8 +512,18 @@ void QGCXPlaneLink::readBytes()
}
// Send updated state
if
(
emitUpdate
)
if
(
emitUpdate
&&
(
QGC
::
groundTimeMilliseconds
()
-
simUpdateLast
)
>
3
)
{
simUpdateHz
=
simUpdateHz
*
0.9
f
+
0.1
f
*
(
1000.0
f
/
(
QGC
::
groundTimeMilliseconds
()
-
simUpdateLast
));
if
(
QGC
::
groundTimeMilliseconds
()
-
simUpdateLastText
>
2000
)
{
emit
statusMessage
(
tr
(
"Receiving from XPlane at %1 Hz"
).
arg
(
static_cast
<
int
>
(
simUpdateHz
)));
// Reset lowpass with current value
simUpdateHz
=
(
1000.0
f
/
(
QGC
::
groundTimeMilliseconds
()
-
simUpdateLast
));
// Set state
simUpdateLastText
=
QGC
::
groundTimeMilliseconds
();
}
simUpdateLast
=
QGC
::
groundTimeMilliseconds
();
emit
hilStateChanged
(
QGC
::
groundTimeUsecs
(),
roll
,
pitch
,
yaw
,
rollspeed
,
pitchspeed
,
yawspeed
,
lat
*
1E7
,
lon
*
1E7
,
alt
*
1E3
,
vx
,
vy
,
vz
,
xacc
*
1000
,
yacc
*
1000
,
zacc
*
1000
);
...
...
@@ -518,7 +531,7 @@ void QGCXPlaneLink::readBytes()
if
(
!
oldConnectionState
&&
xPlaneConnected
)
{
emit
statusMessage
(
"Receiving from XPlane."
);
emit
statusMessage
(
tr
(
"Receiving from XPlane."
)
);
}
// // Echo data for debugging purposes
...
...
src/comm/QGCXPlaneLink.h
View file @
47d59fa9
...
...
@@ -190,6 +190,9 @@ protected:
enum
AIRFRAME
airframeID
;
bool
xPlaneConnected
;
unsigned
int
xPlaneVersion
;
quint64
simUpdateLast
;
quint64
simUpdateLastText
;
float
simUpdateHz
;
void
setName
(
QString
name
);
...
...
src/ui/PX4FirmwareUpgrader.cc
View file @
47d59fa9
#include <QFileDialog>
#include <QDesktopServices>
#include <QSettings>
#include "PX4FirmwareUpgrader.h"
#include "ui_PX4FirmwareUpgrader.h"
#include <QGC.h>
#include <QDebug>
PX4FirmwareUpgrader
::
PX4FirmwareUpgrader
(
QWidget
*
parent
)
:
QWidget
(
parent
),
ui
(
new
Ui
::
PX4FirmwareUpgrader
)
...
...
@@ -21,7 +26,16 @@ PX4FirmwareUpgrader::~PX4FirmwareUpgrader()
void
PX4FirmwareUpgrader
::
selectFirmwareFile
()
{
QSettings
settings
;
QString
path
=
settings
.
value
(
"PX4_FIRMWARE_PATH"
,
QDesktopServices
::
storageLocation
(
QDesktopServices
::
DesktopLocation
)).
toString
();
const
QString
widgetFileExtension
(
".px4"
);
QString
fileName
=
QFileDialog
::
getOpenFileName
(
this
,
tr
(
"Specify File Name"
),
path
,
tr
(
"PX4 Firmware (*%1);;"
).
arg
(
widgetFileExtension
));
settings
.
setValue
(
"PX4_FIRMWARE_PATH"
,
fileName
);
qDebug
()
<<
"EMITTING SIGNAL"
;
emit
firmwareFileNameSet
(
fileName
);
}
void
PX4FirmwareUpgrader
::
setDetectionStatusText
(
const
QString
&
text
)
...
...
@@ -32,6 +46,7 @@ void PX4FirmwareUpgrader::setDetectionStatusText(const QString &text)
void
PX4FirmwareUpgrader
::
setFlashStatusText
(
const
QString
&
text
)
{
ui
->
flashProgressLabel
->
setText
(
text
);
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"LABEL"
<<
text
;
}
void
PX4FirmwareUpgrader
::
setFlashProgress
(
int
percent
)
...
...
src/ui/QGCHilConfiguration.cc
View file @
47d59fa9
...
...
@@ -30,7 +30,12 @@ void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index)
mav
->
enableHilFlightGear
(
false
,
""
);
QGCHilFlightGearConfiguration
*
hfgconf
=
new
QGCHilFlightGearConfiguration
(
mav
,
this
);
hfgconf
->
show
();
ui
->
simulatorConfigurationDockWidget
->
setWidget
(
hfgconf
);
ui
->
simulatorConfigurationLayout
->
addWidget
(
hfgconf
);
QGCFlightGearLink
*
fg
=
dynamic_cast
<
QGCFlightGearLink
*>
(
mav
->
getHILSimulation
());
if
(
fg
)
{
connect
(
fg
,
SIGNAL
(
statusMessage
(
QString
)),
ui
->
statusLabel
,
SLOT
(
setText
(
QString
)));
}
}
else
if
(
2
==
index
||
3
==
index
)
...
...
@@ -39,13 +44,14 @@ void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index)
mav
->
enableHilXPlane
(
false
);
QGCHilXPlaneConfiguration
*
hxpconf
=
new
QGCHilXPlaneConfiguration
(
mav
->
getHILSimulation
(),
this
);
hxpconf
->
show
();
ui
->
simulatorConfiguration
DockWidget
->
set
Widget
(
hxpconf
);
ui
->
simulatorConfiguration
Layout
->
add
Widget
(
hxpconf
);
// Select correct version of XPlane
QGCXPlaneLink
*
xplane
=
dynamic_cast
<
QGCXPlaneLink
*>
(
mav
->
getHILSimulation
());
if
(
xplane
)
{
xplane
->
setVersion
((
index
==
2
)
?
10
:
9
);
connect
(
xplane
,
SIGNAL
(
statusMessage
(
QString
)),
ui
->
statusLabel
,
SLOT
(
setText
(
QString
)));
}
}
}
src/ui/QGCHilConfiguration.ui
View file @
47d59fa9
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
3
05
</width>
<height>
3
55
</height>
<width>
3
66
</width>
<height>
3
01
</height>
</rect>
</property>
<property
name=
"sizePolicy"
>
...
...
@@ -19,22 +19,22 @@
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
columnstretch=
"40,
0,0"
>
<item
row=
"
0
"
column=
"0"
>
<widget
class=
"QLabel"
name=
"s
im
Label"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
rowstretch=
"1,100,1"
columnstretch=
"4
0,0"
>
<item
row=
"
2
"
column=
"0"
>
<widget
class=
"QLabel"
name=
"s
tatus
Label"
>
<property
name=
"text"
>
<string>
S
imulator
</string>
<string>
S
tatus
</string>
</property>
</widget>
</item>
<item
row=
"
3
"
column=
"0"
>
<widget
class=
"QLabel"
name=
"s
tatus
Label"
>
<item
row=
"
0
"
column=
"0"
>
<widget
class=
"QLabel"
name=
"s
im
Label"
>
<property
name=
"text"
>
<string>
S
tatus
</string>
<string>
S
imulator
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"
2
"
>
<item
row=
"0"
column=
"
1
"
>
<widget
class=
"QComboBox"
name=
"simComboBox"
>
<property
name=
"editable"
>
<bool>
true
</bool>
...
...
@@ -61,35 +61,12 @@
</item>
</widget>
</item>
<item
row=
"2"
column=
"0"
colspan=
"3"
>
<widget
class=
"QDockWidget"
name=
"simulatorConfigurationDockWidget"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Preferred"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
20
</width>
<height>
150
</height>
</size>
</property>
<property
name=
"features"
>
<set>
QDockWidget::NoDockWidgetFeatures
</set>
<item
row=
"1"
column=
"0"
colspan=
"2"
>
<layout
class=
"QVBoxLayout"
name=
"simulatorConfigurationLayout"
>
<property
name=
"spacing"
>
<number>
0
</number>
</property>
<property
name=
"windowTitle"
>
<string>
Simulator Options
</string>
</property>
<widget
class=
"QWidget"
name=
"dockWidgetContents"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"MinimumExpanding"
vsizetype=
"Preferred"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
</widget>
</widget>
</layout>
</item>
</layout>
</widget>
...
...
src/ui/QGCVehicleConfig.cc
View file @
47d59fa9
This diff is collapsed.
Click to expand it.
src/ui/QGCVehicleConfig.h
View file @
47d59fa9
...
...
@@ -37,11 +37,81 @@ public slots:
void
stopCalibrationRC
();
/** Start/stop the RC calibration routine */
void
toggleCalibrationRC
(
bool
enabled
);
/** Set trim positions */
void
setTrimPositions
();
/** Detect which channels need to be inverted */
void
detectChannelInversion
();
/** Change the mode setting of the control inputs */
void
setRCModeIndex
(
int
newRcMode
);
/** Render the data updated */
void
updateView
();
/** Set the RC channel */
void
setRollChan
(
int
channel
)
{
rcMapping
[
0
]
=
channel
-
1
;
}
/** Set the RC channel */
void
setPitchChan
(
int
channel
)
{
rcMapping
[
1
]
=
channel
-
1
;
}
/** Set the RC channel */
void
setYawChan
(
int
channel
)
{
rcMapping
[
2
]
=
channel
-
1
;
}
/** Set the RC channel */
void
setThrottleChan
(
int
channel
)
{
rcMapping
[
3
]
=
channel
-
1
;
}
/** Set the RC channel */
void
setModeChan
(
int
channel
)
{
rcMapping
[
4
]
=
channel
-
1
;
}
/** Set the RC channel */
void
setAux1Chan
(
int
channel
)
{
rcMapping
[
5
]
=
channel
-
1
;
}
/** Set the RC channel */
void
setAux2Chan
(
int
channel
)
{
rcMapping
[
6
]
=
channel
-
1
;
}
/** Set the RC channel */
void
setAux3Chan
(
int
channel
)
{
rcMapping
[
7
]
=
channel
-
1
;
}
/** Set channel inversion status */
void
setRollInverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
0
]]
=
inverted
;
}
/** Set channel inversion status */
void
setPitchInverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
1
]]
=
inverted
;
}
/** Set channel inversion status */
void
setYawInverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
2
]]
=
inverted
;
}
/** Set channel inversion status */
void
setThrottleInverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
3
]]
=
inverted
;
}
/** Set channel inversion status */
void
setModeInverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
4
]]
=
inverted
;
}
/** Set channel inversion status */
void
setAux1Inverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
5
]]
=
inverted
;
}
/** Set channel inversion status */
void
setAux2Inverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
6
]]
=
inverted
;
}
/** Set channel inversion status */
void
setAux3Inverted
(
bool
inverted
)
{
rcRev
[
rcMapping
[
7
]]
=
inverted
;
}
protected
slots
:
/** Reset the RC calibration */
void
resetCalibrationRC
();
...
...
@@ -64,12 +134,13 @@ protected slots:
protected:
UASInterface
*
mav
;
///< The current MAV
static
const
unsigned
int
chanMax
=
8
;
///< Maximum number of channels
unsigned
int
chanCount
;
///< Actual channels
int
rcType
;
///< Type of the remote control
quint64
rcTypeUpdateRequested
;
///< Zero if not requested, non-zero if requested
static
const
unsigned
int
rcTypeTimeout
=
5000
;
///< 5 seconds timeout, in milliseconds
in
t
rcMin
[
chanMax
];
///< Minimum values
in
t
rcMax
[
chanMax
];
///< Maximum values
in
t
rcTrim
[
chanMax
];
///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle)
floa
t
rcMin
[
chanMax
];
///< Minimum values
floa
t
rcMax
[
chanMax
];
///< Maximum values
floa
t
rcTrim
[
chanMax
];
///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle)
int
rcMapping
[
chanMax
];
///< PWM to function mappings
float
rcScaling
[
chanMax
];
///< Scaling of channel input to control commands
bool
rcRev
[
chanMax
];
///< Channel reverse
...
...
@@ -87,6 +158,7 @@ protected:
QTimer
updateTimer
;
///< Controls update intervals
enum
RC_MODE
rc_mode
;
///< Mode of the remote control, according to usual convention
QList
<
QGCToolWidget
*>
toolWidgets
;
///< Configurable widgets
bool
calibrationEnabled
;
///< calibration mode on / off
private:
Ui
::
QGCVehicleConfig
*
ui
;
...
...
src/ui/QGCVehicleConfig.ui
View file @
47d59fa9
...
...
@@ -40,7 +40,7 @@
<item
row=
"0"
column=
"0"
colspan=
"2"
>
<widget
class=
"QTabWidget"
name=
"tabWidget"
>
<property
name=
"currentIndex"
>
<number>
1
</number>
<number>
0
</number>
</property>
<widget
class=
"QWidget"
name=
"rcTab"
>
<attribute
name=
"title"
>
...
...
@@ -53,10 +53,10 @@
<item
row=
"8"
column=
"1"
rowspan=
"3"
>
<widget
class=
"QSlider"
name=
"throttleSlider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"value"
>
<number>
0
</number>
...
...
@@ -69,10 +69,10 @@
<item
row=
"8"
column=
"4"
rowspan=
"3"
colspan=
"2"
>
<widget
class=
"QSlider"
name=
"pitchSlider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"value"
>
<number>
0
</number>
...
...
@@ -595,10 +595,10 @@
<item
row=
"11"
column=
"0"
>
<widget
class=
"QSlider"
name=
"yawSlider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"value"
>
<number>
0
</number>
...
...
@@ -611,10 +611,10 @@
<item
row=
"11"
column=
"3"
>
<widget
class=
"QSlider"
name=
"rollSlider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"value"
>
<number>
0
</number>
...
...
@@ -650,10 +650,10 @@
<item
row=
"8"
column=
"10"
rowspan=
"3"
>
<widget
class=
"QSlider"
name=
"aux1Slider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
...
...
@@ -663,10 +663,10 @@
<item
row=
"8"
column=
"11"
rowspan=
"3"
>
<widget
class=
"QSlider"
name=
"aux2Slider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
...
...
@@ -676,10 +676,10 @@
<item
row=
"8"
column=
"12"
rowspan=
"3"
colspan=
"2"
>
<widget
class=
"QSlider"
name=
"aux3Slider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
...
...
@@ -689,10 +689,10 @@
<item
row=
"8"
column=
"9"
rowspan=
"3"
>
<widget
class=
"QSlider"
name=
"modeSwitchSlider"
>
<property
name=
"minimum"
>
<number>
-1
</number>
<number>
0
</number>
</property>
<property
name=
"maximum"
>
<number>
1
</number>
<number>
1
00
</number>
</property>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
...
...
@@ -712,6 +712,13 @@
</property>
</spacer>
</item>
<item
row=
"11"
column=
"14"
>
<widget
class=
"QPushButton"
name=
"setTrimButton"
>
<property
name=
"text"
>
<string>
Set Trim
</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget
class=
"QWidget"
name=
"sensorTab"
>
...
...
@@ -815,8 +822,8 @@ p, li { white-space: pre-wrap; }
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
651
</width>
<height>
2
03
</height>
<width>
98
</width>
<height>
2
8
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_4"
>
...
...
@@ -852,8 +859,8 @@ p, li { white-space: pre-wrap; }
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
651
</width>
<height>
2
04
</height>
<width>
98
</width>
<height>
2
8
</height>
</rect>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_4"
>
...
...
@@ -899,8 +906,8 @@ p, li { white-space: pre-wrap; }
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
651
</width>
<height>
2
03
</height>
<width>
98
</width>
<height>
2
8
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_6"
>
...
...
@@ -959,8 +966,8 @@ p, li { white-space: pre-wrap; }
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
651
</width>
<height>
2
04
</height>
<width>
98
</width>
<height>
2
8
</height>
</rect>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_7"
>
...
...
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