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
faab2eb2
Commit
faab2eb2
authored
May 24, 2014
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
threading fixes, still wip in some aspects
parent
ebdd072e
Changes
11
Hide whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
71 additions
and
35 deletions
+71
-35
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+21
-9
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+3
-1
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+7
-3
QGCXPlaneLink.h
src/comm/QGCXPlaneLink.h
+1
-0
configuration.h
src/configuration.h
+1
-1
QGCMAVLinkUASFactory.cc
src/uas/QGCMAVLinkUASFactory.cc
+4
-11
QGCUASWorker.cc
src/uas/QGCUASWorker.cc
+14
-2
QGCUASWorker.h
src/uas/QGCUASWorker.h
+5
-0
UAS.cc
src/uas/UAS.cc
+11
-6
UAS.h
src/uas/UAS.h
+2
-1
QGCHilXPlaneConfiguration.cc
src/ui/QGCHilXPlaneConfiguration.cc
+2
-1
No files found.
src/comm/MAVLinkProtocol.cc
View file @
faab2eb2
...
...
@@ -44,7 +44,7 @@ Q_DECLARE_METATYPE(mavlink_message_t)
* the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
*/
MAVLinkProtocol
::
MAVLinkProtocol
()
:
heartbeatTimer
(),
heartbeatTimer
(
NULL
),
heartbeatRate
(
MAVLINK_HEARTBEAT_DEFAULT_RATE
),
m_heartbeatsEnabled
(
true
),
m_multiplexingEnabled
(
false
),
...
...
@@ -58,17 +58,14 @@ MAVLinkProtocol::MAVLinkProtocol() :
m_actionGuardEnabled
(
false
),
m_actionRetransmissionTimeout
(
100
),
versionMismatchIgnore
(
false
),
systemId
(
QGC
::
defaultSystemId
)
systemId
(
QGC
::
defaultSystemId
),
_should_exit
(
false
)
{
qRegisterMetaType
<
mavlink_message_t
>
(
"mavlink_message_t"
);
m_authKey
=
"xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx"
;
loadSettings
();
moveToThread
(
this
);
heartbeatTimer
.
moveToThread
(
this
);
// Start heartbeat timer, emitting a heartbeat at the configured rate
connect
(
&
heartbeatTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
sendHeartbeat
()));
heartbeatTimer
.
start
(
1000
/
heartbeatRate
);
// All the *Counter variables are not initialized here, as they should be initialized
// on a per-link basis before those links are used. @see resetMetadataForLink().
...
...
@@ -171,7 +168,7 @@ MAVLinkProtocol::~MAVLinkProtocol()
}
// Tell the thread to exit
quit
()
;
_should_exit
=
true
;
// Wait for it to exit
wait
();
}
...
...
@@ -182,7 +179,22 @@ MAVLinkProtocol::~MAVLinkProtocol()
**/
void
MAVLinkProtocol
::
run
()
{
exec
();
heartbeatTimer
=
new
QTimer
();
heartbeatTimer
->
moveToThread
(
this
);
// Start heartbeat timer, emitting a heartbeat at the configured rate
connect
(
heartbeatTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
sendHeartbeat
()));
heartbeatTimer
->
start
(
1000
/
heartbeatRate
);
while
(
!
_should_exit
)
{
if
(
isFinished
())
{
qDebug
()
<<
"MAVLINK WORKER DONE!"
;
return
;
}
QCoreApplication
::
processEvents
();
QGC
::
SLEEP
::
msleep
(
2
);
}
}
QString
MAVLinkProtocol
::
getLogfileName
()
...
...
@@ -782,7 +794,7 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled)
void
MAVLinkProtocol
::
setHeartbeatRate
(
int
rate
)
{
heartbeatRate
=
rate
;
heartbeatTimer
.
setInterval
(
1000
/
heartbeatRate
);
heartbeatTimer
->
setInterval
(
1000
/
heartbeatRate
);
}
/** @return heartbeat rate in Hertz */
...
...
src/comm/MAVLinkProtocol.h
View file @
faab2eb2
...
...
@@ -214,7 +214,7 @@ public slots:
void
storeSettings
();
protected:
QTimer
heartbeatTimer
;
///< Timer to emit heartbeats
QTimer
*
heartbeatTimer
;
///< Timer to emit heartbeats
int
heartbeatRate
;
///< Heartbeat rate, controls the timer interval
bool
m_heartbeatsEnabled
;
///< Enabled/disable heartbeat emission
bool
m_multiplexingEnabled
;
///< Enable/disable packet multiplexing
...
...
@@ -237,6 +237,8 @@ protected:
int
currLossCounter
[
MAVLINK_COMM_NUM_BUFFERS
];
///< Lost messages during this sample time window. Used for calculating loss %.
bool
versionMismatchIgnore
;
int
systemId
;
bool
_should_exit
;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
mavlink
::
ProtobufManager
protobufManager
;
#endif
...
...
src/comm/QGCXPlaneLink.cc
View file @
faab2eb2
...
...
@@ -57,7 +57,8 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress
simUpdateLastText
(
QGC
::
groundTimeMilliseconds
()),
simUpdateLastGroundTruth
(
QGC
::
groundTimeMilliseconds
()),
simUpdateHz
(
0
),
_sensorHilEnabled
(
true
)
_sensorHilEnabled
(
true
),
_should_exit
(
false
)
{
// We're doing it wrong - because the Qt folks got the API wrong:
// http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
...
...
@@ -75,7 +76,7 @@ QGCXPlaneLink::~QGCXPlaneLink()
{
storeSettings
();
// Tell the thread to exit
quit
()
;
_should_exit
=
true
;
// Wait for it to exit
wait
();
...
...
@@ -216,7 +217,10 @@ void QGCXPlaneLink::run()
writeBytes
((
const
char
*
)
&
ip
,
sizeof
(
ip
));
exec
();
while
(
!
_should_exit
)
{
QCoreApplication
::
processEvents
();
QGC
::
SLEEP
::
msleep
(
5
);
}
}
void
QGCXPlaneLink
::
setPort
(
int
localPort
)
...
...
src/comm/QGCXPlaneLink.h
View file @
faab2eb2
...
...
@@ -210,6 +210,7 @@ protected:
quint64
simUpdateLastGroundTruth
;
float
simUpdateHz
;
bool
_sensorHilEnabled
;
bool
_should_exit
;
void
setName
(
QString
name
);
};
...
...
src/configuration.h
View file @
faab2eb2
...
...
@@ -4,7 +4,7 @@
#include <QString>
/** @brief Polling interval in ms */
#define SERIAL_POLL_INTERVAL
5
#define SERIAL_POLL_INTERVAL
4
/** @brief Heartbeat emission rate, in Hertz (times per second) */
#define MAVLINK_HEARTBEAT_DEFAULT_RATE 1
...
...
src/uas/QGCMAVLinkUASFactory.cc
View file @
faab2eb2
...
...
@@ -32,8 +32,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav
->
setSystemType
((
int
)
heartbeat
->
type
);
mav
->
moveToThread
(
worker
);
// Connect this robot to the UAS object
connect
(
mavlink
,
SIGNAL
(
messageReceived
(
LinkInterface
*
,
mavlink_message_t
)),
mav
,
SLOT
(
receiveMessage
(
LinkInterface
*
,
mavlink_message_t
)));
#ifdef QGC_PROTOBUF_ENABLED
...
...
@@ -48,8 +46,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav
->
setSystemType
((
int
)
heartbeat
->
type
);
mav
->
moveToThread
(
worker
);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
...
...
@@ -67,8 +63,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav
->
setSystemType
((
int
)
heartbeat
->
type
);
mav
->
moveToThread
(
worker
);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
...
...
@@ -83,8 +77,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Set the system type
mav
->
setSystemType
((
int
)
heartbeat
->
type
);
mav
->
moveToThread
(
worker
);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
...
...
@@ -121,6 +113,10 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
break
;
}
// Get the UAS ready
worker
->
start
(
QThread
::
HighPriority
);
connect
(
uas
,
SIGNAL
(
destroyed
()),
worker
,
SLOT
(
quit
()));
// Set the autopilot type
uas
->
setAutopilotType
((
int
)
heartbeat
->
autopilot
);
...
...
@@ -130,8 +126,5 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Now add UAS to "official" list, which makes the whole application aware of it
UASManager
::
instance
()
->
addUAS
(
uas
);
worker
->
start
(
QThread
::
HighPriority
);
connect
(
uas
,
SIGNAL
(
destroyed
()),
worker
,
SLOT
(
quit
()));
return
uas
;
}
src/uas/QGCUASWorker.cc
View file @
faab2eb2
#include "QGCUASWorker.h"
#include <QGC.h>
#include <QCoreApplication>
#include <QDebug>
QGCUASWorker
::
QGCUASWorker
()
:
QThread
()
QGCUASWorker
::
QGCUASWorker
()
:
QThread
(),
_should_exit
(
false
)
{
}
void
QGCUASWorker
::
quit
()
{
_should_exit
=
true
;
}
void
QGCUASWorker
::
run
()
{
QGC
::
SLEEP
::
msleep
(
100
);
while
(
!
_should_exit
)
{
QCoreApplication
::
processEvents
();
QGC
::
SLEEP
::
msleep
(
2
);
}
}
src/uas/QGCUASWorker.h
View file @
faab2eb2
...
...
@@ -8,8 +8,13 @@ class QGCUASWorker : public QThread
public:
QGCUASWorker
();
public
slots
:
void
quit
();
protected:
void
run
();
bool
_should_exit
;
};
#endif // QGCUASWORKER_H
src/uas/UAS.cc
View file @
faab2eb2
...
...
@@ -51,7 +51,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
commStatus
(
COMM_DISCONNECTED
),
receiveDropRate
(
0
),
sendDropRate
(
0
),
statusTimeout
(
new
QTimer
()
),
statusTimeout
(
thread
),
name
(
""
),
type
(
MAV_TYPE_GENERIC
),
...
...
@@ -164,12 +164,13 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
hilEnabled
(
false
),
sensorHil
(
false
),
lastSendTimeGPS
(
0
),
lastSendTimeSensors
(
0
)
lastSendTimeSensors
(
0
),
_thread
(
thread
)
{
moveToThread
(
thread
);
waypointManager
.
moveToThread
(
thread
);
paramMgr
.
moveToThread
(
thread
);
statusTimeout
->
moveToThread
(
thread
);
statusTimeout
.
moveToThread
(
thread
);
for
(
unsigned
int
i
=
0
;
i
<
255
;
++
i
)
{
...
...
@@ -237,9 +238,9 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
color
=
UASInterface
::
getNextColor
();
setBatterySpecs
(
QString
(
""
));
connect
(
statusTimeout
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
updateState
()));
connect
(
&
statusTimeout
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
updateState
()));
connect
(
this
,
SIGNAL
(
systemSpecsChanged
(
int
)),
this
,
SLOT
(
writeSettings
()));
statusTimeout
->
start
(
500
);
statusTimeout
.
start
(
500
);
readSettings
();
//need to init paramMgr after readSettings have been loaded, to properly set autopilot and so forth
paramMgr
.
initWithUAS
(
this
);
...
...
@@ -255,8 +256,11 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
UAS
::~
UAS
()
{
writeSettings
();
_thread
->
quit
();
_thread
->
wait
();
delete
links
;
delete
statusTimeout
;
delete
simulation
;
}
...
...
@@ -369,6 +373,7 @@ void UAS::updateState()
GAudioOutput
::
instance
()
->
notifyNegative
();
}
}
qDebug
()
<<
"UPDATE STATE:"
<<
(
heartbeatInterval
/
1000
)
<<
"milliseconds, LOST:"
<<
connectionLost
;
}
/**
...
...
src/uas/UAS.h
View file @
faab2eb2
...
...
@@ -382,7 +382,7 @@ protected: //COMMENTS FOR TEST UNIT
float
receiveDropRate
;
///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
float
sendDropRate
;
///< Percentage of packets that were not received from the MAV by the GCS
quint64
lastHeartbeat
;
///< Time of the last heartbeat message
QTimer
*
statusTimeout
;
///< Timer for various status timeouts
QTimer
statusTimeout
;
///< Timer for various status timeouts
/// BASIC UAS TYPE, NAME AND STATE
QString
name
;
///< Human-friendly name of the vehicle, e.g. bravo
...
...
@@ -526,6 +526,7 @@ protected: //COMMENTS FOR TEST UNIT
/// SIMULATION
QGCHilLink
*
simulation
;
///< Hardware in the loop simulation link
QThread
*
_thread
;
public:
/** @brief Set the current battery type */
...
...
src/ui/QGCHilXPlaneConfiguration.cc
View file @
faab2eb2
...
...
@@ -25,8 +25,9 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *
{
// connect(ui->randomAttitudeButton, SIGNAL(clicked()), link, SLOT(setRandomAttitude()));
// connect(ui->randomPositionButton, SIGNAL(clicked()), link, SLOT(setRandomPosition()));
connect
(
ui
->
airframeComboBox
,
SIGNAL
(
activated
(
QString
)),
link
,
SLOT
(
selectAirframe
(
QString
)));
ui
->
airframeComboBox
->
setCurrentIndex
(
link
->
getAirFrameIndex
());
connect
(
ui
->
airframeComboBox
,
SIGNAL
(
activated
(
QString
)),
link
,
SLOT
(
selectAirframe
(
QString
)));
// XXX not implemented yet
ui
->
airframeComboBox
->
hide
();
ui
->
sensorHilCheckBox
->
setChecked
(
xplane
->
sensorHilEnabled
());
...
...
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