diff --git a/files/px4/parameter_tooltips/tooltips.txt b/files/px4/parameter_tooltips/tooltips.txt new file mode 100644 index 00000000000..d72273ccdb6 --- /dev/null +++ b/files/px4/parameter_tooltips/tooltips.txt @@ -0,0 +1,7 @@ +^ Name ^ Min ^ Max ^ Default ^ Multiplier ^ Enabled ^ Comment ^ +| BAT_V_EMPTY | 0.9 | 100.0 | 3.2 | 1 | 1 | Voltage of an empty battery cell | +| BAT_V_FULL | 1.0 | 200.0 | 4.05 | 1 | 1 | Voltage of a full battery cell | +| BAT_N_CELLS | 1 | 100 | 3 | 1 | 1 | Number of SERIAL battery cells. Typically this ranges from 2S to 6S in small-scale UAVs | +| BAT_V_SCALING | 0.001 | 1.0 | 0.00838 | 1 | 1 | Conversion from ADC ticks to battery voltage. Depends on the connected board, calibrate with a multimeter. | +| MC_ATTRATE_P | 0.0 | 20.0 | 0.20 | 1 | 1 | Multirotor attitude rate control P gain. This gain controls how much of the motor thrust should be used to control angular velocity. A larger number will increase the control response, but will make the system also more twitchy. | +| FW_ROLLRATE_P | 0.0 | 20.0 | 0.30 | 1 | 1 | Fixed wing roll rate control P gain. This gain controls how strong the ailerons or rudder should be actuated in order to achieve a certain roll rate. A larger number will increase the control response, but will make the system also more twitchy. | \ No newline at end of file diff --git a/files/px4/widgets/px4_mc_attitude_pid_params.qgw b/files/px4/widgets/px4_mc_attitude_pid_params.qgw index a7f8871abcf..1931dfa3b91 100644 --- a/files/px4/widgets/px4_mc_attitude_pid_params.qgw +++ b/files/px4/widgets/px4_mc_attitude_pid_params.qgw @@ -59,4 +59,14 @@ QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_PARAMID=MC_YAWRATE_P QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_COMPONENTID=50 QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MIN=0 QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DISPLAY_INFO=false +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_DISPLAY_INFO=true +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_DISPLAY_INFO=true QGC_TOOL_WIDGET_ITEMS\size=10 diff --git a/src/uas/QGCUASParamManager.h b/src/uas/QGCUASParamManager.h index d3fedc04f5c..5155db5287b 100644 --- a/src/uas/QGCUASParamManager.h +++ b/src/uas/QGCUASParamManager.h @@ -42,6 +42,7 @@ class QGCUASParamManager : public QWidget virtual double getParamMin(const QString& param) = 0; virtual double getParamMax(const QString& param) = 0; virtual double getParamDefault(const QString& param) = 0; + virtual const QString& getParamInfo(const QString& param) = 0; /** @brief Request an update for the parameter list */ void requestParameterListUpdate(int component = 0); diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index 0b8b23ad990..d31793a7220 100644 --- a/src/ui/QGCParamWidget.cc +++ b/src/ui/QGCParamWidget.cc @@ -165,11 +165,29 @@ void QGCParamWidget::loadSettings() void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QString& airframe) { + Q_UNUSED(airframe); + + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + qDebug() << "ATTEMPTING TO LOAD CSV"; + QDir appDir = QApplication::applicationDirPath(); appDir.cd("files"); - QString fileName = QString("%1/%2/%3/parameter_tooltips/tooltips.txt").arg(appDir.canonicalPath()).arg(autopilot.toLower()).arg(airframe.toLower()); + QString fileName = QString("%1/%2/parameter_tooltips/tooltips.txt").arg(appDir.canonicalPath()).arg(autopilot.toLower()); QFile paramMetaFile(fileName); + qDebug() << "AUTOPILOT:" << autopilot; + qDebug() << "FILENAME: " << fileName; + // Load CSV data if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text)) { @@ -189,7 +207,8 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin QString header = in.readLine(); // Ignore top-level comment lines - while (header.startsWith('#') || header.startsWith('/') || header.startsWith('=')) + while (header.startsWith('#') || header.startsWith('/') + || header.startsWith('=') || header.startsWith('^')) { header = in.readLine(); } @@ -266,23 +285,24 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin if (parts.count() > 1) { // min - paramMin.insert(parts.at(0), parts.at(1).toDouble()); + paramMin.insert(parts.at(0).trimmed(), parts.at(1).toDouble()); } if (parts.count() > 2) { // max - paramMax.insert(parts.at(0), parts.at(2).toDouble()); + paramMax.insert(parts.at(0).trimmed(), parts.at(2).toDouble()); } if (parts.count() > 3) { // default - paramDefault.insert(parts.at(0), parts.at(3).toDouble()); + paramDefault.insert(parts.at(0).trimmed(), parts.at(3).toDouble()); } // IGNORING 4 and 5 for now if (parts.count() > 6) { // tooltip - paramToolTips.insert(parts.at(0), parts.at(6).trimmed()); + paramToolTips.insert(parts.at(0).trimmed(), parts.at(6).trimmed()); + qDebug() << "PARAM META:" << parts.at(0).trimmed(); } } } diff --git a/src/ui/QGCParamWidget.h b/src/ui/QGCParamWidget.h index ad031a15461..013c81335a4 100644 --- a/src/ui/QGCParamWidget.h +++ b/src/ui/QGCParamWidget.h @@ -57,6 +57,7 @@ class QGCParamWidget : public QGCUASParamManager 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); } + const QString& getParamInfo(const QString& param) { return paramToolTips.value(param, ""); } signals: /** @brief A parameter was changed in the widget, NOT onboard */ diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui index 5290a8eec25..27f505cf219 100644 --- a/src/ui/QGCVehicleConfig.ui +++ b/src/ui/QGCVehicleConfig.ui @@ -40,7 +40,7 @@ - 0 + 2 @@ -715,10 +715,35 @@ Sensor Calibration - - + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:18pt;">Sensor Calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:16pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt;">The PX4FMU sensors can be calibrated with the buttons on the right. Gyroscope (GYRO) and Accelerometer (ACCEL) calibrations have to be performed with a static, unmoved system. The magnetometer calibration needs to be performed while moving the device.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:16pt;">Magnetometer Calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:16pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt;">Carefully follow the instructions. Click on MAG to start the calibration. Watch the communication console for further instructions (Available through Main Menu -&gt; Tool Widgets -&gt; Communication Console). Do not calibrate the vehicle in vincinity of metal, e.g. from a table or chair. Start the calibration, leave the system unmoved on the table. Wait for the double beep. Next move the system in a figure eight, roll and pitch it strongly and perform the figure eight also upside-down. The calibration is finished after the triple beep.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:16pt;">Accelerometer Calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:16pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt;">Put the system on an absolutely level surface and press ACCEL, wait for the the triple beep. Do not move the system. If no flat surface is available, rather not calibrate the system.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:16pt;">Gyroscope Calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:16pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt;">The orientation is not important for this calibration, but do not move the system until the triple beep or the matching text message in the console.</span></p></body></html> + + + @@ -739,26 +764,51 @@ - - + + - Attitude + Position - + - + - - + + - Position + Attitude - + + + 0 + - + + + true + + + + + 0 + 0 + 541 + 417 + + + + + 0 + + + + + + + diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index c73f460bdf2..93502e6da30 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -25,6 +25,7 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) : scaledInt = ui->valueSlider->maximum() - ui->valueSlider->minimum(); + ui->editInfoCheckBox->hide(); ui->editDoneButton->hide(); ui->editNameLabel->hide(); ui->editRefreshParamsButton->hide(); @@ -51,13 +52,10 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) : connect(ui->editNameLabel, SIGNAL(textChanged(QString)), ui->nameLabel, SLOT(setText(QString))); connect(ui->readButton, SIGNAL(clicked()), this, SLOT(requestParameter())); connect(ui->editRefreshParamsButton, SIGNAL(clicked()), this, SLOT(refreshParamList())); + connect(ui->editInfoCheckBox, SIGNAL(clicked(bool)), this, SLOT(showInfo(bool))); // Set the current UAS if present connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); - setActiveUAS(UASManager::instance()->getActiveUAS()); - - // Get param value after settings have been loaded - QTimer::singleShot(300, this, SLOT(requestParameter())); } QGCParamSlider::~QGCParamSlider() @@ -88,13 +86,14 @@ void QGCParamSlider::setActiveUAS(UASInterface* activeUas) connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(setParameterValue(int,int,int,int,QString,QVariant)), Qt::UniqueConnection); uas = activeUas; // Update current param value - if (parameterName == "") + requestParameter(); + // Set param info + QString text = uas->getParamManager()->getParamInfo(parameterName); + ui->infoLabel->setText(text); + // Force-uncheck and hide label if no description is available + if (ui->editInfoCheckBox->isChecked()) { - refreshParamList(); - } - else - { - requestParameter(); + showInfo((text.length() > 0)); } } } @@ -107,6 +106,12 @@ void QGCParamSlider::requestParameter() } } +void QGCParamSlider::showInfo(bool enable) +{ + ui->editInfoCheckBox->setChecked(enable); + ui->infoLabel->setVisible(enable); +} + void QGCParamSlider::setParamValue(double value) { parameterValue = (float)value; @@ -150,6 +155,11 @@ void QGCParamSlider::selectParameter(int paramIndex) parameterMax = uas->getParamManager()->getParamMax(parameterName); ui->editMaxSpinBox->setValue(parameterMax); } + + // Description + QString text = uas->getParamManager()->getParamInfo(parameterName); + ui->infoLabel->setText(text); + showInfo(!(text.length() > 0)); } } } @@ -163,6 +173,7 @@ void QGCParamSlider::startEditMode() ui->writeButton->hide(); ui->readButton->hide(); + ui->editInfoCheckBox->show(); ui->editDoneButton->show(); ui->editNameLabel->show(); ui->editRefreshParamsButton->show(); @@ -190,6 +201,7 @@ void QGCParamSlider::endEditMode() parameterMin = ui->editMinSpinBox->value(); parameterMax = ui->editMaxSpinBox->value(); + ui->editInfoCheckBox->hide(); ui->editDoneButton->hide(); ui->editNameLabel->hide(); ui->editRefreshParamsButton->hide(); @@ -370,6 +382,7 @@ void QGCParamSlider::writeSettings(QSettings& settings) settings.setValue("QGC_PARAM_SLIDER_COMPONENTID", component); settings.setValue("QGC_PARAM_SLIDER_MIN", ui->editMinSpinBox->value()); settings.setValue("QGC_PARAM_SLIDER_MAX", ui->editMaxSpinBox->value()); + settings.setValue("QGC_PARAM_SLIDER_DISPLAY_INFO", ui->editInfoCheckBox->isChecked()); settings.sync(); } @@ -385,6 +398,12 @@ void QGCParamSlider::readSettings(const QSettings& settings) ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(settings.value("QGC_PARAM_SLIDER_COMPONENTID").toInt()), settings.value("QGC_PARAM_SLIDER_COMPONENTID").toInt()); ui->editMinSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MIN").toFloat()); ui->editMaxSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MAX").toFloat()); + showInfo(settings.value("QGC_PARAM_SLIDER_DISPLAY_INFO", true).toBool()); ui->editSelectParamComboBox->setEnabled(true); ui->editSelectComponentComboBox->setEnabled(true); + + setActiveUAS(UASManager::instance()->getActiveUAS()); + + // Get param value after settings have been loaded + requestParameter(); } diff --git a/src/ui/designer/QGCParamSlider.h b/src/ui/designer/QGCParamSlider.h index 6e9612d6842..d12d9f4f0cb 100644 --- a/src/ui/designer/QGCParamSlider.h +++ b/src/ui/designer/QGCParamSlider.h @@ -39,6 +39,8 @@ public slots: void setParamValue(double value); /** @brief Set an integer parameter value */ void setParamValue(int value); + /** @brief Show descriptive text next to slider */ + void showInfo(bool enable); protected slots: /** @brief Request the parameter of this widget from the MAV */ diff --git a/src/ui/designer/QGCParamSlider.ui b/src/ui/designer/QGCParamSlider.ui index 488be8f12d8..f66bac5bdc9 100644 --- a/src/ui/designer/QGCParamSlider.ui +++ b/src/ui/designer/QGCParamSlider.ui @@ -7,13 +7,13 @@ 0 0 789 - 158 + 170 Form - + 6 @@ -32,14 +32,14 @@ 12 - + <Parameter Name / Label> - + @@ -55,7 +55,7 @@ - + @@ -77,14 +77,7 @@ - - - - Please click first on refresh to update selection menus.. - - - - + false @@ -97,7 +90,14 @@ - + + + + Please click first on refresh to update selection menus.. + + + + false @@ -110,43 +110,20 @@ - - + + 0 0 - - Read the current parameter value on the system - - - Read the current parameter value on the system - - - R - - - - - - - true - - - Refresh - - - - - - - Done + + Qt::Horizontal - + -999999999.000000000000000 @@ -169,33 +146,80 @@ - - + + + + Done + + + + + + + MIN: + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + + + + + MAX: + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + + + + + -999999999 + + + 999999999 + + + + + 0 0 - - - 16777215 - 16777215 - - - Transmit the current slider value to the system + Read the current parameter value on the system - Transmit the current slider value to the system + Read the current parameter value on the system - W + R - - + + + + true + + + Refresh + + + + + 0 @@ -207,52 +231,41 @@ - - + + 0 0 - - Qt::Horizontal + + + 16777215 + 16777215 + - - - - - - MIN: + + Transmit the current slider value to the system - - -999999999.000000000000000 + + Transmit the current slider value to the system - - 999999999.000000000000000 + + W - - - - MAX: - - - -999999999.000000000000000 - - - 999999999.000000000000000 - - + + - - - - -999999999 + + + + Show Info - - 999999999 + + true