Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
c81927fa
Commit
c81927fa
authored
Dec 26, 2014
by
Don Gagne
Browse files
Rework Connect toolbar button usage
Now works for more than Serial links
parent
cf777949
Changes
13
Expand all
Hide whitespace changes
Inline
Side-by-side
src/QGCApplication.cc
View file @
c81927fa
...
...
@@ -252,8 +252,6 @@ bool QGCApplication::_initForNormalAppBoot(void)
_createSingletons
();
enum
MainWindow
::
CUSTOM_MODE
mode
=
(
enum
MainWindow
::
CUSTOM_MODE
)
settings
.
value
(
"QGC_CUSTOM_MODE"
,
(
int
)
MainWindow
::
CUSTOM_MODE_PX4
).
toInt
();
// Show splash screen
QPixmap
splashImage
(
":/files/images/splash.png"
);
QSplashScreen
*
splashScreen
=
new
QSplashScreen
(
splashImage
);
...
...
@@ -268,7 +266,7 @@ bool QGCApplication::_initForNormalAppBoot(void)
// Start the user interface
splashScreen
->
showMessage
(
tr
(
"Starting user interface"
),
Qt
::
AlignLeft
|
Qt
::
AlignBottom
,
QColor
(
62
,
93
,
141
));
MainWindow
*
mainWindow
=
MainWindow
::
_create
(
splashScreen
,
mode
);
MainWindow
*
mainWindow
=
MainWindow
::
_create
(
splashScreen
);
Q_CHECK_PTR
(
mainWindow
);
// If we made it this far and we still don't have a location. Either the specfied location was invalid
...
...
@@ -281,47 +279,10 @@ bool QGCApplication::_initForNormalAppBoot(void)
mainWindow
->
showSettings
();
}
UDPLink
*
udpLink
=
NULL
;
if
(
mainWindow
->
getCustomMode
()
==
MainWindow
::
CUSTOM_MODE_WIFI
)
{
// Connect links
// to make sure that all components are initialized when the
// first messages arrive
udpLink
=
new
UDPLink
(
QHostAddress
::
Any
,
14550
);
LinkManager
::
instance
()
->
addLink
(
udpLink
);
}
else
{
// We want to have a default serial link available for "quick" connecting.
SerialLink
*
slink
=
new
SerialLink
();
LinkManager
::
instance
()
->
addLink
(
slink
);
}
#ifdef QGC_RTLAB_ENABLED
// Add OpalRT Link, but do not connect
OpalLink
*
opalLink
=
new
OpalLink
();
_mainWindow
->
addLink
(
opalLink
);
#endif
// Remove splash screen
splashScreen
->
finish
(
mainWindow
);
mainWindow
->
splashScreenFinished
();
// Check if link could be connected
if
(
udpLink
&&
LinkManager
::
instance
()
->
connectLink
(
udpLink
))
{
QMessageBox
::
StandardButton
button
=
QGCMessageBox
::
critical
(
tr
(
"Could not connect UDP port. Is an instance of %1 already running?"
).
arg
(
qAppName
()),
tr
(
"It is recommended to close the application and stop all instances. Click Yes to close."
),
QMessageBox
::
Yes
|
QMessageBox
::
No
,
QMessageBox
::
No
);
// Exit application
if
(
button
==
QMessageBox
::
Yes
)
{
//mainWindow->close();
QTimer
::
singleShot
(
200
,
mainWindow
,
SLOT
(
close
()));
}
}
// Now that main window is upcheck for lost log files
connect
(
this
,
&
QGCApplication
::
checkForLostLogFiles
,
MAVLinkProtocol
::
instance
(),
&
MAVLinkProtocol
::
checkForLostLogFiles
);
emit
checkForLostLogFiles
();
...
...
src/comm/LinkManager.cc
View file @
c81927fa
...
...
@@ -84,6 +84,9 @@ void LinkManager::addLink(LinkInterface* link)
connect
(
link
,
&
LinkInterface
::
connected
,
mavlink
,
&
MAVLinkProtocol
::
linkConnected
);
connect
(
link
,
&
LinkInterface
::
disconnected
,
mavlink
,
&
MAVLinkProtocol
::
linkDisconnected
);
mavlink
->
resetMetadataForLink
(
link
);
connect
(
link
,
&
LinkInterface
::
connected
,
this
,
&
LinkManager
::
_linkConnected
);
connect
(
link
,
&
LinkInterface
::
disconnected
,
this
,
&
LinkManager
::
_linkDisconnected
);
}
bool
LinkManager
::
connectAll
()
...
...
@@ -131,13 +134,22 @@ bool LinkManager::connectLink(LinkInterface* link)
return
false
;
}
return
link
->
_connect
();
if
(
link
->
_connect
())
{
return
true
;
}
else
{
return
false
;
}
}
bool
LinkManager
::
disconnectLink
(
LinkInterface
*
link
)
{
Q_ASSERT
(
link
);
return
link
->
_disconnect
();
if
(
link
->
_disconnect
())
{
return
true
;
}
else
{
return
false
;
}
}
void
LinkManager
::
deleteLink
(
LinkInterface
*
link
)
...
...
@@ -218,3 +230,13 @@ void LinkManager::_shutdown(void)
deleteLink
(
link
);
}
}
void
LinkManager
::
_linkConnected
(
void
)
{
emit
linkConnected
((
LinkInterface
*
)
sender
());
}
void
LinkManager
::
_linkDisconnected
(
void
)
{
emit
linkDisconnected
((
LinkInterface
*
)
sender
());
}
src/comm/LinkManager.h
View file @
c81927fa
...
...
@@ -91,6 +91,12 @@ public:
signals:
void
newLink
(
LinkInterface
*
link
);
void
linkDeleted
(
LinkInterface
*
link
);
void
linkConnected
(
LinkInterface
*
link
);
void
linkDisconnected
(
LinkInterface
*
link
);
private
slots
:
void
_linkConnected
(
void
);
void
_linkDisconnected
(
void
);
private:
/// All access to LinkManager is through LinkManager::instance
...
...
src/comm/UDPLink.cc
View file @
c81927fa
...
...
@@ -277,16 +277,15 @@ bool UDPLink::_disconnect(void)
this
->
quit
();
this
->
wait
();
if
(
socket
)
{
if
(
socket
)
{
// Make sure delete happen on correct thread
socket
->
deleteLater
();
socket
=
NULL
;
emit
disconnected
();
}
connectState
=
false
;
emit
disconnected
();
return
!
connectState
;
}
...
...
src/qgcunittest/MainWindowTest.cc
View file @
c81927fa
...
...
@@ -42,7 +42,7 @@ void MainWindowTest::init(void)
{
UnitTest
::
init
();
_mainWindow
=
MainWindow
::
_create
(
NULL
,
MainWindow
::
CUSTOM_MODE_PX4
);
_mainWindow
=
MainWindow
::
_create
(
NULL
);
Q_CHECK_PTR
(
_mainWindow
);
}
...
...
src/ui/CommConfigurationWindow.cc
View file @
c81927fa
...
...
@@ -368,7 +368,6 @@ void CommConfigurationWindow::remove()
action
=
NULL
;
if
(
link
)
{
LinkManager
::
instance
()
->
disconnectLink
(
link
);
// disconnect connection
link
->
deleteLater
();
}
link
=
NULL
;
...
...
src/ui/MainWindow.cc
View file @
c81927fa
...
...
@@ -80,11 +80,11 @@ This file is part of the QGROUNDCONTROL project
static
MainWindow
*
_instance
=
NULL
;
///< @brief MainWindow singleton
MainWindow
*
MainWindow
::
_create
(
QSplashScreen
*
splashScreen
,
enum
MainWindow
::
CUSTOM_MODE
mode
)
MainWindow
*
MainWindow
::
_create
(
QSplashScreen
*
splashScreen
)
{
Q_ASSERT
(
_instance
==
NULL
);
new
MainWindow
(
splashScreen
,
mode
);
new
MainWindow
(
splashScreen
);
// _instance is set in constructor
Q_ASSERT
(
_instance
);
...
...
@@ -105,13 +105,12 @@ void MainWindow::deleteInstance(void)
/// @brief Private constructor for MainWindow. MainWindow singleton is only ever created
/// by MainWindow::_create method. Hence no other code should have access to
/// constructor.
MainWindow
::
MainWindow
(
QSplashScreen
*
splashScreen
,
enum
MainWindow
::
CUSTOM_MODE
mode
)
:
MainWindow
::
MainWindow
(
QSplashScreen
*
splashScreen
)
:
currentView
(
VIEW_FLIGHT
),
centerStackActionGroup
(
new
QActionGroup
(
this
)),
autoReconnect
(
false
),
simulationLink
(
NULL
),
lowPowerMode
(
false
),
customMode
(
mode
),
menuActionHelper
(
new
MenuActionHelper
()),
_splashScreen
(
splashScreen
)
{
...
...
@@ -405,10 +404,10 @@ QString MainWindow::getWindowStateKey()
{
if
(
UASManager
::
instance
()
->
getActiveUAS
())
{
return
QString
::
number
(
currentView
)
+
"_windowstate_"
+
QString
::
number
(
getCustomMode
())
+
"_"
+
UASManager
::
instance
()
->
getActiveUAS
()
->
getAutopilotTypeName
();
return
QString
::
number
(
currentView
)
+
"_windowstate_"
+
UASManager
::
instance
()
->
getActiveUAS
()
->
getAutopilotTypeName
();
}
else
return
QString
::
number
(
currentView
)
+
"_windowstate_"
+
QString
::
number
(
getCustomMode
())
;
return
QString
::
number
(
currentView
)
+
"_windowstate_"
;
}
QString
MainWindow
::
getWindowGeometryKey
()
...
...
@@ -938,8 +937,6 @@ void MainWindow::loadSettings()
{
QSettings
settings
;
customMode
=
static_cast
<
enum
MainWindow
::
CUSTOM_MODE
>
(
settings
.
value
(
"QGC_CUSTOM_MODE"
,
(
unsigned
int
)
MainWindow
::
CUSTOM_MODE_NONE
).
toInt
());
settings
.
beginGroup
(
"QGC_MAINWINDOW"
);
autoReconnect
=
settings
.
value
(
"AUTO_RECONNECT"
,
autoReconnect
).
toBool
();
lowPowerMode
=
settings
.
value
(
"LOW_POWER_MODE"
,
lowPowerMode
).
toBool
();
...
...
@@ -953,8 +950,6 @@ void MainWindow::storeSettings()
{
QSettings
settings
;
settings
.
setValue
(
"QGC_CUSTOM_MODE"
,
(
int
)
customMode
);
settings
.
beginGroup
(
"QGC_MAINWINDOW"
);
settings
.
setValue
(
"AUTO_RECONNECT"
,
autoReconnect
);
settings
.
setValue
(
"LOW_POWER_MODE"
,
lowPowerMode
);
...
...
src/ui/MainWindow.h
View file @
c81927fa
...
...
@@ -88,14 +88,6 @@ class MainWindow : public QMainWindow
Q_OBJECT
public:
enum
CUSTOM_MODE
{
CUSTOM_MODE_UNCHANGED
=
0
,
CUSTOM_MODE_NONE
,
CUSTOM_MODE_PX4
,
CUSTOM_MODE_WIFI
};
/// @brief Returns the MainWindow singleton. Will not create the MainWindow if it has not already
/// been created.
static
MainWindow
*
instance
(
void
);
...
...
@@ -104,7 +96,7 @@ public:
void
deleteInstance
(
void
);
/// @brief Creates the MainWindow singleton. Should only be called once by QGCApplication.
static
MainWindow
*
_create
(
QSplashScreen
*
splashScreen
,
enum
MainWindow
::
CUSTOM_MODE
mode
);
static
MainWindow
*
_create
(
QSplashScreen
*
splashScreen
);
/// @brief Called to indicate that splash screen is no longer being displayed.
void
splashScreenFinished
(
void
)
{
_splashScreen
=
NULL
;
}
...
...
@@ -127,19 +119,6 @@ public:
return
lowPowerMode
;
}
void
setCustomMode
(
MainWindow
::
CUSTOM_MODE
mode
)
{
if
(
mode
!=
CUSTOM_MODE_UNCHANGED
)
{
customMode
=
mode
;
}
}
MainWindow
::
CUSTOM_MODE
getCustomMode
()
const
{
return
customMode
;
}
QList
<
QAction
*>
listLinkMenuActions
();
void
hideSplashScreen
(
void
);
...
...
@@ -420,14 +399,13 @@ protected:
bool
lowPowerMode
;
///< If enabled, QGC reduces the update rates of all widgets
QGCFlightGearLink
*
fgLink
;
QTimer
windowNameUpdateTimer
;
CUSTOM_MODE
customMode
;
private
slots
:
void
_addLinkMenu
(
LinkInterface
*
link
);
private:
/// Constructor is private since all creation should be through MainWindow::_create
MainWindow
(
QSplashScreen
*
splashScreen
,
enum
MainWindow
::
CUSTOM_MODE
mode
);
MainWindow
(
QSplashScreen
*
splashScreen
);
void
_openUrl
(
const
QString
&
url
,
const
QString
&
errorMessage
);
...
...
src/ui/QGCToolBar.cc
View file @
c81927fa
...
...
@@ -24,43 +24,41 @@ This file is part of the QGROUNDCONTROL project
#include
<QToolButton>
#include
<QLabel>
#include
<QSpacerItem>
#include
<QSerialPortInfo>
#include
"SerialLink.h"
#include
"UDPLink.h"
#include
"QGCToolBar.h"
#include
"UASManager.h"
#include
"MainWindow.h"
#include
"QGCApplication.h"
#include
"CommConfigurationWindow.h"
QGCToolBar
::
QGCToolBar
(
QWidget
*
parent
)
:
QToolBar
(
parent
),
mav
(
NULL
),
userBaudChoice
(
false
),
userPortChoice
(
false
),
changed
(
true
),
batteryPercent
(
0
),
batteryVoltage
(
0
),
wpId
(
0
),
wpDistance
(
0
),
altitudeMSL
(
0
),
altitudeRel
(
0
),
systemArmed
(
false
),
currentLink
(
NULL
),
firstAction
(
NULL
)
firstAction
(
NULL
),
_linkMgr
(
LinkManager
::
instance
()),
_linkCombo
(
NULL
),
_linkComboAction
(
NULL
),
_linkSelectedOnce
(
false
),
_baudCombo
(
NULL
),
_baudComboAction
(
NULL
),
_linksConnected
(
false
)
{
setObjectName
(
"QGCToolBar"
);
setSizePolicy
(
QSizePolicy
::
MinimumExpanding
,
QSizePolicy
::
MinimumExpanding
);
// Do not load UI, wait for actions
}
void
QGCToolBar
::
globalPositionChanged
(
UASInterface
*
uas
,
double
lat
,
double
lon
,
double
altAMSL
,
double
altWGS84
,
quint64
usec
)
{
Q_UNUSED
(
uas
);
Q_UNUSED
(
lat
);
Q_UNUSED
(
lon
);
Q_UNUSED
(
altWGS84
);
Q_UNUSED
(
usec
);
altitudeMSL
=
altAMSL
;
changed
=
true
;
connect
(
LinkManager
::
instance
(),
&
LinkManager
::
linkConnected
,
this
,
&
QGCToolBar
::
_linkConnected
);
connect
(
LinkManager
::
instance
(),
&
LinkManager
::
linkDisconnected
,
this
,
&
QGCToolBar
::
_linkDisconnected
);
}
void
QGCToolBar
::
heartbeatTimeout
(
bool
timeout
,
unsigned
int
ms
)
...
...
@@ -163,36 +161,36 @@ void QGCToolBar::createUI()
spacer
->
setSizePolicy
(
QSizePolicy
::
Expanding
,
QSizePolicy
::
Expanding
);
addWidget
(
spacer
);
port
Combo
Box
=
new
QComboBox
(
this
);
portComboBox
->
setToolTip
(
tr
(
"Choose the COM port to use"
)
);
portComboBox
->
setEnabled
(
true
);
portComboBox
->
setMinimumWidth
(
100
);
toolBarPortAction
=
addWidget
(
portComboBox
);
baudcomboBox
=
new
QComboBox
(
this
);
baudcomboBox
->
setToolTip
(
tr
(
"Choose what baud rate to use"
));
baudcomboBox
->
setEnabled
(
true
);
baudcomboBox
->
setMinimumWidth
(
40
);
baud
comboBox
->
addItem
(
"9600"
,
9600
);
baud
c
ombo
Box
->
addItem
(
"14400"
,
14400
);
baud
c
ombo
Box
->
addItem
(
"19200"
,
19200
);
baud
c
ombo
Box
->
addItem
(
"38400"
,
3840
0
);
baud
c
ombo
Box
->
addItem
(
"
57
600"
,
57
600
);
baud
c
ombo
Box
->
addItem
(
"1
152
00"
,
1
152
00
);
baud
c
ombo
Box
->
addItem
(
"
2304
00"
,
2304
00
);
baud
c
ombo
Box
->
addItem
(
"
4608
00"
,
4608
00
);
baud
c
ombo
Box
->
addItem
(
"
921
600"
,
921
600
);
baud
c
ombo
Box
->
setCurrentIndex
(
baudcomboBox
->
findData
(
57600
)
);
toolBarBaudAction
=
addWidget
(
baudcomboBox
);
connect
(
baud
c
ombo
Box
,
SIGNAL
(
activated
(
int
)),
this
,
SLOT
(
baudSelected
(
int
))
);
connect
(
portComboBox
,
SIGNAL
(
activated
(
int
)),
this
,
SLOT
(
portSelected
(
int
))
);
connectButton
=
new
QPushButton
(
tr
(
"Connect"
),
this
);
connectButton
->
setObjectName
(
"connectButton"
);
connectButton
->
setToolTip
(
tr
(
"Connect wireless link to MAV"
)
);
connectButton
->
set
Checkable
(
true
);
addWidget
(
connectButton
);
connect
(
connectButton
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
connectLink
(
bool
))
);
_link
Combo
=
new
QComboBox
(
this
);
_linkCombo
->
addItem
(
"WiFi"
);
connect
(
_linkCombo
,
SIGNAL
(
activated
(
int
)),
SLOT
(
_linkComboActivated
(
int
))
);
_linkCombo
->
setToolTip
(
tr
(
"Choose the link to use"
)
);
_linkCombo
->
setEnabled
(
true
);
_linkCombo
->
setMinimumWidth
(
100
);
_linkComboAction
=
addWidget
(
_linkCombo
);
_
baud
Combo
=
new
QComboBox
(
this
);
_
baud
C
ombo
->
setToolTip
(
tr
(
"Choose what baud rate to use"
)
);
_
baud
C
ombo
->
setEnabled
(
true
);
_
baud
C
ombo
->
setMinimumWidth
(
4
0
);
_
baud
C
ombo
->
addItem
(
"
9
600"
,
9
600
);
_
baud
C
ombo
->
addItem
(
"1
44
00"
,
1
44
00
);
_
baud
C
ombo
->
addItem
(
"
192
00"
,
192
00
);
_
baud
C
ombo
->
addItem
(
"
384
00"
,
384
00
);
_
baud
C
ombo
->
addItem
(
"
57
600"
,
57
600
);
_
baud
C
ombo
->
addItem
(
"115200"
,
115200
);
_baudCombo
->
addItem
(
"230400"
,
230400
);
_
baud
C
ombo
->
addItem
(
"460800"
,
460800
);
_baudCombo
->
addItem
(
"921600"
,
921600
);
_baudCombo
->
setCurrentIndex
(
_baudCombo
->
findData
(
57600
));
_baudComboAction
=
addWidget
(
_baudCombo
);
_
connectButton
=
new
QPushButton
(
tr
(
"Connect"
),
this
);
_
connectButton
->
set
ObjectName
(
"connectButton"
);
addWidget
(
_
connectButton
);
connect
(
_
connectButton
,
&
QPushButton
::
clicked
,
this
,
&
QGCToolBar
::
_connectButtonClicked
);
resetToolbarUI
();
...
...
@@ -204,28 +202,9 @@ void QGCToolBar::createUI()
// Configure the toolbar for the current default UAS
setActiveUAS
(
UASManager
::
instance
()
->
getActiveUAS
());
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
setActiveUAS
(
UASInterface
*
)));
// Update label if required
if
(
LinkManager
::
instance
()
->
getSerialLinks
().
count
()
<
1
)
{
connectButton
->
setText
(
tr
(
"New Serial Link"
));
toolBarPortAction
->
setVisible
(
false
);
toolBarBaudAction
->
setVisible
(
false
);
}
else
{
QList
<
SerialLink
*>
links
=
LinkManager
::
instance
()
->
getSerialLinks
();
foreach
(
SerialLink
*
slink
,
links
)
{
addLink
(
slink
);
}
}
connect
(
LinkManager
::
instance
(),
SIGNAL
(
newLink
(
LinkInterface
*
)),
this
,
SLOT
(
addLink
(
LinkInterface
*
)));
connect
(
LinkManager
::
instance
(),
SIGNAL
(
linkDeleted
(
LinkInterface
*
)),
this
,
SLOT
(
removeLink
(
LinkInterface
*
)));
loadSettings
();
connect
(
&
portBoxTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
updateComboBox
()));
portBoxTimer
.
start
(
500
);
connect
(
&
_portListTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCToolBar
::
_updatePortList
);
_portListTimer
.
start
(
500
);
toolBarMessageAction
->
setVisible
(
false
);
toolBarBatteryBarAction
->
setVisible
(
false
);
...
...
@@ -259,18 +238,6 @@ void QGCToolBar::resetToolbarUI()
toolBarBatteryBarAction
->
setVisible
(
false
);
}
void
QGCToolBar
::
baudSelected
(
int
index
)
{
Q_UNUSED
(
index
);
userBaudChoice
=
true
;
}
void
QGCToolBar
::
portSelected
(
int
index
)
{
Q_UNUSED
(
index
);
userPortChoice
=
true
;
}
void
QGCToolBar
::
setPerspectiveChangeActions
(
const
QList
<
QAction
*>
&
actions
)
{
if
(
actions
.
count
()
>
1
)
...
...
@@ -372,7 +339,6 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
disconnect
(
mav
,
SIGNAL
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)),
this
,
SLOT
(
updateBatteryRemaining
(
UASInterface
*
,
double
,
double
,
double
,
int
)));
disconnect
(
mav
,
SIGNAL
(
armingChanged
(
bool
)),
this
,
SLOT
(
updateArmingState
(
bool
)));
disconnect
(
mav
,
SIGNAL
(
heartbeatTimeout
(
bool
,
unsigned
int
)),
this
,
SLOT
(
heartbeatTimeout
(
bool
,
unsigned
int
)));
disconnect
(
active
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)));
if
(
mav
->
getWaypointManager
())
{
disconnect
(
mav
->
getWaypointManager
(),
SIGNAL
(
currentWaypointChanged
(
quint16
)),
this
,
SLOT
(
updateCurrentWaypoint
(
quint16
)));
...
...
@@ -397,7 +363,6 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
connect
(
mav
,
SIGNAL
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)),
this
,
SLOT
(
updateBatteryRemaining
(
UASInterface
*
,
double
,
double
,
double
,
int
)));
connect
(
mav
,
SIGNAL
(
armingChanged
(
bool
)),
this
,
SLOT
(
updateArmingState
(
bool
)));
connect
(
mav
,
SIGNAL
(
heartbeatTimeout
(
bool
,
unsigned
int
)),
this
,
SLOT
(
heartbeatTimeout
(
bool
,
unsigned
int
)));
connect
(
mav
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)));
if
(
mav
->
getWaypointManager
())
{
connect
(
mav
->
getWaypointManager
(),
SIGNAL
(
currentWaypointChanged
(
quint16
)),
this
,
SLOT
(
updateCurrentWaypoint
(
quint16
)));
...
...
@@ -636,175 +601,135 @@ void QGCToolBar::receiveTextMessage(int uasid, int componentid, int severity, QS
lastSystemMessageTimeMs
=
QGC
::
groundTimeMilliseconds
();
}
void
QGCToolBar
::
addLink
(
LinkInterface
*
link
)
void
QGCToolBar
::
_updatePortList
(
void
)
{
// Accept only serial links as current link
SerialLink
*
serial
=
qobject_cast
<
SerialLink
*>
(
link
);
if
(
serial
&&
!
currentLink
)
{
toolBarPortAction
->
setVisible
(
true
);
toolBarBaudAction
->
setVisible
(
true
);
currentLink
=
link
;
connect
(
currentLink
,
&
LinkInterface
::
connected
,
this
,
&
QGCToolBar
::
_linkConnected
);
_updateLinkState
(
link
->
isConnected
());
qDebug
()
<<
"ADD LINK"
;
updateComboBox
();
}
}
void
QGCToolBar
::
removeLink
(
LinkInterface
*
link
)
{
if
(
link
==
currentLink
)
{
currentLink
=
NULL
;
// Try to get a new serial link
foreach
(
SerialLink
*
s
,
LinkManager
::
instance
()
->
getSerialLinks
())
{
addLink
(
s
);
}
// Update GUI according to scan result
if
(
currentLink
)
{
_updateLinkState
(
currentLink
->
isConnected
());
}
else
{
connectButton
->
setText
(
tr
(
"New Serial Link"
));
portComboBox
->
hide
();
baudcomboBox
->
hide
();
}
if
(
!
_linkCombo
->
isVisible
())
{
return
;
}
updateComboBox
();
}
void
QGCToolBar
::
updateComboBox
()
{
if
(
currentLink
&&
!
currentLink
->
isConnected
())
{
// Do not update if not visible
if
(
!
portComboBox
->
isVisible
())
return
;
SerialLink
*
slink
=
qobject_cast
<
SerialLink
*>
(
currentLink
);
QList
<
QString
>
portlist
=
slink
->
getCurrentPorts
();
foreach
(
QString
port
,
portlist
)
{
if
(
portComboBox
->
findText
(
port
)
==
-
1
)
{
portComboBox
->
addItem
(
port
,
port
);
}
}
if
(
!
userPortChoice
)
{
if
(
slink
->
getPortName
().
trimmed
().
length
()
>
0
)
{
int
portIndex
=
portComboBox
->
findData
(
slink
->
getPortName
());
if
(
portIndex
>=
0
)
{
portComboBox
->
setCurrentIndex
(
portIndex
);
portComboBox
->
setEditText
(
slink
->
getPortName
());
}
}
else
{
if
(
portlist
.
length
()
>
0
)
{
portComboBox
->
setEditText
(
portlist
.
last
());
}
else
{
portComboBox
->
setEditText
(
tr
(
"No serial port found"
));
}
QList
<
QSerialPortInfo
>
portList
=
QSerialPortInfo
::
availablePorts
();
foreach
(
QSerialPortInfo
portInfo
,
portList
)
{
if
(
_linkCombo
->
findText
(
portInfo
.
portName
())
==
-
1
)
{
_linkCombo
->
addItem
(
portInfo
.
portName
());
if
(
!
_linkSelectedOnce
&&
portInfo
.
vendorIdentifier
()
==
9900
)
{
// Pre-Select 3DR connection
_linkSelectedOnce
=
true
;
_linkCombo
->
setCurrentIndex
(
_linkCombo
->
findText
(
portInfo
.
portName
()));
}
}
if
(
!
userBaudChoice
)
{
int
index
=
baudcomboBox
->
findData
(
slink
->
getBaudRate
());
if
(
index
>=
0
)
baudcomboBox
->
setCurrentIndex
(
index
);
}
}
}
void
QGCToolBar
::
_linkConnected
(
void
)
void
QGCToolBar
::
_linkConnected
(
LinkInterface
*
link
)
{
_updateLinkState
(
true
);
Q_UNUSED
(
link
);
_updateConnectButton
();
}
void
QGCToolBar
::
_linkDisconnected
(
void
)
void
QGCToolBar
::
_linkDisconnected
(
LinkInterface
*
link
)
{
_updateLinkState
(
false
);
Q_UNUSED
(
link
);
_updateConnectButton
();
}
void
QGCToolBar
::
_update
LinkState
(
bool
connecte
d
)
void
QGCToolBar
::
_update
ConnectButton
(
voi
d
)
{
Q_UNUSED
(
connected
);
if
(
currentLink
&&
currentLink
->
isConnected
()
&&
portComboBox
->
isVisible
())
{
connectButton
->
setText
(
tr
(
"Disconnect"
));
connectButton
->
blockSignals
(
true
);
connectButton
->
setChecked
(
true
);
connectButton
->
blockSignals
(
false
);
toolBarPortAction
->
setVisible
(
false
);
toolBarBaudAction
->
setVisible
(
false
);
toolBarMessageAction
->
setVisible
(
true
);
toolBarWpAction
->
setVisible
(
true
);
QMenu
*
menu
=
new
QMenu
(
this
);
// If there are multiple connected links add/update the connect button menu
int
connectedCount
=
0
;
QList
<
LinkInterface
*>
links
=
_linkMgr
->
getLinks
();
foreach
(
LinkInterface
*
link
,
links
)
{
if
(
link
->
isConnected
())
{
connectedCount
++
;
QAction
*
action
=
menu
->
addAction
(
link
->
getName
());
action
->
setData
(
QVariant
::
fromValue
((
void
*
)
link
));
connect
(
action
,
&
QAction
::
triggered
,
this
,
&
QGCToolBar
::
_disconnectFromMenu
);
}
}
else
{
connectButton
->
setText
(
tr
(
"Connect"
));
connectButton
->
blockSignals
(
true
);
connectButton
->
setChecked
(
false
);
connectButton
->
blockSignals
(
false
);
toolBarPortAction
->
setVisible
(
true
);
toolBarBaudAction
->
setVisible
(
true
);
toolBarMessageAction
->
setVisible
(
false
);
toolBarWpAction
->
setVisible
(
false
);
// Remove old menu
QMenu
*
oldMenu
=
_connectButton
->
menu
();
_connectButton
->
setMenu
(
NULL
);
if
(
oldMenu
)
{
oldMenu
->
deleteLater
();
}
// Add new menu if needed
if
(
connectedCount
>
1
)
{
_connectButton
->
setMenu
(
menu
);
}
else
{
delete
menu
;
}
_linksConnected
=
connectedCount
!=
0
;
_connectButton
->
setText
(
_linksConnected
?
tr
(
"Disconnect"
)
:
tr
(
"Connect"
));
_linkComboAction
->
setVisible
(
!
_linksConnected
);
_baudComboAction
->
setVisible
(
!
_linksConnected
);
toolBarMessageAction
->
setVisible
(
_linksConnected
);
toolBarWpAction
->
setVisible
(
_linksConnected
);
}
void
QGCToolBar
::
connect
Link
(
bool
connectLink
)
void
QGCToolBar
::
_
connect
ButtonClicked
(
bool
checked
)
{
LinkManager
*
linkMgr
=
LinkManager
::
instance
();
Q_ASSERT
(
linkMgr
);
Q_UNUSED
(
checked
);
// No serial port yet present
if
(
connectLink
&&
linkMgr
->
getSerialLinks
().
count
()
==
0
)
{
MainWindow
::
instance
()
->
addLink
();
currentLink
=
linkMgr
->
getLinks
().
last
();
}
else
if
(
connectLink
)
{
SerialLink
*
link
=
qobject_cast
<
SerialLink
*>
(
currentLink
);
if
(
_linksConnected
)
{
// Disconnect
// Should be just one connected link, disconnect it
if
(
link
)
{
link
->
setPortName
(
portComboBox
->
itemData
(
portComboBox
->
currentIndex
()).
toString
().
trimmed
());
int
baud
=
baudcomboBox
->
currentText
().
toInt
();
link
->
setBaudRate
(
baud
);
connect
(
link
,
&
LinkInterface
::
connected
,
this
,
&
QGCToolBar
::
_linkConnected
);
linkMgr
->
connectLink
(
link
);
int
connectedCount
=
0
;
LinkInterface
*
connectedLink
=
NULL
;
QList
<
LinkInterface
*>
links
=
_linkMgr
->
getLinks
();
foreach
(
LinkInterface
*
link
,
links
)
{
if
(
link
->
isConnected
())
{
connectedCount
++
;
connectedLink
=
link
;
}
}
Q_ASSERT
(
connectedCount
==
1
);
Q_ASSERT
(
connectedLink
);
_linkMgr
->
disconnectLink
(
connectedLink
);
}
else
{
// Connect
QString
linkName
=
_linkCombo
->
currentText
();
if
(
linkName
==
"WiFi"
)
{
UDPLink
*
link
=
new
UDPLink
;
Q_CHECK_PTR
(
link
);
_linkMgr
->
addLink
(
link
);
CommConfigurationWindow
*
commDialog
=
new
CommConfigurationWindow
(
link
,
this
);
commDialog
->
exec
();
}
else
{
// Must be a serial port
SerialLink
*
link
=
new
SerialLink
(
linkName
,
_baudCombo
->
currentText
().
toInt
());
Q_CHECK_PTR
(
link
);
_linkMgr
->
addLink
(
link
);
_linkMgr
->
connectLink
(
link
);
}
}
else
if
(
!
connectLink
&&
currentLink
)
{
linkMgr
->
disconnectLink
(
currentLink
);
disconnect
(
currentLink
,
&
LinkInterface
::
connected
,
this
,
&
QGCToolBar
::
_linkConnected
);
}
if
(
currentLink
)
{
_updateLinkState
(
currentLink
->
isConnected
());
}
}
void
QGCToolBar
::
loadSettings
()
{
QSettings
settings
;
settings
.
beginGroup
(
"QGC_TOOLBAR"
);
settings
.
endGroup
();
}
void
QGCToolBar
::
storeSettings
()
void
QGCToolBar
::
_disconnectFromMenu
(
bool
checked
)
{
QSettings
settings
;
settings
.
beginGroup
(
"QGC_TOOLBAR"
);
settings
.
endGroup
();
Q_UNUSED
(
checked
);
QAction
*
action
=
qobject_cast
<
QAction
*>
(
sender
());
Q_ASSERT
(
action
);
LinkInterface
*
link
=
(
LinkInterface
*
)(
action
->
data
().
value
<
void
*>
());
Q_ASSERT
(
link
);
_linkMgr
->
disconnectLink
(
link
);
}
void
QGCToolBar
::
clearStatusString
()
...
...
@@ -816,7 +741,9 @@ void QGCToolBar::clearStatusString()
}
}
QGCToolBar
::
~
QGCToolBar
(
)
void
QGCToolBar
::
_linkComboActivated
(
int
index
)
{
storeSettings
();
Q_UNUSED
(
index
);
_linkSelectedOnce
=
true
;
}
src/ui/QGCToolBar.h
View file @
c81927fa
...
...
@@ -32,8 +32,10 @@ This file is part of the QGROUNDCONTROL project
#include
<QProgressBar>
#include
<QComboBox>
#include
<QTimer>
#include
"UASInterface.h"
#include
"SerialLink.h"
#include
"LinkManager.h"
class
QGCToolBar
:
public
QToolBar
{
...
...
@@ -43,15 +45,10 @@ public:
explicit
QGCToolBar
(
QWidget
*
parent
=
0
);
void
setPerspectiveChangeActions
(
const
QList
<
QAction
*>
&
action
);
void
setPerspectiveChangeAdvancedActions
(
const
QList
<
QAction
*>
&
action
);
~
QGCToolBar
();
public
slots
:
/** @brief Set the system that is currently displayed by this widget */
void
setActiveUAS
(
UASInterface
*
active
);
/** @brief Set the link which is currently handled with connecting / disconnecting */
void
addLink
(
LinkInterface
*
link
);
/** @brief Remove link which is currently handled */
void
removeLink
(
LinkInterface
*
link
);
/** @brief Set the system state */
void
updateState
(
UASInterface
*
system
,
QString
name
,
QString
description
);
/** @brief Set the system mode */
...
...
@@ -74,31 +71,12 @@ public slots:
void
updateView
();
/** @brief Update connection timeout time */
void
heartbeatTimeout
(
bool
timeout
,
unsigned
int
ms
);
/** @brief Update global position */
void
globalPositionChanged
(
UASInterface
*
uas
,
double
lat
,
double
lon
,
double
altAMSL
,
double
altWGS84
,
quint64
usec
);
/** @brief Create or connect link */
void
connectLink
(
bool
connect
);
/** @brief Clear status string */
void
clearStatusString
();
/** @brief Set an activity action as checked in menu */
void
advancedActivityTriggered
(
QAction
*
action
);
void
updateComboBox
();
/**
* @brief User selected baud rate
* @param index The current index of the combo box
*/
void
baudSelected
(
int
index
);
/**
* @brief User selected port
* @param index The current index of the combo box
*/
void
portSelected
(
int
index
);
protected:
void
storeSettings
();
void
loadSettings
();
void
createUI
();
void
resetToolbarUI
();
UASInterface
*
mav
;
...
...
@@ -107,8 +85,6 @@ protected:
QLabel
*
toolBarTimeoutLabel
;
QAction
*
toolBarTimeoutAction
;
///< Needed to set label (in)visible.
QAction
*
toolBarMessageAction
;
QAction
*
toolBarPortAction
;
QAction
*
toolBarBaudAction
;
QAction
*
toolBarWpAction
;
QAction
*
toolBarBatteryBarAction
;
QAction
*
toolBarBatteryVoltageAction
;
...
...
@@ -117,21 +93,14 @@ protected:
QLabel
*
toolBarStateLabel
;
QLabel
*
toolBarWpLabel
;
QLabel
*
toolBarMessageLabel
;
QPushButton
*
connectButton
;
QProgressBar
*
toolBarBatteryBar
;
QLabel
*
toolBarBatteryVoltageLabel
;
QComboBox
*
portComboBox
;
QComboBox
*
baudcomboBox
;
QTimer
portBoxTimer
;
bool
userBaudChoice
;
bool
userPortChoice
;
bool
changed
;
float
batteryPercent
;
float
batteryVoltage
;
int
wpId
;
double
wpDistance
;
float
altitudeMSL
;
float
altitudeRel
;
QString
state
;
QString
mode
;
...
...
@@ -146,12 +115,28 @@ protected:
QButtonGroup
*
group
;
private
slots
:
void
_linkConnected
(
void
);
void
_linkDisconnected
(
void
);
void
_linkConnected
(
LinkInterface
*
link
);
void
_linkDisconnected
(
LinkInterface
*
link
);
void
_disconnectFromMenu
(
bool
checked
);
void
_connectButtonClicked
(
bool
checked
);
void
_linkComboActivated
(
int
index
);
private:
/** @brief Update the link state */
void
_updateLinkState
(
bool
connected
);
void
_updateConnectButton
(
void
);
void
_updatePortList
(
void
);
LinkManager
*
_linkMgr
;
QComboBox
*
_linkCombo
;
QAction
*
_linkComboAction
;
bool
_linkSelectedOnce
;
QTimer
_portListTimer
;
QComboBox
*
_baudCombo
;
QAction
*
_baudComboAction
;
QPushButton
*
_connectButton
;
bool
_linksConnected
;
};
#endif // QGCTOOLBAR_H
src/ui/SettingsDialog.cc
View file @
c81927fa
...
...
@@ -76,15 +76,6 @@ _ui(new Ui::SettingsDialog)
connect
(
_ui
->
deleteSettings
,
&
QAbstractButton
::
toggled
,
this
,
&
SettingsDialog
::
_deleteSettingsToggled
);
// Custom mode
_ui
->
customModeComboBox
->
addItem
(
tr
(
"Default: Generic MAVLink and serial links"
),
MainWindow
::
CUSTOM_MODE_NONE
);
_ui
->
customModeComboBox
->
addItem
(
tr
(
"Wifi: Generic MAVLink, wifi or serial links"
),
MainWindow
::
CUSTOM_MODE_WIFI
);
_ui
->
customModeComboBox
->
addItem
(
tr
(
"PX4: Optimized for PX4 Autopilot Users"
),
MainWindow
::
CUSTOM_MODE_PX4
);
_ui
->
customModeComboBox
->
setCurrentIndex
(
_ui
->
customModeComboBox
->
findData
(
_mainWindow
->
getCustomMode
()));
connect
(
_ui
->
customModeComboBox
,
SIGNAL
(
currentIndexChanged
(
int
)),
this
,
SLOT
(
selectCustomMode
(
int
)));
// Application color style
_ui
->
styleChooser
->
setCurrentIndex
(
qgcApp
()
->
styleIsDark
()
?
0
:
1
);
...
...
@@ -107,11 +98,6 @@ void SettingsDialog::styleChanged(int index)
qgcApp
()
->
setStyle
(
index
==
0
);
}
void
SettingsDialog
::
selectCustomMode
(
int
mode
)
{
_mainWindow
->
setCustomMode
(
static_cast
<
enum
MainWindow
::
CUSTOM_MODE
>
(
_ui
->
customModeComboBox
->
itemData
(
mode
).
toInt
()));
}
void
SettingsDialog
::
_deleteSettingsToggled
(
bool
checked
)
{
if
(
checked
){
...
...
src/ui/SettingsDialog.h
View file @
c81927fa
...
...
@@ -40,11 +40,10 @@ public:
SettingsDialog
(
JoystickInput
*
joystick
,
QWidget
*
parent
=
0
,
Qt
::
WindowFlags
flags
=
Qt
::
Sheet
);
~
SettingsDialog
();
public
slots
:
public
slots
:
void
styleChanged
(
int
index
);
void
selectCustomMode
(
int
mode
);
private
slots
:
private
slots
:
void
_deleteSettingsToggled
(
bool
checked
);
void
_selectSavedFilesDirectory
(
void
);
void
_validateBeforeClose
(
void
);
...
...
src/ui/SettingsDialog.ui
View file @
c81927fa
This diff is collapsed.
Click to expand it.
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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