Browse Source

Standard and Advanced param pages, auto-generated from xml file

QGC4.4
Michael Carpenter 12 years ago
parent
commit
3e383c0115
  1. 9
      qgroundcontrol.pro
  2. 26
      src/ui/configuration/AdvancedParamConfig.cc
  3. 11
      src/ui/configuration/AdvancedParamConfig.h
  4. 48
      src/ui/configuration/AdvancedParamConfig.ui
  5. 7
      src/ui/configuration/ApmHardwareConfig.cc
  6. 355
      src/ui/configuration/ApmSoftwareConfig.cc
  7. 403
      src/ui/configuration/ApmSoftwareConfig.ui
  8. 35
      src/ui/configuration/StandardParamConfig.cc
  9. 12
      src/ui/configuration/StandardParamConfig.h
  10. 48
      src/ui/configuration/StandardParamConfig.ui

9
qgroundcontrol.pro

@ -257,7 +257,8 @@ FORMS += src/ui/MainWindow.ui \ @@ -257,7 +257,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/configuration/FailSafeConfig.ui \
src/ui/configuration/AdvancedParamConfig.ui \
src/ui/configuration/ArduCopterPidConfig.ui \
src/ui/configuration/ApmPlaneLevel.ui
src/ui/configuration/ApmPlaneLevel.ui \
src/ui/configuration/ParamWidget.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
@ -439,7 +440,8 @@ HEADERS += src/MG.h \ @@ -439,7 +440,8 @@ HEADERS += src/MG.h \
src/ui/configuration/FailSafeConfig.h \
src/ui/configuration/AdvancedParamConfig.h \
src/ui/configuration/ArduCopterPidConfig.h \
src/ui/configuration/ApmPlaneLevel.h
src/ui/configuration/ApmPlaneLevel.h \
src/ui/configuration/ParamWidget.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
@ -639,7 +641,8 @@ SOURCES += src/main.cc \ @@ -639,7 +641,8 @@ SOURCES += src/main.cc \
src/ui/configuration/FailSafeConfig.cc \
src/ui/configuration/AdvancedParamConfig.cc \
src/ui/configuration/ArduCopterPidConfig.cc \
src/ui/configuration/ApmPlaneLevel.cc
src/ui/configuration/ApmPlaneLevel.cc \
src/ui/configuration/ParamWidget.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc

26
src/ui/configuration/AdvancedParamConfig.cc

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
#include "AdvancedParamConfig.h"
AdvancedParamConfig::AdvancedParamConfig(QWidget *parent) : QWidget(parent)
AdvancedParamConfig::AdvancedParamConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
}
@ -9,3 +9,27 @@ AdvancedParamConfig::AdvancedParamConfig(QWidget *parent) : QWidget(parent) @@ -9,3 +9,27 @@ AdvancedParamConfig::AdvancedParamConfig(QWidget *parent) : QWidget(parent)
AdvancedParamConfig::~AdvancedParamConfig()
{
}
void AdvancedParamConfig::addRange(QString title,QString description,QString param,double min,double max)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
paramToWidgetMap[param] = widget;
widget->setupDouble(title + "(" + param + ")",description,0,min,max);
ui.verticalLayout->addWidget(widget);
widget->show();
}
void AdvancedParamConfig::addCombo(QString title,QString description,QString param,QList<QPair<int,QString> > valuelist)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
paramToWidgetMap[param] = widget;
widget->setupCombo(title + "(" + param + ")",description,valuelist);
ui.verticalLayout->addWidget(widget);
widget->show();
}
void AdvancedParamConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (paramToWidgetMap.contains(parameterName))
{
paramToWidgetMap[parameterName]->setValue(value.toDouble());
}
}

11
src/ui/configuration/AdvancedParamConfig.h

@ -3,16 +3,21 @@ @@ -3,16 +3,21 @@
#include <QWidget>
#include "ui_AdvancedParamConfig.h"
class AdvancedParamConfig : public QWidget
#include "AP2ConfigWidget.h"
#include "ParamWidget.h"
class AdvancedParamConfig : public AP2ConfigWidget
{
Q_OBJECT
public:
explicit AdvancedParamConfig(QWidget *parent = 0);
~AdvancedParamConfig();
void addRange(QString title,QString description,QString param,double min,double max);
void addCombo(QString title,QString description,QString param,QList<QPair<int,QString> > valuelist);
private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QMap<QString,ParamWidget*> paramToWidgetMap;
Ui::AdvancedParamConfig ui;
};

48
src/ui/configuration/AdvancedParamConfig.ui

