Commit d74a19ce authored by Don Gagne's avatar Don Gagne

Don't request parameter list unless user requested

Also only update the full tree one time once the full parameter list is
ready.
parent 2c0d56c7
...@@ -40,8 +40,6 @@ void QGCBaseParamWidget::setUAS(UASInterface* uas) ...@@ -40,8 +40,6 @@ void QGCBaseParamWidget::setUAS(UASInterface* uas)
connectToParamManager(); connectToParamManager();
connectViewSignalsAndSlots(); connectViewSignalsAndSlots();
layoutWidget(); layoutWidget();
paramMgr->requestParameterListIfEmpty();
} }
} }
...@@ -62,6 +60,9 @@ void QGCBaseParamWidget::connectToParamManager() ...@@ -62,6 +60,9 @@ void QGCBaseParamWidget::connectToParamManager()
// Listen for param list reload finished // Listen for param list reload finished
connect(paramMgr, SIGNAL(parameterListUpToDate()), connect(paramMgr, SIGNAL(parameterListUpToDate()),
this, SLOT(handleOnboardParameterListUpToDate())); this, SLOT(handleOnboardParameterListUpToDate()));
if (paramMgr->parametersReady()) {
handleOnboardParameterListUpToDate();
}
// Listen to communications status messages so we can display them // Listen to communications status messages so we can display them
connect(paramMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)), connect(paramMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)),
......
...@@ -51,7 +51,8 @@ QGCParamWidget::QGCParamWidget(QWidget *parent) : ...@@ -51,7 +51,8 @@ QGCParamWidget::QGCParamWidget(QWidget *parent) :
QGCBaseParamWidget(parent), QGCBaseParamWidget(parent),
componentItems(new QMap<int, QTreeWidgetItem*>()), componentItems(new QMap<int, QTreeWidgetItem*>()),
statusLabel(new QLabel(this)), statusLabel(new QLabel(this)),
tree(new QTreeWidget(this)) tree(new QTreeWidget(this)),
_fullParamListLoaded(false)
{ {
...@@ -236,9 +237,15 @@ void QGCParamWidget::handleOnboardParamUpdate(int compId, const QString& paramNa ...@@ -236,9 +237,15 @@ void QGCParamWidget::handleOnboardParamUpdate(int compId, const QString& paramNa
void QGCParamWidget::handleOnboardParameterListUpToDate() void QGCParamWidget::handleOnboardParameterListUpToDate()
{ {
// Don't load full param list more than once
if (_fullParamListLoaded) {
return;
}
_fullParamListLoaded = true;
//turn off updates while we refresh the entire list //turn off updates while we refresh the entire list
tree->setUpdatesEnabled(false); tree->setUpdatesEnabled(false);
qDebug() << "WARN: LIST UPDATE";
//rewrite the component item tree after receiving the full list //rewrite the component item tree after receiving the full list
QMap<int, QMap<QString, QVariant>*>::iterator i; QMap<int, QMap<QString, QVariant>*>::iterator i;
......
...@@ -104,7 +104,9 @@ protected: ...@@ -104,7 +104,9 @@ protected:
QLabel* statusLabel; ///< User-facing parameter status label QLabel* statusLabel; ///< User-facing parameter status label
QTreeWidget* tree; ///< The parameter tree QTreeWidget* tree; ///< The parameter tree
QStringList _filterList; QStringList _filterList;
private:
bool _fullParamListLoaded;
}; };
#endif // QGCPARAMWIDGET_H #endif // QGCPARAMWIDGET_H
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