Commit e8c6dbb2 authored by tstellanova's avatar tstellanova

consolidating comms-related methods

parent 0757b49e
...@@ -16,13 +16,19 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) : ...@@ -16,13 +16,19 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) :
} }
bool QGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const
{
bool QGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const {
return paramDataModel->getOnboardParameterValue(component,parameter,value); return paramDataModel->getOnboardParameterValue(component,parameter,value);
} }
void QGCUASParamManager::requestParameterUpdate(int component, const QString& parameter)
{
if (mav) {
mav->requestParameter(component, parameter);
}
}
/** /**
* Send a request to deliver the list of onboard parameters * Send a request to deliver the list of onboard parameters
* to the MAV. * to the MAV.
......
...@@ -17,9 +17,6 @@ public: ...@@ -17,9 +17,6 @@ public:
virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const; virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const;
/** @brief Request an update for this specific parameter */
virtual void requestParameterUpdate(int component, const QString& parameter) = 0;
/** @brief Provide tooltips / user-visible descriptions for parameters */ /** @brief Provide tooltips / user-visible descriptions for parameters */
virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs); virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs);
...@@ -36,8 +33,7 @@ signals: ...@@ -36,8 +33,7 @@ signals:
void parameterListUpToDate(int component); void parameterListUpToDate(int component);
/** @brief Request a single parameter */ /** @brief Request a single parameter */
void requestParameter(int component, int 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 */
...@@ -47,6 +43,10 @@ public slots: ...@@ -47,6 +43,10 @@ public slots:
/** @brief Check for missing parameters */ /** @brief Check for missing parameters */
virtual void retransmissionGuardTick(); virtual void retransmissionGuardTick();
/** @brief Request one single parameter */
virtual void requestParameterUpdate(int component, const QString& parameter);
protected: protected:
// Parameter data model // Parameter data model
......
...@@ -72,6 +72,7 @@ ParameterInterface::ParameterInterface(QWidget *parent) : ...@@ -72,6 +72,7 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
ParameterInterface::~ParameterInterface() ParameterInterface::~ParameterInterface()
{ {
delete paramWidgets;
delete m_ui; delete m_ui;
} }
...@@ -97,8 +98,8 @@ void ParameterInterface::addUAS(UASInterface* uas) ...@@ -97,8 +98,8 @@ void ParameterInterface::addUAS(UASInterface* uas)
QGCParamWidget* param = new QGCParamWidget(uas, this); QGCParamWidget* param = new QGCParamWidget(uas, this);
QString ptrStr; QString ptrStr;
ptrStr.sprintf("%8p", param); ptrStr.sprintf("QGCParamWidget %8p (parent %8p)", param,this);
qDebug() << "Created QGCParamWidget " << ptrStr << "for UAS id: " << uasId << " count: " << paramWidgets->count(); qDebug() << "Created " << ptrStr << " for UAS id: " << uasId << " count: " << paramWidgets->count();
paramWidgets->insert(uasId, param); paramWidgets->insert(uasId, param);
m_ui->stackedWidget->addWidget(param); m_ui->stackedWidget->addWidget(param);
......
...@@ -49,7 +49,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -49,7 +49,7 @@ This file is part of the QGROUNDCONTROL project
*/ */
QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
QGCUASParamManager(uas, parent), QGCUASParamManager(uas, parent),
components(new QMap<int, QTreeWidgetItem*>()) componentItems(new QMap<int, QTreeWidgetItem*>())
{ {
// Load settings // Load settings
loadSettings(); loadSettings();
...@@ -145,8 +145,8 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : ...@@ -145,8 +145,8 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(receivedParameterUpdate(int,int,int,int,QString,QVariant))); connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(receivedParameterUpdate(int,int,int,int,QString,QVariant)));
// Connect retransmission guard // Connect retransmission guard
connect(this, SIGNAL(requestParameter(int,QString)), uas, SLOT(requestParameter(int,QString))); connect(this, SIGNAL(requestParameterByName(int,QString)), uas, SLOT(requestParameterByName(int,QString)));
connect(this, SIGNAL(requestParameter(int,int)), uas, SLOT(requestParameter(int,int))); connect(this, SIGNAL(requestParameterByName(int,int)), uas, SLOT(requestParameterByName(int,int)));
connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick())); connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick()));
// Get parameters // Get parameters
...@@ -214,20 +214,20 @@ UASInterface* QGCParamWidget::getUAS() ...@@ -214,20 +214,20 @@ UASInterface* QGCParamWidget::getUAS()
* @param component id of the component * @param component id of the component
* @param componentName human friendly name of the component * @param componentName human friendly name of the component
*/ */
void QGCParamWidget::addComponent(int uas, int component, QString componentName) void QGCParamWidget::addComponentItem(int uas, int component, QString componentName)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
if (components->contains(component)) { if (componentItems->contains(component)) {
// Update existing // Update existing
components->value(component)->setData(0, Qt::DisplayRole, QString("%1 (#%2)").arg(componentName).arg(component)); componentItems->value(component)->setData(0, Qt::DisplayRole, QString("%1 (#%2)").arg(componentName).arg(component));
//components->value(component)->setData(1, Qt::DisplayRole, QString::number(component)); //components->value(component)->setData(1, Qt::DisplayRole, QString::number(component));
components->value(component)->setFirstColumnSpanned(true); componentItems->value(component)->setFirstColumnSpanned(true);
} else { } else {
// Add new // Add new
QStringList list(QString("%1 (#%2)").arg(componentName).arg(component)); QStringList list(QString("%1 (#%2)").arg(componentName).arg(component));
QTreeWidgetItem* comp = new QTreeWidgetItem(list); QTreeWidgetItem* comp = new QTreeWidgetItem(list);
comp->setFirstColumnSpanned(true); comp->setFirstColumnSpanned(true);
components->insert(component, comp); componentItems->insert(component, comp);
// Create grouping and update maps // Create grouping and update maps
paramGroups.insert(component, new QMap<QString, QTreeWidgetItem*>()); paramGroups.insert(component, new QMap<QString, QTreeWidgetItem*>());
tree->addTopLevelItem(comp); tree->addTopLevelItem(comp);
...@@ -391,40 +391,26 @@ void QGCParamWidget::receivedParameterUpdate(int uas, int component, int paramCo ...@@ -391,40 +391,26 @@ void QGCParamWidget::receivedParameterUpdate(int uas, int component, int paramCo
* @param component id of the component * @param component id of the component
* @param parameterName human friendly name of the parameter * @param parameterName human friendly name of the parameter
*/ */
void QGCParamWidget::updateParameterDisplay(int uas, int component, QString parameterName, QVariant value) void QGCParamWidget::updateParameterDisplay(int uas, int componentId, QString parameterName, QVariant value)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
QString ptrStr; // QString ptrStr;
ptrStr.sprintf("%8p", this); // ptrStr.sprintf("%8p", this);
qDebug() << "QGCParamWidget " << ptrStr << " got param" << parameterName; // qDebug() << "QGCParamWidget " << ptrStr << " got param" << parameterName;
// Reference to item in tree // Reference to item in tree
QTreeWidgetItem* parameterItem = NULL; QTreeWidgetItem* parameterItem = NULL;
// Get component // Get component
if (!components->contains(component)) if (!componentItems->contains(componentId)) {
{ QString componentName = tr("Component #%1").arg(componentId);
// QString componentName; addComponentItem(uas, componentId, componentName);
// switch (component)
// {
// case MAV_COMP_ID_CAMERA:
// componentName = tr("Camera (#%1)").arg(component);
// break;
// case MAV_COMP_ID_IMU:
// componentName = tr("IMU (#%1)").arg(component);
// break;
// default:
// componentName = tr("Component #").arg(component);
// break;
// }
QString componentName = tr("Component #%1").arg(component);
addComponent(uas, component, componentName);
} }
// Replace value in data model // Replace value in data model
paramDataModel->handleParameterUpdate(component,parameterName,value); paramDataModel->handleParameterUpdate(componentId,parameterName,value);
QString splitToken = "_"; QString splitToken = "_";
...@@ -432,7 +418,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para ...@@ -432,7 +418,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para
if (parameterName.contains(splitToken)) if (parameterName.contains(splitToken))
{ {
QString parent = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty); QString parent = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty);
QMap<QString, QTreeWidgetItem*>* compParamGroups = paramGroups.value(component); QMap<QString, QTreeWidgetItem*>* compParamGroups = paramGroups.value(componentId);
if (!compParamGroups->contains(parent)) if (!compParamGroups->contains(parent))
{ {
// Insert group item // Insert group item
...@@ -440,7 +426,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para ...@@ -440,7 +426,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para
glist.append(parent); glist.append(parent);
QTreeWidgetItem* item = new QTreeWidgetItem(glist); QTreeWidgetItem* item = new QTreeWidgetItem(glist);
compParamGroups->insert(parent, item); compParamGroups->insert(parent, item);
components->value(component)->addChild(item); componentItems->value(componentId)->addChild(item);
} }
// Append child to group // Append child to group
...@@ -489,7 +475,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para ...@@ -489,7 +475,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para
else else
{ {
bool found = false; bool found = false;
QTreeWidgetItem* parent = components->value(component); QTreeWidgetItem* parent = componentItems->value(componentId);
for (int i = 0; i < parent->childCount(); i++) for (int i = 0; i < parent->childCount(); i++)
{ {
QTreeWidgetItem* child = parent->child(i); QTreeWidgetItem* child = parent->child(i);
...@@ -513,7 +499,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para ...@@ -513,7 +499,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para
// CONFIGURE PARAMETER ITEM // CONFIGURE PARAMETER ITEM
parameterItem->setData(1, Qt::DisplayRole, value); parameterItem->setData(1, Qt::DisplayRole, value);
components->value(component)->addChild(parameterItem); componentItems->value(componentId)->addChild(parameterItem);
parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable); parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable);
} }
//tree->expandAll(); //tree->expandAll();
...@@ -535,7 +521,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para ...@@ -535,7 +521,7 @@ void QGCParamWidget::updateParameterDisplay(int uas, int component, QString para
parameterItem->setToolTip(0, tooltipFormat); parameterItem->setToolTip(0, tooltipFormat);
parameterItem->setToolTip(1, tooltipFormat); parameterItem->setToolTip(1, tooltipFormat);
paramDataModel->handleParameterUpdate(component,parameterName,value); paramDataModel->handleParameterUpdate(componentId,parameterName,value);
} }
...@@ -549,7 +535,7 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column) ...@@ -549,7 +535,7 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column)
parent = parent->parent(); parent = parent->parent();
} }
// Parent is now top-level component // Parent is now top-level component
int componentId = components->key(parent); int componentId = componentItems->key(parent);
QString key = current->data(0, Qt::DisplayRole).toString(); QString key = current->data(0, Qt::DisplayRole).toString();
QVariant value = current->data(1, Qt::DisplayRole); QVariant value = current->data(1, Qt::DisplayRole);
...@@ -603,7 +589,6 @@ void QGCParamWidget::loadParametersFromFile() ...@@ -603,7 +589,6 @@ void QGCParamWidget::loadParametersFromFile()
QTextStream in(&file); QTextStream in(&file);
paramDataModel->readUpdateParametersFromStream(in); paramDataModel->readUpdateParametersFromStream(in);
file.close(); file.close();
} }
void QGCParamWidget::setParameterStatusMsg(const QString& msg) void QGCParamWidget::setParameterStatusMsg(const QString& msg)
...@@ -632,14 +617,6 @@ void QGCParamWidget::requestAllParamsUpdate() ...@@ -632,14 +617,6 @@ void QGCParamWidget::requestAllParamsUpdate()
requestParameterList(); requestParameterList();
} }
/**
* The .. signal is emitted
*/
void QGCParamWidget::requestParameterUpdate(int component, const QString& parameter)
{
if (mav) mav->requestParameter(component, parameter);
}
/** /**
...@@ -830,5 +807,5 @@ void QGCParamWidget::readParameters() ...@@ -830,5 +807,5 @@ void QGCParamWidget::readParameters()
void QGCParamWidget::clear() void QGCParamWidget::clear()
{ {
tree->clear(); tree->clear();
components->clear(); componentItems->clear();
} }
...@@ -61,15 +61,13 @@ signals: ...@@ -61,15 +61,13 @@ signals:
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 addComponentItem(int uas, int component, QString componentName);
/** @brief Add a parameter to the list with retransmission / safety checks */ /** @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); void receivedParameterUpdate(int uas, int component, int paramCount, int paramId, QString parameterName, QVariant value);
/** @brief Add a parameter to the list */ /** @brief Add a parameter to the list */
void updateParameterDisplay(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 */ /** @brief Request list of parameters from MAV */
void requestAllParamsUpdate(); void requestAllParamsUpdate();
/** @brief Request one single 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 */
void setParameter(int component, QString parameterName, QVariant value); void setParameter(int component, QString parameterName, QVariant value);
/** @brief Set all parameters, changes the value in RAM of MAV */ /** @brief Set all parameters, changes the value in RAM of MAV */
...@@ -93,7 +91,7 @@ public slots: ...@@ -93,7 +91,7 @@ public slots:
protected: protected:
QTreeWidget* tree; ///< The parameter tree QTreeWidget* tree; ///< The parameter tree
QLabel* statusLabel; ///< Parameter transmission label QLabel* statusLabel; ///< Parameter transmission label
QMap<int, QTreeWidgetItem*>* components; ///< The list of components QMap<int, QTreeWidgetItem*>* componentItems; ///< The list of component items, stored by component ID
QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups
......
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