@ -6,26 +6,44 @@ @@ -6,26 +6,44 @@
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
<width>725</width>
<height>632</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QLabel" name="label">
<property name="geometry">
<rect>
<x>10</x>
<y>10</y>
<width>181</width>
<height>31</height>
</rect>
</property>
<property name="text">
<string>&lt;h2&gt;Advanced Params&lt;/h2&gt;</string>
</property>
</widget>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>&lt;h2&gt;Advanced Params&lt;/h2&gt;</string>
</property>
</widget>
</item>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>705</width>
<height>585</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QVBoxLayout" name="verticalLayout"/>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>

7
src/ui/configuration/ApmHardwareConfig.cc

@ -30,7 +30,6 @@ This file is part of the QGROUNDCONTROL project @@ -30,7 +30,6 @@ This file is part of the QGROUNDCONTROL project
*/
#include "ApmHardwareConfig.h"
ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
@ -191,4 +190,10 @@ void ApmHardwareConfig::activeUASSet(UASInterface *uas) @@ -191,4 +190,10 @@ void ApmHardwareConfig::activeUASSet(UASInterface *uas)
ui.optionalHardwareButton->setChecked(false);
ui.radio3DRButton->setVisible(false);
ui.antennaTrackerButton->setVisible(false);
}

355
src/ui/configuration/ApmSoftwareConfig.cc

