Browse Source

Refactoring comms code

QGC4.4
tstellanova 12 years ago
parent
commit
a4b6d92f37
  1. 154
      src/uas/QGCUASParamManager.cc
  2. 16
      src/uas/QGCUASParamManager.h
  3. 304
      src/ui/QGCParamWidget.cc
  4. 16
      src/ui/QGCParamWidget.h

154
src/uas/QGCUASParamManager.cc

@ -28,3 +28,157 @@ bool QGCUASParamManager::getParameterValue(int component, const QString& paramet
return paramDataModel->getOnboardParameterValue(component,parameter,value); return paramDataModel->getOnboardParameterValue(component,parameter,value);
} }
/**
* Send a request to deliver the list of onboard parameters
* to the MAV.
*/
void QGCUASParamManager::requestParameterList()
{
if (!mav) {
return;
}
paramDataModel->forgetAllOnboardParameters();
received.clear();
// Clear transmission state
transmissionListMode = true;
transmissionListSizeKnown.clear();
foreach (int key, transmissionMissingPackets.keys())
{
transmissionMissingPackets.value(key)->clear();
}
transmissionActive = true;
setParameterStatusMsg(tr("Requested param list.. waiting"));
mav->requestParameters();
}
/**
* Enabling the retransmission guard enables the parameter widget to track
* dropped parameters and to re-request them. This works for both individual
* parameter reads as well for whole list requests.
*
* @param enabled True if retransmission checking should be enabled, false else
*/
void QGCUASParamManager::setRetransmissionGuardEnabled(bool enabled)
{
if (enabled) {
retransmissionTimer.start(retransmissionTimeout);
} else {
retransmissionTimer.stop();
}
}
void QGCUASParamManager::setParameterStatusMsg(const QString& msg)
{
parameterStatusMsg = msg;
}
void QGCUASParamManager::retransmissionGuardTick()
{
if (transmissionActive) {
//qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS..";
// Check for timeout
// stop retransmission attempts on timeout
if (QGC::groundTimeMilliseconds() > transmissionTimeout) {
setRetransmissionGuardEnabled(false);
transmissionActive = false;
// Empty read retransmission list
// Empty write retransmission list
int missingReadCount = 0;
QList<int> readKeys = transmissionMissingPackets.keys();
foreach (int component, readKeys) {
missingReadCount += transmissionMissingPackets.value(component)->count();
transmissionMissingPackets.value(component)->clear();
}
// Empty write retransmission list
int missingWriteCount = 0;
QList<int> writeKeys = transmissionMissingWriteAckPackets.keys();
foreach (int component, writeKeys) {
missingWriteCount += transmissionMissingWriteAckPackets.value(component)->count();
transmissionMissingWriteAckPackets.value(component)->clear();
}
setParameterStatusMsg(tr("TIMEOUT! MISSING: %1 read, %2 write.").arg(missingReadCount).arg(missingWriteCount));
}
// Re-request at maximum retransmissionBurstRequestSize parameters at once
// to prevent link flooding
QMap<int, QMap<QString, QVariant>*>::iterator i;
QMap<int, QMap<QString, QVariant>*> onboardParams = paramDataModel->getOnboardParameters();
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
// Iterate through the parameters of the component
int component = i.key();
// Request n parameters from this component (at maximum)
QList<int> * paramList = transmissionMissingPackets.value(component, NULL);
if (paramList) {
int count = 0;
foreach (int id, *paramList) {
if (count < retransmissionBurstRequestSize) {
//qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << id << "FROM COMPONENT #" << component;
//TODO mavlink msg type for "request parameter set" ?
emit requestParameter(component, id);
setParameterStatusMsg(tr("Requested retransmission of #%1").arg(id+1));
count++;
} else {
break;
}
}
}
}
// Re-request at maximum retransmissionBurstRequestSize parameters at once
// to prevent write-request link flooding
// Empty write retransmission list
QList<int> writeKeys = transmissionMissingWriteAckPackets.keys();
foreach (int component, writeKeys) {
int count = 0;
QMap <QString, QVariant>* missingParams = transmissionMissingWriteAckPackets.value(component);
foreach (QString key, missingParams->keys()) {
if (count < retransmissionBurstRequestSize) {
// Re-request write operation
QVariant value = missingParams->value(key);
switch ((int)onboardParams.value(component)->value(key).type())
{
case QVariant::Int:
{
QVariant fixedValue(value.toInt());
emit parameterChanged(component, key, fixedValue);
}
break;
case QVariant::UInt:
{
QVariant fixedValue(value.toUInt());
emit parameterChanged(component, key, fixedValue);
}
break;
case QMetaType::Float:
{
QVariant fixedValue(value.toFloat());
emit parameterChanged(component, key, fixedValue);
}
break;
default:
//qCritical() << "ABORTED PARAM RETRANSMISSION, NO VALID QVARIANT TYPE";
return;
}
setParameterStatusMsg(tr("Requested rewrite of: %1: %2").arg(key).arg(missingParams->value(key).toDouble()));
count++;
} else {
break;
}
}
}
} else {
//qDebug() << __FILE__ << __LINE__ << "STOPPING RETRANSMISSION GUARD GRACEFULLY";
setRetransmissionGuardEnabled(false);
}
}

