From 0757b49e899e9d5c904e5695c1b7d71bfe97a3fd Mon Sep 17 00:00:00 2001 From: tstellanova Date: Tue, 6 Aug 2013 13:02:28 -0700 Subject: [PATCH] debug multiple parameter widgets creation --- src/uas/QGCUASParamManager.cc | 13 ++----------- src/uas/QGCUASParamManager.h | 2 -- src/uas/UAS.cc | 2 +- src/ui/ParameterInterface.cc | 12 +++++++++++- src/ui/QGCParamWidget.cc | 25 +++++++++++++++---------- src/ui/QGCParamWidget.h | 4 ++-- 6 files changed, 31 insertions(+), 27 deletions(-) diff --git a/src/uas/QGCUASParamManager.cc b/src/uas/QGCUASParamManager.cc index 3e6107731..532efe813 100644 --- a/src/uas/QGCUASParamManager.cc +++ b/src/uas/QGCUASParamManager.cc @@ -16,22 +16,13 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) : } -/** - * The .. signal is emitted - */ -void QGCUASParamManager::requestParameterListUpdate(int component) -{ - Q_UNUSED(component); -} + bool QGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const { return paramDataModel->getOnboardParameterValue(component,parameter,value); } - - - /** * Send a request to deliver the list of onboard parameters * to the MAV. @@ -69,7 +60,7 @@ void QGCUASParamManager::requestParameterList() */ void QGCUASParamManager::setRetransmissionGuardEnabled(bool enabled) { - qDebug() << "setRetransmissionGuardEnabled: " << enabled; +// qDebug() << "setRetransmissionGuardEnabled: " << enabled; if (enabled) { retransmissionTimer.start(retransmissionTimeout); diff --git a/src/uas/QGCUASParamManager.h b/src/uas/QGCUASParamManager.h index 6e3927b08..3607552df 100644 --- a/src/uas/QGCUASParamManager.h +++ b/src/uas/QGCUASParamManager.h @@ -17,8 +17,6 @@ public: virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const; - /** @brief Request an update for the parameter list */ - void requestParameterListUpdate(int component = 0); /** @brief Request an update for this specific parameter */ virtual void requestParameterUpdate(int component, const QString& parameter) = 0; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 597472af5..3e34dd48a 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1995,7 +1995,7 @@ void UAS::sendMessage(mavlink_message_t message) if (LinkManager::instance()->getLinks().contains(link)) { sendMessage(link, message); - qDebug() << "SENT MESSAGE!"; + qDebug() << "SENT MESSAGE id" << message.msgid; } else { diff --git a/src/ui/ParameterInterface.cc b/src/ui/ParameterInterface.cc index e387a2093..8ad4a450c 100644 --- a/src/ui/ParameterInterface.cc +++ b/src/ui/ParameterInterface.cc @@ -89,8 +89,18 @@ void ParameterInterface::selectUAS(int index) */ void ParameterInterface::addUAS(UASInterface* uas) { + int uasId = uas->getUASID(); + if (paramWidgets->contains(uasId) ) { + qDebug() << "Already have QGCParamWidget for: " << uasId ; + return; + } + QGCParamWidget* param = new QGCParamWidget(uas, this); - paramWidgets->insert(uas->getUASID(), param); + QString ptrStr; + ptrStr.sprintf("%8p", param); + qDebug() << "Created QGCParamWidget " << ptrStr << "for UAS id: " << uasId << " count: " << paramWidgets->count(); + + paramWidgets->insert(uasId, param); m_ui->stackedWidget->addWidget(param); QGCSensorSettingsWidget* sensor = NULL; diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index 7b6f33301..b26348be6 100644 --- a/src/ui/QGCParamWidget.cc +++ b/src/ui/QGCParamWidget.cc @@ -87,7 +87,7 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : QPushButton* refreshButton = new QPushButton(tr("Get")); refreshButton->setToolTip(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(requestParameterListUpdate())); + connect(refreshButton, SIGNAL(clicked()), this, SLOT(requestAllParamsUpdate())); horizontalLayout->addWidget(refreshButton, 2, 0); QPushButton* setButton = new QPushButton(tr("Set")); @@ -151,7 +151,7 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : // Get parameters if (uas) { - requestParameterListUpdate(); + requestAllParamsUpdate(); } } @@ -245,7 +245,8 @@ void QGCParamWidget::addComponent(int uas, int component, QString componentName) */ void QGCParamWidget::receivedParameterUpdate(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value) { - receivedParameterUpdate(uas, component, parameterName, value); + + updateParameterDisplay(uas, component, parameterName, value); // Missing packets list has to be instantiated for all components if (!transmissionMissingPackets.contains(component)) { @@ -390,10 +391,15 @@ void QGCParamWidget::receivedParameterUpdate(int uas, int component, int paramCo * @param component id of the component * @param parameterName human friendly name of the parameter */ -void QGCParamWidget::receivedParameterUpdate(int uas, int component, QString parameterName, QVariant value) +void QGCParamWidget::updateParameterDisplay(int uas, int component, QString parameterName, QVariant value) { - qDebug() << "PARAM WIDGET GOT PARAM:" << parameterName; Q_UNUSED(uas); + + + QString ptrStr; + ptrStr.sprintf("%8p", this); + qDebug() << "QGCParamWidget " << ptrStr << " got param" << parameterName; + // Reference to item in tree QTreeWidgetItem* parameterItem = NULL; @@ -417,9 +423,8 @@ void QGCParamWidget::receivedParameterUpdate(int uas, int component, QString par addComponent(uas, component, componentName); } - // Replace value in map - - paramDataModel->setOnboardParameter(component,parameterName,value); + // Replace value in data model + paramDataModel->handleParameterUpdate(component,parameterName,value); QString splitToken = "_"; @@ -564,7 +569,7 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column) current->setBackground(1, QBrush(QColor(QGC::colorOrange))); //TODO this seems incorrect-- we're pre-updating the onboard value before we've received confirmation - paramDataModel->setOnboardParameterWithType(componentId,key,value); + //paramDataModel->setOnboardParameterWithType(componentId,key,value); } } @@ -608,7 +613,7 @@ void QGCParamWidget::setParameterStatusMsg(const QString& msg) -void QGCParamWidget::requestParameterListUpdate() +void QGCParamWidget::requestAllParamsUpdate() { if (!mav) { return; diff --git a/src/ui/QGCParamWidget.h b/src/ui/QGCParamWidget.h index 9b34813b0..48edbb310 100644 --- a/src/ui/QGCParamWidget.h +++ b/src/ui/QGCParamWidget.h @@ -65,9 +65,9 @@ public slots: /** @brief Add a parameter to the list with retransmission / safety checks */ void receivedParameterUpdate(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value); /** @brief Add a parameter to the list */ - void receivedParameterUpdate(int uas, int component, QString parameterName, QVariant value); + void updateParameterDisplay(int uas, int component, QString parameterName, QVariant value); /** @brief Request list of parameters from MAV */ - void requestParameterListUpdate(); + void requestAllParamsUpdate(); /** @brief Request one single parameter */ void requestParameterUpdate(int component, const QString& parameter); /** @brief Set one parameter, changes value in RAM of MAV */ -- 2.22.0