@ -1,4 +1,7 @@ @@ -1,4 +1,7 @@
#include "ApmSoftwareConfig.h"
#include <QXmlStreamReader>
#include <QDir>
#include <QFile>
ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
@ -82,4 +85,356 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas) @@ -82,4 +85,356 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
ui.advParamListButton->setVisible(true);
ui.arduCoperPidButton->setVisible(true);
QDir autopilotdir(qApp->applicationDirPath() + "/files/" + uas->getAutopilotTypeName().toLower());
QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly))
{
return;
}
QXmlStreamReader xml(xmlfile.readAll());
xmlfile.close();
//TODO: Testing to ensure that incorrectly formated XML won't break this.
while (!xml.atEnd())
{
if (xml.isStartElement() && xml.name() == "paramfile")
{
xml.readNext();
while ((xml.name() != "paramfile") && !xml.atEnd())
{
QString valuetype = "";
if (xml.isStartElement() && (xml.name() == "vehicles" || xml.name() == "libraries")) //Enter into the vehicles loop
{
valuetype = xml.name().toString();
xml.readNext();
while ((xml.name() != valuetype) && !xml.atEnd())
{
if (xml.isStartElement() && xml.name() == "parameters") //This is a parameter block
{
QString parametersname = "";
if (xml.attributes().hasAttribute("name"))
{
parametersname = xml.attributes().value("name").toString();
}
QVariantMap genset;
QVariantMap advset;
QString setname = parametersname;
xml.readNext();
int genarraycount = 0;
int advarraycount = 0;
while ((xml.name() != "parameters") && !xml.atEnd())
{
if (xml.isStartElement() && xml.name() == "param")
{
QString humanname = xml.attributes().value("humanName").toString();
QString name = xml.attributes().value("name").toString();
QString tab= xml.attributes().value("user").toString();
if (tab == "Advanced")
{
advset["title"] = parametersname;
}
else
{
genset["title"] = parametersname;
}
if (name.contains(":"))
{
name = name.split(":")[1];
}
QString docs = xml.attributes().value("documentation").toString();
//paramTooltips[name] = name + " - " + docs;
int type = -1; //Type of item
QMap<QString,QString> fieldmap;
QMap<QString,QString> valuemap;
xml.readNext();
while ((xml.name() != "param") && !xml.atEnd())
{
if (xml.isStartElement() && xml.name() == "values")
{
type = 1; //1 is a combobox
if (tab == "Advanced")
{
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "COMBO";
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
}
else
{
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "COMBO";
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
}
int paramcount = 0;
xml.readNext();
while ((xml.name() != "values") && !xml.atEnd())
{
if (xml.isStartElement() && xml.name() == "value")
{
QString code = xml.attributes().value("code").toString();
QString arg = xml.readElementText();
valuemap[code] = arg;
if (tab == "Advanced")
{
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
}
else
{
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
}
paramcount++;
}
xml.readNext();
}
if (tab == "Advanced")
{
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
}
else
{
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
}
}
if (xml.isStartElement() && xml.name() == "field")
{
type = 2; //2 is a slider
QString fieldtype = xml.attributes().value("name").toString();
QString text = xml.readElementText();
fieldmap[fieldtype] = text;
}
xml.readNext();
}
if (type == -1)
{
//Nothing inside! Assume it's a value, give it a default range.
type = 2;
QString fieldtype = "Range";
QString text = "0 100"; //TODO: Determine a better way of figuring out default ranges.
fieldmap[fieldtype] = text;
}
if (type == 2)
{
if (tab == "Advanced")
{
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "SLIDER";
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
}
else
{
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "SLIDER";
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
}
if (fieldmap.contains("Range"))
{
float min = 0;
float max = 0;
//Some range fields list "0-10" and some list "0 10". Handle both.
if (fieldmap["Range"].split(" ").size() > 1)
{
min = fieldmap["Range"].split(" ")[0].trimmed().toFloat();
max = fieldmap["Range"].split(" ")[1].trimmed().toFloat();
}
else if (fieldmap["Range"].split("-").size() > 1)
{
min = fieldmap["Range"].split("-")[0].trimmed().toFloat();
max = fieldmap["Range"].split("-")[1].trimmed().toFloat();
}
if (tab == "Advanced")
{
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
}
else
{
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
}
}
}
if (tab == "Advanced")
{
advarraycount++;
advset["count"] = advarraycount;
}
else
{
genarraycount++;
genset["count"] = genarraycount;
}
//Right here we have a single param in memory
name;
docs;
valuemap;
fieldmap;
//standardParamConfig
if (valuemap.size() > 0)
{
QList<QPair<int,QString> > valuelist;
for (QMap<QString,QString>::const_iterator i = valuemap.constBegin();i!=valuemap.constEnd();i++)
{
valuelist.append(QPair<int,QString>(i.key().toInt(),i.value()));
}
if (tab == "Standard")
{
standardParamConfig->addCombo(humanname,docs,name,valuelist);
}
else if (tab == "Advanced")
{
advancedParamConfig->addCombo(humanname,docs,name,valuelist);
}
}
else if (fieldmap.size() > 0)
{
float min = 0;
float max = 100;
if (fieldmap.contains("Range"))
{
float min = 0;
float max = 0;
//Some range fields list "0-10" and some list "0 10". Handle both.
if (fieldmap["Range"].split(" ").size() > 1)
{
min = fieldmap["Range"].split(" ")[0].trimmed().toFloat();
max = fieldmap["Range"].split(" ")[1].trimmed().toFloat();
}
else if (fieldmap["Range"].split("-").size() > 1)
{
min = fieldmap["Range"].split("-")[0].trimmed().toFloat();
max = fieldmap["Range"].split("-")[1].trimmed().toFloat();
}
}
if (tab == "Standard")
{
standardParamConfig->addRange(humanname,docs,name,min,max);
}
else if (tab == "Advanced")
{
advancedParamConfig->addRange(humanname,docs,name,max,min);
}
}
}
xml.readNext();
}
if (genarraycount > 0)
{
/*
tool = new QGCToolWidget("", this);
tool->addUAS(mav);
tool->setTitle(parametersname);
tool->setObjectName(parametersname);
tool->setSettings(genset);
QList<QString> paramlist = tool->getParamList();
for (int i=0;i<paramlist.size();i++)
{
//Based on the airframe, we add the parameter to different categories.
if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
{
systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
}
else if (parametersname == "ArduCopter") //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);
}
}
toolWidgets.append(tool);
QGroupBox *box = new QGroupBox(this);
box->setTitle(tool->objectName());
box->setLayout(new QVBoxLayout());
box->layout()->addWidget(tool);
if (valuetype == "vehicles")
{
ui->leftGeneralLayout->addWidget(box);
}
else if (valuetype == "libraries")
{
ui->rightGeneralLayout->addWidget(box);
}
box->hide();
toolToBoxMap[tool] = box;*/
}
if (advarraycount > 0)
{
/*
tool = new QGCToolWidget("", this);
tool->addUAS(mav);
tool->setTitle(parametersname);
tool->setObjectName(parametersname);
tool->setSettings(advset);
QList<QString> paramlist = tool->getParamList();
for (int i=0;i<paramlist.size();i++)
{
//Based on the airframe, we add the parameter to different categories.
if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
{
systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
}
else if (parametersname == "ArduCopter") //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);
}
}
toolWidgets.append(tool);
QGroupBox *box = new QGroupBox(this);
box->setTitle(tool->objectName());
box->setLayout(new QVBoxLayout());
box->layout()->addWidget(tool);
if (valuetype == "vehicles")
{
ui->leftAdvancedLayout->addWidget(box);
}
else if (valuetype == "libraries")
{
ui->rightAdvancedLayout->addWidget(box);
}
box->hide();
toolToBoxMap[tool] = box;*/
}
}
xml.readNext();
}
}
xml.readNext();
}
}
xml.readNext();
}
}

403
src/ui/configuration/ApmSoftwareConfig.ui

