Commit 3319dc65 authored by tstellanova's avatar tstellanova

move sendPendingParams

parent 4c79a3f2
......@@ -70,6 +70,12 @@ void QGCUASParamManager::setParameter(int component, QString parameterName, QVar
paramCommsMgr->setParameter(component,parameterName,value);
}
void QGCUASParamManager::sendPendingParameters()
{
paramCommsMgr->sendPendingParameters();
}
void QGCUASParamManager::loadParamMetaInfoCSV()
{
......
......@@ -46,6 +46,9 @@ public slots:
/** @brief Send one parameter to the MAV: changes value in transient memory of MAV */
virtual void setParameter(int component, QString parameterName, QVariant value);
/** @brief Send all pending parameters to the MAV, for storage in transient (RAM) memory */
virtual void sendPendingParameters();
/** @brief Request list of parameters from MAV */
virtual void requestParameterList();
......
......@@ -100,25 +100,23 @@ void UASParameterCommsMgr::requestParameterList()
Empty read retransmission list
Empty write retransmission list
*/
void UASParameterCommsMgr::clearRetransmissionLists()
void UASParameterCommsMgr::clearRetransmissionLists(int& missingReadCount, int& missingWriteCount )
{
qDebug() << __FILE__ << __LINE__ << "clearRetransmissionLists";
int missingReadCount = 0;
missingReadCount = 0;
QList<int> readKeys = transmissionMissingPackets.keys();
foreach (int component, readKeys) {
missingReadCount += transmissionMissingPackets.value(component)->count();
transmissionMissingPackets.value(component)->clear();
}
int missingWriteCount = 0;
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),
ParamCommsStatusLevel_Warning);
}
......@@ -230,7 +228,6 @@ void UASParameterCommsMgr::retransmissionGuardTick()
return;
}
qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS..";
// Check for timeout
// stop retransmission attempts on timeout
......@@ -238,10 +235,17 @@ void UASParameterCommsMgr::retransmissionGuardTick()
setRetransmissionGuardEnabled(false);
transmissionActive = false;
transmissionListMode = false;
clearRetransmissionLists();
int missingReadCount, missingWriteCount;
clearRetransmissionLists(missingReadCount,missingWriteCount);
if ((missingReadCount > 0) || (missingWriteCount > 0)) {
setParameterStatusMsg(tr("TIMEOUT! MISSING: %1 read, %2 write.").arg(missingReadCount).arg(missingWriteCount),
ParamCommsStatusLevel_Warning);
}
return;
}
qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS..";
resendReadWriteRequests();
}
else {
......@@ -544,15 +548,15 @@ void UASParameterCommsMgr::sendPendingParameters()
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) {
//TODO mavlink command for "set parameter list" ?
setParameter(compid, j.key(), j.value());
parametersSent++;
}
int compId = i.key();
QMap<QString, QVariant>* paramList = i.value();
QMap<QString, QVariant>::iterator j;
setParameterStatusMsg(tr("%1 pending params for component %2").arg(paramList->count()).arg(compId));
for (j = paramList->begin(); j != paramList->end(); ++j) {
//TODO mavlink command for "set parameter list" ?
setParameter(compId, j.key(), j.value());
parametersSent++;
}
}
......
......@@ -39,7 +39,7 @@ protected:
void loadParamCommsSettings();
/** @brief clear transmissionMissingPackets and transmissionMissingWriteAckPackets */
void clearRetransmissionLists();
void clearRetransmissionLists(int& missingReadCount, int& missingWriteCount );
void resendReadWriteRequests();
......
......@@ -88,7 +88,6 @@ void QGCParamWidget::layoutWidget()
tree = new QTreeWidget(this);
statusLabel = new QLabel();
statusLabel->setAutoFillBackground(true);
tree->setColumnWidth(70, 30);
// Set tree widget as widget onto this component
QGridLayout* horizontalLayout;
......@@ -117,7 +116,8 @@ void QGCParamWidget::layoutWidget()
QPushButton* setButton = new QPushButton(tr("Set"));
setButton->setToolTip(tr("Set current parameters in non-permanent onboard memory"));
setButton->setWhatsThis(tr("Set current parameters in non-permanent onboard memory"));
connect(setButton, SIGNAL(clicked()), this, SLOT(setParameters()));
connect(setButton, SIGNAL(clicked()),
this, SLOT(sendPendingParameters()));
horizontalLayout->addWidget(setButton, 2, 1);
QPushButton* writeButton = new QPushButton(tr("Write (ROM)"));
......@@ -159,7 +159,7 @@ void QGCParamWidget::layoutWidget()
headerItems.append("Value");
tree->setHeaderLabels(headerItems);
tree->setColumnCount(2);
tree->setColumnWidth(0,120);
tree->setColumnWidth(0,200);
tree->setColumnWidth(1,120);
tree->setExpandsOnDoubleClick(true);
......@@ -167,8 +167,9 @@ void QGCParamWidget::layoutWidget()
}
void QGCParamWidget::addComponentItem( int compId, QString compName)
void QGCParamWidget::addComponentItem(int compId, QString compName)
{
QString compLine = QString("%1 (#%2)").arg(compName).arg(compId);
QString ptrStr = QString().sprintf("%8p", this);
......@@ -231,37 +232,41 @@ void QGCParamWidget::handleParameterListUpToDate()
}
void QGCParamWidget::updateParameterDisplay(int componentId, QString parameterName, QVariant value)
void QGCParamWidget::updateParameterDisplay(int compId, QString parameterName, QVariant value)
{
// qDebug() << "QGCParamWidget::updateParameterDisplay" << parameterName;
// Reference to item in tree
QTreeWidgetItem* parameterItem = NULL;
// Add component item if necessary
if (!componentItems->contains(componentId)) {
QString componentName = tr("Component #%1").arg(componentId);
addComponentItem(componentId, componentName);
if (!componentItems->contains(compId)) {
QString componentName = tr("Component #%1").arg(compId);
addComponentItem(compId, componentName);
}
QString splitToken = "_";
// Check if auto-grouping can work
if (parameterName.contains(splitToken)) {
QString parent = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty);
QMap<QString, QTreeWidgetItem*>* compParamGroups = paramGroups.value(componentId);
if (!compParamGroups->contains(parent)) {
QString parentStr = parameterName.section(splitToken, 0, 0, QString::SectionSkipEmpty);
QMap<QString, QTreeWidgetItem*>* compParamGroups = paramGroups.value(compId);
if (!compParamGroups->contains(parentStr)) {
// Insert group item
QStringList glist;
glist.append(parent);
glist.append(parentStr);
QTreeWidgetItem* groupItem = new QTreeWidgetItem(glist);
compParamGroups->insert(parent, groupItem);
componentItems->value(componentId)->addChild(groupItem);
compParamGroups->insert(parentStr, groupItem);
// insert new group alphabetized
QList<QString> groupKeys = compParamGroups->uniqueKeys();
int insertIdx = groupKeys.indexOf(parentStr);
componentItems->value(compId)->insertChild(insertIdx,groupItem);
}
// Append child to group
bool found = false;
QTreeWidgetItem* parentItem = compParamGroups->value(parent);
QTreeWidgetItem* parentItem = compParamGroups->value(parentStr);
for (int i = 0; i < parentItem->childCount(); i++) {
QTreeWidgetItem* child = parentItem->child(i);
QString key = child->data(0, Qt::DisplayRole).toString();
......@@ -292,13 +297,13 @@ void QGCParamWidget::updateParameterDisplay(int componentId, QString parameterNa
parameterItem->setData(1, Qt::DisplayRole, value);
}
compParamGroups->value(parent)->addChild(parameterItem);
compParamGroups->value(parentStr)->addChild(parameterItem);
parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable);
}
}
else {
bool found = false;
QTreeWidgetItem* parent = componentItems->value(componentId);
QTreeWidgetItem* parent = componentItems->value(compId);
for (int i = 0; i < parent->childCount(); i++) {
QTreeWidgetItem* child = parent->child(i);
QString key = child->data(0, Qt::DisplayRole).toString();
......@@ -319,7 +324,7 @@ void QGCParamWidget::updateParameterDisplay(int componentId, QString parameterNa
// CONFIGURE PARAMETER ITEM
parameterItem->setData(1, Qt::DisplayRole, value);
componentItems->value(componentId)->addChild(parameterItem);
componentItems->value(compId)->addChild(parameterItem);
parameterItem->setFlags(parameterItem->flags() | Qt::ItemIsEditable);
}
}
......@@ -434,14 +439,6 @@ void QGCParamWidget::requestAllParamsUpdate()
/**
* Set all parameter in the parameter tree on the MAV
*/
void QGCParamWidget::setParameters()
{
paramCommsMgr->sendPendingParameters();
}
/**
* Write the current onboard parameters from RAM into
* permanent storage, e.g. EEPROM or harddisk
......@@ -454,7 +451,7 @@ void QGCParamWidget::writeParameters()
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
// Iterate through the pending parameters of the component, break on the first changed parameter
QMap<QString, QVariant>* compPending = i.value();
changedParamCount += compPending->count();
}
......
......@@ -77,10 +77,7 @@ public slots:
void updateParameterDisplay(int component, QString parameterName, QVariant value);
/** @brief Request list of parameters from MAV */
void requestAllParamsUpdate();
/** @brief Set one parameter, changes value in RAM of MAV */
// virtual void setParameter(int component, QString parameterName, QVariant value);
/** @brief Set all parameters, changes the value in RAM of MAV */
void setParameters();
/** @brief Write the current parameters to permanent storage (EEPROM/HDD) */
void writeParameters();
/** @brief Read the parameters from permanent storage to RAM */
......@@ -103,7 +100,6 @@ protected:
QMap<int, QTreeWidgetItem*>* componentItems; ///< The tree of component items, stored by component ID
QMap<int, QMap<QString, QTreeWidgetItem*>* > paramGroups; ///< Parameter groups to organize component items
};
#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