From 4cfe93ccbb5acad7d450ce0b6bcf2a39243d004f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 19 Aug 2013 20:22:43 +0200 Subject: [PATCH] WIP on airframe config --- src/ui/QGCPX4VehicleConfig.ui.autosave | 1214 ++++++++++++++++++++++ src/ui/px4_configuration/QGCPX4AirframeConfig.cc | 47 +- src/ui/px4_configuration/QGCPX4AirframeConfig.h | 9 + src/ui/px4_configuration/QGCPX4AirframeConfig.ui | 35 +- 4 files changed, 1298 insertions(+), 7 deletions(-) create mode 100644 src/ui/QGCPX4VehicleConfig.ui.autosave diff --git a/src/ui/QGCPX4VehicleConfig.ui.autosave b/src/ui/QGCPX4VehicleConfig.ui.autosave new file mode 100644 index 0000000..93bbce1 --- /dev/null +++ b/src/ui/QGCPX4VehicleConfig.ui.autosave @@ -0,0 +1,1214 @@ + + + QGCPX4VehicleConfig + + + + 0 + 0 + 1256 + 783 + + + + + 0 + 0 + + + + Form + + + + + + + 135 + 0 + + + + + 135 + 16777215 + + + + true + + + + + 0 + 0 + 133 + 757 + + + + + + + QLayout::SetMinAndMaxSize + + + + + Firmware +Upgrade + + + + + + + + 100 + 75 + + + + + 16777215 + 16777215 + + + + RC +Calibration + + + + + + + + 100 + 75 + + + + Sensor +Calibration + + + + + + + Airframe +Config + + + + + + + + 100 + 75 + + + + General +Config + + + + + + + + 100 + 75 + + + + Advanced +Config + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + + 1 + + + + + + + Firmware Upgrade + + + + + + + + + + + + 16 + 75 + true + + + + RC Calibration + + + + + + + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + + + 1 + 0 + + + + + 50 + 200 + + + + + 50 + 200 + + + + + + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + 50 + 200 + + + + + 50 + 200 + + + + + + + + Start Calibration + + + + + + + + + Stick to Channel Mapping and Reverse + + + + + + + + Identify Sub Mode Switch + + + + + + + Identify Throttle Channel + + + + + + + Pitch / Elevator + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Reverse + + + + + + + false + + + 0 + + + 16 + + + + + + + false + + + 0 + + + 16 + + + + + + + false + + + 0 + + + 16 + + + + + + + Yaw / Rudder + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Throttle + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Identify Aux 2 Channel + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Identify Main Mode Switch + + + + + + + Identify Aux 1 Channel + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Reverse + + + + + + + Identify Roll Channel + + + + + + + Reverse Direction / Invert + + + + + + + Identify Yaw Channel + + + + + + + Reverse + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Reverse + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Roll / Ailerons + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Control Channel Name + + + + + + + Normalized Value + + + + + + + Identify Pitch Channel + + + + + + + Aux 2 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + false + + + 0 + + + 16 + + + + + + + Aux 3 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + false + + + 0 + + + 16 + + + + + + + Reverse + + + + + + + false + + + 0 + + + 16 + + + + + + + Reverse + + + + + + + Mode Switch + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Reverse + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Reverse + + + + + + + false + + + 0 + + + 16 + + + + + + + false + + + 0 + + + 16 + + + + + + + Aux 1 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Mapping to Index of RC Channel used for (0 if not used) + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + 16 + 75 + true + + + + + + + + + + true + + + + + 0 + 0 + 98 + 28 + + + + + + + + + + + + + + + + + + + 16 + 75 + true + + + + + + + General Config + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + 13 + 50 + false + + + + Load Platform Defaults + + + + + + + + + + + Configuration + + + + 0 + + + + + true + + + + + 0 + 0 + 98 + 28 + + + + + 0 + + + + + + + + + + + + + + + Configuration + + + + 0 + + + + + true + + + + + 0 + 0 + 98 + 28 + + + + + 0 + + + + + + + + + + + + + + + + + + + + + + 16 + 75 + true + + + + Advanced Configuration + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + Load Platform Defaults + + + + + + + + + + + + 3 + 1 + + + + Onboard Configuration + + + + 0 + + + + + true + + + + + 0 + 0 + 98 + 28 + + + + + 0 + + + + + + + + + + + + + + false + + + Load parameters currently in non-permanent memory of aircraft. + + + + + + Refresh + + + + + + + false + + + Copy parameters from permanent memory to non-permanent current memory of aircraft. DOES NOT update the parameters in this view, click refresh after copying them to get them. + + + + + + + + + Read ROM + + + + + + + false + + + Copy current parameters in non-permanent memory of the aircraft to permanent memory. Transmit your parameters first to write these. + + + + + + Write ROM + + + + + + + Load File + + + + + + + false + + + Save parameters in this view to a file on this computer. + + + + + + Save to File + + + + + + + + + + + + Qt::Horizontal + + + + 10 + 20 + + + + + + + + + 2 + 0 + + + + + 329 + 0 + + + + Changes Pending + + + + + 10 + 30 + 381 + 601 + + + + + 0 + + + + + + 0 + 30 + + + + true + + + + + + + + + + + Qt::Horizontal + + + + 10 + 20 + + + + + + + + + + Status + + + + + + + + + + + + + + QGCRadioChannelDisplay + QWidget +
ui/designer/QGCRadioChannelDisplay.h
+ 1 +
+ + QGCPendingParamWidget + QWidget +
ui/QGCPendingParamWidget.h
+ 1 +
+ + QGCMessageView + QWidget +
QGCMessageView.h
+ 1 +
+
+ + +
diff --git a/src/ui/px4_configuration/QGCPX4AirframeConfig.cc b/src/ui/px4_configuration/QGCPX4AirframeConfig.cc index dbca75c..f9f8443 100644 --- a/src/ui/px4_configuration/QGCPX4AirframeConfig.cc +++ b/src/ui/px4_configuration/QGCPX4AirframeConfig.cc @@ -54,27 +54,58 @@ QGCPX4AirframeConfig::QGCPX4AirframeConfig(QWidget *parent) : setActiveUAS(UASManager::instance()->getActiveUAS()); } +void QGCPX4AirframeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) +{ + Q_UNUSED(uas); + Q_UNUSED(component); + + if (parameterName.contains("SYS_AUTOSTART")) + { + int index = value.toInt(); + if (index > 0) { + setAirframeID(index); + ui->statusLabel->setText(tr("Onboard start script ID: #%1").arg(index)); + } else { + ui->statusLabel->setText(tr("System not configured for autostart.")); + } + } +} + void QGCPX4AirframeConfig::setActiveUAS(UASInterface* uas) { -// if (mav) + if (mav) + { + disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); + } if (!uas) return; mav = uas; + connect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, SLOT(parameterChanged(int,int,QString,QVariant))); + //connect(uas->getParamManager(), SIGNAL()) } void QGCPX4AirframeConfig::setAirframeID(int id) { selectedId = id; + ui->statusLabel->setText(tr("Ground start script ID: #%1").arg(selectedId)); + + if (id > 0 && id < 10) { + ui->planePushButton->setChecked(true); + } + else if (id > 10 && id < 20) + { + ui->quadXPushButton->setChecked(true); + } } void QGCPX4AirframeConfig::applyAndReboot() { // Guard against the case of an edit where we didn't receive all params yet - if (selectedId < 0) + if (selectedId <= 0) { QMessageBox msgBox; msgBox.setText(tr("No airframe selected")); @@ -125,7 +156,9 @@ void QGCPX4AirframeConfig::applyAndReboot() qDebug() << "Setting comp" << components.first() << "SYS_AUTOSTART" << (qint32)selectedId; - mav->getParamManager()->setParameter(components.first(), "SYS_AUTOSTART", (qint32)selectedId); + mav->setParameter(components.first(), "SYS_AUTOSTART", (qint32)selectedId); + + //mav->getParamManager()->setParameter(components.first(), "SYS_AUTOSTART", (qint32)selectedId); // Send pending params mav->getParamManager()->sendPendingParameters(); @@ -146,7 +179,7 @@ void QGCPX4AirframeConfig::setAutoConfig(bool enabled) void QGCPX4AirframeConfig::flyingWingSelected() { - + ui->flyingWingPushButton->setChecked(true); } void QGCPX4AirframeConfig::flyingWingSelected(int index) @@ -157,24 +190,26 @@ void QGCPX4AirframeConfig::flyingWingSelected(int index) void QGCPX4AirframeConfig::planeSelected() { - + ui->planePushButton->setChecked(true); } void QGCPX4AirframeConfig::planeSelected(int index) { int system_index = ui->planeComboBox->itemData(index).toInt(); + planeSelected(); setAirframeID(system_index); } void QGCPX4AirframeConfig::quadXSelected() { - + ui->quadXPushButton->setChecked(true); } void QGCPX4AirframeConfig::quadXSelected(int index) { int system_index = ui->quadXComboBox->itemData(index).toInt(); + quadXSelected(); setAirframeID(system_index); } diff --git a/src/ui/px4_configuration/QGCPX4AirframeConfig.h b/src/ui/px4_configuration/QGCPX4AirframeConfig.h index 4c3c9a0..7180d9e 100644 --- a/src/ui/px4_configuration/QGCPX4AirframeConfig.h +++ b/src/ui/px4_configuration/QGCPX4AirframeConfig.h @@ -25,6 +25,15 @@ public slots: void setActiveUAS(UASInterface* uas); /** + * @brief Handle parameter changes + * @param uas + * @param component + * @param parameterName + * @param value + */ + void parameterChanged(int uas, int component, QString parameterName, QVariant value); + + /** * @brief Quadrotor in X configuration has been selected */ void quadXSelected(); diff --git a/src/ui/px4_configuration/QGCPX4AirframeConfig.ui b/src/ui/px4_configuration/QGCPX4AirframeConfig.ui index e1f6432..e97bfbd 100644 --- a/src/ui/px4_configuration/QGCPX4AirframeConfig.ui +++ b/src/ui/px4_configuration/QGCPX4AirframeConfig.ui @@ -23,7 +23,7 @@ 0 - 0 + -175 762 531 @@ -46,6 +46,9 @@ 120 + + true + @@ -77,6 +80,9 @@ 120 + + true + @@ -108,6 +114,9 @@ 120 + + true + @@ -139,6 +148,9 @@ 120 + + true + @@ -170,6 +182,9 @@ 120 + + true + @@ -201,6 +216,9 @@ 120 + + true + @@ -232,6 +250,9 @@ 120 + + true + @@ -263,6 +284,9 @@ 120 + + true + @@ -284,6 +308,15 @@ + + + 120 + 120 + + + + true +