Commit 9bcd3ed3 authored by tstellanova's avatar tstellanova

debugging retransmission of read param list

parent 31855837
...@@ -49,8 +49,7 @@ void QGCUASParamManager::requestParameterList() ...@@ -49,8 +49,7 @@ void QGCUASParamManager::requestParameterList()
transmissionListSizeKnown.clear(); transmissionListSizeKnown.clear();
transmissionListMode = true; transmissionListMode = true;
foreach (int key, transmissionMissingPackets.keys()) foreach (int key, transmissionMissingPackets.keys()) {
{
transmissionMissingPackets.value(key)->clear(); transmissionMissingPackets.value(key)->clear();
} }
transmissionActive = true; transmissionActive = true;
...@@ -70,6 +69,8 @@ void QGCUASParamManager::requestParameterList() ...@@ -70,6 +69,8 @@ void QGCUASParamManager::requestParameterList()
*/ */
void QGCUASParamManager::setRetransmissionGuardEnabled(bool enabled) void QGCUASParamManager::setRetransmissionGuardEnabled(bool enabled)
{ {
qDebug() << "setRetransmissionGuardEnabled: " << enabled;
if (enabled) { if (enabled) {
retransmissionTimer.start(retransmissionTimeout); retransmissionTimer.start(retransmissionTimeout);
} else { } else {
...@@ -79,6 +80,7 @@ void QGCUASParamManager::setRetransmissionGuardEnabled(bool enabled) ...@@ -79,6 +80,7 @@ void QGCUASParamManager::setRetransmissionGuardEnabled(bool enabled)
void QGCUASParamManager::setParameterStatusMsg(const QString& msg) void QGCUASParamManager::setParameterStatusMsg(const QString& msg)
{ {
qDebug() << "parameterStatusMsg: " << msg;
parameterStatusMsg = msg; parameterStatusMsg = msg;
} }
......
...@@ -26,8 +26,6 @@ public: ...@@ -26,8 +26,6 @@ public:
virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs); virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs);
protected: protected:
/** @brief Check for missing parameters */
virtual void retransmissionGuardTick();
/** @brief Activate / deactivate parameter retransmission */ /** @brief Activate / deactivate parameter retransmission */
virtual void setRetransmissionGuardEnabled(bool enabled); virtual void setRetransmissionGuardEnabled(bool enabled);
...@@ -48,6 +46,8 @@ public slots: ...@@ -48,6 +46,8 @@ public slots:
virtual void setParameter(int component, QString parameterName, QVariant value) = 0; virtual void setParameter(int component, QString parameterName, QVariant value) = 0;
/** @brief Request list of parameters from MAV */ /** @brief Request list of parameters from MAV */
virtual void requestParameterList(); virtual void requestParameterList();
/** @brief Check for missing parameters */
virtual void retransmissionGuardTick();
protected: protected:
...@@ -67,6 +67,8 @@ protected: ...@@ -67,6 +67,8 @@ protected:
int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds int retransmissionTimeout; ///< Retransmission request timeout, in milliseconds
int rewriteTimeout; ///< Write request timeout, in milliseconds int rewriteTimeout; ///< Write request timeout, in milliseconds
int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst int retransmissionBurstRequestSize; ///< Number of packets requested for retransmission per burst
// Status
QString parameterStatusMsg; QString parameterStatusMsg;
}; };
......
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