@ -6,221 +6,210 @@ @@ -6,221 +6,210 @@
<rect>
<x>0</x>
<y>0</y>
<width>718</width>
<height>531</height>
<width>853</width>
<height>619</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QScrollArea" name="scrollArea_6">
<property name="geometry">
<rect>
<x>20</x>
<y>10</y>
<width>175</width>
<height>531</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>175</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>175</width>
<height>16777215</height>
</size>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_3">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>173</width>
<height>529</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_12">
<item>
<layout class="QVBoxLayout" name="navBarLayout">
<property name="sizeConstraint">
<enum>QLayout::SetMinAndMaxSize</enum>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QScrollArea" name="scrollArea_6">
<property name="minimumSize">
<size>
<width>175</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>175</width>
<height>16777215</height>
</size>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_3">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>173</width>
<height>599</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_12">
<item>
<widget class="QPushButton" name="plannerConfigButton">
<property name="minimumSize">
<size>
<width>100</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>APM Planner 2.0 Config</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="basicPidsButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Basic Pids</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="flightModesButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Flight Modes</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="standardParamButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Standard Params</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="geoFenceButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>GeoFence</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="failSafeButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>FailSafe</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="advancedParamButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Advanced Params</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="advParamListButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Adv Parameter List</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="arduCoperPidButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>ArduCoper Pids</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
<layout class="QVBoxLayout" name="navBarLayout">
<property name="sizeConstraint">
<enum>QLayout::SetMinAndMaxSize</enum>
</property>
<item>
<widget class="QPushButton" name="plannerConfigButton">
<property name="minimumSize">
<size>
<width>100</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>APM Planner 2.0 Config</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="basicPidsButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Basic Pids</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="flightModesButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Flight Modes</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="standardParamButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Standard Params</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="geoFenceButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>GeoFence</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="failSafeButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>FailSafe</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="advancedParamButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Advanced Params</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="advParamListButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>Adv Parameter List</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="arduCoperPidButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>ArduCoper Pids</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
<widget class="QStackedWidget" name="stackedWidget">
<property name="geometry">
<rect>
<x>220</x>
<y>20</y>
<width>471</width>
<height>491</height>
</rect>
</property>
</widget>
</widget>
</widget>
</item>
<item>
<widget class="QStackedWidget" name="stackedWidget"/>
</item>
</layout>
</widget>
<resources/>
<connections/>

35
src/ui/configuration/StandardParamConfig.cc

@ -1,11 +1,40 @@ @@ -1,11 +1,40 @@
#include "StandardParamConfig.h"
#include "ParamWidget.h"
StandardParamConfig::StandardParamConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
}
StandardParamConfig::~StandardParamConfig()
{
}
StandardParamConfig::StandardParamConfig(QWidget *parent) : QWidget(parent)
void StandardParamConfig::activeUASSet(UASInterface *uas)
{
ui.setupUi(this);
AP2ConfigWidget::activeUASSet(uas);
}
void StandardParamConfig::addRange(QString title,QString description,QString param,double min,double max)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
paramToWidgetMap[param] = widget;
widget->setupDouble(title + "(" + param + ")",description,0,min,max);
ui.verticalLayout->addWidget(widget);
widget->show();
}
StandardParamConfig::~StandardParamConfig()
void StandardParamConfig::addCombo(QString title,QString description,QString param,QList<QPair<int,QString> > valuelist)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
paramToWidgetMap[param] = widget;
widget->setupCombo(title + "(" + param + ")",description,valuelist);
ui.verticalLayout->addWidget(widget);
widget->show();
}
void StandardParamConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (paramToWidgetMap.contains(parameterName))
{
paramToWidgetMap[parameterName]->setValue(value.toDouble());
}
}

12
src/ui/configuration/StandardParamConfig.h

@ -3,16 +3,22 @@ @@ -3,16 +3,22 @@
#include <QWidget>
#include "ui_StandardParamConfig.h"
class StandardParamConfig : public QWidget
#include "AP2ConfigWidget.h"
#include "ParamWidget.h"
class StandardParamConfig : public AP2ConfigWidget
{
Q_OBJECT
public:
explicit StandardParamConfig(QWidget *parent = 0);
~StandardParamConfig();
void addRange(QString title,QString description,QString param,double min,double max);
void addCombo(QString title,QString description,QString param,QList<QPair<int,QString> > valuelist);
private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QMap<QString,ParamWidget*> paramToWidgetMap;
void activeUASSet(UASInterface *uas);
Ui::StandardParamConfig ui;
};

48
src/ui/configuration/StandardParamConfig.ui

@ -6,26 +6,44 @@ @@ -6,26 +6,44 @@
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
<width>651</width>
<height>552</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QLabel" name="label">
<property name="geometry">
<rect>
<x>20</x>
<y>20</y>
<width>201</width>
<height>41</height>
</rect>
</property>
<property name="text">
<string>&lt;h2&gt;Standard Params&lt;/h2&gt;</string>
</property>
</widget>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>&lt;h2&gt;Standard Params&lt;/h2&gt;</string>
</property>
</widget>
</item>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>631</width>
<height>505</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QVBoxLayout" name="verticalLayout"/>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>

Loading…
Cancel
Save