16
src/uas/QGCUASParamManager.h

@ -31,16 +31,29 @@ public:
/** @brief Request an update for this specific parameter */ /** @brief Request an update for this specific parameter */
virtual void requestParameterUpdate(int component, const QString& parameter) = 0; virtual void requestParameterUpdate(int component, const QString& parameter) = 0;
protected:
/** @brief Check for missing parameters */
virtual void retransmissionGuardTick();
/** @brief Activate / deactivate parameter retransmission */
virtual void setRetransmissionGuardEnabled(bool enabled);
//TODO decouple this UI message display further
virtual void setParameterStatusMsg(const QString& msg);
signals: signals:
void parameterChanged(int component, QString parameter, QVariant value); void parameterChanged(int component, QString parameter, QVariant value);
void parameterChanged(int component, int parameterIndex, QVariant value); void parameterChanged(int component, int parameterIndex, QVariant value);
void parameterListUpToDate(int component); void parameterListUpToDate(int component);
/** @brief Request a single parameter */
void requestParameter(int component, int parameter);
/** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
public slots: public slots:
/** @brief Write one parameter to the MAV */ /** @brief Write one parameter to the MAV */
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() = 0; virtual void requestParameterList();
protected: protected:
@ -60,6 +73,7 @@ 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
QString parameterStatusMsg;
}; };

304
src/ui/QGCParamWidget.cc

