Commit 5796a5a8 authored by Michael Carpenter's avatar Michael Carpenter

Implementation of ArduPlanePid configuration write/refresh, and value ranges

parent f7ec7607
...@@ -15,7 +15,7 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent) ...@@ -15,7 +15,7 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
ui.failSafeButton->setVisible(false); ui.failSafeButton->setVisible(false);
ui.advancedParamButton->setVisible(false); ui.advancedParamButton->setVisible(false);
ui.advParamListButton->setVisible(false); ui.advParamListButton->setVisible(false);
ui.arduCoperPidButton->setVisible(false); ui.arduCopterPidButton->setVisible(false);
/*basicPidConfig = new BasicPidConfig(this); /*basicPidConfig = new BasicPidConfig(this);
ui.stackedWidget->addWidget(basicPidConfig); ui.stackedWidget->addWidget(basicPidConfig);
...@@ -47,10 +47,18 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent) ...@@ -47,10 +47,18 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
buttonToConfigWidgetMap[ui.advancedParamButton] = advancedParamConfig; buttonToConfigWidgetMap[ui.advancedParamButton] = advancedParamConfig;
connect(ui.advancedParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); connect(ui.advancedParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
arduCoperPidConfig = new ArduCopterPidConfig(this); arduCopterPidConfig = new ArduCopterPidConfig(this);
ui.stackedWidget->addWidget(arduCoperPidConfig); ui.stackedWidget->addWidget(arduCopterPidConfig);
buttonToConfigWidgetMap[ui.arduCoperPidButton] = arduCoperPidConfig; buttonToConfigWidgetMap[ui.arduCopterPidButton] = arduCopterPidConfig;
connect(ui.arduCoperPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget())); 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()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*))); connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
if (UASManager::instance()->getActiveUAS()) if (UASManager::instance()->getActiveUAS())
...@@ -84,7 +92,16 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas) ...@@ -84,7 +92,16 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
ui.advancedParamButton->setVisible(true); ui.advancedParamButton->setVisible(true);
ui.advParamListButton->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);
}
else if (uas->getSystemType() == MAV_TYPE_QUADROTOR)
{
ui.arduCopterPidButton->setVisible(true);
ui.arduPlanePidButton->setVisible(false);
}
QDir autopilotdir(qApp->applicationDirPath() + "/files/" + uas->getAutopilotTypeName().toLower()); QDir autopilotdir(qApp->applicationDirPath() + "/files/" + uas->getAutopilotTypeName().toLower());
......
...@@ -10,6 +10,7 @@ ...@@ -10,6 +10,7 @@
#include "FailSafeConfig.h" #include "FailSafeConfig.h"
#include "AdvancedParamConfig.h" #include "AdvancedParamConfig.h"
#include "ArduCopterPidConfig.h" #include "ArduCopterPidConfig.h"
#include "ArduPlanePidConfig.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UASManager.h" #include "UASManager.h"
...@@ -32,7 +33,8 @@ private: ...@@ -32,7 +33,8 @@ private:
GeoFenceConfig *geoFenceConfig; GeoFenceConfig *geoFenceConfig;
FailSafeConfig *failSafeConfig; FailSafeConfig *failSafeConfig;
AdvancedParamConfig *advancedParamConfig; AdvancedParamConfig *advancedParamConfig;
ArduCopterPidConfig *arduCoperPidConfig; ArduCopterPidConfig *arduCopterPidConfig;
ArduPlanePidConfig *arduPlanePidConfig;
QMap<QObject*,QWidget*> buttonToConfigWidgetMap; QMap<QObject*,QWidget*> buttonToConfigWidgetMap;
}; };
......
...@@ -172,7 +172,7 @@ ...@@ -172,7 +172,7 @@
</widget> </widget>
</item> </item>
<item> <item>
<widget class="QPushButton" name="arduCoperPidButton"> <widget class="QPushButton" name="arduCopterPidButton">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
...@@ -180,13 +180,26 @@ ...@@ -180,13 +180,26 @@
</size> </size>
</property> </property>
<property name="text"> <property name="text">
<string>ArduCoper Pids</string> <string>ArduCopter Pids</string>
</property> </property>
<property name="checkable"> <property name="checkable">
<bool>false</bool> <bool>false</bool>
</property> </property>
</widget> </widget>
</item> </item>
<item>
<widget class="QPushButton" name="arduPlanePidButton">
<property name="minimumSize">
<size>
<width>0</width>
<height>35</height>
</size>
</property>
<property name="text">
<string>ArduPlane Pids</string>
</property>
</widget>
</item>
<item> <item>
<spacer name="verticalSpacer"> <spacer name="verticalSpacer">
<property name="orientation"> <property name="orientation">
......
...@@ -4,15 +4,91 @@ ...@@ -4,15 +4,91 @@
ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent) ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent)
{ {
ui.setupUi(this); 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;
} }
ArduPlanePidConfig::~ArduPlanePidConfig() ArduPlanePidConfig::~ArduPlanePidConfig()
{ {
} }
void ArduPlanePidconfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) void ArduPlanePidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{ {
if (parameterName == "") if (nameToBoxMap.contains(parameterName))
{ {
nameToBoxMap[parameterName]->setValue(value.toDouble());
}
}
void ArduPlanePidConfig::writeButtonClicked()
{
if (!m_uas)
{
return;
}
for (QMap<QString,QDoubleSpinBox*>::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<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
{
m_uas->getParamManager()->requestParameterUpdate(1,i.key());
}
} }
...@@ -14,7 +14,10 @@ public: ...@@ -14,7 +14,10 @@ public:
~ArduPlanePidConfig(); ~ArduPlanePidConfig();
private slots: private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value); void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void writeButtonClicked();
void refreshButtonClicked();
private: private:
QMap<QString,QDoubleSpinBox*> nameToBoxMap;
Ui::ArduPlanePidConfig ui; Ui::ArduPlanePidConfig ui;
}; };
......
...@@ -164,9 +164,9 @@ ...@@ -164,9 +164,9 @@
</widget> </widget>
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="servoIMAXSpinBox"> <widget class="QDoubleSpinBox" name="servoRollIMAXSpinBox">
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -252,7 +252,7 @@ ...@@ -252,7 +252,7 @@
<item> <item>
<widget class="QDoubleSpinBox" name="navAltIMAXSpinBox"> <widget class="QDoubleSpinBox" name="navAltIMAXSpinBox">
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -338,7 +338,7 @@ ...@@ -338,7 +338,7 @@
<item> <item>
<widget class="QDoubleSpinBox" name="navASIMAXSpinBox"> <widget class="QDoubleSpinBox" name="navASIMAXSpinBox">
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -424,7 +424,7 @@ ...@@ -424,7 +424,7 @@
<item> <item>
<widget class="QDoubleSpinBox" name="servoYawIMAXSpinBox"> <widget class="QDoubleSpinBox" name="servoYawIMAXSpinBox">
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -510,7 +510,7 @@ ...@@ -510,7 +510,7 @@
<item> <item>
<widget class="QDoubleSpinBox" name="throttleFSSpinBox"> <widget class="QDoubleSpinBox" name="throttleFSSpinBox">
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -596,7 +596,7 @@ ...@@ -596,7 +596,7 @@
<item> <item>
<widget class="QDoubleSpinBox" name="servoPitchIMAXSpinBox"> <widget class="QDoubleSpinBox" name="servoPitchIMAXSpinBox">
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -815,8 +815,11 @@ ...@@ -815,8 +815,11 @@
<property name="decimals"> <property name="decimals">
<number>3</number> <number>3</number>
</property> </property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -826,7 +829,10 @@ ...@@ -826,7 +829,10 @@
<number>3</number> <number>3</number>
</property> </property>
<property name="maximum"> <property name="maximum">
<double>100.000000000000000</double> <double>10000.000000000000000</double>
</property>
<property name="value">
<double>0.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment