Commit 6b29bc4a authored by LM's avatar LM

Working on auto params

parent 04dbdee2
......@@ -72,6 +72,14 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
onboardParams.insert("SYS_ID", systemId);
onboardParams.insert("RC4_REV", 0);
onboardParams.insert("RC5_REV", 1);
onboardParams.insert("HDNG2RLL_P", 0.7f);
onboardParams.insert("HDNG2RLL_I", 0.01f);
onboardParams.insert("HDNG2RLL_D", 0.02f);
onboardParams.insert("HDNG2RLL_IMAX", 500.0f);
onboardParams.insert("RLL2SRV_P", 0.4f);
onboardParams.insert("RLL2SRV_I", 0.0f);
onboardParams.insert("RLL2SRV_D", 0.0f);
onboardParams.insert("RLL2SRV_IMAX", 500.0f);
// Comments on the variables can be found in the header file
......
......@@ -24,6 +24,13 @@ public:
return parameters.value(component)->value(parameter);
}
virtual bool isParamMinKnown(const QString& param) = 0;
virtual bool isParamMaxKnown(const QString& param) = 0;
virtual bool isParamDefaultKnown(const QString& param) = 0;
virtual double getParamMin(const QString& param) = 0;
virtual double getParamMax(const QString& param) = 0;
virtual double getParamDefault(const QString& param) = 0;
/** @brief Request an update for the parameter list */
void requestParameterListUpdate(int component = 0);
/** @brief Request an update for this specific parameter */
......
......@@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project
#include <QList>
#include <QSettings>
#include <QMessageBox>
#include <QApplication>
#include "QGCParamWidget.h"
#include "UASInterface.h"
......@@ -150,16 +151,15 @@ void QGCParamWidget::loadSettings()
void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QString& airframe)
{
QDir appDir = QDir::current();
QDir appDir = QApplication::applicationDirPath();
appDir.cd("files");
QString fileName = QString("/%1/%2/parameter_tooltips/tooltips.txt").arg(autopilot.toLower()).arg(airframe.toLower());
QString filePath = appDir.filePath(fileName);
QFile paramMetaFile(filePath);
QString fileName = QString("%1/%2/%3/parameter_tooltips/tooltips.txt").arg(appDir.canonicalPath()).arg(autopilot.toLower()).arg(airframe.toLower());
QFile paramMetaFile(fileName);
// Load CSV data
if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text))
{
qDebug() << "COULD NOT OPEN PARAM META INFO FILE:" << filePath;
qDebug() << "COULD NOT OPEN PARAM META INFO FILE:" << fileName;
return;
}
......@@ -571,7 +571,7 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
if (paramDefault.contains(parameterName))
{
tooltipFormat = tr("Default: %1, %2");
tooltipFormat = tooltipFormat.arg(paramToolTips.value(parameterName, ""), paramDefault.value(parameterName));
tooltipFormat = tooltipFormat.arg(paramDefault.value(parameterName, 0.0f)).arg(paramToolTips.value(parameterName, ""));
}
else
{
......@@ -590,6 +590,7 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
*/
void QGCParamWidget::requestParameterList()
{
qDebug() << "LOADING PARAM LIST";
if (!mav) return;
// FIXME This call does not belong here
// Once the comm handling is moved to a new
......@@ -615,7 +616,7 @@ void QGCParamWidget::requestParameterList()
// Request twice as mean of forward error correction
mav->requestParameters();
QGC::SLEEP::msleep(10);
QGC::SLEEP::msleep(15);
mav->requestParameters();
}
......
......@@ -50,6 +50,14 @@ public:
QGCParamWidget(UASInterface* uas, QWidget *parent = 0);
/** @brief Get the UAS of this widget */
UASInterface* getUAS();
bool isParamMinKnown(const QString& param) { return paramMin.contains(param); }
bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); }
bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); }
double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); }
double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); }
double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); }
signals:
/** @brief A parameter was changed in the widget, NOT onboard */
void parameterChanged(int component, QString parametername, QVariant value);
......
......@@ -54,6 +54,20 @@ QGCCommandButton::QGCCommandButton(QWidget *parent) :
ui->editCommandComboBox->addItem("CUSTOM 14", 14);
ui->editCommandComboBox->addItem("CUSTOM 15", 15);
ui->editCommandComboBox->addItem("NAV_WAYPOINT", 16);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_LOITER_UNLIM", 17);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_LOITER_TURNS", 18);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_LOITER_TIME", 19);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_RETURN_TO_LAUNCH", 20);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_LAND", 21);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_TAKEOFF", 22);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_ROI", 80);
ui->editCommandComboBox->addItem("MAV_CMD_NAV_PATHPLANNING", 81);
ui->editCommandComboBox->addItem("MAV_CMD_DO_SET_MODE", 176);
ui->editCommandComboBox->addItem("MAV_CMD_DO_CHANGE_SPEED", 178);
ui->editCommandComboBox->addItem("MAV_CMD_DO_SET_HOME", 179);
ui->editCommandComboBox->addItem("MAV_CMD_DO_SET_RELAY", 181);
ui->editCommandComboBox->addItem("MAV_CMD_DO_REPEAT_RELAY", 182);
ui->editCommandComboBox->addItem("MAV_CMD_DO_SET_SERVO", 183);
ui->editCommandComboBox->setEditable(true);
}
......
......@@ -57,7 +57,7 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
setActiveUAS(UASManager::instance()->getActiveUAS());
// Get param value
QTimer::singleShot(1000, this, SLOT(requestParameter()));
QTimer::singleShot(100, this, SLOT(requestParameter()));
}
QGCParamSlider::~QGCParamSlider()
......@@ -119,7 +119,32 @@ void QGCParamSlider::selectComponent(int componentIndex)
void QGCParamSlider::selectParameter(int paramIndex)
{
// Set name
parameterName = ui->editSelectParamComboBox->itemText(paramIndex);
// Update min and max values if available
if (uas)
{
if (uas->getParamManager())
{
// Current value
uas->getParamManager()->requestParameterUpdate(component, parameterName);
// Minimum
if (uas->getParamManager()->isParamMinKnown(parameterName))
{
parameterMin = uas->getParamManager()->getParamMin(parameterName);
ui->editMinSpinBox->setValue(parameterMin);
}
// Maximum
if (uas->getParamManager()->isParamMaxKnown(parameterName))
{
parameterMax = uas->getParamManager()->getParamMax(parameterName);
ui->editMaxSpinBox->setValue(parameterMax);
}
}
}
}
void QGCParamSlider::startEditMode()
......
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