diff --git a/libs/eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h b/libs/eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h index 2116dcc740dc0e94b261d5475c3adaccb4115690..e0344e62a240f253fdc4fe7443b8e7d6f5a9a64c 100644 --- a/libs/eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h +++ b/libs/eigen/Eigen/src/Core/products/GeneralBlockPanelKernel.h @@ -88,7 +88,7 @@ void computeProductBlockingSizes(std::ptrdiff_t& k, std::ptrdiff_t& m, std::ptrd // at the register level. For vectorization purpose, these small vertical panels are unpacked, // e.g., each coefficient is replicated to fit a packet. This small vertical panel has to // stay in L1 cache. - std::ptrdiff_t l1, l2; + std::ptrdiff_t l1, l2, initial_n; typedef gebp_traits Traits; enum { @@ -98,11 +98,12 @@ void computeProductBlockingSizes(std::ptrdiff_t& k, std::ptrdiff_t& m, std::ptrd mr_mask = (0xffffffff/mr)*mr }; + initial_n = n; manage_caching_sizes(GetAction, &l1, &l2); k = std::min(k, l1/kdiv); std::ptrdiff_t _m = k>0 ? l2/(4 * sizeof(LhsScalar) * k) : 0; if(_m diff --git a/qgroundcontrol.pri b/qgroundcontrol.pri index fdf608780b64848d5f8dd550cd51ec3431088cd7..1ba7dbdbe6662adf0bdb532d6389a228c9dc241d 100644 --- a/qgroundcontrol.pri +++ b/qgroundcontrol.pri @@ -73,12 +73,6 @@ macx|macx-g++42|macx-g++|macx-llvm: { QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qml/components/ QMAKE_POST_LINK += && cp -rf $$BASEDIR/qml/components/*.qml $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qml/components - QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qml/resources - QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qml/resources/qgroundcontrol - QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qml/resources/qgroundcontrol/toolbar - QMAKE_POST_LINK += && cp -rf $$BASEDIR/qml/resources/qgroundcontrol/toolbar/*.png $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qml/resources/qgroundcontrol/toolbar - - # Fix library paths inside executable QMAKE_POST_LINK += && install_name_tool -change libOpenThreads.dylib "@executable_path/../libs/libOpenThreads.dylib" $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qgroundcontrol QMAKE_POST_LINK += && install_name_tool -change libosg.dylib "@executable_path/../libs/libosg.dylib" $$TARGETDIR/qgroundcontrol.app/Contents/MacOS/qgroundcontrol diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 5096f8451e3c7e4e90f0f96d022f5f35d5a819fb..eab224e4425d255eef7e74ebf94fff75c74927bd 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -811,17 +811,7 @@ OTHER_FILES += \ OTHER_FILES += \ qml/ApmToolBar.qml \ qml/components/Button.qml \ - qml/components/TextButton.qml \ - qml/resources/qgroundcontrol/toolbar/connect.png \ - qml/resources/qgroundcontrol/toolbar/flightplanner.png \ - qml/resources/qgroundcontrol/toolbar/helpwizard.png \ - qml/resources/qgroundcontrol/toolbar/softwareconfig.png \ - qml/resources/qgroundcontrol/toolbar/terminal.png \ - qml/resources/qgroundcontrol/toolbar/simulation.png \ - qml/resources/qgroundcontrol/toolbar/hardwareconfig.png \ - qml/resources/qgroundcontrol/toolbar/flightdata.png \ - qml/resources/qgroundcontrol/toolbar/disconnect.png \ - qml/resources/qgroundcontrol/toolbar/donate.png \ + qml/components/TextButton.qml #qmlcomponents.path += $${DESTDIR}$${TARGET}/components diff --git a/src/ui/PrimaryFlightDisplay.cc b/src/ui/PrimaryFlightDisplay.cc index a68acdf545b3c351432dc1421bcb84146064b8a2..d0070d2292c24ee800fb85bf0a06b4179646f2f7 100644 --- a/src/ui/PrimaryFlightDisplay.cc +++ b/src/ui/PrimaryFlightDisplay.cc @@ -293,6 +293,9 @@ void PrimaryFlightDisplay::forgetUAS(UASInterface* uas) */ void PrimaryFlightDisplay::setActiveUAS(UASInterface* uas) { + if (uas == this->uas) + return; //no need to rewire + // Disconnect the previous one (if any) forgetUAS(this->uas); diff --git a/src/ui/QGCConfigView.cc b/src/ui/QGCConfigView.cc index b33e6e664be214c5281fcf31cdffc0b512281ff4..fb8f519b73bd3be644e0827c7ed7c1da95596406 100644 --- a/src/ui/QGCConfigView.cc +++ b/src/ui/QGCConfigView.cc @@ -14,12 +14,9 @@ QGCConfigView::QGCConfigView(QWidget *parent) : connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASChanged(UASInterface*))); - if (ui->waitingLabel) { - ui->gridLayout->removeWidget(ui->waitingLabel); - delete ui->waitingLabel; - ui->waitingLabel = NULL; - } - ui->gridLayout->addWidget(new QGCPX4VehicleConfig()); + //don't show a configuration widget if no vehicle is connected + //show a placeholder informational widget instead + } QGCConfigView::~QGCConfigView() @@ -32,26 +29,35 @@ void QGCConfigView::activeUASChanged(UASInterface* uas) if (currUAS == uas) return; - if (ui->waitingLabel) { - ui->gridLayout->removeWidget(ui->waitingLabel); - delete ui->waitingLabel; - ui->waitingLabel = NULL; - } - - if (currUAS && currUAS->getAutopilotType() != uas->getAutopilotType()) { - foreach (QObject* obj, ui->gridLayout->children()) { - QWidget* w = dynamic_cast(obj); - if (w) { + //remove all child widgets since they could contain stale data + //for example, when we switch from one PX4 UAS to another UAS + foreach (QObject* obj, ui->gridLayout->children()) { + QWidget* w = dynamic_cast(obj); + if (w) { + if (obj != ui->waitingLabel) { ui->gridLayout->removeWidget(w); delete obj; } } } - switch (uas->getAutopilotType()) { - case MAV_AUTOPILOT_PX4: - ui->gridLayout->addWidget(new QGCPX4VehicleConfig()); - default: - ui->gridLayout->addWidget(new QGCVehicleConfig()); + if (NULL != uas) { + ui->gridLayout->removeWidget(ui->waitingLabel); + ui->waitingLabel->setVisible(false); + + switch (uas->getAutopilotType()) { + case MAV_AUTOPILOT_PX4: + ui->gridLayout->addWidget(new QGCPX4VehicleConfig()); + break; + default: + ui->gridLayout->addWidget(new QGCVehicleConfig()); + break; + } } + else { + //restore waiting label if we no longer have a connection + ui->gridLayout->addWidget(ui->waitingLabel); + ui->waitingLabel->setVisible(true); + } + } diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index a0c01d0f5e2cd6f266d7b9724a8102b85bff16ac..3ea93d914b270768f522fc1469afd970e56f0f53 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -18,6 +18,16 @@ #include "QGCToolWidget.h" #include "ui_QGCPX4VehicleConfig.h" + +#define WIDGET_INDEX_RC 0 +#define WIDGET_INDEX_SENSOR_CAL 1 +#define WIDGET_INDEX_GENERAL_CONFIG 2 +#define WIDGET_INDEX_ADV_CONFIG 3 + + +#define MIN_PWM_VAL 800 +#define MAX_PWM_VAL 2200 + QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : QWidget(parent), mav(NULL), @@ -30,7 +40,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : rcAux1(0.0f), rcAux2(0.0f), rcAux3(0.0f), - changed(true), + dataModelChanged(true), rc_mode(RC_MODE_NONE), calibrationEnabled(false), ui(new Ui::QGCPX4VehicleConfig) @@ -60,7 +70,9 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : connect(ui->generalMenuButton,SIGNAL(clicked()),this,SLOT(generalMenuButtonClicked())); connect(ui->advancedMenuButton,SIGNAL(clicked()),this,SLOT(advancedMenuButtonClicked())); - ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1); + + int selectedRcModeIdx = (RC_MODE_NONE != rc_mode) ? (int)(rc_mode -1) : -1; + ui->rcModeComboBox->setCurrentIndex(selectedRcModeIdx); ui->rcCalibrationButton->setCheckable(true); connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool))); @@ -68,32 +80,35 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int))); //connect(ui->setTrimButton, SIGNAL(clicked()), this, SLOT(setTrimPositions())); - /* Connect RC mapping assignments */ - connect(ui->rollSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setRollChan(int))); - connect(ui->pitchSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setPitchChan(int))); - connect(ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYawChan(int))); - connect(ui->throttleSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setThrottleChan(int))); - connect(ui->modeSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setModeChan(int))); - connect(ui->aux1SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux1Chan(int))); - connect(ui->aux2SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux2Chan(int))); - connect(ui->aux3SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux3Chan(int))); - - // Connect RC reverse assignments - connect(ui->invertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setRollInverted(bool))); - connect(ui->invertCheckBox_2, SIGNAL(clicked(bool)), this, SLOT(setPitchInverted(bool))); - connect(ui->invertCheckBox_3, SIGNAL(clicked(bool)), this, SLOT(setYawInverted(bool))); - connect(ui->invertCheckBox_4, SIGNAL(clicked(bool)), this, SLOT(setThrottleInverted(bool))); - connect(ui->invertCheckBox_5, SIGNAL(clicked(bool)), this, SLOT(setModeInverted(bool))); - connect(ui->invertCheckBox_6, SIGNAL(clicked(bool)), this, SLOT(setAux1Inverted(bool))); - connect(ui->invertCheckBox_7, SIGNAL(clicked(bool)), this, SLOT(setAux2Inverted(bool))); - connect(ui->invertCheckBox_8, SIGNAL(clicked(bool)), this, SLOT(setAux3Inverted(bool))); + + + //TODO the following methods are not yet implemented + +// Connect RC mapping assignments +// connect(ui->rollSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setRollChan(int))); +// connect(ui->pitchSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setPitchChan(int))); +// connect(ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYawChan(int))); +// connect(ui->throttleSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setThrottleChan(int))); +// connect(ui->modeSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setModeChan(int))); +// connect(ui->aux1SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux1Chan(int))); +// connect(ui->aux2SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux2Chan(int))); +// connect(ui->aux3SpinBox, SIGNAL(valueChanged(int)), this, SLOT(setAux3Chan(int))); + +// // Connect RC reverse assignments +// connect(ui->invertCheckBox, SIGNAL(clicked(bool)), this, SLOT(setRollInverted(bool))); +// connect(ui->invertCheckBox_2, SIGNAL(clicked(bool)), this, SLOT(setPitchInverted(bool))); +// connect(ui->invertCheckBox_3, SIGNAL(clicked(bool)), this, SLOT(setYawInverted(bool))); +// connect(ui->invertCheckBox_4, SIGNAL(clicked(bool)), this, SLOT(setThrottleInverted(bool))); +// connect(ui->invertCheckBox_5, SIGNAL(clicked(bool)), this, SLOT(setModeInverted(bool))); +// connect(ui->invertCheckBox_6, SIGNAL(clicked(bool)), this, SLOT(setAux1Inverted(bool))); +// connect(ui->invertCheckBox_7, SIGNAL(clicked(bool)), this, SLOT(setAux2Inverted(bool))); +// connect(ui->invertCheckBox_8, SIGNAL(clicked(bool)), this, SLOT(setAux3Inverted(bool))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); setActiveUAS(UASManager::instance()->getActiveUAS()); - for (unsigned int i = 0; i < chanMax; i++) - { + for (unsigned int i = 0; i < chanMax; i++) { rcValue[i] = UINT16_MAX; rcMapping[i] = i; } @@ -107,22 +122,23 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : } void QGCPX4VehicleConfig::rcMenuButtonClicked() { - ui->stackedWidget->setCurrentIndex(0); + //TODO eg ui->stackedWidget->findChild("rcConfig"); + ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_RC); } void QGCPX4VehicleConfig::sensorMenuButtonClicked() { - ui->stackedWidget->setCurrentIndex(1); + ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_SENSOR_CAL); } void QGCPX4VehicleConfig::generalMenuButtonClicked() { - ui->stackedWidget->setCurrentIndex(ui->stackedWidget->count()-2); + ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_GENERAL_CONFIG); } void QGCPX4VehicleConfig::advancedMenuButtonClicked() { - ui->stackedWidget->setCurrentIndex(ui->stackedWidget->count()-1); + ui->stackedWidget->setCurrentIndex(WIDGET_INDEX_ADV_CONFIG); } QGCPX4VehicleConfig::~QGCPX4VehicleConfig() @@ -132,10 +148,10 @@ QGCPX4VehicleConfig::~QGCPX4VehicleConfig() void QGCPX4VehicleConfig::setRCModeIndex(int newRcMode) { - if (newRcMode > 0 && newRcMode < 6) - { - //rc_mode = (enum RC_MODE) (newRcMode+1); - changed = true; + newRcMode += 1; //promote from an index to a mode enum + if (newRcMode > 0 && newRcMode < 5) { + rc_mode = (enum RC_MODE) (newRcMode); + dataModelChanged = true; } } @@ -165,7 +181,6 @@ void QGCPX4VehicleConfig::setTrimPositions() } else { - // Reject QMessageBox msgBox; msgBox.setText(tr("Throttle Stick Trim Position Invalid")); @@ -195,7 +210,6 @@ void QGCPX4VehicleConfig::startCalibrationRC() { QMessageBox::information(0,"Warning!","You are about to start radio calibration.\nPlease ensure all motor power is disconnected AND all props are removed from the vehicle.\nAlso ensure transmitter and reciever are powered and connected\n\nClick OK to confirm"); QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches"); - ui->rcTypeComboBox->setEnabled(false); ui->rcCalibrationButton->setText(tr("Stop RC Calibration")); resetCalibrationRC(); calibrationEnabled = true; @@ -213,8 +227,8 @@ void QGCPX4VehicleConfig::stopCalibrationRC() { QMessageBox::information(0,"Trims","Ensure all sticks are centeres and throttle is in the downmost position, click OK to continue"); calibrationEnabled = false; - ui->rcTypeComboBox->setEnabled(true); ui->rcCalibrationButton->setText(tr("Start RC Calibration")); + ui->rollWidget->hideMinMax(); ui->pitchWidget->hideMinMax(); ui->yawWidget->hideMinMax(); @@ -223,6 +237,7 @@ void QGCPX4VehicleConfig::stopCalibrationRC() ui->radio6Widget->hideMinMax(); ui->radio7Widget->hideMinMax(); ui->radio8Widget->hideMinMax(); + QString statusstr; statusstr = "Below you will find the detected radio calibration information that will be sent to the autopilot\n"; statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading very close to 1500\n\n"; @@ -230,7 +245,7 @@ void QGCPX4VehicleConfig::stopCalibrationRC() statusstr += "--------------------\n"; for (int i=0;i<8;i++) { - statusstr += QString::number(i) + "\t" + QString::number(rcMin[i]) + "\t" + QString::number(rcValue[i]) + "\t" + QString::number(rcMax[i]) + "\n"; + statusstr += QString::number(i) +"\t"+ QString::number(rcMin[i]) +"\t"+ QString::number(rcValue[i]) +"\t"+ QString::number(rcMax[i]) +"\n"; } QMessageBox::information(0,"Status",statusstr); } @@ -288,7 +303,7 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary) foreach (QString file,vehicledir.entryList(QDir::Files | QDir::NoDotAndDotDot)) { if (file.toLower().endsWith(".qgw")) { - QWidget* parent = left?ui->advancedLeftContents:ui->advancedRightContents; + QWidget* parent = ui->advanceColumnContents; tool = new QGCToolWidget("", parent); if (tool->loadSettings(vehicledir.absoluteFilePath(file), false)) { @@ -297,16 +312,8 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary) box->setTitle(tool->objectName()); box->setLayout(new QVBoxLayout(box)); box->layout()->addWidget(tool); - if (left) - { - left = false; - ui->advancedLeftLayout->addWidget(box); - } - else - { - left = true; - ui->advancedRightLayout->addWidget(box); - } + ui->advancedColumnLayout->addWidget(box); + } else { delete tool; } @@ -316,7 +323,7 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary) // Load tabs for general configuration foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot)) { - QPushButton *button = new QPushButton(ui->scrollAreaWidgetContents_3); + QPushButton *button = new QPushButton(ui->leftNavScrollAreaWidgetContents); connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked())); ui->navBarLayout->insertWidget(2,button); button->setMinimumHeight(75); @@ -360,7 +367,7 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary) // Load additional tabs for vehicle specific configuration foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot)) { - QPushButton *button = new QPushButton(ui->scrollAreaWidgetContents_3); + QPushButton *button = new QPushButton(ui->leftNavScrollAreaWidgetContents); connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked())); ui->navBarLayout->insertWidget(2,button); @@ -808,8 +815,9 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) } - // Do nothing if system is the same - if (mav == active) return; + // Do nothing if UAS is already visible + if (mav == active) + return; if (mav) { @@ -829,11 +837,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) { child->deleteLater(); } - foreach(QWidget* child, ui->advancedLeftContents->findChildren()) - { - child->deleteLater(); - } - foreach(QWidget* child, ui->advancedRightContents->findChildren()) + foreach(QWidget* child, ui->advanceColumnContents->findChildren()) { child->deleteLater(); } @@ -1013,13 +1017,10 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) // Update calibration data if (calibrationEnabled) { - if (val < rcMin[chan]) - { + if (val < rcMin[chan]) { rcMin[chan] = val; } - - if (val > rcMax[chan]) - { + if (val > rcMax[chan]) { rcMax[chan] = val; } } @@ -1030,12 +1031,10 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) // Normalized value float normalized; - if (val >= rcTrim[chan]) - { + if (val >= rcTrim[chan]) { normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); } - else - { + else { normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]); } @@ -1044,23 +1043,16 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) // Invert normalized = (rcRev[chan]) ? -1.0f*normalized : normalized; - if (chan == rcMapping[0]) - { - // ROLL + if (chan == rcMapping[0]) { rcRoll = normalized; } - if (chan == rcMapping[1]) - { - // PITCH + else if (chan == rcMapping[1]) { rcPitch = normalized; } - if (chan == rcMapping[2]) - { + else if (chan == rcMapping[2]) { rcYaw = normalized; } - if (chan == rcMapping[3]) - { - // THROTTLE + else if (chan == rcMapping[3]) { if (rcRev[chan]) { rcThrottle = 1.0f + normalized; } else { @@ -1069,28 +1061,20 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) rcThrottle = qBound(0.0f, rcThrottle, 1.0f); } - if (chan == rcMapping[4]) - { - // MODE SWITCH - rcMode = normalized; + else if (chan == rcMapping[4]) { + rcMode = normalized;// MODE SWITCH } - if (chan == rcMapping[5]) - { - // AUX1 - rcAux1 = normalized; + else if (chan == rcMapping[5]) { + rcAux1 = normalized; // AUX1 } - if (chan == rcMapping[6]) - { - // AUX2 - rcAux2 = normalized; + else if (chan == rcMapping[6]) { + rcAux2 = normalized;// AUX2 } - if (chan == rcMapping[7]) - { - // AUX3 - rcAux3 = normalized; + else if (chan == rcMapping[7]) { + rcAux3 = normalized; // AUX3 } - changed = true; + dataModelChanged = true; //qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized; } @@ -1128,52 +1112,182 @@ void QGCPX4VehicleConfig::updateInvertedCheckboxes(int index) } } +void QGCPX4VehicleConfig::handleRcParameterChange(QString parameterName, QVariant value) +{ + if (parameterName.startsWith("RC_")) { + if (parameterName.startsWith("RC_MAP_")) { + //RC Mapping radio channels to meaning + // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3 + + int intValue = value.toInt() - 1; + if (parameterName.startsWith("RC_MAP_ROLL")) { + rcMapping[0] = intValue; + ui->rollSpinBox->setValue(rcMapping[0]+1); + ui->rollSpinBox->setEnabled(true); + } + else if (parameterName.startsWith("RC_MAP_PITCH")) { + rcMapping[1] = intValue; + ui->pitchSpinBox->setValue(rcMapping[1]+1); + ui->pitchSpinBox->setEnabled(true); + } + else if (parameterName.startsWith("RC_MAP_YAW")) { + rcMapping[2] = intValue; + ui->yawSpinBox->setValue(rcMapping[2]+1); + ui->yawSpinBox->setEnabled(true); + } + else if (parameterName.startsWith("RC_MAP_THROTTLE")) { + rcMapping[3] = intValue; + ui->throttleSpinBox->setValue(rcMapping[3]+1); + ui->throttleSpinBox->setEnabled(true); + } + else if (parameterName.startsWith("RC_MAP_MODE_SW")) { + rcMapping[4] = intValue; + ui->modeSpinBox->setValue(rcMapping[4]+1); + ui->modeSpinBox->setEnabled(true); + } + else if (parameterName.startsWith("RC_MAP_AUX1")) { + rcMapping[5] = intValue; + ui->aux1SpinBox->setValue(rcMapping[5]+1); + ui->aux1SpinBox->setEnabled(true); + } + else if (parameterName.startsWith("RC_MAP_AUX2")) { + rcMapping[6] = intValue; + ui->aux2SpinBox->setValue(rcMapping[6]+1); + ui->aux2SpinBox->setEnabled(true); + } + else if (parameterName.startsWith("RC_MAP_AUX3")) { + rcMapping[7] = intValue; + ui->aux3SpinBox->setValue(rcMapping[7]+1); + ui->aux3SpinBox->setEnabled(true); + } + } + else if (parameterName.startsWith("RC_SCALE_")) { + // Scaling + float floatVal = value.toFloat(); + if (parameterName.startsWith("RC_SCALE_ROLL")) { + rcScaling[0] = floatVal; + } + else if (parameterName.startsWith("RC_SCALE_PITCH")) { + rcScaling[1] = floatVal; + } + else if (parameterName.startsWith("RC_SCALE_YAW")) { + rcScaling[2] = floatVal; + } + else if (parameterName.startsWith("RC_SCALE_THROTTLE")) { + rcScaling[3] = floatVal; + } + else if (parameterName.startsWith("RC_SCALE_MODE_SW")) { + rcScaling[4] = floatVal; + } + else if (parameterName.startsWith("RC_SCALE_AUX1")) { + rcScaling[5] = floatVal; + } + else if (parameterName.startsWith("RC_SCALE_AUX2")) { + rcScaling[6] = floatVal; + } + else if (parameterName.startsWith("RC_SCALE_AUX3")) { + rcScaling[7] = floatVal; + } + } + else if (parameterName.startsWith("RC_TYPE")) { + if (0 != rcTypeUpdateRequested) { + rcTypeUpdateRequested = 0; + updateStatus(tr("Received RC type update, setting parameters based on model.")); + rcType = value.toInt(); + // Request all other parameters as well + requestCalibrationRC(); + } + } + } + else { + // Channel calibration values + bool ok = false; + unsigned int index = chanMax; + 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 + int intVal = value.toInt(); + + if (minTpl.exactMatch(parameterName)) { + index = parameterName.mid(2, 1).toInt(&ok) - 1; + if (ok && index < chanMax) { + rcMin[index] = intVal; + updateRcWidgetValues(); + } + } + else if (maxTpl.exactMatch(parameterName)) { + index = parameterName.mid(2, 1).toInt(&ok) - 1; + if (ok && index < chanMax) { + rcMax[index] = intVal; + updateRcWidgetValues(); + } + } + else if (trimTpl.exactMatch(parameterName)) { + index = parameterName.mid(2, 1).toInt(&ok) - 1; + if (ok && index < chanMax) { + rcTrim[index] = intVal; + } + } + else if (revTpl.exactMatch(parameterName)) { + index = parameterName.mid(2, 1).toInt(&ok) - 1; + if (ok && index < chanMax) { + rcRev[index] = (intVal == -1) ? true : false; + updateInvertedCheckboxes(index); + } + } + } + +} + void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { Q_UNUSED(uas); Q_UNUSED(component); - if (!doneLoadingConfig) - { + if (!doneLoadingConfig) { //We do not want to attempt to generate any UI elements until loading of the config file is complete. //We should re-request params later if needed, that is not implemented yet. return; } - if (paramToWidgetMap.contains(parameterName)) - { + if (parameterName.startsWith("RC")) { + handleRcParameterChange(parameterName,value); + return; + } + + if (paramToWidgetMap.contains(parameterName)) { //Main group of parameters of the selected airframe paramToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value); - if (toolToBoxMap.contains(paramToWidgetMap.value(parameterName))) - { + if (toolToBoxMap.contains(paramToWidgetMap.value(parameterName))) { toolToBoxMap[paramToWidgetMap.value(parameterName)]->show(); } - else - { + else { qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName; } } - else if (libParamToWidgetMap.contains(parameterName)) - { + else if (libParamToWidgetMap.contains(parameterName)) { //All the library parameters libParamToWidgetMap.value(parameterName)->setParameterValue(uas,component,parameterName,value); - if (toolToBoxMap.contains(libParamToWidgetMap.value(parameterName))) - { + if (toolToBoxMap.contains(libParamToWidgetMap.value(parameterName))) { toolToBoxMap[libParamToWidgetMap.value(parameterName)]->show(); } - else - { + else { qCritical() << "Widget with no box, possible memory corruption for param:" << parameterName; } } - else - { + else { //Param recieved that we have no metadata for. Search to see if it belongs in a //group with some other params bool found = false; - for (int i=0;iobjectName())) - { + for (int i=0;iobjectName())) { //It should be grouped with this one, add it. toolWidgets[i]->addParam(uas,component,parameterName,value); libParamToWidgetMap.insert(parameterName,toolWidgets[i]); @@ -1181,24 +1295,14 @@ void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString param break; } } - if (!found) - { + if (!found) { //New param type, create a QGroupBox for it. - QWidget* parent; - if (ui->advancedLeftLayout->count() > ui->advancedRightLayout->count()) - { - parent = ui->advancedRightContents; - } - else - { - parent = ui->advancedLeftContents; - } + QWidget* parent = ui->advanceColumnContents; // Create the tool, attaching it to the QGroupBox QGCToolWidget *tool = new QGCToolWidget("", parent); QString tooltitle = parameterName; - if (parameterName.split("_").size() > 1) - { + if (parameterName.split("_").size() > 1) { tooltitle = parameterName.split("_")[0] + "_"; } tool->setTitle(tooltitle); @@ -1214,204 +1318,27 @@ void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString param libParamToWidgetMap.insert(parameterName,tool); toolWidgets.append(tool); + ui->advancedColumnLayout->addWidget(box); - // Make sure we have similar number of widgets on each side. - if (ui->advancedLeftLayout->count() > ui->advancedRightLayout->count()) - { - ui->advancedRightLayout->addWidget(box); - } - else - { - ui->advancedLeftLayout->addWidget(box); - } toolToBoxMap[tool] = box; } } - // 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) - 1; - //qDebug() << "PARAM:" << parameterName << "index:" << index; - if (ok && index < chanMax) - { - rcMin[index] = value.toInt(); - updateMinMax(); - } - } - - if (maxTpl.exactMatch(parameterName)) { - bool ok; - unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; - if (ok && index < chanMax) - { - rcMax[index] = value.toInt(); - updateMinMax(); - } - } - - if (trimTpl.exactMatch(parameterName)) { - bool ok; - unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; - if (ok && index < chanMax) - { - rcTrim[index] = value.toInt(); - } - } - - if (revTpl.exactMatch(parameterName)) { - bool ok; - unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; - if (ok && index < chanMax) - { - rcRev[index] = (value.toInt() == -1) ? true : false; - updateInvertedCheckboxes(index); - } - } - -// 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; - updateStatus(tr("Received RC type update, setting parameters based on model.")); - rcType = value.toInt(); - // 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() - 1; - ui->rollSpinBox->setValue(rcMapping[0]+1); - ui->rollSpinBox->setEnabled(true); - } - - if (parameterName.contains("RC_MAP_PITCH")) { - rcMapping[1] = value.toInt() - 1; - ui->pitchSpinBox->setValue(rcMapping[1]+1); - ui->pitchSpinBox->setEnabled(true); - } - - if (parameterName.contains("RC_MAP_YAW")) { - rcMapping[2] = value.toInt() - 1; - ui->yawSpinBox->setValue(rcMapping[2]+1); - ui->yawSpinBox->setEnabled(true); - } - - if (parameterName.contains("RC_MAP_THROTTLE")) { - rcMapping[3] = value.toInt() - 1; - ui->throttleSpinBox->setValue(rcMapping[3]+1); - ui->throttleSpinBox->setEnabled(true); - } - - if (parameterName.contains("RC_MAP_MODE_SW")) { - rcMapping[4] = value.toInt() - 1; - ui->modeSpinBox->setValue(rcMapping[4]+1); - ui->modeSpinBox->setEnabled(true); - } - - if (parameterName.contains("RC_MAP_AUX1")) { - rcMapping[5] = value.toInt() - 1; - ui->aux1SpinBox->setValue(rcMapping[5]+1); - ui->aux1SpinBox->setEnabled(true); - } - - if (parameterName.contains("RC_MAP_AUX2")) { - rcMapping[6] = value.toInt() - 1; - ui->aux2SpinBox->setValue(rcMapping[6]+1); - ui->aux2SpinBox->setEnabled(true); - } - - if (parameterName.contains("RC_MAP_AUX3")) { - rcMapping[7] = value.toInt() - 1; - ui->aux3SpinBox->setValue(rcMapping[7]+1); - ui->aux3SpinBox->setEnabled(true); - } - - // Scaling - - if (parameterName.contains("RC_SCALE_ROLL")) { - rcScaling[0] = value.toFloat(); - } - - if (parameterName.contains("RC_SCALE_PITCH")) { - rcScaling[1] = value.toFloat(); - } - - if (parameterName.contains("RC_SCALE_YAW")) { - rcScaling[2] = value.toFloat(); - } - - if (parameterName.contains("RC_SCALE_THROTTLE")) { - rcScaling[3] = value.toFloat(); - } - - if (parameterName.contains("RC_SCALE_MODE_SW")) { - rcScaling[4] = value.toFloat(); - } - - if (parameterName.contains("RC_SCALE_AUX1")) { - rcScaling[5] = value.toFloat(); - } - - if (parameterName.contains("RC_SCALE_AUX2")) { - rcScaling[6] = value.toFloat(); - } - - if (parameterName.contains("RC_SCALE_AUX3")) { - rcScaling[7] = value.toFloat(); - } } void QGCPX4VehicleConfig::updateStatus(const QString& str) { - ui->statusLabel->setText(str); - ui->statusLabel->setStyleSheet(""); + ui->advancedStatusLabel->setText(str); + ui->advancedStatusLabel->setStyleSheet(""); } void QGCPX4VehicleConfig::updateError(const QString& str) { - ui->statusLabel->setText(str); - ui->statusLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.name())); -} -void QGCPX4VehicleConfig::updateMinMax() -{ - // Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3 - /*ui->rollWidget->setMin(rcMin[0]); - ui->rollWidget->setMax(rcMax[0]); - ui->pitchWidget->setMin(rcMin[1]); - ui->pitchWidget->setMax(rcMax[1]); - ui->yawWidget->setMin(rcMin[2]); - ui->yawWidget->setMax(rcMax[2]); - ui->throttleWidget->setMin(rcMin[3]); - ui->throttleWidget->setMax(rcMax[3]); - ui->radio5Widget->setMin(rcMin[4]); - ui->radio5Widget->setMax(rcMax[4]); - ui->radio6Widget->setMin(rcMin[5]); - ui->radio6Widget->setMax(rcMax[5]); - ui->radio7Widget->setMin(rcMin[6]); - ui->radio7Widget->setMax(rcMax[6]); - ui->radio8Widget->setMin(rcMin[7]); - ui->radio8Widget->setMax(rcMax[7]);*/ + ui->advancedStatusLabel->setText(str); + ui->advancedStatusLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.name())); } + void QGCPX4VehicleConfig::setRCType(int type) { if (!mav) return; @@ -1434,148 +1361,90 @@ void QGCPX4VehicleConfig::checktimeOuts() } } -void QGCPX4VehicleConfig::updateView() + +void QGCPX4VehicleConfig::updateRcWidgetValues() { - if (changed) - { - if (rc_mode == RC_MODE_1) - { - //ui->rollSlider->setValue(rcRoll * 50 + 50); - //ui->pitchSlider->setValue(rcThrottle * 100); - //ui->yawSlider->setValue(rcYaw * 50 + 50); - //ui->throttleSlider->setValue(rcPitch * 50 + 50); - ui->rollWidget->setValue(rcValue[0]); - ui->throttleWidget->setValue(rcValue[1]); - ui->yawWidget->setValue(rcValue[2]); - ui->pitchWidget->setValue(rcValue[3]); - - ui->rollWidget->setMin(rcMin[0]); - ui->rollWidget->setMax(rcMax[0]); - ui->throttleWidget->setMin(rcMin[1]); - ui->throttleWidget->setMax(rcMax[1]); - ui->yawWidget->setMin(rcMin[2]); - ui->yawWidget->setMax(rcMax[2]); - ui->pitchWidget->setMin(rcMin[3]); - ui->pitchWidget->setMax(rcMax[3]); - } - else if (rc_mode == RC_MODE_2) - { - //ui->rollSlider->setValue(rcRoll * 50 + 50); - //ui->pitchSlider->setValue(rcPitch * 50 + 50); - //ui->yawSlider->setValue(rcYaw * 50 + 50); - //ui->throttleSlider->setValue(rcThrottle * 100); - ui->rollWidget->setValue(rcValue[0]); - ui->pitchWidget->setValue(rcValue[1]); - ui->yawWidget->setValue(rcValue[2]); - ui->throttleWidget->setValue(rcValue[3]); - - ui->rollWidget->setMin(rcMin[0]); - ui->rollWidget->setMax(rcMax[0]); - ui->pitchWidget->setMin(rcMin[1]); - ui->pitchWidget->setMax(rcMax[1]); - ui->yawWidget->setMin(rcMin[2]); - ui->yawWidget->setMax(rcMax[2]); - ui->throttleWidget->setMin(rcMin[3]); - ui->throttleWidget->setMax(rcMax[3]); - } - else if (rc_mode == RC_MODE_3) - { - //ui->rollSlider->setValue(rcYaw * 50 + 50); - //ui->pitchSlider->setValue(rcThrottle * 100); - //ui->yawSlider->setValue(rcRoll * 50 + 50); - //ui->throttleSlider->setValue(rcPitch * 50 + 50); - ui->yawWidget->setValue(rcValue[0]); - ui->throttleWidget->setValue(rcValue[1]); - ui->rollWidget->setValue(rcValue[2]); - ui->pitchWidget->setValue(rcValue[3]); - - ui->yawWidget->setMin(rcMin[0]); - ui->yawWidget->setMax(rcMax[0]); - ui->throttleWidget->setMin(rcMin[1]); - ui->throttleWidget->setMax(rcMax[1]); - ui->rollWidget->setMin(rcMin[2]); - ui->rollWidget->setMax(rcMax[2]); - ui->pitchWidget->setMin(rcMin[3]); - ui->pitchWidget->setMax(rcMax[3]); - } - else if (rc_mode == RC_MODE_4) - { - //ui->rollSlider->setValue(rcYaw * 50 + 50); - //ui->pitchSlider->setValue(rcPitch * 50 + 50); - //ui->yawSlider->setValue(rcRoll * 50 + 50); - //ui->throttleSlider->setValue(rcThrottle * 100); - ui->yawWidget->setValue(rcValue[0]); - ui->pitchWidget->setValue(rcValue[1]); - ui->rollWidget->setValue(rcValue[2]); - ui->throttleWidget->setValue(rcValue[3]); - - ui->yawWidget->setMin(rcMin[0]); - ui->yawWidget->setMax(rcMax[0]); - ui->pitchWidget->setMin(rcMin[1]); - ui->pitchWidget->setMax(rcMax[1]); - ui->rollWidget->setMin(rcMin[2]); - ui->rollWidget->setMax(rcMax[2]); - ui->throttleWidget->setMin(rcMin[3]); - ui->throttleWidget->setMax(rcMax[3]); - } - else if (rc_mode == RC_MODE_NONE) - { - ui->rollWidget->setValue(rcValue[0]); - ui->pitchWidget->setValue(rcValue[1]); - ui->throttleWidget->setValue(rcValue[2]); - ui->yawWidget->setValue(rcValue[3]); - - ui->rollWidget->setMin(800); - ui->rollWidget->setMax(2200); - ui->pitchWidget->setMin(800); - ui->pitchWidget->setMax(2200); - ui->throttleWidget->setMin(800); - ui->throttleWidget->setMax(2200); - ui->yawWidget->setMin(800); - ui->yawWidget->setMax(2200); - } + //TODO set eg pitchSpinBox values + + switch (rc_mode) { + case RC_MODE_1: + ui->rollWidget->setValueAndRange(rcValue[0],rcMin[0],rcMax[0]); + ui->throttleWidget->setValueAndRange(rcValue[1],rcMin[1],rcMax[1]); + ui->yawWidget->setValueAndRange(rcValue[2],rcMin[2],rcMax[2]); + ui->pitchWidget->setValueAndRange(rcValue[3],rcMin[3],rcMax[3]); + setRollChan(1); + setThrottleChan(2); - ui->chanLabel->setText(QString("%1/%2").arg(rcValue[rcMapping[0]]).arg(rcRoll, 5, 'f', 2, QChar(' '))); - ui->chanLabel_2->setText(QString("%1/%2").arg(rcValue[rcMapping[1]]).arg(rcPitch, 5, 'f', 2, QChar(' '))); - ui->chanLabel_3->setText(QString("%1/%2").arg(rcValue[rcMapping[2]]).arg(rcYaw, 5, 'f', 2, QChar(' '))); - ui->chanLabel_4->setText(QString("%1/%2").arg(rcValue[rcMapping[3]]).arg(rcThrottle, 5, 'f', 2, QChar(' '))); + break; + case RC_MODE_NONE: + case RC_MODE_2: + ui->rollWidget->setValueAndRange(rcValue[0],rcMin[0],rcMax[0]); + ui->pitchWidget->setValueAndRange(rcValue[1],rcMin[1],rcMax[1]); + ui->throttleWidget->setValueAndRange(rcValue[2],rcMin[2],rcMax[2]); + ui->yawWidget->setValueAndRange(rcValue[3],rcMin[3],rcMax[3]); + break; + + case RC_MODE_3: + ui->yawWidget->setValueAndRange(rcValue[0],rcMin[0],rcMax[0]); + ui->throttleWidget->setValueAndRange(rcValue[1],rcMin[1],rcMax[1]); + ui->rollWidget->setValueAndRange(rcValue[2],rcMin[2],rcMax[2]); + ui->pitchWidget->setValueAndRange(rcValue[3],rcMin[3],rcMax[3]); + break; + + case RC_MODE_4: + ui->yawWidget->setValueAndRange(rcValue[0],rcMin[0],rcMax[0]); + ui->pitchWidget->setValueAndRange(rcValue[1],rcMin[1],rcMax[1]); + ui->rollWidget->setValueAndRange(rcValue[2],rcMin[2],rcMax[2]); + ui->throttleWidget->setValueAndRange(rcValue[3],rcMin[3],rcMax[3]); + break; + } + + ui->radio5Widget->setValueAndRange(rcValue[4],rcMin[4],rcMax[4]); + ui->radio6Widget->setValueAndRange(rcValue[5],rcMin[5],rcMax[5]); + ui->radio7Widget->setValueAndRange(rcValue[6],rcMin[6],rcMax[6]); + ui->radio8Widget->setValueAndRange(rcValue[7],rcMin[7],rcMax[7]); +} + +void QGCPX4VehicleConfig::updateView() +{ + if (dataModelChanged) { + dataModelChanged = false; + //update the selected RC mode + int selectedRcModeIdx = (RC_MODE_NONE != rc_mode) ? (rc_mode -1) : -1; + ui->rcModeComboBox->setCurrentIndex(selectedRcModeIdx); + updateRcWidgetValues(); - //ui->modeSwitchSlider->setValue(rcMode * 50 + 50); - ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[rcMapping[4]]).arg(rcMode, 5, 'f', 2, QChar(' '))); + //update the channel labels + ui->rollChanLabel->setText(QString("%1").arg(rcRoll, 5, 'f', 2, QChar(' '))); + ui->pitchChanLabel->setText(QString("%1").arg(rcPitch, 5, 'f', 2, QChar(' '))); + ui->yawChanLabel->setText(QString("%1").arg(rcYaw, 5, 'f', 2, QChar(' '))); + ui->throttleChanLabel->setText(QString("%1").arg(rcThrottle, 5, 'f', 2, QChar(' '))); if (rcValue[rcMapping[4] != UINT16_MAX]) { - ui->radio5Widget->setValue(rcValue[4]); - ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' '))); + ui->modeChanLabel->setText(QString("%1").arg(rcMode, 5, 'f', 2, QChar(' '))); } else { - ui->chanLabel_5->setText(tr("---")); + ui->modeChanLabel->setText(tr("---")); } if (rcValue[rcMapping[5]] != UINT16_MAX) { - //ui->aux1Slider->setValue(rcAux1 * 50 + 50); - ui->radio6Widget->setValue(rcValue[5]); - ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[rcMapping[5]]).arg(rcAux1, 5, 'f', 2, QChar(' '))); + ui->aux1ChanLabel->setText(QString("%1").arg(rcAux1, 5, 'f', 2, QChar(' '))); } else { - ui->chanLabel_6->setText(tr("---")); + ui->aux1ChanLabel->setText(tr("---")); } if (rcValue[rcMapping[6]] != UINT16_MAX) { - //ui->aux2Slider->setValue(rcAux2 * 50 + 50); - ui->radio7Widget->setValue(rcValue[6]); - ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[rcMapping[6]]).arg(rcAux2, 5, 'f', 2, QChar(' '))); + ui->aux2ChanLabel->setText(QString("%1").arg(rcAux2, 5, 'f', 2, QChar(' '))); } else { - ui->chanLabel_7->setText(tr("---")); + ui->aux2ChanLabel->setText(tr("---")); } if (rcValue[rcMapping[7]] != UINT16_MAX) { - //ui->aux3Slider->setValue(rcAux3 * 50 + 50); - ui->radio8Widget->setValue(rcValue[7]); - ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[rcMapping[7]]).arg(rcAux3, 5, 'f', 2, QChar(' '))); + ui->aux3ChanLabel->setText(QString("%1").arg(rcAux3, 5, 'f', 2, QChar(' '))); } else { - ui->chanLabel_8->setText(tr("---")); + ui->aux3ChanLabel->setText(tr("---")); } - changed = false; } } diff --git a/src/ui/QGCPX4VehicleConfig.h b/src/ui/QGCPX4VehicleConfig.h index 4ed7e006988977a7e7d1bd37d29b2bb7ecdcbef5..b11d2e60e2b9c3b62f014fed62c5888ab61c20d0 100644 --- a/src/ui/QGCPX4VehicleConfig.h +++ b/src/ui/QGCPX4VehicleConfig.h @@ -56,8 +56,9 @@ public slots: void setRCModeIndex(int newRcMode); /** Render the data updated */ void updateView(); + void updateRcWidgetValues(); + void handleRcParameterChange(QString parameterName, QVariant value); - void updateMinMax(); /** Set the RC channel */ void setRollChan(int channel) { @@ -176,10 +177,10 @@ protected: float rcThrottle; ///< PPM input channel used as throttle control input float rcMode; ///< PPM input channel used as mode switch control input float rcAux1; ///< PPM input channel used as aux 1 input - float rcAux2; ///< PPM input channel used as aux 1 input - float rcAux3; ///< PPM input channel used as aux 1 input + float rcAux2; ///< PPM input channel used as aux 2 input + float rcAux3; ///< PPM input channel used as aux 3 input bool rcCalChanged; ///< Set if the calibration changes (and needs to be written) - bool changed; ///< Set if any of the input data changed + bool dataModelChanged; ///< 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 diff --git a/src/ui/QGCPX4VehicleConfig.ui b/src/ui/QGCPX4VehicleConfig.ui index 883dfd72fffe2047ede9edbabf49e82e4f0528c1..8607a55643c540d831a7b0290ace9a4f673e7e58 100644 --- a/src/ui/QGCPX4VehicleConfig.ui +++ b/src/ui/QGCPX4VehicleConfig.ui @@ -7,7 +7,7 @@ 0 0 1256 - 711 + 783 @@ -21,7 +21,7 @@ - + 135 @@ -37,13 +37,13 @@ true - + 0 0 133 - 691 + 757 @@ -138,712 +138,184 @@ Config - 3 + 0 - + + + + 16 + 75 + true + + RC Calibration - - - - - Advanced - - - - - - - Qt::Horizontal - - + + + + - 40 - 20 + 250 + 40 - - - - - - - - - - Advanced - - - - - - - - false - - - false - - - - Select transmitter model - - - - - - - - true - - - - Mode 1 - - - - - Mode 2 - - - - - Mode 3 - - - - - Mode 4 - - - - - - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - Invert - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Yaw / Rudder - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Invert - - - - - - - Invert - - - - - - - false - - - 1 - - - 8 - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - Pitch / Elevator - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - Aux 2 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - Invert - - - - - - - false - - - 1 - - - 8 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Throttle - - - - - - - Invert - - - - - - - false - - - 1 - - - 8 - - - - - - - false - - - 1 - - - 8 - - - - - - - Mode Switch - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - false - - - 1 - - - 8 - - - - - - - false - - - 1 - - - 8 - - - - - - - Aux 1 - - - - - - - false - - - 1 - - - 8 - - - - - - - 0000 - - - Qt::AlignCenter - - - - - - - Aux 3 - - - - - - - Invert - - - - - - - false - - - 1 - - - 8 - - - - - - - Invert - - - - - - - Invert - - - - - - - Roll / Ailerons - - - - - - - - - - - - Qt::Horizontal - - + - 40 - 20 + 250 + 40 - + - - - - - - - - QLayout::SetMinAndMaxSize - + + - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + + + + 250 + 40 + + + + + 250 + 40 + + + - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 50 - 200 - - - - - 50 - 200 - - - - - - - - Qt::Horizontal - - - - 250 - 20 - - - - - - - - - 50 - 200 - - - - - 50 - 200 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - + + + + 250 + 40 + + + + + 250 + 40 + + + - - - - - - 250 - 40 - - - - - 250 - 40 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + 250 + 40 + + + + + 250 + 40 + + + - - - - Qt::Horizontal + + + + + 1 + 0 + - - QSizePolicy::Preferred + + + 50 + 200 + - + - 40 - 20 + 50 + 200 - + + + + + + + 250 + 40 + + + + + 250 + 40 + + + + + + + + + 50 + 200 + + + + + 50 + 200 + + + + + + + + Start Calibration + + - + - + - Start Calibration + Show advanced RC settings - + Qt::Horizontal @@ -857,6 +329,438 @@ Config + + + + Advanced + + + + + + + + RC Transmitter Mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + true + + + + 320 + 16777215 + + + + + Mode 1 + + + + + Mode 2 + + + + + Mode 3 + + + + + Mode 4 + + + + + + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Aux 3 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + false + + + 1 + + + 8 + + + + + + + Invert + + + + + + + Roll / Ailerons + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Aux 1 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Invert + + + + + + + Mode Switch + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Invert + + + + + + + Invert + + + + + + + false + + + 1 + + + 8 + + + + + + + false + + + 1 + + + 8 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + false + + + 1 + + + 8 + + + + + + + Yaw / Rudder + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Invert + + + + + + + Throttle + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + false + + + 1 + + + 8 + + + + + + + Pitch / Elevator + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Aux 2 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + false + + + 1 + + + 8 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + false + + + 1 + + + 8 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Invert + + + + + + + false + + + 1 + + + 8 + + + + + + + 0000 + + + Qt::AlignCenter + + + + + + + Invert + + + + + + + Invert + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + @@ -873,9 +777,16 @@ Config + + + 16 + 75 + true + + - + Sensor Calibration @@ -889,8 +800,8 @@ Config <!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:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> -<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-family:'MS Shell Dlg 2'; font-size:8pt;"><br /></p></body></html> +</style></head><body style=" font-family:'Lucida Grande'; font-size:16pt; font-weight:600; font-style:normal;"> +<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-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400;"><br /></p></body></html> @@ -906,8 +817,8 @@ p, li { white-space: pre-wrap; } 0 0 - 530 - 574 + 26 + 26 @@ -925,9 +836,16 @@ p, li { white-space: pre-wrap; } + + + 16 + 75 + true + + - + General Config @@ -953,6 +871,13 @@ p, li { white-space: pre-wrap; } + + + 13 + 50 + false + + Load Platform Defaults @@ -981,8 +906,8 @@ p, li { white-space: pre-wrap; } 0 0 - 525 - 523 + 16 + 16 @@ -1018,8 +943,8 @@ p, li { white-space: pre-wrap; } 0 0 - 524 - 523 + 16 + 16 @@ -1043,9 +968,16 @@ p, li { white-space: pre-wrap; } - + + + + 16 + 75 + true + + - Advanced Config + Advanced Configuration @@ -1065,10 +997,10 @@ p, li { white-space: pre-wrap; } - + - + Load Platform Defaults @@ -1079,9 +1011,15 @@ p, li { white-space: pre-wrap; } - + + + + 3 + 1 + + - Configuration + Onboard Configuration @@ -1092,13 +1030,13 @@ p, li { white-space: pre-wrap; } true - + 0 0 - 525 - 523 + 16 + 16 @@ -1106,184 +1044,209 @@ p, li { white-space: pre-wrap; } 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 + + + + + + + false + + + Save parameters in this view to a file on this computer. + + + + + + Save to File + + + + + - + + + Qt::Horizontal + + + + 10 + 20 + + + + + + + + + 2 + 0 + + + + + 329 + 0 + + - Configuration + Changes Pending - - - 0 + + + + 10 + 30 + 381 + 601 + - - - - true - - - - - 0 - 0 - 524 - 523 - + + + 0 + + + + + + + + false + + + Set current parameters in non-permanent onboard memory. + + + + + + Commit to UAS - - - 0 - - - - - - - - + + + + + false + + + Set current parameters in non-permanent onboard memory. + + + + + + Clear + + + + + + + false + + + Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them. + + + + + + Load from File + + + + + + + + + Qt::Horizontal + + + + 10 + 20 + + + + - - - - - - - - - - No pending changes - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - false - - - Copy current parameters in non-permanent memory of the aircraft to permanent memory. Transmit your parameters first to write these. - - - - - - Write (ROM) - - - - - - - false - - - Set current parameters in non-permanent onboard memory. - - - - - - Set (UAS) - - - - - - - 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 - - - Load parameters currently in non-permanent memory of aircraft. - - - - - - Get (UAS) - - - - - - - false - - - Load parameters from a file on this computer in the view. To write them to the aircraft, use transmit after loading them. - - - - - - Load (File) - - - - - - - false - - - Save parameters in this view to a file on this computer. - - - - + + - Save (File) + Status - - + + diff --git a/src/ui/designer/QGCRadioChannelDisplay.cpp b/src/ui/designer/QGCRadioChannelDisplay.cpp index 148965eb61934ac64f34424fae464e04ba103574..275afc28e7164b520f1870b92da11b1d3f3b9a44 100644 --- a/src/ui/designer/QGCRadioChannelDisplay.cpp +++ b/src/ui/designer/QGCRadioChannelDisplay.cpp @@ -1,5 +1,10 @@ #include "QGCRadioChannelDisplay.h" #include + +#define DIMMEST_COLOR QColor::fromRgb(0,100,0) +#define MIDBRIGHT_COLOR QColor::fromRgb(0,180,0) +#define BRIGHTEST_COLOR QColor::fromRgb(64,255,0) + QGCRadioChannelDisplay::QGCRadioChannelDisplay(QWidget *parent) : QWidget(parent) { m_showMinMax = false; @@ -8,6 +13,12 @@ QGCRadioChannelDisplay::QGCRadioChannelDisplay(QWidget *parent) : QWidget(parent m_value = 1500; m_orientation = Qt::Vertical; m_name = "Yaw"; + + m_fillBrush = QBrush(Qt::green, Qt::SolidPattern); + + + + } void QGCRadioChannelDisplay::setName(QString name) { @@ -20,87 +31,118 @@ void QGCRadioChannelDisplay::setOrientation(Qt::Orientation orient) m_orientation = orient; update(); } + void QGCRadioChannelDisplay::paintEvent(QPaintEvent *event) { //Values range from 0-3000. //1500 is the middle, static servo value. QPainter painter(this); - int currval = m_value; - if (currval > m_max) - { - currval = m_max; + + + + int fontHeight = painter.fontMetrics().height(); + int twiceFontHeight = fontHeight * 2; + + painter.setBrush(Qt::Dense4Pattern); + painter.setPen(QColor::fromRgb(128,128,64)); + + int curVal = m_value; + if (curVal > m_max) { + curVal = m_max; } - if (currval < m_min) - { - currval = m_min; + if (curVal < m_min) { + curVal = m_min; } if (m_orientation == Qt::Vertical) { - painter.drawRect(0,0,width()-1,(height()-1) - (painter.fontMetrics().height() * 2)); - painter.setBrush(Qt::SolidPattern); + QLinearGradient gradientBrush(0, 0, this->width(), this->height()); + gradientBrush.setColorAt(1.0,DIMMEST_COLOR); + gradientBrush.setColorAt(0.5,MIDBRIGHT_COLOR); + gradientBrush.setColorAt(0.0, BRIGHTEST_COLOR); + + //draw border + painter.drawRect(0,0,width()-1,(height()-1) - twiceFontHeight); painter.setPen(QColor::fromRgb(50,255,50)); - //m_value - m_min / m_max - m_min + painter.setBrush(Qt::SolidPattern); - if (!m_showMinMax) - { - int newval = (height()-2-(painter.fontMetrics().height() * 2)) * ((float)(currval - m_min) / ((m_max-m_min)+1)); - int newvaly = (height()-2-(painter.fontMetrics().height() * 2)) - newval; - painter.drawRect(1,newvaly,width()-3,((height()-2) - newvaly - (painter.fontMetrics().height() * 2))); - } - else - { - int newval = (height()-2-(painter.fontMetrics().height() * 2)) * ((float)(currval / 3001.0)); - int newvaly = (height()-2-(painter.fontMetrics().height() * 2)) - newval; - painter.drawRect(1,newvaly,width()-3,((height()-2) - newvaly - (painter.fontMetrics().height() * 2))); + //draw the text value of the widget, and its label + QString valStr = QString::number(m_value); + painter.setPen(QColor::fromRgb(255,255,255)); + painter.drawText((width()/2.0) - (painter.fontMetrics().width(m_name)/2.0),((height()-3) - (fontHeight*1)),m_name); + painter.drawText((width()/2.0) - (painter.fontMetrics().width(valStr)/2.0),((height()-3) - (fontHeight * 0)),valStr); + + painter.setPen(QColor::fromRgb(128,128,64)); + painter.setBrush(gradientBrush); + + if (!m_showMinMax) { + //draw just the value + int newval = (height()-2-twiceFontHeight) * ((float)(curVal - m_min) / ((m_max-m_min)+1)); + int yVal = (height()-2-twiceFontHeight) - newval; + painter.drawRect(1,yVal,width()-3,((height()-2) - yVal - twiceFontHeight)); } + else { + //draw the value + int newval = (height()-2-twiceFontHeight) * ((float)(curVal / 3001.0)); + int yVal = (height()-2-twiceFontHeight) - newval; + painter.drawRect(1,yVal,width()-3,((height()-2) - yVal - twiceFontHeight)); - QString valstr = QString::number(m_value); - painter.setPen(QColor::fromRgb(255,255,255)); - painter.drawText((width()/2.0) - (painter.fontMetrics().width(m_name)/2.0),((height()-3) - (painter.fontMetrics().height()*1)),m_name); - painter.drawText((width()/2.0) - (painter.fontMetrics().width(valstr)/2.0),((height()-3) - (painter.fontMetrics().height() * 0)),valstr); - if (m_showMinMax) - { - painter.setBrush(Qt::NoBrush); + //draw min max indicator bars painter.setPen(QColor::fromRgb(255,0,0)); - int maxyval = (height()-3 - (painter.fontMetrics().height() * 2)) - (((height()-3-(painter.fontMetrics().height() * 2)) * ((float)m_max / 3000.0))); - int minyval = (height()-3 - (painter.fontMetrics().height() * 2)) - (((height()-3-(painter.fontMetrics().height() * 2)) * ((float)m_min / 3000.0))); - painter.drawRect(2,maxyval,width()-3,minyval - maxyval); + painter.setBrush(Qt::NoBrush); + + int yMax = (height()-3 - twiceFontHeight) - (((height()-3-twiceFontHeight) * ((float)m_max / 3000.0))); + int yMin = (height()-3 - twiceFontHeight) - (((height()-3-twiceFontHeight) * ((float)m_min / 3000.0))); + painter.drawRect(2,yMax,width()-3,yMin - yMax); + + //draw min and max labels QString minstr = QString::number(m_min); - painter.drawText((width() / 2.0) - (painter.fontMetrics().width("min")/2.0),minyval,"min"); - painter.drawText((width() / 2.0) - (painter.fontMetrics().width(minstr)/2.0),minyval + painter.fontMetrics().height(),minstr); + painter.drawText((width() / 2.0) - (painter.fontMetrics().width("min")/2.0),yMin,"min"); + painter.drawText((width() / 2.0) - (painter.fontMetrics().width(minstr)/2.0),yMin + fontHeight,minstr); QString maxstr = QString::number(m_max); - painter.drawText((width() / 2.0) - (painter.fontMetrics().width("max")/2.0),maxyval,"max"); - painter.drawText((width() / 2.0) - (painter.fontMetrics().width(maxstr)/2.0),maxyval + painter.fontMetrics().height(),maxstr); + painter.drawText((width() / 2.0) - (painter.fontMetrics().width("max")/2.0),yMax,"max"); + painter.drawText((width() / 2.0) - (painter.fontMetrics().width(maxstr)/2.0),yMax + fontHeight,maxstr); - //painter.drawRect(width() * ,2,((width()-1) * ((float)m_max / 3000.0)) - (width() * ((float)m_min / 3000.0)),(height()-5) - (painter.fontMetrics().height() * 2)); } } - else + else //horizontal orientation { - painter.drawRect(0,0,width()-1,(height()-1) - (painter.fontMetrics().height() * 2)); - painter.setBrush(Qt::SolidPattern); + QLinearGradient hGradientBrush(0, 0, this->width(), this->height()); + hGradientBrush.setColorAt(0.0,DIMMEST_COLOR); + hGradientBrush.setColorAt(0.5,MIDBRIGHT_COLOR); + hGradientBrush.setColorAt(1.0, BRIGHTEST_COLOR); + + //draw the value + painter.drawRect(0,0,width()-1,(height()-1) - twiceFontHeight); painter.setPen(QColor::fromRgb(50,255,50)); - if (!m_showMinMax) - { - painter.drawRect(1,1,(width()-3) * ((float)(currval-m_min) / (m_max-m_min)),(height()-3) - (painter.fontMetrics().height() * 2)); - } - else - { - painter.drawRect(1,1,(width()-3) * ((float)currval / 3000.0),(height()-3) - (painter.fontMetrics().height() * 2)); - } + painter.setBrush(hGradientBrush); + + //draw the value string painter.setPen(QColor::fromRgb(255,255,255)); QString valstr = QString::number(m_value); - painter.drawText((width()/2.0) - (painter.fontMetrics().width(m_name)/2.0),((height()-3) - (painter.fontMetrics().height()*1)),m_name); - painter.drawText((width()/2.0) - (painter.fontMetrics().width(valstr)/2.0),((height()-3) - (painter.fontMetrics().height() * 0)),valstr); - if (m_showMinMax) - { + painter.drawText((width()/2.0) - (painter.fontMetrics().width(m_name)/2.0),((height()-3) - (fontHeight*1)),m_name); + painter.drawText((width()/2.0) - (painter.fontMetrics().width(valstr)/2.0),((height()-3) - (fontHeight * 0)),valstr); + + + painter.setPen(QColor::fromRgb(0,128,0)); + painter.setBrush(hGradientBrush); + + if (!m_showMinMax) { + //draw just the value + painter.drawRect(1,1,(width()-3) * ((float)(curVal-m_min) / (m_max-m_min)),(height()-3) - twiceFontHeight); + } + else { + //draw the value + painter.drawRect(1,1,(width()-3) * ((float)curVal / 3000.0),(height()-3) - twiceFontHeight); + + //draw the min and max bars painter.setBrush(Qt::NoBrush); painter.setPen(QColor::fromRgb(255,0,0)); - painter.drawRect(width() * ((float)m_min / 3000.0),2,((width()-1) * ((float)m_max / 3000.0)) - (width() * ((float)m_min / 3000.0)),(height()-5) - (painter.fontMetrics().height() * 2)); + painter.drawRect(width() * ((float)m_min / 3000.0),2,((width()-1) * ((float)m_max / 3000.0)) - (width() * ((float)m_min / 3000.0)),(height()-5) - twiceFontHeight); + //draw the min and max strings QString minstr = QString::number(m_min); painter.drawText((width() * ((float)m_min / 3000.0)) - (painter.fontMetrics().width("min")/2.0),((height()-3) - (painter.fontMetrics().height()*1)),"min"); painter.drawText((width() * ((float)m_min / 3000.0)) - (painter.fontMetrics().width(minstr)/2.0),((height()-3) - (painter.fontMetrics().height() * 0)),minstr); @@ -141,6 +183,19 @@ void QGCRadioChannelDisplay::hideMinMax() update(); } + +void QGCRadioChannelDisplay::setValueAndRange(int val, int min, int max) +{ + setValue(val); + setMinMax(min,max); +} + +void QGCRadioChannelDisplay::setMinMax(int min, int max) +{ + setMin(min); + setMax(max); +} + void QGCRadioChannelDisplay::setMin(int value) { m_min = value; diff --git a/src/ui/designer/QGCRadioChannelDisplay.h b/src/ui/designer/QGCRadioChannelDisplay.h index be8958a23a8bd9e63e718ebaa3ef356f4a8b6e4f..59bb65438aa0a1edc5638d2c25a16452ad203468 100644 --- a/src/ui/designer/QGCRadioChannelDisplay.h +++ b/src/ui/designer/QGCRadioChannelDisplay.h @@ -12,6 +12,8 @@ public: void setValue(int value); void showMinMax(); void hideMinMax(); + void setValueAndRange(int val, int min, int max); + void setMinMax(int min, int max); void setMin(int value); void setMax(int value); void setName(QString name); @@ -27,6 +29,8 @@ private: int m_max; bool m_showMinMax; QString m_name; + QBrush m_fillBrush; + signals: public slots: