diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 80d0414c31208cf1a904c9f7e66db576725549cb..9663d2260b87115267d2a25c1eb3bba59120c61b 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -255,7 +255,12 @@ FORMS += src/ui/MainWindow.ui \
src/ui/configuration/GeoFenceConfig.ui \
src/ui/configuration/FailSafeConfig.ui \
src/ui/configuration/AdvancedParamConfig.ui \
- src/ui/configuration/ArduCopterPidConfig.ui
+ src/ui/configuration/ArduCopterPidConfig.ui \
+ src/ui/configuration/ApmPlaneLevel.ui \
+ src/ui/configuration/ParamWidget.ui \
+ src/ui/configuration/ArduPlanePidConfig.ui \
+ src/ui/configuration/AdvParameterList.ui \
+ src/ui/configuration/ArduRoverPidConfig.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
@@ -437,7 +442,12 @@ HEADERS += src/MG.h \
src/ui/configuration/FailSafeConfig.h \
src/ui/configuration/AdvancedParamConfig.h \
src/ui/configuration/ArduCopterPidConfig.h \
- src/ui/apmtoolbar.h
+ src/ui/apmtoolbar.h \
+ src/ui/configuration/ApmPlaneLevel.h \
+ src/ui/configuration/ParamWidget.h \
+ src/ui/configuration/ArduPlanePidConfig.h \
+ src/ui/configuration/AdvParameterList.h \
+ src/ui/configuration/ArduRoverPidConfig.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
@@ -637,7 +647,12 @@ SOURCES += src/main.cc \
src/ui/configuration/FailSafeConfig.cc \
src/ui/configuration/AdvancedParamConfig.cc \
src/ui/configuration/ArduCopterPidConfig.cc \
- src/ui/apmtoolbar.cpp
+ src/ui/apmtoolbar.cpp \
+ src/ui/configuration/ApmPlaneLevel.cc \
+ src/ui/configuration/ParamWidget.cc \
+ src/ui/configuration/ArduPlanePidConfig.cc \
+ src/ui/configuration/AdvParameterList.cc \
+ src/ui/configuration/ArduRoverPidConfig.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
diff --git a/src/QGCCore.cc b/src/QGCCore.cc
index c4a38bf0e3812c5db9f8224ac8a312ae04c6ee8d..d2379d63b5613ac1e24528cb86d5199cbd09a66b 100644
--- a/src/QGCCore.cc
+++ b/src/QGCCore.cc
@@ -72,7 +72,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
this->setApplicationName(QGC_APPLICATION_NAME);
this->setApplicationVersion(QGC_APPLICATION_VERSION);
this->setOrganizationName(QLatin1String("diydrones"));
- this->setOrganizationDomain("org.diydrones");
+ this->setOrganizationDomain("com.diydrones");
// Set settings format
QSettings::setDefaultFormat(QSettings::IniFormat);
diff --git a/src/ui/configuration/AccelCalibrationConfig.ui b/src/ui/configuration/AccelCalibrationConfig.ui
index a1b99045e6bb722490a4ceefb2eebec1e7b946f4..6555a572584b14a77a048a68d7d8cb0a2ccd2c13 100644
--- a/src/ui/configuration/AccelCalibrationConfig.ui
+++ b/src/ui/configuration/AccelCalibrationConfig.ui
@@ -34,8 +34,8 @@
70
160
- 81
- 31
+ 111
+ 41
@@ -48,8 +48,8 @@ Accelerometer
20
50
- 211
- 91
+ 311
+ 101
diff --git a/src/ui/configuration/AdvParameterList.cc b/src/ui/configuration/AdvParameterList.cc
new file mode 100644
index 0000000000000000000000000000000000000000..e1abae86eca3d16cd500550c75d3d29330d07088
--- /dev/null
+++ b/src/ui/configuration/AdvParameterList.cc
@@ -0,0 +1,55 @@
+#include "AdvParameterList.h"
+
+
+AdvParameterList::AdvParameterList(QWidget *parent) : AP2ConfigWidget(parent)
+{
+ ui.setupUi(this);
+ ui.tableWidget->setColumnCount(4);
+ ui.tableWidget->horizontalHeader()->hide();
+ ui.tableWidget->verticalHeader()->hide();
+ //ui.tableWidget->setHorizontalHeader(0);
+ //ui.tableWidget->setVerticalHeader(0);
+ ui.tableWidget->setColumnWidth(0,200);
+ ui.tableWidget->setColumnWidth(1,100);
+ ui.tableWidget->setColumnWidth(2,200);
+ ui.tableWidget->setColumnWidth(3,800);
+
+}
+
+AdvParameterList::~AdvParameterList()
+{
+}
+void AdvParameterList::setParameterMetaData(QString name,QString humanname,QString description)
+{
+ paramToNameMap[name] = humanname;
+ paramToDescriptionMap[name] = description;
+}
+
+void AdvParameterList::parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+
+ if (!paramValueMap.contains(parameterName))
+ {
+ ui.tableWidget->setRowCount(ui.tableWidget->rowCount()+1);
+ if (paramToNameMap.contains(parameterName))
+ {
+ ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,0,new QTableWidgetItem(paramToNameMap[parameterName]));
+ }
+ else
+ {
+ ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,0,new QTableWidgetItem("Unknown"));
+ }
+ ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,1,new QTableWidgetItem(QString::number(value.toFloat(),'f',2)));
+ ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,2,new QTableWidgetItem(parameterName));
+ if (paramToDescriptionMap.contains(parameterName))
+ {
+ ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,3,new QTableWidgetItem(paramToDescriptionMap[parameterName]));
+ }
+ else
+ {
+ ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,3,new QTableWidgetItem("Unknown"));
+ }
+ paramValueMap[parameterName] = ui.tableWidget->item(ui.tableWidget->rowCount()-1,1);
+ }
+ paramValueMap[parameterName]->setText(QString::number(value.toFloat(),'f',2));
+}
diff --git a/src/ui/configuration/AdvParameterList.h b/src/ui/configuration/AdvParameterList.h
new file mode 100644
index 0000000000000000000000000000000000000000..6a530f9f193c5448755301b496a5f64da00e65e7
--- /dev/null
+++ b/src/ui/configuration/AdvParameterList.h
@@ -0,0 +1,25 @@
+#ifndef ADVPARAMETERLIST_H
+#define ADVPARAMETERLIST_H
+
+#include
+#include "ui_AdvParameterList.h"
+#include "AP2ConfigWidget.h"
+
+class AdvParameterList : public AP2ConfigWidget
+{
+ Q_OBJECT
+
+public:
+ explicit AdvParameterList(QWidget *parent = 0);
+ void setParameterMetaData(QString name,QString humanname,QString description);
+ ~AdvParameterList();
+private slots:
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
+private:
+ QMap paramValueMap;
+ QMap paramToNameMap;
+ QMap paramToDescriptionMap;
+ Ui::AdvParameterList ui;
+};
+
+#endif // ADVPARAMETERLIST_H
diff --git a/src/ui/configuration/AdvParameterList.ui b/src/ui/configuration/AdvParameterList.ui
new file mode 100644
index 0000000000000000000000000000000000000000..9b9d40849b5392d85b9da2e490ad3fe1a1f5ccdb
--- /dev/null
+++ b/src/ui/configuration/AdvParameterList.ui
@@ -0,0 +1,31 @@
+
+
+ AdvParameterList
+
+
+
+ 0
+ 0
+ 666
+ 497
+
+
+
+ Form
+
+
+ -
+
+
+ <h2>Advanced Parameter List</h2>
+
+
+
+ -
+
+
+
+
+
+
+
diff --git a/src/ui/configuration/AdvancedParamConfig.cc b/src/ui/configuration/AdvancedParamConfig.cc
index 4ab92e0b7583d15163b90081130216332aec02bb..5f4102c242e95bb9a217816adfc8484260811411 100644
--- a/src/ui/configuration/AdvancedParamConfig.cc
+++ b/src/ui/configuration/AdvancedParamConfig.cc
@@ -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)
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 > 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());
+ }
+}
diff --git a/src/ui/configuration/AdvancedParamConfig.h b/src/ui/configuration/AdvancedParamConfig.h
index 5cf8b9fafbcb6f93d329d4073c50a299020e4af8..9c69156d89b6b0b231a10148e2343d194de4bf61 100644
--- a/src/ui/configuration/AdvancedParamConfig.h
+++ b/src/ui/configuration/AdvancedParamConfig.h
@@ -3,16 +3,21 @@
#include
#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 > valuelist);
+private slots:
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
+ QMap paramToWidgetMap;
Ui::AdvancedParamConfig ui;
};
diff --git a/src/ui/configuration/AdvancedParamConfig.ui b/src/ui/configuration/AdvancedParamConfig.ui
index d49c182d9ee40ac0c53cb10e8a51472d81566983..596861a3a2aeb2ea2792cc74ea184cf89ee3dae1 100644
--- a/src/ui/configuration/AdvancedParamConfig.ui
+++ b/src/ui/configuration/AdvancedParamConfig.ui
@@ -6,26 +6,44 @@
0
0
- 400
- 300
+ 725
+ 632
Form
-
-
-
- 10
- 10
- 181
- 31
-
-
-
- <h2>Advanced Params</h2>
-
-
+
+ -
+
+
+ <h2>Advanced Params</h2>
+
+
+
+ -
+
+
+ true
+
+
+
+
+ 0
+ 0
+ 705
+ 585
+
+
+
+
-
+
+
+
+
+
+
+
diff --git a/src/ui/configuration/ApmHardwareConfig.cc b/src/ui/configuration/ApmHardwareConfig.cc
index 07c28f12f09f03ac27d73976c75e3c50257a5c0e..0341ab345bef34fc6ef8e39017c16fe409af8103 100644
--- a/src/ui/configuration/ApmHardwareConfig.cc
+++ b/src/ui/configuration/ApmHardwareConfig.cc
@@ -30,35 +30,28 @@ This file is part of the QGROUNDCONTROL project
*/
#include "ApmHardwareConfig.h"
-
ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
- //ui.firmwareButton->setVisible(valse);
+
+
ui.manditoryHardware->setVisible(false);
ui.frameTypeButton->setVisible(false);
ui.compassButton->setVisible(false);
ui.accelCalibrateButton->setVisible(false);
+ ui.arduPlaneLevelButton->setVisible(false);
ui.radioCalibrateButton->setVisible(false);
ui.optionalHardwareButton->setVisible(false);
- //ui.radio3DRButton->setVisible(false);
ui.batteryMonitorButton->setVisible(false);
ui.sonarButton->setVisible(false);
ui.airspeedButton->setVisible(false);
ui.opticalFlowButton->setVisible(false);
ui.osdButton->setVisible(false);
ui.cameraGimbalButton->setVisible(false);
- //ui.antennaTrackerButton->setVisible(false);
-
- connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.frameTypeButton,SLOT(setShown(bool)));
- connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setShown(bool)));
- connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.accelCalibrateButton,SLOT(setShown(bool)));
- connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setShown(bool)));
connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.radio3DRButton,SLOT(setShown(bool)));
connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.batteryMonitorButton,SLOT(setShown(bool)));
connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.sonarButton,SLOT(setShown(bool)));
- connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.airspeedButton,SLOT(setShown(bool)));
connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.opticalFlowButton,SLOT(setShown(bool)));
connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.osdButton,SLOT(setShown(bool)));
connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.cameraGimbalButton,SLOT(setShown(bool)));
@@ -87,6 +80,11 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap[ui.accelCalibrateButton] = accelConfig;
connect(ui.accelCalibrateButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
+ planeLevel = new ApmPlaneLevel(this);
+ ui.stackedWidget->addWidget(planeLevel);
+ buttonToConfigWidgetMap[ui.arduPlaneLevelButton] = planeLevel;
+ connect(ui.arduPlaneLevelButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
+
radioConfig = new RadioCalibrationConfig(this);
ui.stackedWidget->addWidget(radioConfig);
buttonToConfigWidgetMap[ui.radioCalibrateButton] = radioConfig;
@@ -133,8 +131,6 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap[ui.antennaTrackerButton] = antennaTrackerConfig;
connect(ui.antennaTrackerButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
-
-
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
if (UASManager::instance()->getActiveUAS())
{
@@ -159,11 +155,33 @@ void ApmHardwareConfig::activeUASSet(UASInterface *uas)
{
return;
}
+ if (uas->getSystemType() == MAV_TYPE_FIXED_WING)
+ {
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setShown(bool)));
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.arduPlaneLevelButton,SLOT(setShown(bool)));
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setShown(bool)));
+ connect(ui.optionalHardwareButton,SIGNAL(toggled(bool)),ui.airspeedButton,SLOT(setShown(bool)));
+ }
+ else if (uas->getSystemType() == MAV_TYPE_QUADROTOR)
+ {
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.frameTypeButton,SLOT(setShown(bool)));
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setShown(bool)));
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.accelCalibrateButton,SLOT(setShown(bool)));
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setShown(bool)));
+ }
+ else if (uas->getSystemType() == MAV_TYPE_GROUND_ROVER)
+ {
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setShown(bool)));
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setShown(bool)));
+ }
+ else
+ {
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.compassButton,SLOT(setShown(bool)));
+ connect(ui.manditoryHardware,SIGNAL(toggled(bool)),ui.radioCalibrateButton,SLOT(setShown(bool)));
+ }
ui.firmwareButton->setVisible(true);
ui.manditoryHardware->setVisible(true);
- ui.manditoryHardware->setChecked(false);
+ ui.manditoryHardware->setChecked(true);
ui.optionalHardwareButton->setVisible(true);
- ui.optionalHardwareButton->setChecked(false);
- ui.radio3DRButton->setVisible(false);
- ui.antennaTrackerButton->setVisible(false);
+ ui.optionalHardwareButton->setChecked(true);
}
diff --git a/src/ui/configuration/ApmHardwareConfig.h b/src/ui/configuration/ApmHardwareConfig.h
index e21fe05d70a850f02f95d73400b106f2bfb3f5c5..6d48bf95476f43bff38695a1b1141f1dfc0b292a 100644
--- a/src/ui/configuration/ApmHardwareConfig.h
+++ b/src/ui/configuration/ApmHardwareConfig.h
@@ -48,6 +48,7 @@ This file is part of the QGROUNDCONTROL project
#include "OsdConfig.h"
#include "CameraGimbalConfig.h"
#include "AntennaTrackerConfig.h"
+#include "ApmPlaneLevel.h"
class ApmHardwareConfig : public QWidget
{
@@ -70,6 +71,7 @@ private:
OsdConfig *osdConfig;
CameraGimbalConfig *cameraGimbalConfig;
AntennaTrackerConfig *antennaTrackerConfig;
+ ApmPlaneLevel *planeLevel;
private slots:
void activeUASSet(UASInterface *uas);
void activateStackedWidget();
diff --git a/src/ui/configuration/ApmHardwareConfig.ui b/src/ui/configuration/ApmHardwareConfig.ui
index 1a514ede9272239c6f72a2816f3b26c7924e401d..e4a711b060d08d3c1cb58b395d54e9341587cb41 100644
--- a/src/ui/configuration/ApmHardwareConfig.ui
+++ b/src/ui/configuration/ApmHardwareConfig.ui
@@ -43,7 +43,7 @@
0
0
156
- 635
+ 676
@@ -129,6 +129,25 @@
+ -
+
+
+
+ 0
+ 35
+
+
+
+ Qt::LeftToRight
+
+
+ false
+
+
+ ArduPlane Level
+
+
+
-
diff --git a/src/ui/configuration/ApmPlaneLevel.cc b/src/ui/configuration/ApmPlaneLevel.cc
new file mode 100644
index 0000000000000000000000000000000000000000..7b00374834ebdadee6eaac9418b0310f09bc66ae
--- /dev/null
+++ b/src/ui/configuration/ApmPlaneLevel.cc
@@ -0,0 +1,59 @@
+#include "ApmPlaneLevel.h"
+#include
+
+ApmPlaneLevel::ApmPlaneLevel(QWidget *parent) : AP2ConfigWidget(parent)
+{
+ ui.setupUi(this);
+ connect(ui.levelPushButton,SIGNAL(clicked()),this,SLOT(levelClicked()));
+ connect(ui.manualLevelCheckBox,SIGNAL(toggled(bool)),this,SLOT(manualCheckBoxToggled(bool)));
+}
+
+ApmPlaneLevel::~ApmPlaneLevel()
+{
+}
+void ApmPlaneLevel::levelClicked()
+{
+ QMessageBox::information(0,"Warning","Be sure the plane is completly level, then click ok");
+ MAV_CMD command = MAV_CMD_PREFLIGHT_CALIBRATION;
+ int confirm = 0;
+ float param1 = 1;
+ float param2 = 0;
+ float param3 = 1;
+ float param4 = 0;
+ float param5 = 0;
+ float param6 = 0;
+ float param7 = 0;
+ int component = 1;
+ m_uas->executeCommand(command, confirm, param1, param2, param3, param4, param5, param6, param7, component);
+ QMessageBox::information(0,"Warning","Leveling completed");
+}
+
+void ApmPlaneLevel::manualCheckBoxToggled(bool checked)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ if (checked)
+ {
+ m_uas->getParamManager()->setParameter(1,"MANUAL_LEVEL",1);
+ }
+ else
+ {
+ m_uas->getParamManager()->setParameter(1,"MANUAL_LEVEL",0);
+ }
+}
+void ApmPlaneLevel::parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+ if (parameterName == "MANUAL_LEVEL")
+ {
+ if (value.toInt() == 1)
+ {
+ ui.manualLevelCheckBox->setChecked(true);
+ }
+ else
+ {
+ ui.manualLevelCheckBox->setChecked(false);
+ }
+ }
+}
diff --git a/src/ui/configuration/ApmPlaneLevel.h b/src/ui/configuration/ApmPlaneLevel.h
new file mode 100644
index 0000000000000000000000000000000000000000..a6a38078f3704b10a283126fc84a6aebfe8738bd
--- /dev/null
+++ b/src/ui/configuration/ApmPlaneLevel.h
@@ -0,0 +1,23 @@
+#ifndef APMPLANELEVEL_H
+#define APMPLANELEVEL_H
+
+#include
+#include "ui_ApmPlaneLevel.h"
+#include "AP2ConfigWidget.h"
+
+class ApmPlaneLevel : public AP2ConfigWidget
+{
+ Q_OBJECT
+
+public:
+ explicit ApmPlaneLevel(QWidget *parent = 0);
+ ~ApmPlaneLevel();
+private slots:
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
+ void levelClicked();
+ void manualCheckBoxToggled(bool checked);
+private:
+ Ui::ApmPlaneLevel ui;
+};
+
+#endif // APMPLANELEVEL_H
diff --git a/src/ui/configuration/ApmPlaneLevel.ui b/src/ui/configuration/ApmPlaneLevel.ui
new file mode 100644
index 0000000000000000000000000000000000000000..ef22b19992f262acf776e84fbfca097e2074c997
--- /dev/null
+++ b/src/ui/configuration/ApmPlaneLevel.ui
@@ -0,0 +1,99 @@
+
+
+ ApmPlaneLevel
+
+
+
+ 0
+ 0
+ 400
+ 300
+
+
+
+ Form
+
+
+
+
+ 10
+ 10
+ 141
+ 31
+
+
+
+ <h2>ArduPlane Level</h2>
+
+
+
+
+
+ 50
+ 70
+ 271
+ 41
+
+
+
+ By Default your plane will autolevel on every boot.
+To disable this action you need to turn on manual
+level and perform a level to calibrate the accel offsets.
+
+
+
+
+
+ 50
+ 150
+ 291
+ 16
+
+
+
+ Level your plane and click Level to set default accel offsets
+
+
+
+
+
+ 160
+ 180
+ 75
+ 23
+
+
+
+ Level
+
+
+
+
+
+ 120
+ 230
+ 151
+ 51
+
+
+
+ For advanced users ONLY
+
+
+
+
+ 30
+ 20
+ 91
+ 17
+
+
+
+ Manual Level
+
+
+
+
+
+
+
diff --git a/src/ui/configuration/ApmSoftwareConfig.cc b/src/ui/configuration/ApmSoftwareConfig.cc
index cfecf5de17669b998d058ae653c7eea453748eeb..0412287222b5aa94171c5b9fba035793bdda3be9 100644
--- a/src/ui/configuration/ApmSoftwareConfig.cc
+++ b/src/ui/configuration/ApmSoftwareConfig.cc
@@ -1,23 +1,21 @@
#include "ApmSoftwareConfig.h"
+#include
+#include
+#include
ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
- ui.basicPidsButton->setVisible(false);
ui.flightModesButton->setVisible(false);
ui.standardParamButton->setVisible(false);
- ui.geoFenceButton->setVisible(false);
ui.failSafeButton->setVisible(false);
ui.advancedParamButton->setVisible(false);
ui.advParamListButton->setVisible(false);
- ui.arduCoperPidButton->setVisible(false);
-
- basicPidConfig = new BasicPidConfig(this);
- ui.stackedWidget->addWidget(basicPidConfig);
- buttonToConfigWidgetMap[ui.basicPidsButton] = basicPidConfig;
- connect(ui.basicPidsButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
+ ui.arduCopterPidButton->setVisible(false);
+ ui.arduRoverPidButton->setVisible(false);
+ ui.arduPlanePidButton->setVisible(false);
flightConfig = new FlightModeConfig(this);
ui.stackedWidget->addWidget(flightConfig);
@@ -29,11 +27,6 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap[ui.standardParamButton] = standardParamConfig;
connect(ui.standardParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
- geoFenceConfig = new GeoFenceConfig(this);
- ui.stackedWidget->addWidget(geoFenceConfig);
- buttonToConfigWidgetMap[ui.geoFenceButton] = geoFenceConfig;
- connect(ui.geoFenceButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
-
failSafeConfig = new FailSafeConfig(this);
ui.stackedWidget->addWidget(failSafeConfig);
buttonToConfigWidgetMap[ui.failSafeButton] = failSafeConfig;
@@ -44,10 +37,25 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap[ui.advancedParamButton] = advancedParamConfig;
connect(ui.advancedParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
- arduCoperPidConfig = new ArduCopterPidConfig(this);
- ui.stackedWidget->addWidget(arduCoperPidConfig);
- buttonToConfigWidgetMap[ui.arduCoperPidButton] = arduCoperPidConfig;
- connect(ui.arduCoperPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
+ advParameterList = new AdvParameterList(this);
+ ui.stackedWidget->addWidget(advParameterList);
+ buttonToConfigWidgetMap[ui.advParamListButton] = advParameterList;
+ connect(ui.advParamListButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
+
+ arduCopterPidConfig = new ArduCopterPidConfig(this);
+ ui.stackedWidget->addWidget(arduCopterPidConfig);
+ buttonToConfigWidgetMap[ui.arduCopterPidButton] = arduCopterPidConfig;
+ connect(ui.arduCopterPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
+
+ arduPlanePidConfig = new ArduPlanePidConfig(this);
+ ui.stackedWidget->addWidget(arduPlanePidConfig);
+ buttonToConfigWidgetMap[ui.arduPlanePidButton] = arduPlanePidConfig;
+ connect(ui.arduPlanePidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
+
+ arduRoverPidConfig = new ArduRoverPidConfig(this);
+ ui.stackedWidget->addWidget(arduRoverPidConfig);
+ buttonToConfigWidgetMap[ui.arduRoverPidButton] = arduRoverPidConfig;
+ connect(ui.arduRoverPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
if (UASManager::instance()->getActiveUAS())
@@ -73,13 +81,383 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
return;
}
- ui.basicPidsButton->setVisible(true);
ui.flightModesButton->setVisible(true);
ui.standardParamButton->setVisible(true);
- ui.geoFenceButton->setVisible(true);
ui.failSafeButton->setVisible(true);
ui.advancedParamButton->setVisible(true);
ui.advParamListButton->setVisible(true);
- ui.arduCoperPidButton->setVisible(true);
+ if (uas->getSystemType() == MAV_TYPE_FIXED_WING)
+ {
+ ui.arduPlanePidButton->setVisible(true);
+ ui.arduCopterPidButton->setVisible(false);
+ ui.arduRoverPidButton->setVisible(false);
+ }
+ else if (uas->getSystemType() == MAV_TYPE_QUADROTOR)
+ {
+ ui.arduCopterPidButton->setVisible(true);
+ ui.arduPlanePidButton->setVisible(false);
+ ui.arduRoverPidButton->setVisible(false);
+ }
+ else if (uas->getSystemType() == MAV_TYPE_GROUND_ROVER)
+ {
+ ui.arduRoverPidButton->setVisible(true);
+ ui.arduCopterPidButton->setVisible(false);
+ ui.arduPlanePidButton->setVisible(false);
+ }
+
+
+ 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.
+ //Also, move this into the Param Manager, as it should handle all metadata.
+ 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 fieldmap;
+ QMap 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 > valuelist;
+ for (QMap::const_iterator i = valuemap.constBegin();i!=valuemap.constEnd();i++)
+ {
+ valuelist.append(QPair(i.key().toInt(),i.value()));
+ }
+ if (tab == "Standard")
+ {
+ standardParamConfig->addCombo(humanname,docs,name,valuelist);
+ }
+ else if (tab == "Advanced")
+ {
+ advancedParamConfig->addCombo(humanname,docs,name,valuelist);
+ }
+ advParameterList->setParameterMetaData(name,humanname,docs);
+ }
+ 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);
+ }
+ advParameterList->setParameterMetaData(name,humanname,docs);
+ }
+
+ }
+ xml.readNext();
+ }
+ if (genarraycount > 0)
+ {
+ /*
+ tool = new QGCToolWidget("", this);
+ tool->addUAS(mav);
+ tool->setTitle(parametersname);
+ tool->setObjectName(parametersname);
+ tool->setSettings(genset);
+ QList paramlist = tool->getParamList();
+ for (int i=0;iinsert(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 paramlist = tool->getParamList();
+ for (int i=0;iinsert(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();
+ }
+
}
diff --git a/src/ui/configuration/ApmSoftwareConfig.h b/src/ui/configuration/ApmSoftwareConfig.h
index c28d366b0ecaf9a90e9a8d2774995cb12eb3747c..7b0b5138e36705c361f3dc81c3098a5b36f3d96f 100644
--- a/src/ui/configuration/ApmSoftwareConfig.h
+++ b/src/ui/configuration/ApmSoftwareConfig.h
@@ -10,7 +10,9 @@
#include "FailSafeConfig.h"
#include "AdvancedParamConfig.h"
#include "ArduCopterPidConfig.h"
-
+#include "ArduPlanePidConfig.h"
+#include "ArduRoverPidConfig.h"
+#include "AdvParameterList.h"
#include "UASInterface.h"
#include "UASManager.h"
@@ -32,7 +34,10 @@ private:
GeoFenceConfig *geoFenceConfig;
FailSafeConfig *failSafeConfig;
AdvancedParamConfig *advancedParamConfig;
- ArduCopterPidConfig *arduCoperPidConfig;
+ ArduCopterPidConfig *arduCopterPidConfig;
+ ArduPlanePidConfig *arduPlanePidConfig;
+ ArduRoverPidConfig *arduRoverPidConfig;
+ AdvParameterList *advParameterList;
QMap buttonToConfigWidgetMap;
};
diff --git a/src/ui/configuration/ApmSoftwareConfig.ui b/src/ui/configuration/ApmSoftwareConfig.ui
index ab26e10fbeb7300b9df4d0b5953647efd832a459..c29e3b6ff7e9e85f421d04ab5471ac08e41d67ee 100644
--- a/src/ui/configuration/ApmSoftwareConfig.ui
+++ b/src/ui/configuration/ApmSoftwareConfig.ui
@@ -6,221 +6,204 @@
0
0
- 718
- 531
+ 853
+ 619
Form
-
-
-
- 20
- 10
- 175
- 531
-
-
-
-
- 175
- 0
-
-
-
-
- 175
- 16777215
-
-
-
- true
-
-
-
-
- 0
- 0
- 173
- 529
-
-
-
-
-
-
-
- QLayout::SetMinAndMaxSize
-
+
+
-
+
+
+
+ 175
+ 0
+
+
+
+
+ 175
+ 16777215
+
+
+
+ true
+
+
+
+
+ 0
+ 0
+ 173
+ 599
+
+
+
-
-
-
-
- 100
- 35
-
-
-
- APM Planner 2.0 Config
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- Basic Pids
-
-
- false
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- Flight Modes
-
-
- false
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- Standard Params
-
-
- false
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- GeoFence
-
-
- false
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- FailSafe
-
-
- false
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- Advanced Params
-
-
- false
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- Adv Parameter List
-
-
- false
-
-
-
- -
-
-
-
- 0
- 35
-
-
-
- ArduCoper Pids
-
-
- false
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 40
-
-
-
+
+
+ QLayout::SetMinAndMaxSize
+
+
-
+
+
+
+ 100
+ 35
+
+
+
+ APM Planner 2.0 Config
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ Flight Modes
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ Standard Params
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ FailSafe
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ Advanced Params
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ Adv Parameter List
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ ArduCopter Pids
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ ArduPlane Pids
+
+
+
+ -
+
+
+
+ 0
+ 35
+
+
+
+ ArduRover Pids
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
-
-
-
-
-
-
-
- 220
- 20
- 471
- 491
-
-
-
+
+
+
+ -
+
+
+
diff --git a/src/ui/configuration/ArduCopterPidConfig.cc b/src/ui/configuration/ArduCopterPidConfig.cc
index 1674ae23623fa0cec3ae2ac860b07215f4e71479..f64dec4c2b628b331a764f63b98fc0c821056736 100644
--- a/src/ui/configuration/ArduCopterPidConfig.cc
+++ b/src/ui/configuration/ArduCopterPidConfig.cc
@@ -1,14 +1,196 @@
#include "ArduCopterPidConfig.h"
-#include "ui_ArduCopterPidConfig.h"
-ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) :
- QWidget(parent),
- ui(new Ui::ArduCopterPidConfig)
+ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
- ui->setupUi(this);
+ ui.setupUi(this);
+ nameToBoxMap["STB_RLL_P"] = ui.stabilPitchPSpinBox;
+ nameToBoxMap["STB_PIT_P"] = ui.stabilRollPSpinBox;
+ nameToBoxMap["STB_YAW_P"] = ui.stabilYawPSpinBox;
+ nameToBoxMap["HLD_LAT_P"] = ui.loiterPidPSpinBox;
+
+ nameToBoxMap["RATE_RLL_P"] = ui.rateRollPSpinBox;
+ nameToBoxMap["RATE_RLL_I"] = ui.rateRollISpinBox;
+ nameToBoxMap["RATE_RLL_D"] = ui.rateRollDSpinBox;
+ nameToBoxMap["RATE_RLL_IMAX"] = ui.rateRollIMAXSpinBox;
+
+ nameToBoxMap["RATE_PIT_P"] = ui.ratePitchPSpinBox;
+ nameToBoxMap["RATE_PIT_I"] = ui.ratePitchISpinBox;
+ nameToBoxMap["RATE_PIT_D"] = ui.ratePitchDSpinBox;
+ nameToBoxMap["RATE_PIT_IMAX"] = ui.ratePitchIMAXSpinBox;
+
+ nameToBoxMap["RATE_YAW_P"] = ui.rateYawPSpinBox;
+ nameToBoxMap["RATE_YAW_I"] = ui.rateYawISpinBox;
+ nameToBoxMap["RATE_YAW_D"] = ui.rateYawDSpinBox;
+ nameToBoxMap["RATE_YAW_IMAX"] = ui.rateYawIMAXSpinBox;
+
+ nameToBoxMap["LOITER_LAT_P"] = ui.rateLoiterPSpinBox;
+ nameToBoxMap["LOITER_LAT_I"] = ui.rateLoiterISpinBox;
+ nameToBoxMap["LOITER_LAT_D"] = ui.rateLoiterDSpinBox;
+ nameToBoxMap["LOITER_LAT_IMAX"] = ui.rateLoiterIMAXSpinBox;
+
+ nameToBoxMap["THR_ACCEL_P"] = ui.throttleAccelPSpinBox;
+ nameToBoxMap["THR_ACCEL_I"] = ui.throttleAccelISpinBox;
+ nameToBoxMap["THR_ACCEL_D"] = ui.throttleAccelDSpinBox;
+ nameToBoxMap["THR_ACCEL_IMAX"] = ui.throttleAccelIMAXSpinBox;
+
+ nameToBoxMap["THR_RATE_P"] = ui.throttleRatePSpinBox;
+ nameToBoxMap["THR_RATE_D"] = ui.throttleDateDSpinBox;
+
+ nameToBoxMap["THR_ALT_P"] = ui.altitudeHoldPSpinBox;
+
+ nameToBoxMap["WPNAV_SPEED"] = ui.wpNavLoiterSpeedSpinBox;
+ nameToBoxMap["WPNAV_RADIUS"] = ui.wpNavRadiusSpinBox;
+ nameToBoxMap["WPNAV_SPEED_DN"] = ui.wpNavSpeedDownSpinBox;
+ nameToBoxMap["WPNAV_LOIT_SPEED"] = ui.wpNavSpeedSpinBox;
+ nameToBoxMap["WPNAV_SPEED_UP"] = ui.wpNavSpeedUpSpinBox;
+
+ nameToBoxMap["TUNE_HIGH"] = ui.ch6MaxSpinBox;
+ nameToBoxMap["TUNE_LOW"] = ui.ch6MinSpinBox;
+
+ connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
+ connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
+
+
+
+ ch6ValueToTextList.append(QPair(0,"CH6_NONE"));
+ ch6ValueToTextList.append(QPair(1,"CH6_STABILIZE_KP"));
+ ch6ValueToTextList.append(QPair(2,"CH6_STABILIZE_KI"));
+ ch6ValueToTextList.append(QPair(3,"CH6_YAW_KP"));
+ ch6ValueToTextList.append(QPair(24,"CH6_YAW_KI"));
+ ch6ValueToTextList.append(QPair(4,"CH6_RATE_KP"));
+ ch6ValueToTextList.append(QPair(5,"CH6_RATE_KI"));
+ ch6ValueToTextList.append(QPair(6,"CH6_YAW_RATE_KP"));
+ ch6ValueToTextList.append(QPair(26,"CH6_YAW_RATE_KD"));
+ ch6ValueToTextList.append(QPair(7,"CH6_THROTTLE_KP"));
+ ch6ValueToTextList.append(QPair(9,"CH6_RELAY"));
+ ch6ValueToTextList.append(QPair(10,"CH6_WP_SPEED"));
+ ch6ValueToTextList.append(QPair(12,"CH6_LOITER_KP"));
+ ch6ValueToTextList.append(QPair(13,"CH6_HELI_EXTERNAL_GYRO"));
+ ch6ValueToTextList.append(QPair(14,"CH6_THR_HOLD_KP"));
+ ch6ValueToTextList.append(QPair(17,"CH6_OPTFLOW_KP"));
+ ch6ValueToTextList.append(QPair(18,"CH6_OPTFLOW_KI"));
+ ch6ValueToTextList.append(QPair(19,"CH6_OPTFLOW_KD"));
+ ch6ValueToTextList.append(QPair(21,"CH6_RATE_KD"));
+ ch6ValueToTextList.append(QPair(22,"CH6_LOITER_RATE_KP"));
+ ch6ValueToTextList.append(QPair(23,"CH6_LOITER_RATE_KD"));
+ ch6ValueToTextList.append(QPair(25,"CH6_ACRO_KP"));
+ ch6ValueToTextList.append(QPair(27,"CH6_LOITER_KI"));
+ ch6ValueToTextList.append(QPair(28,"CH6_LOITER_RATE_KI"));
+ ch6ValueToTextList.append(QPair(29,"CH6_STABILIZE_KD"));
+ ch6ValueToTextList.append(QPair(30,"CH6_AHRS_YAW_KP"));
+ ch6ValueToTextList.append(QPair(31,"CH6_AHRS_KP"));
+ ch6ValueToTextList.append(QPair(32,"CH6_INAV_TC"));
+ ch6ValueToTextList.append(QPair(33,"CH6_THROTTLE_KI"));
+ ch6ValueToTextList.append(QPair(34,"CH6_THR_ACCEL_KP"));
+ ch6ValueToTextList.append(QPair(35,"CH6_THR_ACCEL_KI"));
+ ch6ValueToTextList.append(QPair(36,"CH6_THR_ACCEL_KD"));
+ ch6ValueToTextList.append(QPair(38,"CH6_DECLINATION"));
+ ch6ValueToTextList.append(QPair(39,"CH6_CIRCLE_RATE"));
+ for (int i=0;iaddItem(ch6ValueToTextList[i].second);
+ }
+
+ ch7ValueToTextList.append(QPair(0,"Do nothing"));
+ ch7ValueToTextList.append(QPair(2,"Flip"));
+ ch7ValueToTextList.append(QPair(3,"Simple mode"));
+ ch7ValueToTextList.append(QPair(4,"RTL"));
+ ch7ValueToTextList.append(QPair(5,"Save Trim"));
+ ch7ValueToTextList.append(QPair(7,"Save WP"));
+ ch7ValueToTextList.append(QPair(8,"Multi Mode"));
+ ch7ValueToTextList.append(QPair(9,"Camera Trigger"));
+ ch7ValueToTextList.append(QPair(10,"Sonar"));
+ ch7ValueToTextList.append(QPair(11,"Fence"));
+ ch7ValueToTextList.append(QPair(12,"ResetToArmedYaw"));
+ for (int i=0;iaddItem(ch7ValueToTextList[i].second);
+ }
+
+ ch8ValueToTextList.append(QPair(0,"Do nothing"));
+ ch8ValueToTextList.append(QPair(2,"Flip"));
+ ch8ValueToTextList.append(QPair(3,"Simple mode"));
+ ch8ValueToTextList.append(QPair(4,"RTL"));
+ ch8ValueToTextList.append(QPair(5,"Save Trim"));
+ ch8ValueToTextList.append(QPair(7,"Save WP"));
+ ch8ValueToTextList.append(QPair(8,"Multi Mode"));
+ ch8ValueToTextList.append(QPair(9,"Camera Trigger"));
+ ch8ValueToTextList.append(QPair(10,"Sonar"));
+ ch8ValueToTextList.append(QPair(11,"Fence"));
+ ch8ValueToTextList.append(QPair(12,"ResetToArmedYaw"));
+ for (int i=0;iaddItem(ch8ValueToTextList[i].second);
+ }
+
}
ArduCopterPidConfig::~ArduCopterPidConfig()
{
- delete ui;
+}
+void ArduCopterPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+ if (nameToBoxMap.contains(parameterName))
+ {
+ nameToBoxMap[parameterName]->setValue(value.toDouble());
+ }
+ else if (parameterName == "TUNE")
+ {
+ for (int i=0;isetCurrentIndex(i);
+ }
+ }
+ }
+ else if (parameterName == "CH7_OPT")
+ {
+ for (int i=0;isetCurrentIndex(i);
+ }
+ }
+ }
+ else if (parameterName == "CH8_OPT")
+ {
+ for (int i=0;isetCurrentIndex(i);
+ }
+ }
+ }
+}
+void ArduCopterPidConfig::writeButtonClicked()
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
+ {
+ m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value());
+ }
+ m_uas->getParamManager()->setParameter(1,"TUNE",ch8ValueToTextList[ui.ch6OptComboBox->currentIndex()].first);
+ m_uas->getParamManager()->setParameter(1,"CH7_OPT",ch7ValueToTextList[ui.ch7OptComboBox->currentIndex()].first);
+ m_uas->getParamManager()->setParameter(1,"CH8_OPT",ch8ValueToTextList[ui.ch8OptComboBox->currentIndex()].first);
+}
+
+void ArduCopterPidConfig::refreshButtonClicked()
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
+ {
+ m_uas->getParamManager()->requestParameterUpdate(1,i.key());
+ }
+ m_uas->getParamManager()->requestParameterUpdate(1,"TUNE");
+ m_uas->getParamManager()->requestParameterUpdate(1,"CH7_OPT");
+ m_uas->getParamManager()->requestParameterUpdate(1,"CH8_OPT");
}
diff --git a/src/ui/configuration/ArduCopterPidConfig.h b/src/ui/configuration/ArduCopterPidConfig.h
index 6f7eae7e8545235a9f05887b4d1cb152d1f6059c..dff3bb5a55465a9b7b943038786aca5d6705afb2 100644
--- a/src/ui/configuration/ArduCopterPidConfig.h
+++ b/src/ui/configuration/ArduCopterPidConfig.h
@@ -2,21 +2,27 @@
#define ARDUCOPTERPIDCONFIG_H
#include
+#include "ui_ArduCopterPidConfig.h"
-namespace Ui {
-class ArduCopterPidConfig;
-}
+#include "AP2ConfigWidget.h"
-class ArduCopterPidConfig : public QWidget
+class ArduCopterPidConfig : public AP2ConfigWidget
{
Q_OBJECT
public:
explicit ArduCopterPidConfig(QWidget *parent = 0);
~ArduCopterPidConfig();
-
+private slots:
+ void writeButtonClicked();
+ void refreshButtonClicked();
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
- Ui::ArduCopterPidConfig *ui;
+ QList > ch6ValueToTextList;
+ QList > ch7ValueToTextList;
+ QList > ch8ValueToTextList;
+ QMap nameToBoxMap;
+ Ui::ArduCopterPidConfig ui;
};
#endif // ARDUCOPTERPIDCONFIG_H
diff --git a/src/ui/configuration/ArduCopterPidConfig.ui b/src/ui/configuration/ArduCopterPidConfig.ui
index a472f6a8f75c96e1f40aded60bcbdfa5085f61dd..351ce51ed24e4463b9c9ac508fe2bea5c50730df 100644
--- a/src/ui/configuration/ArduCopterPidConfig.ui
+++ b/src/ui/configuration/ArduCopterPidConfig.ui
@@ -6,8 +6,8 @@
0
0
- 400
- 300
+ 750
+ 596
@@ -26,6 +26,1035 @@
<h2>ArduCopter Pids</h2>
+
+
+
+ 120
+ 540
+ 75
+ 23
+
+
+
+ Write Params
+
+
+
+
+
+ 220
+ 540
+ 91
+ 23
+
+
+
+ Refresh Params
+
+
+
+
+
+ 10
+ 70
+ 695
+ 401
+
+
+
+ -
+
+
+ Rate Yaw
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Loiter PID
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Rate Pitch
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Stabilize Roll
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Stabilize Pitch
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Rate Roll
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Altitude Hold
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Stabilize Yaw
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Rate Loiter
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Lock Pitch and Roll Values
+
+
+
+ -
+
+
-
+
+
-
+
+
+ Ch6 Opt
+
+
+
+ -
+
+
+
+
+ -
+
+
-
+
+
+ Min
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ Max
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+ -
+
+
-
+
+
+ Ch7 Opt
+
+
+
+ -
+
+
+
+
+ -
+
+
-
+
+
+ Ch8 Opt
+
+
+
+ -
+
+
+
+
+
+
+ -
+
+
+ Throttle Accel
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
+
+
+ -
+
+
+ Throttle Rate
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ D
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
+
+
+ -
+
+
+ WPNav (cm's)
+
+
+
-
+
+
-
+
+
-
+
+
+ Speed
+
+
+
+ -
+
+
+ Radius
+
+
+
+ -
+
+
+ Speed Up
+
+
+
+ -
+
+
+ speed Down
+
+
+
+ -
+
+
+ Loiter Speed
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/ui/configuration/ArduPlanePidConfig.cc b/src/ui/configuration/ArduPlanePidConfig.cc
new file mode 100644
index 0000000000000000000000000000000000000000..f97e6af607edc98d3cd67004b97367b7ba4bce6b
--- /dev/null
+++ b/src/ui/configuration/ArduPlanePidConfig.cc
@@ -0,0 +1,97 @@
+#include "ArduPlanePidConfig.h"
+
+
+ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent)
+{
+ ui.setupUi(this);
+
+ nameToBoxMap["RLL2SRV_P"] = ui.servoRollPSpinBox;
+ nameToBoxMap["RLL2SRV_I"] = ui.servoRollISpinBox;
+ nameToBoxMap["RLL2SRV_D"] = ui.servoRollDSpinBox;
+ nameToBoxMap["RLL2SRV_IMAX"] = ui.servoRollIMAXSpinBox;
+
+ nameToBoxMap["PTCH2SRV_P"] = ui.servoPitchPSpinBox;
+ nameToBoxMap["PTCH2SRV_I"] = ui.servoPitchISpinBox;
+ nameToBoxMap["PTCH2SRV_D"] = ui.servoPitchDSpinBox;
+ nameToBoxMap["PTCH2SRV_IMAX"] = ui.servoPitchIMAXSpinBox;
+
+ nameToBoxMap["YW2SRV_P"] = ui.servoYawPSpinBox;
+ nameToBoxMap["YW2SRV_I"] = ui.servoYawISpinBox;
+ nameToBoxMap["YW2SRV_D"] = ui.servoYawDSpinBox;
+ nameToBoxMap["YW2SRV_IMAX"] = ui.servoYawIMAXSpinBox;
+
+ nameToBoxMap["ALT2PTCH_P"] = ui.navAltPSpinBox;
+ nameToBoxMap["ALT2PTCH_I"] = ui.navAltISpinBox;
+ nameToBoxMap["ALT2PTCH_D"] = ui.navAltDSpinBox;
+ nameToBoxMap["ALT2PTCH_IMAX"] = ui.navAltIMAXSpinBox;
+
+ nameToBoxMap["ARSP2PTCH_P"] = ui.navASPSpinBox;
+ nameToBoxMap["ARSP2PTCH_I"] = ui.navASISpinBox;
+ nameToBoxMap["ARSP2PTCH_D"] = ui.navASDSpinBox;
+ nameToBoxMap["ARSP2PTCH_IMAX"] = ui.navASIMAXSpinBox;
+
+ nameToBoxMap["ENRGY2THR_P"] = ui.energyPSpinBox;
+ nameToBoxMap["ENRGY2THR_I"] = ui.energyISpinBox;
+ nameToBoxMap["ENRGY2THR_D"] = ui.energyDSpinBox;
+ nameToBoxMap["ENRGY2THR_IMAX"] = ui.energyIMAXSpinBox;
+
+ nameToBoxMap["KFF_PTCH2THR"] = ui.otherPitchCompSpinBox;
+ nameToBoxMap["KFF_PTCHCOMP"] = ui.otherPtTSpinBox;
+ nameToBoxMap["KFF_RDDRMIX"] = ui.otherRudderMixSpinBox;
+
+ nameToBoxMap["TRIM_THROTTLE"] = ui.throttleCruiseSpinBox;
+ nameToBoxMap["THR_FS_VALUE"] = ui.throttleFSSpinBox;
+ nameToBoxMap["THR_MAX"] = ui.throttleMaxSpinBox;
+ nameToBoxMap["THR_MIN"] = ui.throttleMinSpinBox;
+
+ nameToBoxMap["TRIM_ARSPD_CM"] = ui.airspeedCruiseSpinBox;
+ nameToBoxMap["ARSPD_FBW_MAX"] = ui.airspeedFBWMaxSpinBox;
+ nameToBoxMap["ARSPD_FBW_MIN"] = ui.airspeedFBWMinSpinBox;
+ nameToBoxMap["ARSPD_RATIO"] = ui.airspeedRatioSpinBox;
+
+ nameToBoxMap["NAVL1_DAMPING"] = ui.l1DampingSpinBox;
+ nameToBoxMap["NAVL1_PERIOD"] = ui.l1PeriodSpinBox;
+
+ nameToBoxMap["LIM_ROLL_CD"] = ui.navBankMaxSpinBox;
+ nameToBoxMap["LIM_PITCH_MAX"] = ui.navPitchMaxSpinBox;
+ nameToBoxMap["LIM_PITCH_MIN"] = ui.navPitchMinSpinBox;
+
+ connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
+ connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
+
+}
+
+ArduPlanePidConfig::~ArduPlanePidConfig()
+{
+}
+void ArduPlanePidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+ if (nameToBoxMap.contains(parameterName))
+ {
+ nameToBoxMap[parameterName]->setValue(value.toDouble());
+ }
+}
+void ArduPlanePidConfig::writeButtonClicked()
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
+ {
+ m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value());
+ }
+}
+
+void ArduPlanePidConfig::refreshButtonClicked()
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
+ {
+ m_uas->getParamManager()->requestParameterUpdate(1,i.key());
+ }
+
+}
diff --git a/src/ui/configuration/ArduPlanePidConfig.h b/src/ui/configuration/ArduPlanePidConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..b0f12c4b8d1623eebcfaba037663622a7e27302c
--- /dev/null
+++ b/src/ui/configuration/ArduPlanePidConfig.h
@@ -0,0 +1,24 @@
+#ifndef ARDUPLANEPIDCONFIG_H
+#define ARDUPLANEPIDCONFIG_H
+
+#include
+#include "ui_ArduPlanePidConfig.h"
+#include "AP2ConfigWidget.h"
+
+class ArduPlanePidConfig : public AP2ConfigWidget
+{
+ Q_OBJECT
+
+public:
+ explicit ArduPlanePidConfig(QWidget *parent = 0);
+ ~ArduPlanePidConfig();
+private slots:
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
+ void writeButtonClicked();
+ void refreshButtonClicked();
+private:
+ QMap nameToBoxMap;
+ Ui::ArduPlanePidConfig ui;
+};
+
+#endif // ARDUPLANEPIDCONFIG_H
diff --git a/src/ui/configuration/ArduPlanePidConfig.ui b/src/ui/configuration/ArduPlanePidConfig.ui
new file mode 100644
index 0000000000000000000000000000000000000000..4ee4c406b15f97f025969bdefc401c22fe9a3fd6
--- /dev/null
+++ b/src/ui/configuration/ArduPlanePidConfig.ui
@@ -0,0 +1,963 @@
+
+
+ ArduPlanePidConfig
+
+
+
+ 0
+ 0
+ 733
+ 641
+
+
+
+ Form
+
+
+
+
+ 20
+ 10
+ 681
+ 581
+
+
+
+ -
+
+
+ L1 Control - Turn Control
+
+
+
-
+
+
-
+
+
-
+
+
+ Period
+
+
+
+ -
+
+
+ Damping
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
+
+
+ -
+
+
+ Servo Roll Pid
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Nav Pitch Alt Pid
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Nav Pitch AS Pid
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Servo Yaw Pid
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Throttle 0-100%
+
+
+
-
+
+
-
+
+
-
+
+
+ Cruise
+
+
+
+ -
+
+
+ Min
+
+
+
+ -
+
+
+ Max
+
+
+
+ -
+
+
+ FS Value
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Servo Pitch Pid
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Aiespeed m/s
+
+
+
-
+
+
-
+
+
-
+
+
+ Cruise
+
+
+
+ -
+
+
+ FBW min
+
+
+
+ -
+
+
+ FBW max
+
+
+
+ -
+
+
+ Ratio
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 100.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Other Mix's
+
+
+
-
+
+
-
+
+
-
+
+
+ P to T
+
+
+
+ -
+
+
+ Pitch Comp
+
+
+
+ -
+
+
+ Rudder Mix
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Navigation Angles
+
+
+
-
+
+
-
+
+
-
+
+
+ Bank Max
+
+
+
+ -
+
+
+ Pitch Max
+
+
+
+ -
+
+
+ Pitch Min
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 10000.000000000000000
+
+
+ 0.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Energy/Alt Pid
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ 100.000000000000000
+
+
+
+ -
+
+
+ 100.000000000000000
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 260
+ 600
+ 75
+ 23
+
+
+
+ Write Params
+
+
+
+
+
+ 350
+ 600
+ 75
+ 23
+
+
+
+ Refresh Params
+
+
+
+
+
+
diff --git a/src/ui/configuration/ArduRoverPidConfig.cc b/src/ui/configuration/ArduRoverPidConfig.cc
new file mode 100644
index 0000000000000000000000000000000000000000..60f2f28f97a4325e3b46ad06df9683d8ef440c99
--- /dev/null
+++ b/src/ui/configuration/ArduRoverPidConfig.cc
@@ -0,0 +1,78 @@
+#include "ArduRoverPidConfig.h"
+
+
+ArduRoverPidConfig::ArduRoverPidConfig(QWidget *parent) : AP2ConfigWidget(parent)
+{
+ ui.setupUi(this);
+ nameToBoxMap["STEER2SRV_P"] = ui.steer2ServoPSpinBox;
+ nameToBoxMap["STEER2SRV_I"] = ui.steer2ServoISpinBox;
+ nameToBoxMap["STEER2SRV_D"] = ui.steer2ServoDSpinBox;
+ nameToBoxMap["STEER2SRV_IMAX"] = ui.steer2ServoIMAXSpinBox;
+
+ nameToBoxMap["XTRK_ANGLE_CD"] = ui.xtrackEntryAngleSpinBox;
+ nameToBoxMap["XTRK_GAIN_SC"] = ui.xtrackGainSpinBox;
+
+ nameToBoxMap["CRUISE_THROTTLE"] = ui.throttleCruiseSpinBox;
+ nameToBoxMap["THR_MIN"] = ui.throttleMinSpinBox;
+ nameToBoxMap["THR_MAX"] = ui.throttleMaxSpinBox;
+ nameToBoxMap["FS_THR_VALUE"] = ui.throttleFSSpinBox;
+
+ nameToBoxMap["HDNG2STEER_P"] = ui.heading2SteerPSpinBox;
+ nameToBoxMap["HDNG2STEER_I"] = ui.heading2SteerISpinBox;
+ nameToBoxMap["HDNG2STEER_D"] = ui.heading2SteerDSpinBox;
+ nameToBoxMap["HDNG2STEER_IMAX"] = ui.heading2SteerIMAXSpinBox;
+
+ nameToBoxMap["SPEED2THR_P"] = ui.speed2ThrottlePSpinBox;
+ nameToBoxMap["SPEED2THR_I"] = ui.speed2ThrottleISpinBox;
+ nameToBoxMap["SPEED2THR_D"] = ui.speed2ThrottleDSpinBox;
+ nameToBoxMap["SPEED2THR_IMAX"] = ui.speed2ThrottleIMAXSpinBox;
+
+ nameToBoxMap["CRUISE_SPEED"] = ui.roverCruiseSpinBox;
+ nameToBoxMap["SPEED_TURN_GAIN"] = ui.roverTurnSpeedSpinBox;
+ nameToBoxMap["SPEED_TURN_DIST"] = ui.roverTurnDistSpinBox;
+ nameToBoxMap["WP_RADIUS"] = ui.roverWPRadiusSpinBox;
+
+ nameToBoxMap["SONAR_TRIGGER_CM"] = ui.sonarTriggerSpinBox;
+ nameToBoxMap["SONAR_TURN_ANGLE"] = ui.sonarTurnAngleSpinBox;
+ nameToBoxMap["SONAR_TURN_TIME"] = ui.sonarTurnTimeSpinBox;
+ nameToBoxMap["SONAR_DEBOUNCE"] = ui.sonaeDebounceSpinBox;
+
+ connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
+ connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
+
+}
+
+ArduRoverPidConfig::~ArduRoverPidConfig()
+{
+}
+void ArduRoverPidConfig::writeButtonClicked()
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
+ {
+ m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value());
+ }
+}
+
+void ArduRoverPidConfig::refreshButtonClicked()
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ for (QMap::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
+ {
+ m_uas->getParamManager()->requestParameterUpdate(1,i.key());
+ }
+}
+
+void ArduRoverPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+ if (nameToBoxMap.contains(parameterName))
+ {
+ nameToBoxMap[parameterName]->setValue(value.toFloat());
+ }
+}
diff --git a/src/ui/configuration/ArduRoverPidConfig.h b/src/ui/configuration/ArduRoverPidConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..214658bdccf2f45dc8e450a2da29e81f60876e49
--- /dev/null
+++ b/src/ui/configuration/ArduRoverPidConfig.h
@@ -0,0 +1,23 @@
+#ifndef ARDUROVERPIDCONFIG_H
+#define ARDUROVERPIDCONFIG_H
+
+#include
+#include "ui_ArduRoverPidConfig.h"
+#include "AP2ConfigWidget.h"
+class ArduRoverPidConfig : public AP2ConfigWidget
+{
+ Q_OBJECT
+
+public:
+ explicit ArduRoverPidConfig(QWidget *parent = 0);
+ ~ArduRoverPidConfig();
+private slots:
+ void writeButtonClicked();
+ void refreshButtonClicked();
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
+private:
+ QMap nameToBoxMap;
+ Ui::ArduRoverPidConfig ui;
+};
+
+#endif // ARDUROVERPIDCONFIG_H
diff --git a/src/ui/configuration/ArduRoverPidConfig.ui b/src/ui/configuration/ArduRoverPidConfig.ui
new file mode 100644
index 0000000000000000000000000000000000000000..47831616e0adbd2578e60934c450c831c1ea7ce3
--- /dev/null
+++ b/src/ui/configuration/ArduRoverPidConfig.ui
@@ -0,0 +1,732 @@
+
+
+ ArduRoverPidConfig
+
+
+
+ 0
+ 0
+ 626
+ 607
+
+
+
+ Form
+
+
+
+
+ 10
+ 10
+ 151
+ 21
+
+
+
+ <h2>ArduRover Pids</h2>
+
+
+
+
+
+ 60
+ 90
+ 504
+ 419
+
+
+
+ -
+
+
+ Steer 2 Servo
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Speed 2 Throttle
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Heading 2 Steer
+
+
+
-
+
+
-
+
+
-
+
+
+ P
+
+
+
+ -
+
+
+ I
+
+
+
+ -
+
+
+ D
+
+
+
+ -
+
+
+ INT_MAX
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Throttle 0-100%
+
+
+
-
+
+
-
+
+
-
+
+
+ Cruise
+
+
+
+ -
+
+
+ Min
+
+
+
+ -
+
+
+ Max
+
+
+
+ -
+
+
+ FS Value
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Xtrack Pids
+
+
+
-
+
+
-
+
+
-
+
+
+ Gain (cm)
+
+
+
+ -
+
+
+ Entry Angle
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
+
+
+ -
+
+
+ Sonar
+
+
+
-
+
+
-
+
+
-
+
+
+ Trigger cm
+
+
+
+ -
+
+
+ Turn Angle
+
+
+
+ -
+
+
+ Turn Time
+
+
+
+ -
+
+
+ Debounce
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Rover
+
+
+
-
+
+
-
+
+
-
+
+
+ Cruise Speed
+
+
+
+ -
+
+
+ Turn Speed
+
+
+
+ -
+
+
+ Turn Dist
+
+
+
+ -
+
+
+ WP Radius
+
+
+
+
+
+ -
+
+
-
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ 3
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+ -
+
+
+ -10000.000000000000000
+
+
+ 10000.000000000000000
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 300
+ 540
+ 91
+ 23
+
+
+
+ Refresh Params
+
+
+
+
+
+ 200
+ 540
+ 75
+ 23
+
+
+
+ Write Params
+
+
+
+
+
+
diff --git a/src/ui/configuration/BatteryMonitorConfig.cc b/src/ui/configuration/BatteryMonitorConfig.cc
index 5e74cedde21a4a1a71b0869b713dc93e816cadf9..05b6dc2343e896aa4ade956f4a51163f9fc5d6ec 100644
--- a/src/ui/configuration/BatteryMonitorConfig.cc
+++ b/src/ui/configuration/BatteryMonitorConfig.cc
@@ -32,6 +32,16 @@ BatteryMonitorConfig::BatteryMonitorConfig(QWidget *parent) : AP2ConfigWidget(pa
}
+void BatteryMonitorConfig::activeUASSet(UASInterface *uas)
+{
+ if (!uas)
+ {
+ return;
+ }
+ connect(uas,SIGNAL(batteryChanged(UASInterface*,double,double,double,int)),this,SLOT(batteryChanged(UASInterface*,double,double,double,int)));
+ AP2ConfigWidget::activeUASSet(uas);
+}
+
void BatteryMonitorConfig::calcDividerSet()
{
if (!m_uas)
@@ -222,6 +232,14 @@ void BatteryMonitorConfig::apmVerCurrentIndexChanged(int index)
BatteryMonitorConfig::~BatteryMonitorConfig()
{
}
+void BatteryMonitorConfig::batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds)
+{
+ ui.calcVoltsLineEdit->setText(QString::number(voltage,'f',2));
+ if (ui.measuredVoltsLineEdit->text() == "")
+ {
+ ui.measuredVoltsLineEdit->setText(ui.calcVoltsLineEdit->text());
+ }
+}
void BatteryMonitorConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
diff --git a/src/ui/configuration/BatteryMonitorConfig.h b/src/ui/configuration/BatteryMonitorConfig.h
index 183d782d236ab30fad476f0d6fcee5bc7a146421..2bbdb56f2ed7aa443802c2d98d532b1310b390e6 100644
--- a/src/ui/configuration/BatteryMonitorConfig.h
+++ b/src/ui/configuration/BatteryMonitorConfig.h
@@ -20,6 +20,8 @@ private slots:
void calcDividerSet();
void ampsPerVoltSet();
void batteryCapacitySet();
+ void activeUASSet(UASInterface *uas);
+ void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
private:
Ui::BatteryMonitorConfig ui;
};
diff --git a/src/ui/configuration/CompassConfig.cc b/src/ui/configuration/CompassConfig.cc
index 5c37b0cbf6a0ca5ad7900d35aace8e5f219f8d73..43da906fd809e3115c260055a9d088c776b9da9c 100644
--- a/src/ui/configuration/CompassConfig.cc
+++ b/src/ui/configuration/CompassConfig.cc
@@ -16,6 +16,33 @@ CompassConfig::CompassConfig(QWidget *parent) : QWidget(parent)
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
activeUASSet(UASManager::instance()->getActiveUAS());
+ ui.orientationComboBox->addItem("ROTATION_NONE");
+ ui.orientationComboBox->addItem("ROTATION_YAW_45");
+ ui.orientationComboBox->addItem("ROTATION_YAW_90");
+ ui.orientationComboBox->addItem("ROTATION_YAW_135");
+ ui.orientationComboBox->addItem("ROTATION_YAW_180");
+ ui.orientationComboBox->addItem("ROTATION_YAW_225");
+ ui.orientationComboBox->addItem("ROTATION_YAW_270");
+ ui.orientationComboBox->addItem("ROTATION_YAW_315");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_180");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_45");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_90");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_135");
+ ui.orientationComboBox->addItem("ROTATION_PITCH_180");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_225");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_270");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_180_YAW_315");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_90");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_90_YAW_45");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_90_YAW_90");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_90_YAW_135");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_270");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_270_YAW_45");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_270_YAW_90");
+ ui.orientationComboBox->addItem("ROTATION_ROLL_270_YAW_135");
+ ui.orientationComboBox->addItem("ROTATION_PITCH_90");
+ ui.orientationComboBox->addItem("ROTATION_PITCH_270");
+ ui.orientationComboBox->addItem("ROTATION_MAX");
}
CompassConfig::~CompassConfig()
{
@@ -39,12 +66,14 @@ void CompassConfig::parameterChanged(int uas, int component, QString parameterNa
ui.enableCheckBox->setChecked(false);
ui.autoDecCheckBox->setEnabled(false);
ui.declinationLineEdit->setEnabled(false);
+ ui.orientationComboBox->setEnabled(false);
}
else
{
ui.enableCheckBox->setChecked(true);
ui.autoDecCheckBox->setEnabled(true);
ui.declinationLineEdit->setEnabled(true);
+ ui.orientationComboBox->setEnabled(true);
}
ui.enableCheckBox->setEnabled(true);
}
@@ -63,6 +92,12 @@ void CompassConfig::parameterChanged(int uas, int component, QString parameterNa
{
ui.declinationLineEdit->setText(QString::number(value.toDouble()));
}
+ else if (parameterName == "COMPASS_ORIENT")
+ {
+ disconnect(ui.orientationComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(orientationComboChanged(int)));
+ ui.orientationComboBox->setCurrentIndex(value.toInt());
+ connect(ui.orientationComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(orientationComboChanged(int)));
+ }
}
void CompassConfig::enableClicked(bool enabled)
@@ -104,5 +139,11 @@ void CompassConfig::autoDecClicked(bool enabled)
void CompassConfig::orientationComboChanged(int index)
{
+ //COMPASS_ORIENT
+ if (!m_uas)
+ {
+ return;
+ }
+ m_uas->getParamManager()->setParameter(1,"COMPASS_ORIENT",index);
}
diff --git a/src/ui/configuration/CompassConfig.ui b/src/ui/configuration/CompassConfig.ui
index 7ac1ede4fa0c325327b60794af9f79e8e3b4b875..95b9362b441dc7279f45a2c26adf80606b89d7ea 100644
--- a/src/ui/configuration/CompassConfig.ui
+++ b/src/ui/configuration/CompassConfig.ui
@@ -55,9 +55,9 @@
- 300
+ 290
180
- 91
+ 101
23
@@ -70,7 +70,7 @@
390
180
- 91
+ 101
23
@@ -118,7 +118,7 @@
10
70
- 201
+ 211
111
diff --git a/src/ui/configuration/FailSafeConfig.cc b/src/ui/configuration/FailSafeConfig.cc
index 5f7ff81b06b9dc288654df17dfaed9e2ed6317bd..2517a322ca129f2fa9ae10f85842b30c2b1e0635 100644
--- a/src/ui/configuration/FailSafeConfig.cc
+++ b/src/ui/configuration/FailSafeConfig.cc
@@ -1,11 +1,400 @@
#include "FailSafeConfig.h"
-FailSafeConfig::FailSafeConfig(QWidget *parent) : QWidget(parent)
+FailSafeConfig::FailSafeConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
+ ui.radio1In->setName("Radio 1");
+ ui.radio1In->setMin(800);
+ ui.radio1In->setMax(2200);
+ ui.radio1In->setOrientation(Qt::Horizontal);
+ ui.radio2In->setName("Radio 2");
+ ui.radio2In->setMin(800);
+ ui.radio2In->setMax(2200);
+ ui.radio2In->setOrientation(Qt::Horizontal);
+ ui.radio3In->setName("Radio 3");
+ ui.radio3In->setMin(800);
+ ui.radio3In->setMax(2200);
+ ui.radio3In->setOrientation(Qt::Horizontal);
+ ui.radio4In->setName("Radio 4");
+ ui.radio4In->setMin(800);
+ ui.radio4In->setMax(2200);
+ ui.radio4In->setOrientation(Qt::Horizontal);
+ ui.radio5In->setName("Radio 5");
+ ui.radio5In->setMin(800);
+ ui.radio5In->setMax(2200);
+ ui.radio5In->setOrientation(Qt::Horizontal);
+ ui.radio6In->setName("Radio 6");
+ ui.radio6In->setMin(800);
+ ui.radio6In->setMax(2200);
+ ui.radio6In->setOrientation(Qt::Horizontal);
+ ui.radio7In->setName("Radio 7");
+ ui.radio7In->setMin(800);
+ ui.radio7In->setMax(2200);
+ ui.radio7In->setOrientation(Qt::Horizontal);
+ ui.radio8In->setName("Radio 8");
+ ui.radio8In->setMin(800);
+ ui.radio8In->setMax(2200);
+ ui.radio8In->setOrientation(Qt::Horizontal);
+
+ ui.radio1Out->setName("Radio 1");
+ ui.radio1Out->setMin(800);
+ ui.radio1Out->setMax(2200);
+ ui.radio1Out->setOrientation(Qt::Horizontal);
+ ui.radio2Out->setName("Radio 2");
+ ui.radio2Out->setMin(800);
+ ui.radio2Out->setMax(2200);
+ ui.radio2Out->setOrientation(Qt::Horizontal);
+ ui.radio3Out->setName("Radio 3");
+ ui.radio3Out->setMin(800);
+ ui.radio3Out->setMax(2200);
+ ui.radio3Out->setOrientation(Qt::Horizontal);
+ ui.radio4Out->setName("Radio 4");
+ ui.radio4Out->setMin(800);
+ ui.radio4Out->setMax(2200);
+ ui.radio4Out->setOrientation(Qt::Horizontal);
+ ui.radio5Out->setName("Radio 5");
+ ui.radio5Out->setMin(800);
+ ui.radio5Out->setMax(2200);
+ ui.radio5Out->setOrientation(Qt::Horizontal);
+ ui.radio6Out->setName("Radio 6");
+ ui.radio6Out->setMin(800);
+ ui.radio6Out->setMax(2200);
+ ui.radio6Out->setOrientation(Qt::Horizontal);
+ ui.radio7Out->setName("Radio 7");
+ ui.radio7Out->setMin(800);
+ ui.radio7Out->setMax(2200);
+ ui.radio7Out->setOrientation(Qt::Horizontal);
+ ui.radio8Out->setName("Radio 8");
+ ui.radio8Out->setMin(800);
+ ui.radio8Out->setMax(2200);
+ ui.radio8Out->setOrientation(Qt::Horizontal);
+
+ ui.throttleFailSafeComboBox->addItem("Disable");
+ ui.throttleFailSafeComboBox->addItem("Enabled - Always TRL");
+ ui.throttleFailSafeComboBox->addItem("Enabled - Continue in auto");
+
+ connect(ui.batteryFailCheckBox,SIGNAL(clicked(bool)),this,SLOT(batteryFailChecked(bool)));
+ connect(ui.fsLongCheckBox,SIGNAL(clicked(bool)),this,SLOT(fsLongClicked(bool)));
+ connect(ui.fsShortCheckBox,SIGNAL(clicked(bool)),this,SLOT(fsShortClicked(bool)));
+ connect(ui.gcsCheckBox,SIGNAL(clicked(bool)),this,SLOT(gcsChecked(bool)));
+ connect(ui.throttleActionCheckBox,SIGNAL(clicked(bool)),this,SLOT(throttleActionChecked(bool)));
+ connect(ui.throttleCheckBox,SIGNAL(clicked(bool)),this,SLOT(throttleChecked(bool)));
+ connect(ui.throttlePwmSpinBox,SIGNAL(editingFinished()),this,SLOT(throttlePwmChanged()));
+ connect(ui.throttleFailSafeComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(throttleFailSafeChanged(int)));
+}
+void FailSafeConfig::gcsChecked(bool checked)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ if (checked)
+ {
+ m_uas->setParameter(1,"FS_GCS_ENABL",1);
+ }
+ else
+ {
+ m_uas->setParameter(1,"FS_GCS_ENABL",0);
+ }
+}
+
+void FailSafeConfig::throttleActionChecked(bool checked)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ if (checked)
+ {
+ m_uas->setParameter(1,"THR_FS_ACTION",1);
+ }
+ else
+ {
+ m_uas->setParameter(1,"THR_FS_ACTION",0);
+ }
+}
+
+void FailSafeConfig::throttleChecked(bool checked)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ if (checked)
+ {
+ m_uas->setParameter(1,"THR_FAILSAFE",1);
+ }
+ else
+ {
+ m_uas->setParameter(1,"THR_FAILSAFE",0);
+ }
+}
+
+void FailSafeConfig::throttlePwmChanged()
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ m_uas->setParameter(1,"THR_FS_VALUE",ui.throttlePwmSpinBox->value());
+}
+
+void FailSafeConfig::throttleFailSafeChanged(int index)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ m_uas->setParameter(1,"FS_THR_ENABLE",index);
+}
+
+void FailSafeConfig::fsLongClicked(bool checked)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ if (checked)
+ {
+ m_uas->setParameter(1,"FS_LONG_ACTN",1);
+ }
+ else
+ {
+ m_uas->setParameter(1,"FS_LONG_ACTN",0);
+ }
+}
+
+void FailSafeConfig::fsShortClicked(bool checked)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ if (checked)
+ {
+ m_uas->setParameter(1,"FS_SHORT_ACTN",1);
+ }
+ else
+ {
+ m_uas->setParameter(1,"FS_SHORT_ACTN",0);
+ }
+}
+
+void FailSafeConfig::batteryFailChecked(bool checked)
+{
+ if (!m_uas)
+ {
+ return;
+ }
+ if (checked)
+ {
+ m_uas->setParameter(1,"FS_BATT_ENABLE",1);
+ }
+ else
+ {
+ m_uas->setParameter(1,"FS_BATT_ENABLE",0);
+ }
}
FailSafeConfig::~FailSafeConfig()
{
}
+void FailSafeConfig::activeUASSet(UASInterface *uas)
+{
+ AP2ConfigWidget::activeUASSet(uas);
+ connect(uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanges(int,float)));
+ connect(uas,SIGNAL(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)),this,SLOT(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)));
+ connect(uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool)));
+ if (uas->getSystemType() == MAV_TYPE_FIXED_WING)
+ {
+ ui.batteryFailCheckBox->setVisible(false);
+ ui.throttleFailSafeComboBox->setVisible(false);
+ ui.batteryVoltSpinBox->setVisible(false);
+ ui.label_6->setVisible(false);
+
+ ui.throttlePwmSpinBox->setVisible(true); //Both
+
+ ui.throttleCheckBox->setVisible(true);
+ ui.throttleActionCheckBox->setVisible(true);
+ ui.gcsCheckBox->setVisible(true);
+ ui.fsLongCheckBox->setVisible(true);
+ ui.fsShortCheckBox->setVisible(true);
+ }
+ else if (uas->getSystemType() == MAV_TYPE_QUADROTOR)
+ {
+ ui.batteryFailCheckBox->setVisible(true);
+ ui.throttleFailSafeComboBox->setVisible(true);
+ ui.batteryVoltSpinBox->setVisible(true);
+ ui.label_6->setVisible(true);
+
+ ui.throttlePwmSpinBox->setVisible(true); //Both
+
+ ui.throttleCheckBox->setVisible(false);
+ ui.throttleActionCheckBox->setVisible(false);
+ ui.gcsCheckBox->setVisible(false);
+ ui.fsLongCheckBox->setVisible(false);
+ ui.fsShortCheckBox->setVisible(false);
+ }
+ else
+ {
+ //Show all, just in case
+ ui.batteryFailCheckBox->setVisible(true);
+ ui.throttleFailSafeComboBox->setVisible(true);
+ ui.batteryVoltSpinBox->setVisible(true);
+ ui.throttlePwmSpinBox->setVisible(true); //Both
+ ui.throttleCheckBox->setVisible(true);
+ ui.throttleActionCheckBox->setVisible(true);
+ ui.gcsCheckBox->setVisible(true);
+ ui.fsLongCheckBox->setVisible(true);
+ ui.fsShortCheckBox->setVisible(true);
+ }
+
+}
+void FailSafeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+ //Arducopter
+ if (parameterName == "FS_THR_ENABLE")
+ {
+ ui.throttleFailSafeComboBox->setCurrentIndex(value.toInt());
+ }
+ else if (parameterName == "FS_THR_VALUE")
+ {
+ ui.throttlePwmSpinBox->setValue(value.toFloat());
+ }
+ else if (parameterName == "FS_BATT_ENABLE")
+ {
+ if (value.toInt() == 0)
+ {
+ ui.batteryFailCheckBox->setChecked(false);
+ }
+ else
+ {
+ ui.batteryFailCheckBox->setChecked(true);
+ }
+ }
+ else if (parameterName == "LOW_VOLT")
+ {
+ ui.batteryVoltSpinBox->setValue(value.toFloat());
+ }
+ //Arduplane
+ else if (parameterName == "THR_FAILSAFE")
+ {
+ if (value.toInt() == 0)
+ {
+ ui.throttleCheckBox->setChecked(false);
+ }
+ else
+ {
+ ui.throttleCheckBox->setChecked(true);
+ }
+ }
+ else if (parameterName == "THR_FS_VALUE")
+ {
+ ui.throttlePwmSpinBox->setValue(value.toFloat());
+ }
+ else if (parameterName == "THR_FS_ACTION")
+ {
+ if (value.toInt() == 0)
+ {
+ ui.throttleActionCheckBox->setChecked(false);
+ }
+ else
+ {
+ ui.throttleActionCheckBox->setChecked(true);
+ }
+ }
+ else if (parameterName == "FS_GCS_ENABL")
+ {
+ if (value.toInt() == 0)
+ {
+ ui.gcsCheckBox->setChecked(false);
+ }
+ else
+ {
+ ui.gcsCheckBox->setChecked(true);
+ }
+ }
+ else if (parameterName == "FS_SHORT_ACTN")
+ {
+ if (value.toInt() == 0)
+ {
+ ui.fsShortCheckBox->setChecked(false);
+ }
+ else
+ {
+ ui.fsShortCheckBox->setChecked(true);
+ }
+ }
+ else if (parameterName == "FS_LONG_ACTN")
+ {
+ if (value.toInt() == 0)
+ {
+ ui.fsLongCheckBox->setChecked(false);
+ }
+ else
+ {
+ ui.fsLongCheckBox->setChecked(true);
+ }
+ }
+
+}
+
+void FailSafeConfig::armingChanged(bool armed)
+{
+ if (armed)
+ {
+ ui.armedLabel->setText("ARMED
");
+ }
+ else
+ {
+ ui.armedLabel->setText("DISARMED
");
+ }
+}
+
+void FailSafeConfig::remoteControlChannelRawChanges(int chan,float value)
+{
+ if (chan == 0)
+ {
+ ui.radio1In->setValue(value);
+ }
+ else if (chan == 1)
+ {
+ ui.radio2In->setValue(value);
+ }
+ else if (chan == 2)
+ {
+ ui.radio3In->setValue(value);
+ }
+ else if (chan == 3)
+ {
+ ui.radio4In->setValue(value);
+ }
+ else if (chan == 4)
+ {
+ ui.radio5In->setValue(value);
+ }
+ else if (chan == 5)
+ {
+ ui.radio6In->setValue(value);
+ }
+ else if (chan == 6)
+ {
+ ui.radio7In->setValue(value);
+ }
+ else if (chan == 7)
+ {
+ ui.radio8In->setValue(value);
+ }
+}
+void FailSafeConfig::hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
+{
+ ui.radio1Out->setValue(act1);
+ ui.radio2Out->setValue(act2);
+ ui.radio3Out->setValue(act3);
+ ui.radio4Out->setValue(act4);
+ ui.radio5Out->setValue(act5);
+ ui.radio6Out->setValue(act6);
+ ui.radio7Out->setValue(act7);
+ ui.radio8Out->setValue(act8);
+}
diff --git a/src/ui/configuration/FailSafeConfig.h b/src/ui/configuration/FailSafeConfig.h
index a22e96493e763f795f55ccdc9751aaa1fe27dfc6..162246e899861f560891d8336eaddc631039ea79 100644
--- a/src/ui/configuration/FailSafeConfig.h
+++ b/src/ui/configuration/FailSafeConfig.h
@@ -3,15 +3,28 @@
#include
#include "ui_FailSafeConfig.h"
-
-class FailSafeConfig : public QWidget
+#include "AP2ConfigWidget.h"
+class FailSafeConfig : public AP2ConfigWidget
{
Q_OBJECT
public:
explicit FailSafeConfig(QWidget *parent = 0);
~FailSafeConfig();
-
+private slots:
+ void activeUASSet(UASInterface *uas);
+ void remoteControlChannelRawChanges(int chan,float value);
+ void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
+ void armingChanged(bool armed);
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
+ void batteryFailChecked(bool checked);
+ void fsLongClicked(bool checked);
+ void fsShortClicked(bool checked);
+ void gcsChecked(bool checked);
+ void throttleActionChecked(bool checked);
+ void throttleChecked(bool checked);
+ void throttlePwmChanged();
+ void throttleFailSafeChanged(int index);
private:
Ui::FailSafeConfig ui;
};
diff --git a/src/ui/configuration/FailSafeConfig.ui b/src/ui/configuration/FailSafeConfig.ui
index fe4eef1cb8987c9d1a0798030a9330080dc72593..69375dd53599967a7c06b48b2aeb1f2f3213397c 100644
--- a/src/ui/configuration/FailSafeConfig.ui
+++ b/src/ui/configuration/FailSafeConfig.ui
@@ -6,8 +6,8 @@
0
0
- 400
- 300
+ 822
+ 536
@@ -26,7 +26,427 @@
<h2>Fail Safe</h2>
+
+
+
+ 20
+ 70
+ 252
+ 441
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+
+
+
+
+
+ 300
+ 70
+ 252
+ 441
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+ -
+
+
+
+ 250
+ 40
+
+
+
+
+ 250
+ 40
+
+
+
+
+
+
+
+
+
+ 570
+ 60
+ 181
+ 181
+
+
+
+ Status
+
+
+ -
+
+
+ TextLabel
+
+
+
+ -
+
+
+ TextLabel
+
+
+
+ -
+
+
+ TextLabel
+
+
+
+
+
+
+
+
+ 570
+ 250
+ 161
+ 261
+
+
+
+ Failsafe Options
+
+
+ -
+
+
+ Throttle FailSafe
+
+
+
+ -
+
+
+ -
+
+
-
+
+
+ FS Pwm
+
+
+
+ -
+
+
+ 3000
+
+
+
+
+
+ -
+
+
+ Throttle FailSafe Action
+
+
+
+ -
+
+
+ GCS FailSafe
+
+
+
+ -
+
+
+ FailSafe Short (1 sec)
+
+
+
+ -
+
+
+ FailSafe Long (20 sec)
+
+
+
+ -
+
+
+ Battery Failsafe
+
+
+
+ -
+
+
-
+
+
+ Low Battery
+
+
+
+ -
+
+
+ 100.000000000000000
+
+
+
+
+
+
+
+
+
+ QGCRadioChannelDisplay
+ QWidget
+ ui/designer/QGCRadioChannelDisplay.h
+ 1
+
+
diff --git a/src/ui/configuration/ParamWidget.cc b/src/ui/configuration/ParamWidget.cc
new file mode 100644
index 0000000000000000000000000000000000000000..93b3bfd26455959198253a45956f129a8af155f8
--- /dev/null
+++ b/src/ui/configuration/ParamWidget.cc
@@ -0,0 +1,79 @@
+#include "ParamWidget.h"
+
+
+ParamWidget::ParamWidget(QWidget *parent) : QWidget(parent)
+{
+ ui.setupUi(this);
+}
+
+ParamWidget::~ParamWidget()
+{
+}
+
+void ParamWidget::setupInt(QString title,QString description,int value,int min,int max)
+{
+ type = INT;
+ ui.titleLabel->setText("" + title + "
");
+ ui.descriptionLabel->setText(description);
+ ui.valueComboBox->hide();
+ ui.valueSlider->show();
+ ui.intSpinBox->show();
+ ui.doubleSpinBox->hide();
+ m_min = min;
+ m_max = max;
+}
+
+void ParamWidget::setupDouble(QString title,QString description,double value,double min,double max)
+{
+ type = DOUBLE;
+ ui.titleLabel->setText("" + title + "
");
+ ui.descriptionLabel->setText(description);
+ ui.valueComboBox->hide();
+ ui.valueSlider->show();
+ ui.intSpinBox->hide();
+ ui.doubleSpinBox->show();
+ m_min = min;
+ m_max = max;
+}
+
+void ParamWidget::setupCombo(QString title,QString description,QList > list)
+{
+ type = COMBO;
+ ui.titleLabel->setText("" + title + "
");
+ ui.descriptionLabel->setText(description);
+ ui.valueComboBox->show();
+ ui.valueSlider->hide();
+ ui.intSpinBox->hide();
+ ui.doubleSpinBox->hide();
+ m_valueList = list;
+ ui.valueComboBox->clear();
+ for (int i=0;iaddItem(m_valueList[i].second);
+ }
+}
+
+void ParamWidget::setValue(double value)
+{
+ if (type == INT)
+ {
+ ui.intSpinBox->setValue(value);
+ ui.valueSlider->setValue(((value + m_min) / (m_max + m_min)) * 100.0);
+ }
+ else if (type == DOUBLE)
+ {
+ ui.doubleSpinBox->setValue(value);
+ ui.valueSlider->setValue(((value + m_min) / (m_max + m_min)) * 100.0);
+ }
+ else if (type == COMBO)
+ {
+ for (int i=0;isetCurrentIndex(i);
+ return;
+ }
+ }
+ }
+}
diff --git a/src/ui/configuration/ParamWidget.h b/src/ui/configuration/ParamWidget.h
new file mode 100644
index 0000000000000000000000000000000000000000..aa375d296752f2d2cc9c052d8b5d60a3b9ec2c35
--- /dev/null
+++ b/src/ui/configuration/ParamWidget.h
@@ -0,0 +1,34 @@
+#ifndef PARAMWIDGET_H
+#define PARAMWIDGET_H
+
+#include
+#include "ui_ParamWidget.h"
+
+class ParamWidget : public QWidget
+{
+ Q_OBJECT
+
+public:
+ explicit ParamWidget(QWidget *parent = 0);
+ ~ParamWidget();
+ void setupInt(QString title,QString description,int value,int min,int max);
+ void setupDouble(QString title,QString description,double value,double min,double max);
+ void setupCombo(QString title,QString description,QList > list);
+ void setValue(double value);
+private:
+ enum VIEWTYPE
+ {
+ INT,
+ DOUBLE,
+ COMBO
+ };
+ double m_min;
+ double m_max;
+ double m_dvalue;
+ int m_ivalue;
+ VIEWTYPE type;
+ QList > m_valueList;
+ Ui::ParamWidget ui;
+};
+
+#endif // PARAMWIDGET_H
diff --git a/src/ui/configuration/ParamWidget.ui b/src/ui/configuration/ParamWidget.ui
new file mode 100644
index 0000000000000000000000000000000000000000..ddf4653b8f09169cdc55b6e2edad622e647743c7
--- /dev/null
+++ b/src/ui/configuration/ParamWidget.ui
@@ -0,0 +1,78 @@
+
+
+ ParamWidget
+
+
+
+ 0
+ 0
+ 619
+ 207
+
+
+
+ Form
+
+
+ -
+
+
-
+
+
+ TextLabel
+
+
+
+ -
+
+
+ TextLabel
+
+
+ true
+
+
+
+ -
+
+
-
+
+
+ -
+
+
+ -
+
+
+ 100
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+
+
+
+
+
diff --git a/src/ui/configuration/SonarConfig.ui b/src/ui/configuration/SonarConfig.ui
index 6bce3475ae776af46200c947cb29004b44b9e676..7c40d028ce6c772db234b8972473c3ed906b7019 100644
--- a/src/ui/configuration/SonarConfig.ui
+++ b/src/ui/configuration/SonarConfig.ui
@@ -58,7 +58,7 @@
- CheckBox
+ Enable
diff --git a/src/ui/configuration/StandardParamConfig.cc b/src/ui/configuration/StandardParamConfig.cc
index d67891bbfb94e65133b36df0d59b237e0e2951e8..0be1d02f225d64f954a4e0f23805c2fa7cdfd7fe 100644
--- a/src/ui/configuration/StandardParamConfig.cc
+++ b/src/ui/configuration/StandardParamConfig.cc
@@ -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 > 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());
+ }
}
diff --git a/src/ui/configuration/StandardParamConfig.h b/src/ui/configuration/StandardParamConfig.h
index 9e43a9bd99ffa222f3c27100871bb290b4dcb787..d337b9b4f226c5a5a18d694dc3fe3b16ce916fd1 100644
--- a/src/ui/configuration/StandardParamConfig.h
+++ b/src/ui/configuration/StandardParamConfig.h
@@ -3,16 +3,22 @@
#include
#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 > valuelist);
+private slots:
+ void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
+ QMap paramToWidgetMap;
+ void activeUASSet(UASInterface *uas);
Ui::StandardParamConfig ui;
};
diff --git a/src/ui/configuration/StandardParamConfig.ui b/src/ui/configuration/StandardParamConfig.ui
index cdbb320c0e634be0615dfc81d06172c2e813840e..53a96d984792d7aa6198efe9bfb7f3864b57c523 100644
--- a/src/ui/configuration/StandardParamConfig.ui
+++ b/src/ui/configuration/StandardParamConfig.ui
@@ -6,26 +6,44 @@
0
0
- 400
- 300
+ 651
+ 552
Form
-
-
-
- 20
- 20
- 201
- 41
-
-
-
- <h2>Standard Params</h2>
-
-
+
+ -
+
+
+ <h2>Standard Params</h2>
+
+
+
+ -
+
+
+ true
+
+
+
+
+ 0
+ 0
+ 631
+ 505
+
+
+
+
-
+
+
+
+
+
+
+