diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index 78448ef6bec5096364a103bd69b822cbd9f75d74..d10d3adbe46a8f349227490ade06e8082c37d6dc 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -35,6 +35,10 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : ui(new Ui::QGCVehicleConfig) { doneLoadingConfig = false; + systemTypeToParamMap["FIXED_WING"] = new QMap(); + systemTypeToParamMap["QUADROTOR"] = new QMap(); + systemTypeToParamMap["GROUND_ROVER"] = new QMap(); + libParamToWidgetMap = new QMap(); setObjectName("QGC_VEHICLECONFIG"); ui->setupUi(this); @@ -457,7 +461,24 @@ void QGCVehicleConfig::loadConfig() QList paramlist = tool->getParamList(); for (int i=0;iinsert(paramlist[i],tool); + } + else if (parametersname == "ArduCoptor") //MAV_TYPE_QUADROTOR "QUADROTOR + { + systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool); + } + else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER + { + systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool); + } + else + { + libParamToWidgetMap->insert(paramlist[i],tool); + } + //paramToWidgetMap[paramlist[i]] = tool; } toolWidgets.append(tool); @@ -529,12 +550,21 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); + if (systemTypeToParamMap.contains(mav->getSystemTypeName())) + { + paramToWidgetMap = systemTypeToParamMap[mav->getSystemTypeName()]; + } + else + { + qDebug() << "No parameters defined for system type:" << mav->getSystemTypeName(); + } + if (!paramTooltips.isEmpty()) { mav->getParamManager()->setParamInfo(paramTooltips); } - mav->requestParameters(); + // mav->requestParameters(); QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/"; qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName(); @@ -769,20 +799,41 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete { return; } - if (paramToWidgetMap.contains(parameterName)) + if (paramToWidgetMap->contains(parameterName)) + { + paramToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value); + if (toolToBoxMap.contains(paramToWidgetMap->value(parameterName))) + { + if (value.type() == QVariant::Char) + { + //qDebug() << "Parameter update (char):" << parameterName << QVariant(value.toUInt()); + } + else + { + //qDebug() << "Parameter update:" << parameterName << value; + } + toolToBoxMap[paramToWidgetMap->value(parameterName)]->show(); + } + else + { + qDebug() << "ERROR!!!!!!!!!! widget with no box:" << parameterName; + } + } + else if (libParamToWidgetMap->contains(parameterName)) { - paramToWidgetMap[parameterName]->setParameterValue(uas,component,parameterName,value); - if (toolToBoxMap.contains(paramToWidgetMap[parameterName])) + //It's a lib param + libParamToWidgetMap->value(parameterName)->setParameterValue(uas,component,parameterName,value); + if (toolToBoxMap.contains(libParamToWidgetMap->value(parameterName))) { if (value.type() == QVariant::Char) { - qDebug() << "Parameter update (char):" << parameterName << QVariant(value.toUInt()); + //qDebug() << "Parameter update (char):" << parameterName << QVariant(value.toUInt()); } else { - qDebug() << "Parameter update:" << parameterName << value; + //qDebug() << "Parameter update:" << parameterName << value; } - toolToBoxMap[paramToWidgetMap[parameterName]]->show(); + toolToBoxMap[libParamToWidgetMap->value(parameterName)]->show(); } else { @@ -800,7 +851,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete //It should be grouped with this one. qDebug() << parameterName << toolWidgets[i]->objectName(); toolWidgets[i]->addParam(uas,component,parameterName,value); - paramToWidgetMap[parameterName] = toolWidgets[i]; + libParamToWidgetMap->insert(parameterName,toolWidgets[i]); found = true; break; } @@ -817,7 +868,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete tool->setObjectName(tooltitle); //tool->setSettings(set); tool->addParam(uas,component,parameterName,value); - paramToWidgetMap[parameterName] = tool; + libParamToWidgetMap->insert(parameterName,tool); toolWidgets.append(tool); QGroupBox *box = new QGroupBox(this); box->setTitle(tool->objectName()); diff --git a/src/ui/QGCVehicleConfig.h b/src/ui/QGCVehicleConfig.h index 928ab67c8a88eeb5eb5b67894c146f079f11e0c8..ef22e5957b9de75d6bc9aeef9a5ba9d7a7dacd00 100644 --- a/src/ui/QGCVehicleConfig.h +++ b/src/ui/QGCVehicleConfig.h @@ -172,7 +172,10 @@ protected: enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention QList toolWidgets; ///< Configurable widgets bool calibrationEnabled; ///< calibration mode on / off - QMap paramToWidgetMap; + + QMap *paramToWidgetMap; + QMap *libParamToWidgetMap; + QMap*> systemTypeToParamMap; QMap toolToBoxMap; QMap paramTooltips;