Commit e5c72b63 authored by Lorenz Meier's avatar Lorenz Meier

MAVLink protocol: Change QTimer API

parent 734a145c
......@@ -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 */
......
......@@ -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
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment