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
e5c72b63
Commit
e5c72b63
authored
May 19, 2014
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
MAVLink protocol: Change QTimer API
parent
734a145c
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
5 additions
and
5 deletions
+5
-5
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+4
-4
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+1
-1
No files found.
src/comm/MAVLinkProtocol.cc
View file @
e5c72b63
...
...
@@ -44,7 +44,7 @@ Q_DECLARE_METATYPE(mavlink_message_t)
* the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
*/
MAVLinkProtocol
::
MAVLinkProtocol
()
:
heartbeatTimer
(
new
QTimer
(
this
)
),
heartbeatTimer
(),
heartbeatRate
(
MAVLINK_HEARTBEAT_DEFAULT_RATE
),
m_heartbeatsEnabled
(
true
),
m_multiplexingEnabled
(
false
),
...
...
@@ -66,8 +66,8 @@ MAVLinkProtocol::MAVLinkProtocol() :
loadSettings
();
moveToThread
(
this
);
// Start heartbeat timer, emitting a heartbeat at the configured rate
connect
(
heartbeatTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
sendHeartbeat
()));
heartbeatTimer
->
start
(
1000
/
heartbeatRate
);
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().
...
...
@@ -781,7 +781,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 @
e5c72b63
...
...
@@ -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
...
...
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