@ -87,7 +87,7 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
QPushButton* refreshButton = new QPushButton(tr("Get")); QPushButton* refreshButton = new QPushButton(tr("Get"));
refreshButton->setToolTip(tr("Load parameters currently in non-permanent memory of aircraft.")); refreshButton->setToolTip(tr("Load parameters currently in non-permanent memory of aircraft."));
refreshButton->setWhatsThis(tr("Load parameters currently in non-permanent memory of aircraft.")); refreshButton->setWhatsThis(tr("Load parameters currently in non-permanent memory of aircraft."));
connect(refreshButton, SIGNAL(clicked()), this, SLOT(requestParameterList())); connect(refreshButton, SIGNAL(clicked()), this, SLOT(requestParameterListUpdate()));
horizontalLayout->addWidget(refreshButton, 2, 0); horizontalLayout->addWidget(refreshButton, 2, 0);
QPushButton* setButton = new QPushButton(tr("Set")); QPushButton* setButton = new QPushButton(tr("Set"));
@ -150,8 +150,11 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick())); connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick()));
// Get parameters // Get parameters
if (uas) requestParameterList(); if (uas) {
requestParameterListUpdate();
} }
}
void QGCParamWidget::loadSettings() void QGCParamWidget::loadSettings()
{ {
@ -642,38 +645,7 @@ void QGCParamWidget::receivedParameterUpdate(int uas, int component, QString par
} }
/**
* Send a request to deliver the list of onboard parameters
* to the MAV.
*/
void QGCParamWidget::requestParameterList()
{
if (!mav) return;
// FIXME This call does not belong here
// Once the comm handling is moved to a new
// Param manager class the settings can be directly
// loaded from MAVLink protocol
loadSettings();
// End of FIXME
// Clear view and request param list
clear();
paramDataModel->forgetAllOnboardParameters();
received.clear();
// Clear transmission state
transmissionListMode = true;
transmissionListSizeKnown.clear();
foreach (int key, transmissionMissingPackets.keys())
{
transmissionMissingPackets.value(key)->clear();
}
transmissionActive = true;
// Set status text
statusLabel->setText(tr("Requested param list.. waiting"));
mav->requestParameters();
}
void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column) void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column)
{ {
@ -740,133 +712,122 @@ void QGCParamWidget::loadParametersFromFile()
} }
/** void QGCParamWidget::setParameterStatusMsg(const QString& msg)
* Enabling the retransmission guard enables the parameter widget to track
* dropped parameters and to re-request them. This works for both individual
* parameter reads as well for whole list requests.
*
* @param enabled True if retransmission checking should be enabled, false else
*/
void QGCParamWidget::setRetransmissionGuardEnabled(bool enabled)
{ {
if (enabled) { statusLabel->setText(msg);
retransmissionTimer.start(retransmissionTimeout);
} else {
retransmissionTimer.stop();
}
} }
void QGCParamWidget::retransmissionGuardTick()
{
if (transmissionActive) {
//qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS..";
// Check for timeout
// stop retransmission attempts on timeout
if (QGC::groundTimeMilliseconds() > transmissionTimeout) {
setRetransmissionGuardEnabled(false);
transmissionActive = false;
// Empty read retransmission list void QGCParamWidget::requestParameterListUpdate()
// Empty write retransmission list {
int missingReadCount = 0; if (!mav) {
QList<int> readKeys = transmissionMissingPackets.keys(); return;
foreach (int component, readKeys) {
missingReadCount += transmissionMissingPackets.value(component)->count();
transmissionMissingPackets.value(component)->clear();
} }
// Empty write retransmission list // FIXME This call does not belong here
int missingWriteCount = 0; // Once the comm handling is moved to a new
QList<int> writeKeys = transmissionMissingWriteAckPackets.keys(); // Param manager class the settings can be directly
foreach (int component, writeKeys) { // loaded from MAVLink protocol
missingWriteCount += transmissionMissingWriteAckPackets.value(component)->count(); loadSettings();
transmissionMissingWriteAckPackets.value(component)->clear(); // End of FIXME
// Clear view and request param list
clear();
requestParameterList();
} }
statusLabel->setText(tr("TIMEOUT! MISSING: %1 read, %2 write.").arg(missingReadCount).arg(missingWriteCount));
/**
* The .. signal is emitted
*/
void QGCParamWidget::requestParameterUpdate(int component, const QString& parameter)
{
if (mav) mav->requestParameter(component, parameter);
} }
// Re-request at maximum retransmissionBurstRequestSize parameters at once
// to prevent link flooding
/**
* Set all parameter in the parameter tree on the MAV
*/
void QGCParamWidget::setParameters()
{
// Iterate through all components, through all parameters and emit them
int parametersSent = 0;
QMap<int, QMap<QString, QVariant>*> changedValues = paramDataModel->getPendingParameters();
QMap<int, QMap<QString, QVariant>*>::iterator i; QMap<int, QMap<QString, QVariant>*>::iterator i;
QMap<int, QMap<QString, QVariant>*> onboardParams = paramDataModel->getOnboardParameters(); for (i = changedValues.begin(); i != changedValues.end(); ++i) {
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
// Iterate through the parameters of the component // Iterate through the parameters of the component
int component = i.key(); int compid = i.key();
// Request n parameters from this component (at maximum) QMap<QString, QVariant>* comp = i.value();
QList<int> * paramList = transmissionMissingPackets.value(component, NULL); {
if (paramList) { QMap<QString, QVariant>::iterator j;
int count = 0; for (j = comp->begin(); j != comp->end(); ++j) {
foreach (int id, *paramList) { setParameter(compid, j.key(), j.value());
if (count < retransmissionBurstRequestSize) { parametersSent++;
//qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << id << "FROM COMPONENT #" << component;
emit requestParameter(component, id);
statusLabel->setText(tr("Requested retransmission of #%1").arg(id+1));
count++;
} else {
break;
}
} }
} }
} }
// Re-request at maximum retransmissionBurstRequestSize parameters at once // Change transmission status if necessary
// to prevent write-request link flooding if (parametersSent == 0) {
// Empty write retransmission list statusLabel->setText(tr("No transmission: No changed values."));
QList<int> writeKeys = transmissionMissingWriteAckPackets.keys(); } else {
foreach (int component, writeKeys) { statusLabel->setText(tr("Transmitting %1 parameters.").arg(parametersSent));
int count = 0; // Set timeouts
QMap <QString, QVariant>* missingParams = transmissionMissingWriteAckPackets.value(component); if (transmissionActive)
foreach (QString key, missingParams->keys()) {
if (count < retransmissionBurstRequestSize) {
// Re-request write operation
QVariant value = missingParams->value(key);
switch ((int)onboardParams.value(component)->value(key).type())
{
case QVariant::Int:
{
QVariant fixedValue(value.toInt());
emit parameterChanged(component, key, fixedValue);
}
break;
case QVariant::UInt:
{ {
QVariant fixedValue(value.toUInt()); transmissionTimeout += parametersSent*rewriteTimeout;
emit parameterChanged(component, key, fixedValue);
} }
break; else
case QMetaType::Float:
{ {
QVariant fixedValue(value.toFloat()); transmissionActive = true;
emit parameterChanged(component, key, fixedValue); quint64 newTransmissionTimeout = QGC::groundTimeMilliseconds() + parametersSent*rewriteTimeout;
} if (newTransmissionTimeout > transmissionTimeout) {
break; transmissionTimeout = newTransmissionTimeout;
default:
//qCritical() << "ABORTED PARAM RETRANSMISSION, NO VALID QVARIANT TYPE";
return;
}
statusLabel->setText(tr("Requested rewrite of: %1: %2").arg(key).arg(missingParams->value(key).toDouble()));
count++;
} else {
break;
}
} }
} }
} else { // Enable guard
//qDebug() << __FILE__ << __LINE__ << "STOPPING RETRANSMISSION GUARD GRACEFULLY"; setRetransmissionGuardEnabled(true);
setRetransmissionGuardEnabled(false);
} }
} }
/** /**
* The .. signal is emitted * Write the current onboard parameters from RAM into
* permanent storage, e.g. EEPROM or harddisk
*/ */
void QGCParamWidget::requestParameterUpdate(int component, const QString& parameter) void QGCParamWidget::writeParameters()
{ {
if (mav) mav->requestParameter(component, parameter); int changedParamCount = 0;
QMap<int, QMap<QString, QVariant>*>::iterator i;
QMap<int, QMap<QString, QVariant>*> changedValues = paramDataModel->getPendingParameters();
for (i = changedValues.begin(); i != changedValues.end() , (0 == changedParamCount); ++i)
{
// Iterate through the parameters of the component
QMap<QString, QVariant>* comp = i.value();
QMap<QString, QVariant>::iterator j;
for (j = comp->begin(); j != comp->end(); ++j)
{
changedParamCount++;
break;//it only takes one changed param to warrant warning the user
}
} }
if (changedParamCount > 0)
{
QMessageBox msgBox;
msgBox.setText(tr("There are locally changed parameters. Please transmit them first (<TRANSMIT>) or update them with the onboard values (<REFRESH>) before storing onboard from RAM to ROM."));
msgBox.exec();
}
else
{
if (!mav) return;
mav->writeParametersToStorage();
}
}
/** /**
* @param component the subsystem which has the parameter * @param component the subsystem which has the parameter
@ -959,87 +920,6 @@ void QGCParamWidget::setParameter(int component, QString parameterName, QVariant
setRetransmissionGuardEnabled(true); setRetransmissionGuardEnabled(true);
} }
/**
* Set all parameter in the parameter tree on the MAV
*/
void QGCParamWidget::setParameters()
{
// Iterate through all components, through all parameters and emit them
int parametersSent = 0;
QMap<int, QMap<QString, QVariant>*> changedValues = paramDataModel->getPendingParameters();
QMap<int, QMap<QString, QVariant>*>::iterator i;
for (i = changedValues.begin(); i != changedValues.end(); ++i) {
// Iterate through the parameters of the component
int compid = i.key();
QMap<QString, QVariant>* comp = i.value();
{
QMap<QString, QVariant>::iterator j;
for (j = comp->begin(); j != comp->end(); ++j) {
setParameter(compid, j.key(), j.value());
parametersSent++;
}
}
}
// Change transmission status if necessary
if (parametersSent == 0) {
statusLabel->setText(tr("No transmission: No changed values."));
} else {
statusLabel->setText(tr("Transmitting %1 parameters.").arg(parametersSent));
// Set timeouts
if (transmissionActive)
{
transmissionTimeout += parametersSent*rewriteTimeout;
}
else
{
transmissionActive = true;
quint64 newTransmissionTimeout = QGC::groundTimeMilliseconds() + parametersSent*rewriteTimeout;
if (newTransmissionTimeout > transmissionTimeout) {
transmissionTimeout = newTransmissionTimeout;
}
}
// Enable guard
setRetransmissionGuardEnabled(true);
}
}
/**
* Write the current onboard parameters from RAM into
* permanent storage, e.g. EEPROM or harddisk
*/
void QGCParamWidget::writeParameters()
{
int changedParamCount = 0;
QMap<int, QMap<QString, QVariant>*>::iterator i;
QMap<int, QMap<QString, QVariant>*> changedValues = paramDataModel->getPendingParameters();
for (i = changedValues.begin(); i != changedValues.end() , (0 == changedParamCount); ++i)
{
// Iterate through the parameters of the component
QMap<QString, QVariant>* comp = i.value();
QMap<QString, QVariant>::iterator j;
for (j = comp->begin(); j != comp->end(); ++j)
{
changedParamCount++;
break;//it only takes one changed param to warrant warning the user
}
}
if (changedParamCount > 0)
{
QMessageBox msgBox;
msgBox.setText(tr("There are locally changed parameters. Please transmit them first (<TRANSMIT>) or update them with the onboard values (<REFRESH>) before storing onboard from RAM to ROM."));
msgBox.exec();
}
else
{
if (!mav) return;
mav->writeParametersToStorage();
}
}
void QGCParamWidget::readParameters() void QGCParamWidget::readParameters()
{ {
if (!mav) return; if (!mav) return;

16
src/ui/QGCParamWidget.h

@ -60,13 +60,13 @@ public:
QString getParamInfo(const QString& param) { return paramToolTips.value(param, ""); } QString getParamInfo(const QString& param) { return paramToolTips.value(param, ""); }
void setParamInfo(const QMap<QString,QString>& paramInfo); void setParamInfo(const QMap<QString,QString>& paramInfo);
protected:
virtual void setParameterStatusMsg(const QString& msg);
signals: signals:
/** @brief A parameter was changed in the widget, NOT onboard */ /** @brief A parameter was changed in the widget, NOT onboard */
//void parameterChanged(int component, QString parametername, float value); // defined in QGCUASParamManager already //void parameterChanged(int component, QString parametername, float value); // defined in QGCUASParamManager already
/** @brief Request a single parameter */
void requestParameter(int component, int parameter);
/** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
public slots: public slots:
/** @brief Add a component to the list */ /** @brief Add a component to the list */
void addComponent(int uas, int component, QString componentName); void addComponent(int uas, int component, QString componentName);
@ -75,7 +75,7 @@ public slots:
/** @brief Add a parameter to the list */ /** @brief Add a parameter to the list */
void receivedParameterUpdate(int uas, int component, QString parameterName, QVariant value); void receivedParameterUpdate(int uas, int component, QString parameterName, QVariant value);
/** @brief Request list of parameters from MAV */ /** @brief Request list of parameters from MAV */
void requestParameterList(); void requestParameterListUpdate();
/** @brief Request one single parameter */ /** @brief Request one single parameter */
void requestParameterUpdate(int component, const QString& parameter); void requestParameterUpdate(int component, const QString& parameter);
/** @brief Set one parameter, changes value in RAM of MAV */ /** @brief Set one parameter, changes value in RAM of MAV */
@ -96,8 +96,7 @@ public slots:
/** @brief Load parameters from a file */ /** @brief Load parameters from a file */
void loadParametersFromFile(); void loadParametersFromFile();
/** @brief Check for missing parameters */
void retransmissionGuardTick();
protected: protected:
QTreeWidget* tree; ///< The parameter tree QTreeWidget* tree; ///< The parameter tree
@ -112,8 +111,7 @@ protected:
QMap<QString, double> paramDefault; ///< Default param values QMap<QString, double> paramDefault; ///< Default param values
QMap<QString, double> paramMax; ///< Minimum param values QMap<QString, double> paramMax; ///< Minimum param values
/** @brief Activate / deactivate parameter retransmission */
void setRetransmissionGuardEnabled(bool enabled);
/** @brief Load settings */ /** @brief Load settings */
void loadSettings(); void loadSettings();
/** @brief Load meta information from CSV */ /** @brief Load meta information from CSV */

Loading…
Cancel
Save