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
bb350243
Commit
bb350243
authored
Aug 31, 2010
by
Bryan Godbolt
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of
git://github.com/pixhawk/qgroundcontrol
into dev
parents
7cee3ba2
1755f202
Changes
14
Show whitespace changes
Inline
Side-by-side
Showing
14 changed files
with
588 additions
and
263 deletions
+588
-263
style-mission.css
images/style-mission.css
+1
-0
Core.cc
src/Core.cc
+6
-2
PxQuadMAV.cc
src/uas/PxQuadMAV.cc
+0
-1
UAS.cc
src/uas/UAS.cc
+38
-0
UAS.h
src/uas/UAS.h
+7
-0
UASInterface.h
src/uas/UASInterface.h
+8
-0
MainWindow.cc
src/ui/MainWindow.cc
+449
-196
MainWindow.h
src/ui/MainWindow.h
+20
-21
QGCParamWidget.cc
src/ui/QGCParamWidget.cc
+1
-4
QGCRemoteControlView.cc
src/ui/QGCRemoteControlView.cc
+18
-18
QGCRemoteControlView.h
src/ui/QGCRemoteControlView.h
+1
-1
QGCSensorSettingsWidget.cc
src/ui/QGCSensorSettingsWidget.cc
+6
-0
QGCSensorSettingsWidget.ui
src/ui/QGCSensorSettingsWidget.ui
+26
-13
UASControlWidget.cc
src/ui/uas/UASControlWidget.cc
+7
-7
No files found.
images/style-mission.css
View file @
bb350243
*
{
font-family
:
"Bitstream Vera Sans"
;
font
:
"Roman"
;
font-size
:
12px
;
}
QWidget
#colorIcon
{}
QWidget
{
...
...
src/Core.cc
View file @
bb350243
...
...
@@ -72,6 +72,8 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
// Show splash screen
QPixmap
splashImage
(
":images/splash.png"
);
QSplashScreen
*
splashScreen
=
new
QSplashScreen
(
splashImage
,
Qt
::
WindowStaysOnTopHint
);
// Delete splash screen after mainWindow was displayed
splashScreen
->
setAttribute
(
Qt
::
WA_DeleteOnClose
);
splashScreen
->
show
();
splashScreen
->
showMessage
(
tr
(
"Loading application fonts"
),
Qt
::
AlignLeft
|
Qt
::
AlignBottom
,
QColor
(
62
,
93
,
141
));
...
...
@@ -79,13 +81,15 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
// Exit main application when last window is closed
connect
(
this
,
SIGNAL
(
lastWindowClosed
()),
this
,
SLOT
(
quit
()));
//
Set
application font
//
Load
application font
QFontDatabase
fontDatabase
=
QFontDatabase
();
const
QString
fontFileName
=
":/general/vera.ttf"
;
///< Font file is part of the QRC file and compiled into the app
const
QString
fontFamilyName
=
"Bitstream Vera Sans"
;
if
(
!
QFile
::
exists
(
fontFileName
))
printf
(
"ERROR! font file: %s DOES NOT EXIST!
\n
"
,
fontFileName
.
toStdString
().
c_str
());
fontDatabase
.
addApplicationFont
(
fontFileName
);
setFont
(
fontDatabase
.
font
(
fontFamilyName
,
"Roman"
,
12
));
// Avoid Using setFont(). In the Qt docu you can read the following:
// "Warning: Do not use this function in conjunction with Qt Style Sheets."
// setFont(fontDatabase.font(fontFamilyName, "Roman", 12));
// Start the comm link manager
splashScreen
->
showMessage
(
tr
(
"Starting Communication Links"
),
Qt
::
AlignLeft
|
Qt
::
AlignBottom
,
QColor
(
62
,
93
,
141
));
...
...
src/uas/PxQuadMAV.cc
View file @
bb350243
...
...
@@ -139,7 +139,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
errCountChanged
(
uasId
,
"IMU"
,
"SPI0"
,
status
.
spi0_err_count
);
emit
errCountChanged
(
uasId
,
"IMU"
,
"SPI1"
,
status
.
spi1_err_count
);
emit
errCountChanged
(
uasId
,
"IMU"
,
"UART"
,
status
.
uart_total_err_count
);
qDebug
()
<<
"System Load:"
<<
status
.
load
;
emit
UAS
::
valueChanged
(
this
,
"Load"
,
((
float
)
status
.
load
)
/
1000.0
f
,
MG
::
TIME
::
getGroundTimeNow
());
}
break
;
...
...
src/uas/UAS.cc
View file @
bb350243
...
...
@@ -391,6 +391,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_rc_channels_t
channels
;
mavlink_msg_rc_channels_decode
(
&
message
,
&
channels
);
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
255.0
f
);
for
(
int
i
=
0
;
i
<
8
;
i
++
)
{
switch
(
i
)
...
...
@@ -576,6 +577,43 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
#endif
}
void
UAS
::
setLocalPositionOffset
(
float
x
,
float
y
,
float
z
,
float
yaw
)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_message_t
msg
;
mavlink_msg_position_control_offset_set_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
0
,
x
,
y
,
z
,
yaw
);
sendMessage
(
msg
);
#endif
}
void
UAS
::
startRadioControlCalibration
()
{
mavlink_message_t
msg
;
mavlink_msg_action_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_ACTION_CALIBRATE_RC
);
sendMessage
(
msg
);
}
void
UAS
::
startMagnetometerCalibration
()
{
mavlink_message_t
msg
;
mavlink_msg_action_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_ACTION_CALIBRATE_MAG
);
sendMessage
(
msg
);
}
void
UAS
::
startGyroscopeCalibration
()
{
mavlink_message_t
msg
;
mavlink_msg_action_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_ACTION_CALIBRATE_GYRO
);
sendMessage
(
msg
);
}
void
UAS
::
startPressureCalibration
()
{
mavlink_message_t
msg
;
mavlink_msg_action_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_IMU
,
MAV_ACTION_CALIBRATE_PRESSURE
);
sendMessage
(
msg
);
}
quint64
UAS
::
getUnixTime
(
quint64
time
)
{
if
(
time
==
0
)
...
...
src/uas/UAS.h
View file @
bb350243
...
...
@@ -221,6 +221,13 @@ public slots:
/** @brief Set local position setpoint */
void
setLocalPositionSetpoint
(
float
x
,
float
y
,
float
z
,
float
yaw
);
/** @brief Add an offset in body frame to the setpoint */
void
setLocalPositionOffset
(
float
x
,
float
y
,
float
z
,
float
yaw
);
void
startRadioControlCalibration
();
void
startMagnetometerCalibration
();
void
startGyroscopeCalibration
();
void
startPressureCalibration
();
signals:
...
...
src/uas/UASInterface.h
View file @
bb350243
...
...
@@ -211,6 +211,12 @@ public slots:
virtual
void
enableRawSensorFusionTransmission
(
bool
enabled
)
=
0
;
virtual
void
setLocalPositionSetpoint
(
float
x
,
float
y
,
float
z
,
float
yaw
)
=
0
;
virtual
void
setLocalPositionOffset
(
float
x
,
float
y
,
float
z
,
float
yaw
)
=
0
;
virtual
void
startRadioControlCalibration
()
=
0
;
virtual
void
startMagnetometerCalibration
()
=
0
;
virtual
void
startGyroscopeCalibration
()
=
0
;
virtual
void
startPressureCalibration
()
=
0
;
protected:
QColor
color
;
...
...
@@ -331,6 +337,8 @@ signals:
void
positionYawControlEnabled
(
bool
enabled
);
/** @brief Value of a remote control channel */
void
remoteControlChannelChanged
(
int
channelId
,
float
raw
,
float
normalized
);
/** @brief Remote control RSSI changed */
void
remoteControlRSSIChanged
(
float
rssi
);
/**
* @brief Localization quality changed
...
...
src/ui/MainWindow.cc
View file @
bb350243
...
...
@@ -108,6 +108,7 @@ MainWindow::~MainWindow()
void
MainWindow
::
buildWidgets
()
{
//FIXME: memory of acceptList will never be freed again
QStringList
*
acceptList
=
new
QStringList
();
acceptList
->
append
(
"roll IMU"
);
acceptList
->
append
(
"pitch IMU"
);
...
...
@@ -116,50 +117,93 @@ void MainWindow::buildWidgets()
acceptList
->
append
(
"pitchspeed IMU"
);
acceptList
->
append
(
"yawspeed IMU"
);
//FIXME: memory of acceptList2 will never be freed again
QStringList
*
acceptList2
=
new
QStringList
();
acceptList2
->
append
(
"Battery"
);
acceptList2
->
append
(
"Pressure"
);
//TODO: move protocol outside UI
mavlink
=
new
MAVLinkProtocol
();
linechart
=
new
Linecharts
(
this
);
control
=
new
UASControlWidget
(
this
);
list
=
new
UASListWidget
(
this
);
waypoints
=
new
WaypointList
(
this
,
NULL
);
info
=
new
UASInfoWidget
(
this
);
detection
=
new
ObjectDetectionView
(
"images/patterns"
,
this
);
hud
=
new
HUD
(
640
,
480
,
this
);
debugConsole
=
new
DebugConsole
(
this
);
map
=
new
MapWidget
(
this
);
protocol
=
new
XMLCommProtocolWidget
(
this
);
parameters
=
new
ParameterInterface
(
this
);
watchdogControl
=
new
WatchdogControl
(
this
);
hsi
=
new
HSIDisplay
(
this
);
headDown1
=
new
HDDisplay
(
acceptList
,
this
);
headDown2
=
new
HDDisplay
(
acceptList2
,
this
);
// Center widgets
linechartWidget
=
new
Linecharts
(
this
);
hudWidget
=
new
HUD
(
640
,
480
,
this
);
mapWidget
=
new
MapWidget
(
this
);
protocolWidget
=
new
XMLCommProtocolWidget
(
this
);
dataplotWidget
=
new
QGCDataPlot2D
(
this
);
// Dock widgets
controlDockWidget
=
new
QDockWidget
(
tr
(
"Control"
),
this
);
controlDockWidget
->
setWidget
(
new
UASControlWidget
(
this
)
);
listDockWidget
=
new
QDockWidget
(
tr
(
"Unmanned Systems"
),
this
);
listDockWidget
->
setWidget
(
new
UASListWidget
(
this
)
);
waypointsDockWidget
=
new
QDockWidget
(
tr
(
"Waypoint List"
),
this
);
waypointsDockWidget
->
setWidget
(
new
WaypointList
(
this
,
NULL
)
);
infoDockWidget
=
new
QDockWidget
(
tr
(
"Status Details"
),
this
);
infoDockWidget
->
setWidget
(
new
UASInfoWidget
(
this
)
);
detectionDockWidget
=
new
QDockWidget
(
tr
(
"Object Recognition"
),
this
);
detectionDockWidget
->
setWidget
(
new
ObjectDetectionView
(
"images/patterns"
,
this
)
);
debugConsoleDockWidget
=
new
QDockWidget
(
tr
(
"Communication Console"
),
this
);
debugConsoleDockWidget
->
setWidget
(
new
DebugConsole
(
this
)
);
parametersDockWidget
=
new
QDockWidget
(
tr
(
"Onboard Parameters"
),
this
);
parametersDockWidget
->
setWidget
(
new
ParameterInterface
(
this
)
);
watchdogControlDockWidget
=
new
QDockWidget
(
tr
(
"Process Control"
),
this
);
watchdogControlDockWidget
->
setWidget
(
new
WatchdogControl
(
this
)
);
hsiDockWidget
=
new
QDockWidget
(
tr
(
"Horizontal Situation Indicator"
),
this
);
hsiDockWidget
->
setWidget
(
new
HSIDisplay
(
this
)
);
headDown1DockWidget
=
new
QDockWidget
(
tr
(
"Primary Flight Display"
),
this
);
headDown1DockWidget
->
setWidget
(
new
HDDisplay
(
acceptList
,
this
)
);
headDown2DockWidget
=
new
QDockWidget
(
tr
(
"Payload Status"
),
this
);
headDown2DockWidget
->
setWidget
(
new
HDDisplay
(
acceptList2
,
this
)
);
rcViewDockWidget
=
new
QDockWidget
(
tr
(
"Radio Control"
),
this
);
rcViewDockWidget
->
setWidget
(
new
QGCRemoteControlView
(
this
)
);
// Dialogue widgets
//FIXME: free memory in destructor
joystick
=
new
JoystickInput
();
dataplot
=
new
QGCDataPlot2D
(
this
);
rcView
=
new
QGCRemoteControlView
(
this
);
}
void
MainWindow
::
connectWidgets
()
{
connect
(
UASManager
::
instance
(),
SIGNAL
(
UASCreated
(
UASInterface
*
)),
linechart
,
SLOT
(
addSystem
(
UASInterface
*
)));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
int
)),
linechart
,
SLOT
(
selectSystem
(
int
)));
connect
(
linechart
,
SIGNAL
(
logfileWritten
(
QString
)),
this
,
SLOT
(
loadDataView
(
QString
)));
connect
(
mavlink
,
SIGNAL
(
receiveLossChanged
(
int
,
float
)),
info
,
SLOT
(
updateSendLoss
(
int
,
float
)));
if
(
linechartWidget
)
{
connect
(
UASManager
::
instance
(),
SIGNAL
(
UASCreated
(
UASInterface
*
)),
linechartWidget
,
SLOT
(
addSystem
(
UASInterface
*
)));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
int
)),
linechartWidget
,
SLOT
(
selectSystem
(
int
)));
connect
(
linechartWidget
,
SIGNAL
(
logfileWritten
(
QString
)),
this
,
SLOT
(
loadDataView
(
QString
)));
}
if
(
infoDockWidget
&&
infoDockWidget
->
widget
())
{
connect
(
mavlink
,
SIGNAL
(
receiveLossChanged
(
int
,
float
)),
infoDockWidget
->
widget
(),
SLOT
(
updateSendLoss
(
int
,
float
)));
}
}
void
MainWindow
::
arrangeCenterStack
()
{
centerStack
=
new
QStackedWidget
(
this
);
QStackedWidget
*
centerStack
=
new
QStackedWidget
(
this
);
if
(
!
centerStack
)
return
;
centerStack
->
addWidget
(
linechar
t
);
centerStack
->
addWidget
(
protocol
);
centerStack
->
addWidget
(
map
);
centerStack
->
addWidget
(
hud
);
centerStack
->
addWidget
(
dataplo
t
);
if
(
linechartWidget
)
centerStack
->
addWidget
(
linechartWidge
t
);
if
(
protocolWidget
)
centerStack
->
addWidget
(
protocolWidget
);
if
(
mapWidget
)
centerStack
->
addWidget
(
mapWidget
);
if
(
hudWidget
)
centerStack
->
addWidget
(
hudWidget
);
if
(
dataplotWidget
)
centerStack
->
addWidget
(
dataplotWidge
t
);
setCentralWidget
(
centerStack
);
}
...
...
@@ -425,13 +469,35 @@ void MainWindow::UASCreated(UASInterface* uas)
ui
.
menuConnected_Systems
->
addAction
(
icon
,
tr
(
"Select %1 for control"
).
arg
(
uas
->
getUASName
()),
uas
,
SLOT
(
setSelected
()));
// FIXME Should be not inside the mainwindow
connect
(
uas
,
SIGNAL
(
textMessageReceived
(
int
,
int
,
int
,
QString
)),
debugConsole
,
SLOT
(
receiveTextMessage
(
int
,
int
,
int
,
QString
)));
if
(
debugConsoleDockWidget
)
{
DebugConsole
*
debugConsole
=
dynamic_cast
<
DebugConsole
*>
(
debugConsoleDockWidget
->
widget
());
if
(
debugConsole
)
{
connect
(
uas
,
SIGNAL
(
textMessageReceived
(
int
,
int
,
int
,
QString
)),
debugConsole
,
SLOT
(
receiveTextMessage
(
int
,
int
,
int
,
QString
)));
}
}
// Health / System status indicator
info
->
addUAS
(
uas
);
if
(
infoDockWidget
)
{
UASInfoWidget
*
infoWidget
=
dynamic_cast
<
UASInfoWidget
*>
(
infoDockWidget
->
widget
());
if
(
infoWidget
)
{
infoWidget
->
addUAS
(
uas
);
}
}
// UAS List
list
->
addUAS
(
uas
);
if
(
listDockWidget
)
{
UASListWidget
*
listWidget
=
dynamic_cast
<
UASListWidget
*>
(
listDockWidget
->
widget
());
if
(
listWidget
)
{
listWidget
->
addUAS
(
uas
);
}
}
// Camera view
//camera->addUAS(uas);
...
...
@@ -455,27 +521,42 @@ void MainWindow::UASCreated(UASInterface* uas)
void
MainWindow
::
clearView
()
{
// Halt HUD
hud
->
stop
();
linechart
->
setActive
(
false
);
headDown1
->
stop
();
headDown2
->
stop
();
hsi
->
stop
();
if
(
hudWidget
)
hudWidget
->
stop
();
// Disable linechart
if
(
linechartWidget
)
linechartWidget
->
setActive
(
false
);
// Halt HDDs
if
(
headDown1DockWidget
)
{
HDDisplay
*
hddWidget
=
dynamic_cast
<
HDDisplay
*>
(
headDown1DockWidget
->
widget
()
);
if
(
hddWidget
)
hddWidget
->
stop
();
}
if
(
headDown2DockWidget
)
{
HDDisplay
*
hddWidget
=
dynamic_cast
<
HDDisplay
*>
(
headDown2DockWidget
->
widget
()
);
if
(
hddWidget
)
hddWidget
->
stop
();
}
// Halt HSI
if
(
hsiDockWidget
)
{
HSIDisplay
*
hsi
=
dynamic_cast
<
HSIDisplay
*>
(
hsiDockWidget
->
widget
()
);
if
(
hsi
)
hsi
->
stop
();
}
// Remove all dock widgets
Q
List
<
QObject
*>
list
=
this
->
children
(
);
// Remove all dock widgets
from main window
Q
ObjectList
childList
(
this
->
children
()
);
QList
<
QObject
*>::
iterator
i
;
for
(
i
=
list
.
begin
();
i
!=
list
.
end
();
++
i
)
QObjectList
::
iterator
i
;
QDockWidget
*
dockWidget
;
for
(
i
=
childList
.
begin
();
i
!=
childList
.
end
();
++
i
)
{
QDockWidget
*
w
idget
=
dynamic_cast
<
QDockWidget
*>
(
*
i
);
if
(
w
idget
)
dockW
idget
=
dynamic_cast
<
QDockWidget
*>
(
*
i
);
if
(
dockW
idget
)
{
// Hide widgets
QWidget
*
childWidget
=
dynamic_cast
<
QWidget
*>
(
widget
->
widget
());
if
(
childWidget
)
childWidget
->
setVisible
(
false
);
// Remove dock widget
this
->
removeDockWidget
(
widget
);
//delete widget;
// Remove dock widget from main window
this
->
removeDockWidget
(
dockWidget
);
// Deletion of dockWidget would also delete all child
// widgets of dockWidget
// Is there a way to unset a widget from QDockWidget?
}
}
}
...
...
@@ -486,45 +567,69 @@ void MainWindow::loadSlugsView()
// Engineer view, used in EMAV2009
// LINE CHART
linechart
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechart
);
if
(
linechartWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
linechartWidget
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechartWidget
);
}
}
// UAS CONTROL
QDockWidget
*
container1
=
new
QDockWidget
(
tr
(
"Control"
),
this
);
container1
->
setWidget
(
control
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container1
);
if
(
controlDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
controlDockWidget
);
controlDockWidget
->
show
();
}
// UAS LIST
QDockWidget
*
container4
=
new
QDockWidget
(
tr
(
"Unmanned Systems"
),
this
);
container4
->
setWidget
(
list
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container4
);
if
(
listDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
listDockWidget
);
listDockWidget
->
show
();
}
// UAS STATUS
QDockWidget
*
container3
=
new
QDockWidget
(
tr
(
"Status Details"
),
this
);
container3
->
setWidget
(
info
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container3
);
if
(
infoDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
infoDockWidget
);
infoDockWidget
->
show
();
}
// HORIZONTAL SITUATION INDICATOR
QDockWidget
*
container6
=
new
QDockWidget
(
tr
(
"Horizontal Situation Indicator"
),
this
);
container6
->
setWidget
(
hsi
);
if
(
hsiDockWidget
)
{
HSIDisplay
*
hsi
=
dynamic_cast
<
HSIDisplay
*>
(
hsiDockWidget
->
widget
()
);
if
(
hsi
)
{
hsi
->
start
();
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container6
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
hsiDockWidget
);
hsiDockWidget
->
show
();
}
}
// WAYPOINT LIST
QDockWidget
*
container5
=
new
QDockWidget
(
tr
(
"Waypoint List"
),
this
);
container5
->
setWidget
(
waypoints
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container5
);
if
(
waypointsDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
waypointsDockWidget
);
waypointsDockWidget
->
show
();
}
// DEBUG CONSOLE
QDockWidget
*
container7
=
new
QDockWidget
(
tr
(
"Communication Console"
),
this
);
container7
->
setWidget
(
debugConsole
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container7
);
if
(
debugConsoleDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
debugConsoleDockWidget
);
debugConsoleDockWidget
->
show
();
}
// ONBOARD PARAMETERS
QDockWidget
*
containerParams
=
new
QDockWidget
(
tr
(
"Onboard Parameters"
),
this
);
containerParams
->
setWidget
(
parameters
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
containerParams
);
if
(
parametersDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
parametersDockWidget
);
parametersDockWidget
->
show
();
}
this
->
show
();
}
...
...
@@ -535,44 +640,64 @@ void MainWindow::loadPixhawkView()
// Engineer view, used in EMAV2009
// LINE CHART
linechart
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechart
);
if
(
linechartWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
linechartWidget
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechartWidget
);
}
}
// UAS CONTROL
QDockWidget
*
container1
=
new
QDockWidget
(
tr
(
"Control"
),
this
);
container1
->
setWidget
(
control
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container1
);
if
(
controlDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
controlDockWidget
);
controlDockWidget
->
show
();
}
// UAS LIST
QDockWidget
*
container4
=
new
QDockWidget
(
tr
(
"Unmanned Systems"
),
this
);
container4
->
setWidget
(
list
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container4
);
if
(
listDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
listDockWidget
);
listDockWidget
->
show
();
}
// UAS STATUS
QDockWidget
*
container3
=
new
QDockWidget
(
tr
(
"Status Details"
),
this
);
container3
->
setWidget
(
info
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container3
);
if
(
infoDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
infoDockWidget
);
infoDockWidget
->
show
();
}
// WAYPOINT LIST
QDockWidget
*
container5
=
new
QDockWidget
(
tr
(
"Waypoint List"
),
this
);
container5
->
setWidget
(
waypoints
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container5
);
if
(
waypointsDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
waypointsDockWidget
);
waypointsDockWidget
->
show
();
}
// DEBUG CONSOLE
QDockWidget
*
container7
=
new
QDockWidget
(
tr
(
"Communication Console"
),
this
);
container7
->
setWidget
(
debugConsole
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container7
);
if
(
debugConsoleDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
debugConsoleDockWidget
);
debugConsoleDockWidget
->
show
();
}
// RADIO CONTROL VIEW
QDockWidget
*
rcContainer
=
new
QDockWidget
(
tr
(
"Radio Control"
),
this
);
rcContainer
->
setWidget
(
rcView
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
rcContainer
);
if
(
rcViewDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
rcViewDockWidget
);
rcViewDockWidget
->
show
();
}
// ONBOARD PARAMETERS
QDockWidget
*
containerParams
=
new
QDockWidget
(
tr
(
"Onboard Parameters"
),
this
);
containerParams
->
setWidget
(
parameters
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
containerParams
);
if
(
parametersDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
parametersDockWidget
);
parametersDockWidget
->
show
();
}
this
->
show
();
}
...
...
@@ -580,14 +705,30 @@ void MainWindow::loadPixhawkView()
void
MainWindow
::
loadDataView
()
{
clearView
();
centerStack
->
setCurrentWidget
(
dataplot
);
// DATAPLOT
if
(
dataplotWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
centerStack
->
setCurrentWidget
(
dataplotWidget
);
}
}
void
MainWindow
::
loadDataView
(
QString
fileName
)
{
clearView
();
centerStack
->
setCurrentWidget
(
dataplot
);
dataplot
->
loadFile
(
fileName
);
// DATAPLOT
if
(
dataplotWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
centerStack
->
setCurrentWidget
(
dataplotWidget
);
dataplotWidget
->
loadFile
(
fileName
);
}
}
}
void
MainWindow
::
loadPilotView
()
...
...
@@ -595,20 +736,38 @@ void MainWindow::loadPilotView()
clearView
();
// HEAD UP DISPLAY
centerStack
->
setCurrentWidget
(
hud
);
hud
->
start
();
if
(
hudWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
centerStack
->
setCurrentWidget
(
hudWidget
);
hudWidget
->
start
();
}
}
//connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), pfd, SLOT(setActiveUAS(UASInterface*)));
QDockWidget
*
container1
=
new
QDockWidget
(
tr
(
"Primary Flight Display"
),
this
);
container1
->
setWidget
(
headDown1
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
container1
);
QDockWidget
*
container2
=
new
QDockWidget
(
tr
(
"Payload Status"
),
this
);
container2
->
setWidget
(
headDown2
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
container2
);
if
(
headDown1DockWidget
)
{
HDDisplay
*
hdd
=
dynamic_cast
<
HDDisplay
*>
(
headDown1DockWidget
->
widget
());
if
(
hdd
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
headDown1DockWidget
);
headDown1DockWidget
->
show
();
hdd
->
start
();
}
headDown1
->
start
();
headDown2
->
start
();
}
if
(
headDown2DockWidget
)
{
HDDisplay
*
hdd
=
dynamic_cast
<
HDDisplay
*>
(
headDown2DockWidget
->
widget
());
if
(
hdd
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
headDown2DockWidget
);
headDown2DockWidget
->
show
();
hdd
->
start
();
}
}
this
->
show
();
}
...
...
@@ -618,43 +777,68 @@ void MainWindow::loadOperatorView()
clearView
();
// MAP
centerStack
->
setCurrentWidget
(
map
);
if
(
mapWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
centerStack
->
setCurrentWidget
(
mapWidget
);
}
}
// UAS CONTROL
QDockWidget
*
container1
=
new
QDockWidget
(
tr
(
"Control"
),
this
);
container1
->
setWidget
(
control
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container1
);
if
(
controlDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
controlDockWidget
);
controlDockWidget
->
show
();
}
// UAS LIST
QDockWidget
*
container4
=
new
QDockWidget
(
tr
(
"Unmanned Systems"
),
this
);
container4
->
setWidget
(
list
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container4
);
if
(
listDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
listDockWidget
);
listDockWidget
->
show
();
}
// UAS STATUS
QDockWidget
*
container3
=
new
QDockWidget
(
tr
(
"Status Details"
),
this
);
container3
->
setWidget
(
info
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container3
);
if
(
infoDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
infoDockWidget
);
infoDockWidget
->
show
();
}
// WAYPOINT LIST
QDockWidget
*
container5
=
new
QDockWidget
(
tr
(
"Waypoint List"
),
this
);
container5
->
setWidget
(
waypoints
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container5
);
if
(
waypointsDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
waypointsDockWidget
);
waypointsDockWidget
->
show
();
}
// HORIZONTAL SITUATION INDICATOR
QDockWidget
*
container7
=
new
QDockWidget
(
tr
(
"Horizontal Situation Indicator"
),
this
);
container7
->
setWidget
(
hsi
);
if
(
hsiDockWidget
)
{
HSIDisplay
*
hsi
=
dynamic_cast
<
HSIDisplay
*>
(
hsiDockWidget
->
widget
()
);
if
(
hsi
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
hsiDockWidget
);
hsiDockWidget
->
show
();
hsi
->
start
();
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container7
);
}
}
// OBJECT DETECTION
QDockWidget
*
container6
=
new
QDockWidget
(
tr
(
"Object Recognition"
),
this
);
container6
->
setWidget
(
detection
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
container6
);
if
(
detectionDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
detectionDockWidget
);
detectionDockWidget
->
show
();
}
// PROCESS CONTROL
QDockWidget
*
pControl
=
new
QDockWidget
(
tr
(
"Process Control"
),
this
);
pControl
->
setWidget
(
watchdogControl
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
pControl
);
if
(
watchdogControlDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
watchdogControlDockWidget
);
watchdogControlDockWidget
->
show
();
}
this
->
show
();
}
...
...
@@ -663,8 +847,15 @@ void MainWindow::loadSettingsView()
clearView
();
// LINE CHART
linechart
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechart
);
if
(
linechartWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
linechartWidget
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechartWidget
);
}
}
/*
// COMM XML
...
...
@@ -673,9 +864,12 @@ void MainWindow::loadSettingsView()
addDockWidget(Qt::LeftDockWidgetArea, container1);*/
// ONBOARD PARAMETERS
QDockWidget
*
container6
=
new
QDockWidget
(
tr
(
"Onboard Parameters"
),
this
);
container6
->
setWidget
(
parameters
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
container6
);
if
(
parametersDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
parametersDockWidget
);
parametersDockWidget
->
show
();
}
this
->
show
();
}
...
...
@@ -685,39 +879,57 @@ void MainWindow::loadEngineerView()
// Engineer view, used in EMAV2009
// LINE CHART
linechart
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechart
);
if
(
linechartWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
linechartWidget
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechartWidget
);
}
}
// UAS CONTROL
QDockWidget
*
container1
=
new
QDockWidget
(
tr
(
"Control"
),
this
);
container1
->
setWidget
(
control
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container1
);
if
(
controlDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
controlDockWidget
);
controlDockWidget
->
show
();
}
// UAS LIST
QDockWidget
*
container4
=
new
QDockWidget
(
tr
(
"Unmanned Systems"
),
this
);
container4
->
setWidget
(
list
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container4
);
if
(
listDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
listDockWidget
);
listDockWidget
->
show
();
}
// UAS STATUS
QDockWidget
*
container3
=
new
QDockWidget
(
tr
(
"Status Details"
),
this
);
container3
->
setWidget
(
info
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
container3
);
if
(
infoDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
infoDockWidget
);
infoDockWidget
->
show
();
}
// WAYPOINT LIST
QDockWidget
*
container5
=
new
QDockWidget
(
tr
(
"Waypoint List"
),
this
);
container5
->
setWidget
(
waypoints
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container5
);
if
(
waypointsDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
waypointsDockWidget
);
waypointsDockWidget
->
show
();
}
// DEBUG CONSOLE
QDockWidget
*
container7
=
new
QDockWidget
(
tr
(
"Communication Console"
),
this
);
container7
->
setWidget
(
debugConsole
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
container7
);
if
(
debugConsoleDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
debugConsoleDockWidget
);
debugConsoleDockWidget
->
show
();
}
// ONBOARD PARAMETERS
QDockWidget
*
containerParams
=
new
QDockWidget
(
tr
(
"Onboard Parameters"
),
this
);
containerParams
->
setWidget
(
parameters
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
containerParams
);
if
(
parametersDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
parametersDockWidget
);
parametersDockWidget
->
show
();
}
this
->
show
();
}
...
...
@@ -725,7 +937,16 @@ void MainWindow::loadEngineerView()
void
MainWindow
::
loadMAVLinkView
()
{
clearView
();
centerStack
->
setCurrentWidget
(
protocol
);
if
(
protocolWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
centerStack
->
setCurrentWidget
(
protocolWidget
);
}
}
this
->
show
();
}
...
...
@@ -733,55 +954,87 @@ void MainWindow::loadAllView()
{
clearView
();
QDockWidget
*
containerPFD
=
new
QDockWidget
(
tr
(
"Primary Flight Display"
),
this
);
containerPFD
->
setWidget
(
headDown1
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
containerPFD
);
QDockWidget
*
containerPayload
=
new
QDockWidget
(
tr
(
"Payload Status"
),
this
);
containerPayload
->
setWidget
(
headDown2
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
containerPayload
);
if
(
headDown1DockWidget
)
{
HDDisplay
*
hdd
=
dynamic_cast
<
HDDisplay
*>
(
headDown1DockWidget
->
widget
());
if
(
hdd
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
headDown1DockWidget
);
headDown1DockWidget
->
show
();
hdd
->
start
();
}
headDown1
->
start
();
headDown2
->
start
();
}
if
(
headDown2DockWidget
)
{
HDDisplay
*
hdd
=
dynamic_cast
<
HDDisplay
*>
(
headDown2DockWidget
->
widget
());
if
(
hdd
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
headDown2DockWidget
);
headDown2DockWidget
->
show
();
hdd
->
start
();
}
}
// UAS CONTROL
QDockWidget
*
containerControl
=
new
QDockWidget
(
tr
(
"Control"
),
this
);
containerControl
->
setWidget
(
control
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
containerControl
);
if
(
controlDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
controlDockWidget
);
controlDockWidget
->
show
();
}
// UAS LIST
QDockWidget
*
containerUASList
=
new
QDockWidget
(
tr
(
"Unmanned Systems"
),
this
);
containerUASList
->
setWidget
(
list
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
containerUASList
);
if
(
listDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
listDockWidget
);
listDockWidget
->
show
();
}
// UAS STATUS
QDockWidget
*
containerStatus
=
new
QDockWidget
(
tr
(
"Status Details"
),
this
);
containerStatus
->
setWidget
(
info
);
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
containerStatus
);
if
(
infoDockWidget
)
{
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
infoDockWidget
);
infoDockWidget
->
show
();
}
// WAYPOINT LIST
QDockWidget
*
containerWaypoints
=
new
QDockWidget
(
tr
(
"Waypoint List"
),
this
);
containerWaypoints
->
setWidget
(
waypoints
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
containerWaypoints
);
if
(
waypointsDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
waypointsDockWidget
);
waypointsDockWidget
->
show
();
}
// DEBUG CONSOLE
QDockWidget
*
containerComm
=
new
QDockWidget
(
tr
(
"Communication Console"
),
this
);
containerComm
->
setWidget
(
debugConsole
);
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
containerComm
);
if
(
debugConsoleDockWidget
)
{
addDockWidget
(
Qt
::
BottomDockWidgetArea
,
debugConsoleDockWidget
);
debugConsoleDockWidget
->
show
();
}
// OBJECT DETECTION
QDockWidget
*
containerObjRec
=
new
QDockWidget
(
tr
(
"Object Recognition"
),
this
);
containerObjRec
->
setWidget
(
detection
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
containerObjRec
);
if
(
detectionDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
detectionDockWidget
);
detectionDockWidget
->
show
();
}
// LINE CHART
linechart
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechart
);
if
(
linechartWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
linechartWidget
->
setActive
(
true
);
centerStack
->
setCurrentWidget
(
linechartWidget
);
}
}
// ONBOARD PARAMETERS
QDockWidget
*
containerParams
=
new
QDockWidget
(
tr
(
"Onboard Parameters"
),
this
);
containerParams
->
setWidget
(
parameters
);
addDockWidget
(
Qt
::
RightDockWidgetArea
,
containerParams
);
if
(
parametersDockWidget
)
{
addDockWidget
(
Qt
::
RightDockWidgetArea
,
parametersDockWidget
);
parametersDockWidget
->
show
();
}
this
->
show
();
}
...
...
src/ui/MainWindow.h
View file @
bb350243
...
...
@@ -154,24 +154,26 @@ protected:
LinkInterface
*
udpLink
;
QSettings
settings
;
UASControlWidget
*
control
;
Linecharts
*
linechart
;
UASInfoWidget
*
info
;
CameraView
*
camera
;
UASListWidget
*
list
;
WaypointList
*
waypoints
;
ObjectDetectionView
*
detection
;
HUD
*
hud
;
DebugConsole
*
debugConsole
;
MapWidget
*
map
;
ParameterInterface
*
parameters
;
XMLCommProtocolWidget
*
protocol
;
HDDisplay
*
headDown1
;
HDDisplay
*
headDown2
;
WatchdogControl
*
watchdogControl
;
HSIDisplay
*
hsi
;
QGCDataPlot2D
*
dataplot
;
QGCRemoteControlView
*
rcView
;
// Center widgets
QPointer
<
Linecharts
>
linechartWidget
;
QPointer
<
HUD
>
hudWidget
;
QPointer
<
MapWidget
>
mapWidget
;
QPointer
<
XMLCommProtocolWidget
>
protocolWidget
;
QPointer
<
QGCDataPlot2D
>
dataplotWidget
;
// Dock widgets
QPointer
<
QDockWidget
>
controlDockWidget
;
QPointer
<
QDockWidget
>
infoDockWidget
;
QPointer
<
QDockWidget
>
cameraDockWidget
;
QPointer
<
QDockWidget
>
listDockWidget
;
QPointer
<
QDockWidget
>
waypointsDockWidget
;
QPointer
<
QDockWidget
>
detectionDockWidget
;
QPointer
<
QDockWidget
>
debugConsoleDockWidget
;
QPointer
<
QDockWidget
>
parametersDockWidget
;
QPointer
<
QDockWidget
>
headDown1DockWidget
;
QPointer
<
QDockWidget
>
headDown2DockWidget
;
QPointer
<
QDockWidget
>
watchdogControlDockWidget
;
QPointer
<
QDockWidget
>
hsiDockWidget
;
QPointer
<
QDockWidget
>
rcViewDockWidget
;
// Popup widgets
JoystickWidget
*
joystickWidget
;
...
...
@@ -187,9 +189,6 @@ protected:
QAction
*
killUASAct
;
QAction
*
simulateUASAct
;
QDockWidget
*
controlDock
;
QStackedWidget
*
centerStack
;
LogCompressor
*
comp
;
QString
screenFileName
;
QTimer
*
videoTimer
;
...
...
src/ui/QGCParamWidget.cc
View file @
bb350243
...
...
@@ -2,9 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL/PIXHAWK PROJECT
<http://www.qgroundcontrol.org>
<http://pixhawk.ethz.ch>
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
...
...
@@ -22,7 +20,6 @@ This file is part of the QGROUNDCONTROL project
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of class QGCParamWidget
...
...
src/ui/QGCRemoteControlView.cc
View file @
bb350243
...
...
@@ -52,18 +52,21 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
nameLabel
=
new
QLabel
(
this
);
nameLabel
->
setText
(
"No MAV selected yet.."
);
layout
->
addWidget
(
nameLabel
,
0
,
0
,
1
,
2
);
// Add spacer left of button
layout
->
addItem
(
new
QSpacerItem
(
0
,
0
,
QSizePolicy
::
Expanding
,
QSizePolicy
::
Expanding
),
2
,
0
);
// Set stretch to maximize spacer, not button
layout
->
setColumnStretch
(
0
,
100
);
layout
->
setColumnStretch
(
1
,
1
);
// Calibrate button
QPushButton
*
calibrateButton
=
new
QPushButton
(
this
);
calibrateButton
->
setText
(
tr
(
"Calibrate"
));
// Connect to calibration slot
connect
(
calibrateButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
calibrate
()));
// Add button
layout
->
addWidget
(
calibrateButton
,
2
,
1
);
// RSSI bar
// Create new layout
QHBoxLayout
*
rssiLayout
=
new
QHBoxLayout
();
rssiLayout
->
setSpacing
(
5
);
// Add content
rssiLayout
->
addWidget
(
new
QLabel
(
tr
(
"Signal"
),
this
));
// Append raw label
// Append progress bar
rssiBar
=
new
QProgressBar
(
this
);
rssiBar
->
setMinimum
(
0
);
rssiBar
->
setMaximum
(
100
);
rssiBar
->
setValue
(
0
);
rssiLayout
->
addWidget
(
rssiBar
);
layout
->
addItem
(
rssiLayout
,
2
,
0
,
1
,
2
);
setVisible
(
false
);
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
int
)),
this
,
SLOT
(
setUASId
(
int
)));
...
...
@@ -75,11 +78,6 @@ QGCRemoteControlView::~QGCRemoteControlView()
delete
channelLayout
;
}
void
QGCRemoteControlView
::
calibrate
()
{
// Run auto-calibration
}
void
QGCRemoteControlView
::
setUASId
(
int
id
)
{
if
(
uasId
!=
-
1
)
...
...
@@ -89,6 +87,7 @@ void QGCRemoteControlView::setUASId(int id)
{
// The UAS exists, disconnect any existing connections
disconnect
(
uas
,
SIGNAL
(
remoteControlChannelChanged
(
int
,
float
,
float
)),
this
,
SLOT
(
setChannel
(
int
,
float
,
float
)));
disconnect
(
uas
,
SIGNAL
(
remoteControlRSSIChanged
(
float
)),
this
,
SLOT
(
setRemoteRSSI
(
float
)));
}
}
...
...
@@ -99,6 +98,7 @@ void QGCRemoteControlView::setUASId(int id)
// New UAS exists, connect
nameLabel
->
setText
(
QString
(
"RC Input of %1"
).
arg
(
newUAS
->
getUASName
()));
connect
(
newUAS
,
SIGNAL
(
remoteControlChannelChanged
(
int
,
float
,
float
)),
this
,
SLOT
(
setChannel
(
int
,
float
,
float
)));
connect
(
newUAS
,
SIGNAL
(
remoteControlRSSIChanged
(
float
)),
this
,
SLOT
(
setRemoteRSSI
(
float
)));
}
}
...
...
@@ -132,7 +132,7 @@ void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized)
void
QGCRemoteControlView
::
appendChannelWidget
(
int
channelId
)
{
// Create new layout
QHBoxLayout
*
layout
=
new
QHBoxLayout
(
this
);
QHBoxLayout
*
layout
=
new
QHBoxLayout
();
// Add content
layout
->
addWidget
(
new
QLabel
(
QString
(
"Channel %1"
).
arg
(
channelId
+
1
),
this
));
QLabel
*
raw
=
new
QLabel
(
this
);
...
...
src/ui/QGCRemoteControlView.h
View file @
bb350243
...
...
@@ -51,7 +51,6 @@ public slots:
void
setUASId
(
int
id
);
void
setChannel
(
int
channelId
,
float
raw
,
float
normalized
);
void
setRemoteRSSI
(
float
rssiNormalized
);
void
calibrate
();
void
redraw
();
protected
slots
:
...
...
@@ -67,6 +66,7 @@ protected:
QVector
<
float
>
normalized
;
QVector
<
QLabel
*>
rawLabels
;
QVector
<
QProgressBar
*>
progressBars
;
QProgressBar
*
rssiBar
;
QLabel
*
nameLabel
;
private:
...
...
src/ui/QGCSensorSettingsWidget.cc
View file @
bb350243
...
...
@@ -46,6 +46,12 @@ QGCSensorSettingsWidget::QGCSensorSettingsWidget(UASInterface* uas, QWidget *par
connect
(
ui
->
sendExtra1CheckBox
,
SIGNAL
(
toggled
(
bool
)),
mav
,
SLOT
(
enableExtra1Transmission
(
bool
)));
connect
(
ui
->
sendExtra2CheckBox
,
SIGNAL
(
toggled
(
bool
)),
mav
,
SLOT
(
enableExtra2Transmission
(
bool
)));
connect
(
ui
->
sendExtra3CheckBox
,
SIGNAL
(
toggled
(
bool
)),
mav
,
SLOT
(
enableExtra3Transmission
(
bool
)));
// Calibration
connect
(
ui
->
rcCalButton
,
SIGNAL
(
clicked
()),
mav
,
SLOT
(
startRadioControlCalibration
()));
connect
(
ui
->
magCalButton
,
SIGNAL
(
clicked
()),
mav
,
SLOT
(
startMagnetometerCalibration
()));
connect
(
ui
->
pressureCalButton
,
SIGNAL
(
clicked
()),
mav
,
SLOT
(
startPressureCalibration
()));
connect
(
ui
->
gyroCalButton
,
SIGNAL
(
clicked
()),
mav
,
SLOT
(
startGyroscopeCalibration
()));
}
QGCSensorSettingsWidget
::~
QGCSensorSettingsWidget
()
...
...
src/ui/QGCSensorSettingsWidget.ui
View file @
bb350243
...
...
@@ -90,38 +90,51 @@
<property
name=
"title"
>
<string>
Calibration Wizards
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
columnstretch=
"0,50"
>
<property
name=
"margin"
>
<number>
6
</number>
</property>
<item
row=
"
0
"
column=
"0"
>
<widget
class=
"QPushButton"
name=
"
gyro
CalButton"
>
<item
row=
"
1
"
column=
"0"
>
<widget
class=
"QPushButton"
name=
"
mag
CalButton"
>
<property
name=
"text"
>
<string>
Start
dynamic c
alibration
</string>
<string>
Start
Mag. C
alibration
</string>
</property>
</widget>
</item>
<item
row=
"
0"
column=
"1
"
>
<widget
class=
"Q
Label"
name=
"gyroCalDate
"
>
<item
row=
"
4"
column=
"0
"
>
<widget
class=
"Q
PushButton"
name=
"gyroCalButton
"
>
<property
name=
"text"
>
<string>
Date unknow
n
</string>
<string>
Start Gyro Calibratio
n
</string>
</property>
</widget>
</item>
<item
row=
"
1
"
column=
"0"
>
<widget
class=
"QPushButton"
name=
"
mag
CalButton"
>
<item
row=
"
0
"
column=
"0"
>
<widget
class=
"QPushButton"
name=
"
rc
CalButton"
>
<property
name=
"text"
>
<string>
Start
static c
alibration
</string>
<string>
Start
RC C
alibration
</string>
</property>
</widget>
</item>
<item
row=
"
1"
column=
"1
"
>
<widget
class=
"Q
Label"
name=
"magCalLabel
"
>
<item
row=
"
2"
column=
"0
"
>
<widget
class=
"Q
PushButton"
name=
"pressureCalButton
"
>
<property
name=
"text"
>
<string>
Date unknow
n
</string>
<string>
Start Pressure Calibratio
n
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"1"
>
<spacer
name=
"horizontalSpacer"
>
<property
name=
"orientation"
>
<enum>
Qt::Horizontal
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
0
</width>
<height>
0
</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
...
...
src/ui/uas/UASControlWidget.cc
View file @
bb350243
...
...
@@ -51,13 +51,13 @@ This file is part of the PIXHAWK project
#define CONTROL_MODE_TEST2 "MODE TEST2"
#define CONTROL_MODE_TEST3 "MODE TEST3"
#define CONTROL_MODE_LOCKED_INDEX
2
#define CONTROL_MODE_MANUAL_INDEX
3
#define CONTROL_MODE_GUIDED_INDEX
4
#define CONTROL_MODE_AUTO_INDEX
5
#define CONTROL_MODE_TEST1_INDEX
6
#define CONTROL_MODE_TEST2_INDEX
7
#define CONTROL_MODE_TEST3_INDEX
8
#define CONTROL_MODE_LOCKED_INDEX
1
#define CONTROL_MODE_MANUAL_INDEX
2
#define CONTROL_MODE_GUIDED_INDEX
3
#define CONTROL_MODE_AUTO_INDEX
4
#define CONTROL_MODE_TEST1_INDEX
5
#define CONTROL_MODE_TEST2_INDEX
6
#define CONTROL_MODE_TEST3_INDEX
7
UASControlWidget
::
UASControlWidget
(
QWidget
*
parent
)
:
QWidget
(
parent
),
uas
(
0
),
...
...
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