diff --git a/files/px4/parameter_tooltips/tooltips.txt b/files/px4/parameter_tooltips/tooltips.txt new file mode 100644 index 0000000000000000000000000000000000000000..d72273ccdb6329716600419265b05528a2a36975 --- /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/quadrotor/widgets/px4_calibration.qgw b/files/px4/quadrotor/widgets/px4_calibration.qgw deleted file mode 100644 index dd81822ad54f3f676211a6788bc0f6af441cfc39..0000000000000000000000000000000000000000 --- a/files/px4/quadrotor/widgets/px4_calibration.qgw +++ /dev/null @@ -1,50 +0,0 @@ -[PX4%20Calibration%20Tool] -QGC_TOOL_WIDGET_ITEMS\1\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=Reboot (only in standby) -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_BUTTONTEXT=REBOOT -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_COMMANDID=246 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM1=1 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM1=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM2=1 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=1 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\4\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_BUTTONTEXT=GYRO -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_COMMANDID=241 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM1=1 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM2=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM3=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM4=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM5=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM6=0 -QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM7=0 -QGC_TOOL_WIDGET_ITEMS\size=4 diff --git a/files/px4/hexarotor/widgets/px4_calibration.qgw b/files/px4/widgets/px4_calibration.qgw similarity index 95% rename from files/px4/hexarotor/widgets/px4_calibration.qgw rename to files/px4/widgets/px4_calibration.qgw index dd81822ad54f3f676211a6788bc0f6af441cfc39..cd751672c51bdedede873b0fee3f956f010d2eaa 100644 --- a/files/px4/hexarotor/widgets/px4_calibration.qgw +++ b/files/px4/widgets/px4_calibration.qgw @@ -12,7 +12,7 @@ QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0 QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0 QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0 QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON -QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration +QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Magnetometer calibration QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241 QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false diff --git a/files/px4/widgets/px4_fw_attitude_pid_params.qgw b/files/px4/widgets/px4_fw_attitude_pid_params.qgw new file mode 100644 index 0000000000000000000000000000000000000000..6f3186e78f3544c718ee98a9d5f02d205f3fc85b --- /dev/null +++ b/files/px4/widgets/px4_fw_attitude_pid_params.qgw @@ -0,0 +1,8 @@ +[PX4%20Fixed%20Wing%20Attitude%20Control] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Roll Rate P Gain +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=FW_ROLLRATE_P +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=2 +QGC_TOOL_WIDGET_ITEMS\size=1 diff --git a/files/px4/widgets/px4_fw_position_pid_params.qgw b/files/px4/widgets/px4_fw_position_pid_params.qgw new file mode 100644 index 0000000000000000000000000000000000000000..e99f9890e9beb6984c4932c9a2be46cad04bb521 --- /dev/null +++ b/files/px4/widgets/px4_fw_position_pid_params.qgw @@ -0,0 +1,8 @@ +[PX4%20Fixed%20Wing%20Position%20Control] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Heading P Gain +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=FW_HEADING_P +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=2 +QGC_TOOL_WIDGET_ITEMS\size=1 diff --git a/files/px4/widgets/px4_mc_attitude_pid_params.qgw b/files/px4/widgets/px4_mc_attitude_pid_params.qgw new file mode 100644 index 0000000000000000000000000000000000000000..1931dfa3b912adac6f5185a7bfee217e3dee332a --- /dev/null +++ b/files/px4/widgets/px4_mc_attitude_pid_params.qgw @@ -0,0 +1,72 @@ +[PX4%20Multirotor%20Attitude%20Control] +QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Attitude P Gain +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=MC_ATT_P +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=1.5 +QGC_TOOL_WIDGET_ITEMS\2\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DESCRIPTION=Attitude I Gain +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_PARAMID=MC_ATT_I +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\3\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DESCRIPTION=Attitude D Gain +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_PARAMID=MC_ATT_D +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Anti-Windup +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=MC_ATT_AWU +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\5\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Output Limit +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_PARAMID=MC_ATT_LIM +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MAX=3 +QGC_TOOL_WIDGET_ITEMS\6\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw P Gain +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_P +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MAX=1.2 +QGC_TOOL_WIDGET_ITEMS\7\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw D Gain +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_D +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MAX=1 +QGC_TOOL_WIDGET_ITEMS\8\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate P Gain +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_P +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MAX=1.5 +QGC_TOOL_WIDGET_ITEMS\9\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate D Gain +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_D +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_COMPONENTID=50 +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MIN=0 +QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MAX=0.3 +QGC_TOOL_WIDGET_ITEMS\10\TYPE=SLIDER +QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_DESCRIPTION=Yaw Rate P Gain +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 d3fedc04f5c171a3b0caa7cd9a50c57d8d5c2ef3..069edc8a8c77a68520d654dcca892b4ebc82616d 100644 --- a/src/uas/QGCUASParamManager.h +++ b/src/uas/QGCUASParamManager.h @@ -42,6 +42,7 @@ public: virtual double getParamMin(const QString& param) = 0; virtual double getParamMax(const QString& param) = 0; virtual double getParamDefault(const QString& param) = 0; + virtual QString getParamInfo(const QString& param) = 0; /** @brief Request an update for the parameter list */ void requestParameterListUpdate(int component = 0); diff --git a/src/uas/UAS.h b/src/uas/UAS.h index c67f036791ef0497ef7a8878989770ce777d0bc0..478edf60b7a5fa4645c67b01d1f01bda26d62b08 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -478,6 +478,9 @@ public: case MAV_AUTOPILOT_FP: return "FP"; break; + case MAV_AUTOPILOT_PX4: + return "PX4"; + break; default: return ""; break; diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 2209ab70fcf76e71be63002149cc321762a9aa06..da698e4b6de3c808fabfb068d2f686cd1d505ebe 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -565,11 +565,11 @@ void MainWindow::buildCommonWidgets() addCentralWidget(hudWidget, tr("Head Up Display")); } -// if (!configWidget) -// { -// configWidget = new QGCVehicleConfig(this); -// addCentralWidget(configWidget, tr("Vehicle Configuration")); -// } + if (!configWidget) + { + configWidget = new QGCVehicleConfig(this); + addCentralWidget(configWidget, tr("Vehicle Configuration")); + } if (!dataplotWidget) { @@ -745,10 +745,14 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance) void MainWindow::loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType) { - QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; + QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/widgets/"; + QString platformDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; QDir widgets(defaultsDir); QStringList files = widgets.entryList(); + QDir platformWidgets(platformDir); + files.append(platformWidgets.entryList()); + if (files.count() == 0) { qDebug() << "No default custom widgets for system " << systemType << "autopilot" << autopilotType << " found"; diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index 0b8b23ad9903b40087d6640c6249c1e1113bad4b..d31793a7220b8f0e0e5a9caef17aa5236cb1aa6e 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 ad031a15461ef51280c7a4cc6e439618beb912ad..8dc801e5778d77ed768abed00736714ae098fb7f 100644 --- a/src/ui/QGCParamWidget.h +++ b/src/ui/QGCParamWidget.h @@ -57,6 +57,7 @@ public: 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); } + 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/QGCRemoteControlView.cc b/src/ui/QGCRemoteControlView.cc index 7efc3150e7017a19d6affda4752a88fc0e37c2ed..bfef68ea263d9e2605cefcaa7e9f8399f61dec45 100644 --- a/src/ui/QGCRemoteControlView.cc +++ b/src/ui/QGCRemoteControlView.cc @@ -55,13 +55,13 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) : this->setVisible(false); //setVisible(false); - calibrate = new QPushButton(tr("Calibrate"), this); - QHBoxLayout *calibrateButtonLayout = new QHBoxLayout(); - calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter); - layout->addItem(calibrateButtonLayout, 3, 0, 1, 2); +// calibrate = new QPushButton(tr("Calibrate"), this); +// QHBoxLayout *calibrateButtonLayout = new QHBoxLayout(); +// calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter); +// layout->addItem(calibrateButtonLayout, 3, 0, 1, 2); - calibrationWindow = new RadioCalibrationWindow(this); - connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show())); +// calibrationWindow = new RadioCalibrationWindow(this); +// connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show())); connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int))); @@ -91,8 +91,8 @@ void QGCRemoteControlView::setUASId(int id) // The UAS exists, disconnect any existing connections disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float))); disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float))); - disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); - disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); + //disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); + //disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float))); } } @@ -124,15 +124,15 @@ void QGCRemoteControlView::setUASId(int id) { // New UAS exists, connect nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName())); - calibrationWindow->setUASId(id); - connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); + //calibrationWindow->setUASId(id); + //connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer&)), calibrationWindow, SLOT(receive(const QPointer&))); connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float))); connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float))); connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float))); // only connect raw channels to calibration window widget - connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); + //connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); } } @@ -178,7 +178,7 @@ void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized) void QGCRemoteControlView::appendChannelWidget(int channelId) { // Create new layout - QHBoxLayout* layout = new QHBoxLayout(this); + QHBoxLayout* layout = new QHBoxLayout(); // Add content layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this)); QLabel* raw = new QLabel(this); diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index 3f6565e618fe4caedd9c52e52979294e25ad9103..c0f08fa90bd68cb8800c7a794038d52813f62fd4 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -5,12 +5,22 @@ #include "QGCVehicleConfig.h" #include "UASManager.h" #include "QGC.h" +#include "QGCToolWidget.h" #include "ui_QGCVehicleConfig.h" QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : QWidget(parent), mav(NULL), changed(true), + rc_mode(RC_MODE_2), + rcRoll(0.0f), + rcPitch(0.0f), + rcYaw(0.0f), + rcThrottle(0.0f), + rcMode(0.0f), + rcAux1(0.0f), + rcAux2(0.0f), + rcAux3(0.0f), ui(new Ui::QGCVehicleConfig) { setObjectName("QGC_VEHICLECONFIG"); @@ -19,8 +29,11 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : requestCalibrationRC(); if (mav) mav->requestParameter(0, "RC_TYPE"); + ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1); + connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool))); connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters())); + connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); @@ -41,6 +54,14 @@ QGCVehicleConfig::~QGCVehicleConfig() delete ui; } +void QGCVehicleConfig::setRCModeIndex(int newRcMode) +{ + if (newRcMode > 0 && newRcMode < 5) + { + rc_mode = (enum RC_MODE) (newRcMode+1); + changed = true; + } +} void QGCVehicleConfig::toggleCalibrationRC(bool enabled) { @@ -57,12 +78,14 @@ void QGCVehicleConfig::toggleCalibrationRC(bool enabled) void QGCVehicleConfig::startCalibrationRC() { ui->rcTypeComboBox->setEnabled(false); + ui->rcCalibrationButton->setText(tr("Stop RC Calibration")); resetCalibrationRC(); } void QGCVehicleConfig::stopCalibrationRC() { ui->rcTypeComboBox->setEnabled(true); + ui->rcCalibrationButton->setText(tr("Start RC Calibration")); } void QGCVehicleConfig::setActiveUAS(UASInterface* active) @@ -77,15 +100,69 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active) SLOT(remoteControlChannelRawChanged(int,float))); disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); - resetCalibrationRC(); + + foreach (QGCToolWidget* tool, toolWidgets) + { + delete tool; + } } + // Reset current state + resetCalibrationRC(); + // Connect new system mav = active; connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(remoteControlChannelRawChanged(int,float))); connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); + + mav->requestParameters(); + + QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/"; + + QGCToolWidget* tool; + + // Load calibration + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_calibration.qgw", false)) + { + toolWidgets.append(tool); + ui->sensorLayout->addWidget(tool); + } + // Load multirotor attitude pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_mc_attitude_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->multiRotorAttitudeLayout->addWidget(tool); + } + + // Load multirotor position pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_mc_position_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->multiRotorPositionLayout->addWidget(tool); + } + + // Load fixed wing attitude pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_fw_attitude_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->fixedWingAttitudeLayout->addWidget(tool); + } + + // Load fixed wing position pid + tool = new QGCToolWidget("", this); + if (tool->loadSettings(defaultsDir + "px4_fw_position_pid_params.qgw", false)) + { + toolWidgets.append(tool); + ui->fixedWingPositionLayout->addWidget(tool); + } + + updateStatus(QString("Reading from system %1").arg(mav->getUASName())); } void QGCVehicleConfig::resetCalibrationRC() @@ -177,6 +254,16 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) if (chan < 0 || static_cast(chan) >= chanMax) return; + if (val < rcMin[chan]) + { + rcMin[chan] = val; + } + + if (val > rcMax[chan]) + { + rcMax[chan] = val; + } + if (chan == rcMapping[0]) { // ROLL @@ -252,16 +339,19 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) { // AUX1 rcAux1 = val; + rcValue[5] = val; } else if (chan == rcMapping[6]) { // AUX2 rcAux2 = val; + rcValue[6] = val; } else if (chan == rcMapping[7]) { // AUX3 rcAux3 = val; + rcValue[7] = val; } changed = true; @@ -273,6 +363,91 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete { Q_UNUSED(uas); Q_UNUSED(component); + + // Channel calibration values + QRegExp minTpl("RC?_MIN"); + minTpl.setPatternSyntax(QRegExp::Wildcard); + QRegExp maxTpl("RC?_MAX"); + maxTpl.setPatternSyntax(QRegExp::Wildcard); + QRegExp trimTpl("RC?_TRIM"); + trimTpl.setPatternSyntax(QRegExp::Wildcard); + QRegExp revTpl("RC?_REV"); + revTpl.setPatternSyntax(QRegExp::Wildcard); + + // Do not write the RC type, as these values depend on this + // active onboard parameter + + if (minTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcMin[index] = value.toInt(); + } + } + + if (maxTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcMax[index] = value.toInt(); + } + } + + if (trimTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcTrim[index] = value.toInt(); + } + } + + if (revTpl.exactMatch(parameterName)) { + bool ok; + unsigned int index = parameterName.mid(2, 1).toInt(&ok); + if (ok && (index > 0) && (index < chanMax)) + { + rcRev[index] = (value.toInt() == -1) ? true : false; + + unsigned int mapindex = rcMapping[index]; + + switch (mapindex) + { + case 0: + ui->invertCheckBox->setChecked(rcRev[index]); + break; + case 1: + ui->invertCheckBox_2->setChecked(rcRev[index]); + break; + case 2: + ui->invertCheckBox_3->setChecked(rcRev[index]); + break; + case 3: + ui->invertCheckBox_4->setChecked(rcRev[index]); + break; + case 4: + ui->invertCheckBox_5->setChecked(rcRev[index]); + break; + case 5: + ui->invertCheckBox_6->setChecked(rcRev[index]); + break; + case 6: + ui->invertCheckBox_7->setChecked(rcRev[index]); + break; + case 7: + ui->invertCheckBox_8->setChecked(rcRev[index]); + break; + } + } + } + +// mav->setParameter(0, trimTpl.arg(i), rcTrim[i]); +// mav->setParameter(0, maxTpl.arg(i), rcMax[i]); +// mav->setParameter(0, revTpl.arg(i), (rcRev[i]) ? -1 : 1); +// } + if (rcTypeUpdateRequested > 0 && parameterName == QString("RC_TYPE")) { rcTypeUpdateRequested = 0; @@ -281,6 +456,82 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete // Request all other parameters as well requestCalibrationRC(); } + + // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3 + + if (parameterName.contains("RC_MAP_ROLL")) { + rcMapping[0] = value.toInt(); + ui->rollSpinBox->setValue(rcMapping[0]); + } + + if (parameterName.contains("RC_MAP_PITCH")) { + rcMapping[1] = value.toInt(); + ui->pitchSpinBox->setValue(rcMapping[1]); + } + + if (parameterName.contains("RC_MAP_YAW")) { + rcMapping[2] = value.toInt(); + ui->yawSpinBox->setValue(rcMapping[2]); + } + + if (parameterName.contains("RC_MAP_THROTTLE")) { + rcMapping[3] = value.toInt(); + ui->throttleSpinBox->setValue(rcMapping[3]); + } + + if (parameterName.contains("RC_MAP_MODE_SW")) { + rcMapping[4] = value.toInt(); + ui->modeSpinBox->setValue(rcMapping[4]); + } + + if (parameterName.contains("RC_MAP_AUX1")) { + rcMapping[5] = value.toInt(); + ui->aux1SpinBox->setValue(rcMapping[5]); + } + + if (parameterName.contains("RC_MAP_AUX2")) { + rcMapping[6] = value.toInt(); + ui->aux1SpinBox->setValue(rcMapping[6]); + } + + if (parameterName.contains("RC_MAP_AUX3")) { + rcMapping[7] = value.toInt(); + ui->aux1SpinBox->setValue(rcMapping[7]); + } + + // Scaling + + if (parameterName.contains("RC_SCALE_ROLL")) { + rcScaling[0] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_PITCH")) { + rcScaling[1] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_YAW")) { + rcScaling[2] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_THROTTLE")) { + rcScaling[3] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_MODE_SW")) { + rcScaling[4] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_AUX1")) { + rcScaling[5] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_AUX2")) { + rcScaling[6] = value.toInt(); + } + + if (parameterName.contains("RC_SCALE_AUX3")) { + rcScaling[7] = value.toInt(); + } } void QGCVehicleConfig::updateStatus(const QString& str) @@ -321,10 +572,47 @@ void QGCVehicleConfig::updateView() { if (changed) { - ui->rollSlider->setValue(rcValue[0]); - ui->pitchSlider->setValue(rcValue[1]); - ui->yawSlider->setValue(rcValue[2]); - ui->throttleSlider->setValue(rcValue[3]); + if (rc_mode == RC_MODE_1) + { + ui->rollSlider->setValue(rcRoll); + ui->pitchSlider->setValue(rcThrottle); + ui->yawSlider->setValue(rcYaw); + ui->throttleSlider->setValue(rcPitch); + } + else if (rc_mode == RC_MODE_2) + { + ui->rollSlider->setValue(rcRoll); + ui->pitchSlider->setValue(rcPitch); + ui->yawSlider->setValue(rcYaw); + ui->throttleSlider->setValue(rcThrottle); + } + else if (rc_mode == RC_MODE_3) + { + ui->rollSlider->setValue(rcYaw); + ui->pitchSlider->setValue(rcThrottle); + ui->yawSlider->setValue(rcRoll); + ui->throttleSlider->setValue(rcPitch); + } + else if (rc_mode == RC_MODE_4) + { + ui->rollSlider->setValue(rcYaw); + ui->pitchSlider->setValue(rcPitch); + ui->yawSlider->setValue(rcRoll); + ui->throttleSlider->setValue(rcThrottle); + } + + ui->chanLabel->setText(QString("%1/%2").arg(rcValue[0]).arg(rcRoll)); + ui->chanLabel_2->setText(QString("%1/%2").arg(rcValue[1]).arg(rcPitch)); + ui->chanLabel_3->setText(QString("%1/%2").arg(rcValue[2]).arg(rcYaw)); + ui->chanLabel_4->setText(QString("%1/%2").arg(rcValue[3]).arg(rcThrottle)); + ui->modeSwitchSlider->setValue(rcMode); + ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[4]).arg(rcMode)); + ui->aux1Slider->setValue(rcAux1); + ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[5]).arg(rcAux1)); + ui->aux2Slider->setValue(rcAux2); + ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[6]).arg(rcAux2)); + ui->aux3Slider->setValue(rcAux3); + ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[7]).arg(rcAux3)); changed = false; } } diff --git a/src/ui/QGCVehicleConfig.h b/src/ui/QGCVehicleConfig.h index a9b09f869373d3a4f3a105991d29a55293a6573b..caec352a16d2c76524477ae37c839002c07730c4 100644 --- a/src/ui/QGCVehicleConfig.h +++ b/src/ui/QGCVehicleConfig.h @@ -3,7 +3,9 @@ #include #include +#include +#include "QGCToolWidget.h" #include "UASInterface.h" namespace Ui { @@ -18,6 +20,13 @@ public: explicit QGCVehicleConfig(QWidget *parent = 0); ~QGCVehicleConfig(); + enum RC_MODE { + RC_MODE_1 = 1, + RC_MODE_2 = 2, + RC_MODE_3 = 3, + RC_MODE_4 = 4 + }; + public slots: /** Set the MAV currently being calibrated */ void setActiveUAS(UASInterface* active); @@ -28,6 +37,8 @@ public slots: void stopCalibrationRC(); /** Start/stop the RC calibration routine */ void toggleCalibrationRC(bool enabled); + /** Change the mode setting of the control inputs */ + void setRCModeIndex(int newRcMode); /** Render the data updated */ void updateView(); @@ -60,6 +71,7 @@ protected: int rcMax[chanMax]; ///< Maximum values int rcTrim[chanMax]; ///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle) int rcMapping[chanMax]; ///< PWM to function mappings + float rcScaling[chanMax]; ///< Scaling of channel input to control commands bool rcRev[chanMax]; ///< Channel reverse int rcValue[chanMax]; ///< Last values float rcRoll; ///< PPM input channel used as roll control input @@ -73,6 +85,8 @@ protected: bool rcCalChanged; ///< Set if the calibration changes (and needs to be written) bool changed; ///< Set if any of the input data changed QTimer updateTimer; ///< Controls update intervals + enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention + QList toolWidgets; ///< Configurable widgets private: Ui::QGCVehicleConfig *ui; diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui index 85ac487c498719e876d377a9f4422d87d0ec624b..27f505cf2198b04ec18180f1c45b734200028fa6 100644 --- a/src/ui/QGCVehicleConfig.ui +++ b/src/ui/QGCVehicleConfig.ui @@ -6,7 +6,7 @@ 0 0 - 658 + 717 586 @@ -23,45 +23,137 @@ 6 + + + + Store to EEPROM + + + + + + + No pending changes + + + - 0 + 2 RC Calibration - - - + + + + + -1 + + + 1 + + + 0 + Qt::Vertical - - - - + + + + -1 - - :/files/images/rc_stick.svg + + 1 - - true + + 0 + + + Qt::Vertical - - + + + + + + false + + + false + + + + Select transmitter model + + + + + + + + true + + + + Mode 1 + + + + + Mode 2 + + + + + Mode 3 + + + + + Mode 4 + + + + + + + + Qt::Vertical + + + 598 + 5 + + + + + + + + + - - + + + + + + + + + Qt::Horizontal @@ -73,93 +165,409 @@ - - + + + + + + Aux 3 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Pitch / Elevator + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Aux 2 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Invert + + + + + + + 1 + + + 8 + + + + + + + 1 + + + 8 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Throttle + + + + + + + Invert + + + + + + + 1 + + + 8 + + + + + + + 1 + + + 8 + + + + + + + Mode Switch + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 1 + + + 8 + + + + + + + 1 + + + 8 + + + + + + + Aux 1 + + + + + + + 1 + + + 8 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 1 + + + 8 + + + + + + + Roll / Ailerons + + + + + + + Invert + + + + + + + Invert + + + + + + + Invert + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Invert + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Yaw / Rudder + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Invert + + + + + + + Invert + + + + + + + + + Qt::Horizontal + + + + 22 + 122 + + + + + + Qt::Vertical - 5 - 5 + 598 + 17 - - + + - - - - - - 800 - - - 2200 - - - 1500 + + :/files/images/rc_stick.svg - - Qt::Horizontal + + true - - - - false + + + + Qt::Horizontal - - - Select control mode - - - - - - - - - Select transmitter model - - - - - - - + - 100 - 100 + 40 + 20 + + + + + + + 1 + 1 + + - 50 - 50 + 10 + 10 - 50 - 50 + 100 + 100 - - - - - - - :/files/images/rc_stick.svg @@ -168,87 +576,128 @@ - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + -1 + + + 1 + + + 0 + + + Qt::Horizontal + + + + - 800 + -1 - 2200 + 1 - 1500 + 0 Qt::Horizontal - - + + - + Start Calibration - - + + + + Qt::Vertical + + + QSizePolicy::MinimumExpanding + + + + 20 + 10 + + + + + + - 800 + -1 - 2200 - - - 1500 + 1 Qt::Vertical - - + + + + -1 + + + 1 + Qt::Vertical - - + + + + -1 + + + 1 + Qt::Vertical - - + + - 800 + -1 - 2200 + 1 Qt::Vertical - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + + Qt::Horizontal @@ -260,235 +709,158 @@ - - - - Start Calibration - - - Sensor Calibration - - - - 30 - 20 - 161 - 32 - - - - Gyro Calibration - - - - - - 30 - 80 - 161 - 32 - - - - Accel Calibration - - - - - - 30 - 140 - 161 - 32 - - - - Mag 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> + + + + - Multirotor Attitude Control + Multirotor Control - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - - - - - - - Set Gains - - + + - - + + Load Platform Defaults - - - - - - - - - - Qt::Horizontal - - - - - - - - - - Qt::Horizontal - + + + + + + + Position + + + + + + + + + + + + Attitude + + + + 0 + + + + + true + + + + + 0 + 0 + 541 + 417 + + + + + 0 + + + + + + + + + + + + - - - - Qt::Horizontal - + + + + + Fixed Wing Control + + + + + + Attitude + + + + + + - - + + - - - - Qt::Horizontal + + + + Load Platform Defaults - - - - - - - Qt::Horizontal + + + + Position + + + + + - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - No pending changes - - - - - - - Store to EEPROM - - - diff --git a/src/ui/RadioCalibration/RadioCalibrationWindow.h b/src/ui/RadioCalibration/RadioCalibrationWindow.h index 855540132b97aeb115e709c0b4ddd18ee23117c8..536a4993c1e211553915fdacb9437b3255923c6e 100644 --- a/src/ui/RadioCalibration/RadioCalibrationWindow.h +++ b/src/ui/RadioCalibration/RadioCalibrationWindow.h @@ -50,8 +50,6 @@ This file is part of the QGROUNDCONTROL project #include "SwitchCalibrator.h" #include "CurveCalibrator.h" -#include "../../../mavlink/include/mavlink/v1.0/common/mavlink.h" -#include "../../../mavlink/include/mavlink/v1.0/mavlink_types.h" #include "UAS.h" #include "UASManager.h" #include "RadioCalibrationData.h" diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index c73f460bdf22024f589be90225b68a3b96c49e3c..93502e6da308860372ae9d078d4a4002008e6273 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 6e9612d6842be4d4d59797b7c439329ec2b4c6d8..d12d9f4f0cbbf74cb1f4f311ad03854f4cb7715d 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 488be8f12d8db70894033a85228bb0cee159b260..ff26c4011a25896eb836fb3e2abe5681a7c445bf 100644 --- a/src/ui/designer/QGCParamSlider.ui +++ b/src/ui/designer/QGCParamSlider.ui @@ -7,13 +7,13 @@ 0 0 789 - 158 + 244 Form - + 6 @@ -32,72 +32,17 @@ 12 - - - - <Parameter Name / Label> - - - - - - - - 60 - 0 - - - - Name - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 60 - 0 - - - - - 250 - 16777215 - + + + + -999999999 - 1000000 - - - Qt::Horizontal - - - - - - - Please click first on refresh to update selection menus.. - - - - - - - false - - - Select component - - - Select component + 999999999 - + false @@ -110,44 +55,27 @@ - - + + - 0 + 60 0 - - Read the current parameter value on the system - - - Read the current parameter value on the system - - R - - - - - - - true + Name - - Refresh + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - Done + + + + MIN: - - - - -999999999.000000000000000 @@ -156,6 +84,13 @@ + + + + <Parameter Name / Label> + + + @@ -169,7 +104,7 @@ - + @@ -194,8 +129,8 @@ - - + + 0 @@ -207,33 +142,78 @@ - - + + - 0 + 60 0 + + + 250 + 16777215 + + + + 1000000 + Qt::Horizontal - - - - MIN: + + + + Show Info - - -999999999.000000000000000 + + true - - 999999999.000000000000000 + + + + + + false + + + Select component + + + Select component - + + + + + 0 + 0 + + + + Read the current parameter value on the system + + + Read the current parameter value on the system + + + R + + + + + + + Please click first on refresh to update selection menus.. + + + + MAX: @@ -246,16 +226,62 @@ - - + + - -999999999 + -999999999.000000000000000 - 999999999 + 999999999.000000000000000 + + + + + + + + + + + 0 + 0 + + + + Qt::Horizontal + + + + true + + + Refresh + + + + + + + Done + + + + + + + Qt::Vertical + + + + 20 + 40 + + + +