diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 29123742495f631ccd259c5e39a31582411c7756..dcc1768f170ca4a509bd54ffb6e7d5a07eb91472 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -3070,6 +3070,11 @@ void UAS::sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw float pitchspeed, float yawspeed, double lat, double lon, double alt, float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc) { + Q_UNUSED(time_us); + Q_UNUSED(xacc); + Q_UNUSED(yacc); + Q_UNUSED(zacc); + float q[4]; double cosPhi_2 = cos(double(roll) / 2.0); diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 2c424b1b83cc9b16ef71352c7f4c514d1b619b14..13c134eef8c00674a0f908a71e1d5daed354b7e1 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -117,6 +117,9 @@ HUD::HUD(int width, int height, QWidget* parent) imageRequested(false), image(NULL) { + Q_UNUSED(width); + Q_UNUSED(height); + // Set auto fill to false setAutoFillBackground(false); @@ -501,11 +504,18 @@ void HUD::paintText(QString text, QColor color, float fontSize, float refX, floa */ void HUD::setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight) { + Q_UNUSED(referencePositionX); + Q_UNUSED(referencePositionY); + Q_UNUSED(referenceWidth); + Q_UNUSED(referenceHeight); +#if 0 + // code ifdef'ed out but left in to silence warnings int pixelWidth = (int)(referenceWidth * scalingFactor); int pixelHeight = (int)(referenceHeight * scalingFactor); // Translate and scale the GL view in the virtual reference coordinate units on the screen int pixelPositionX = (int)((referencePositionX * scalingFactor) + xCenterOffset); int pixelPositionY = this->height() - (referencePositionY * scalingFactor) + yCenterOffset - pixelHeight; +#endif } void HUD::paintRollPitchStrips() @@ -515,7 +525,7 @@ void HUD::paintRollPitchStrips() void HUD::paintEvent(QPaintEvent *event) { - + Q_UNUSED(event); paintHUD(); } diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index a958dc1ed9f7b27d9abfcb90baa675059ba8f23f..6536484013c1b8e73f66bc88a911a1cc691b4b9a 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -800,6 +800,7 @@ void MainWindow::loadDockWidget(const QString& name) void MainWindow::addToCentralStackedWidget(QWidget* widget, VIEW_SECTIONS viewSection, const QString& title) { + Q_UNUSED(viewSection); Q_UNUSED(title); Q_ASSERT(widget->objectName().length() != 0); diff --git a/src/ui/PrimaryFlightDisplay.cc b/src/ui/PrimaryFlightDisplay.cc index b50503fcd843ad6311a5a5efe9c523b6df4d8aa0..9a206fae81127a2cf2b33bdc21c2422690247fa9 100644 --- a/src/ui/PrimaryFlightDisplay.cc +++ b/src/ui/PrimaryFlightDisplay.cc @@ -606,6 +606,8 @@ void PrimaryFlightDisplay::drawPitchScale( bool drawNumbersRight ) { + Q_UNUSED(intrusion); + float displayPitch = this->pitch; if (isnan(displayPitch)) displayPitch = 0; diff --git a/src/ui/QGCHilConfiguration.cc b/src/ui/QGCHilConfiguration.cc index e501e8c6aaf7d16252fbd65b74e3c7599324953f..8d2a52af4e99119df9357c0f113cff7274d01588 100644 --- a/src/ui/QGCHilConfiguration.cc +++ b/src/ui/QGCHilConfiguration.cc @@ -48,7 +48,7 @@ QGCHilConfiguration::~QGCHilConfiguration() void QGCHilConfiguration::setVersion(QString version) { - + Q_UNUSED(version); } void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index) diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index 831b74b942dd8a5caca7f80523a11403e5d294a5..5ab600af7c35cfc2021bf2435173c1578d2d6884 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -355,6 +355,8 @@ void QGCPX4VehicleConfig::toggleCalibrationRC(bool enabled) void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled) { + Q_UNUSED(enabled); + if (!ui->dsm2RadioButton->isChecked() && !ui->dsmxRadioButton && !ui->dsmx8RadioButton) { // Reject QMessageBox warnMsgBox; diff --git a/src/ui/UASRawStatusView.cpp b/src/ui/UASRawStatusView.cpp index b46af50268e2c84ac6c9f09d81f2642047713dde..1862ea7a3f34955b59a90edef6078407d85fb177 100644 --- a/src/ui/UASRawStatusView.cpp +++ b/src/ui/UASRawStatusView.cpp @@ -47,6 +47,7 @@ void UASRawStatusView::valueChanged(const int uasId, const QString& name, const } void UASRawStatusView::resizeEvent(QResizeEvent *event) { + Q_UNUSED(event); m_tableDirty = true; } diff --git a/src/ui/configuration/AP2ConfigWidget.cc b/src/ui/configuration/AP2ConfigWidget.cc index 3ce8751b72423c7abb0383c63f617c7d51399250..d48158b3222d4a4b1e9c86200e7320b42fac81e8 100644 --- a/src/ui/configuration/AP2ConfigWidget.cc +++ b/src/ui/configuration/AP2ConfigWidget.cc @@ -25,7 +25,10 @@ void AP2ConfigWidget::activeUASSet(UASInterface *uas) void AP2ConfigWidget::parameterChanged(int uas, int component, QString parameterName, QVariant value) { - + Q_UNUSED(uas); + Q_UNUSED(component); + Q_UNUSED(parameterName); + Q_UNUSED(value); } void AP2ConfigWidget::showNullMAVErrorMessageBox() { diff --git a/src/ui/configuration/AccelCalibrationConfig.cc b/src/ui/configuration/AccelCalibrationConfig.cc index f552580d1f9ed9032cc70b9cb3f987ac01d35ca5..8be7913521a392640284544994dcd634343ee9f5 100644 --- a/src/ui/configuration/AccelCalibrationConfig.cc +++ b/src/ui/configuration/AccelCalibrationConfig.cc @@ -71,6 +71,8 @@ void AccelCalibrationConfig::calibrateButtonClicked() } void AccelCalibrationConfig::hideEvent(QHideEvent *evt) { + Q_UNUSED(evt); + if (!m_uas || !m_accelAckCount) { return; @@ -82,6 +84,9 @@ void AccelCalibrationConfig::hideEvent(QHideEvent *evt) } void AccelCalibrationConfig::uasTextMessageReceived(int uasid, int componentid, int severity, QString text) { + Q_UNUSED(uasid); + Q_UNUSED(componentid); + //command received: " Severity 1 //Place APM Level and press any key" severity 5 if (severity == 5) diff --git a/src/ui/configuration/AdvParameterList.cc b/src/ui/configuration/AdvParameterList.cc index 24a5bc384e146e91954e7da57caedd6892bd6e14..bc0bb670234ffa0e1e78a036697276a75c47c2fb 100644 --- a/src/ui/configuration/AdvParameterList.cc +++ b/src/ui/configuration/AdvParameterList.cc @@ -25,7 +25,9 @@ void AdvParameterList::setParameterMetaData(QString name,QString humanname,QStri void AdvParameterList::parameterChanged(int uas, int component, QString parameterName, QVariant value) { - + Q_UNUSED(uas); + Q_UNUSED(component); + if (!m_paramValueMap.contains(parameterName)) { ui.tableWidget->setRowCount(ui.tableWidget->rowCount()+1); diff --git a/src/ui/configuration/AdvancedParamConfig.cc b/src/ui/configuration/AdvancedParamConfig.cc index 98f0c1c62e4df6cca8798dc05b15c1df7fe96da1..8edbe1fd64eff09d572d9bc31a3ee74f45d583b5 100644 --- a/src/ui/configuration/AdvancedParamConfig.cc +++ b/src/ui/configuration/AdvancedParamConfig.cc @@ -33,6 +33,9 @@ void AdvancedParamConfig::addCombo(QString title,QString description,QString par } void AdvancedParamConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (m_paramToWidgetMap.contains(parameterName)) { if (value.type() == QVariant::Double) diff --git a/src/ui/configuration/AirspeedConfig.cc b/src/ui/configuration/AirspeedConfig.cc index 27699996b103dec27c5dc40e2169d609a1a85e2e..25da75fc28042d4b54529d786e2dcc5ebeb8b8be 100644 --- a/src/ui/configuration/AirspeedConfig.cc +++ b/src/ui/configuration/AirspeedConfig.cc @@ -14,6 +14,9 @@ AirspeedConfig::~AirspeedConfig() } void AirspeedConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "ARSPD_ENABLE") { if (value.toInt() == 0) diff --git a/src/ui/configuration/ApmFirmwareConfig.cc b/src/ui/configuration/ApmFirmwareConfig.cc index 4ef8950d592de49ba3cc094d28cb3263ad5e5492..0468b24d178a9fc14a163abd7e4d4d23e4f94c60 100644 --- a/src/ui/configuration/ApmFirmwareConfig.cc +++ b/src/ui/configuration/ApmFirmwareConfig.cc @@ -387,6 +387,7 @@ void ApmFirmwareConfig::flashButtonClicked() void ApmFirmwareConfig::firmwareListError(QNetworkReply::NetworkError error) { + Q_UNUSED(error); QNetworkReply *reply = qobject_cast(sender()); qDebug() << "Error!" << reply->errorString(); } diff --git a/src/ui/configuration/ApmPlaneLevel.cc b/src/ui/configuration/ApmPlaneLevel.cc index 49b1b20f5e1811f3744f6b73037f17a236251dd5..3bda80e928a29c71d315b8eeef068b06002a26cc 100644 --- a/src/ui/configuration/ApmPlaneLevel.cc +++ b/src/ui/configuration/ApmPlaneLevel.cc @@ -52,6 +52,9 @@ void ApmPlaneLevel::manualCheckBoxToggled(bool checked) } void ApmPlaneLevel::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "MANUAL_LEVEL") { if (value.toInt() == 1) diff --git a/src/ui/configuration/ArduCopterPidConfig.cc b/src/ui/configuration/ArduCopterPidConfig.cc index 7d5f274cbd4b8822e3ee09c64df79230148271da..632d3d17c31407163570b9d148008e059855a92a 100644 --- a/src/ui/configuration/ArduCopterPidConfig.cc +++ b/src/ui/configuration/ArduCopterPidConfig.cc @@ -139,6 +139,9 @@ ArduCopterPidConfig::~ArduCopterPidConfig() } void ArduCopterPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (m_nameToBoxMap.contains(parameterName)) { m_nameToBoxMap[parameterName]->setValue(value.toDouble()); diff --git a/src/ui/configuration/ArduPlanePidConfig.cc b/src/ui/configuration/ArduPlanePidConfig.cc index 157c2db3878a989b6b5673daa2a04e1274ef4917..13db80b961ce4281d6aa55391352c483d3171c1c 100644 --- a/src/ui/configuration/ArduPlanePidConfig.cc +++ b/src/ui/configuration/ArduPlanePidConfig.cc @@ -66,6 +66,9 @@ ArduPlanePidConfig::~ArduPlanePidConfig() } void ArduPlanePidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (m_nameToBoxMap.contains(parameterName)) { m_nameToBoxMap[parameterName]->setValue(value.toDouble()); diff --git a/src/ui/configuration/ArduRoverPidConfig.cc b/src/ui/configuration/ArduRoverPidConfig.cc index e84d79943c3790fa6138138b1e1397fa48533e92..026bb83507829987c3fc1acf903c088f75d2709e 100644 --- a/src/ui/configuration/ArduRoverPidConfig.cc +++ b/src/ui/configuration/ArduRoverPidConfig.cc @@ -73,6 +73,9 @@ void ArduRoverPidConfig::refreshButtonClicked() void ArduRoverPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (nameToBoxMap.contains(parameterName)) { nameToBoxMap[parameterName]->setValue(value.toFloat()); diff --git a/src/ui/configuration/BatteryMonitorConfig.cc b/src/ui/configuration/BatteryMonitorConfig.cc index 68692aa62bb2fc49bf58c6bca50515c836782cfd..a4d3ca319c9337236d9a0599a0971d607a58581c 100644 --- a/src/ui/configuration/BatteryMonitorConfig.cc +++ b/src/ui/configuration/BatteryMonitorConfig.cc @@ -49,6 +49,7 @@ void BatteryMonitorConfig::activeUASSet(UASInterface *uas) } void BatteryMonitorConfig::alertOnLowClicked(bool checked) { + Q_UNUSED(checked); } void BatteryMonitorConfig::calcDividerSet() @@ -246,6 +247,11 @@ BatteryMonitorConfig::~BatteryMonitorConfig() } void BatteryMonitorConfig::batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds) { + Q_UNUSED(uas); + Q_UNUSED(current); + Q_UNUSED(percent); + Q_UNUSED(seconds); + ui.calcVoltsLineEdit->setText(QString::number(voltage,'f',2)); if (ui.measuredVoltsLineEdit->text() == "") { @@ -255,6 +261,9 @@ void BatteryMonitorConfig::batteryChanged(UASInterface* uas, double voltage, dou void BatteryMonitorConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "VOLT_DIVIDER") { ui.calcDividerLineEdit->setText(QString::number(value.toFloat(),'f',4)); diff --git a/src/ui/configuration/CameraGimbalConfig.cc b/src/ui/configuration/CameraGimbalConfig.cc index 6b14b1a466cac5260f33f8f1d3df77e21d3a228b..7d4317e48a1c56fa785d950254fad69c75576bc7 100644 --- a/src/ui/configuration/CameraGimbalConfig.cc +++ b/src/ui/configuration/CameraGimbalConfig.cc @@ -265,6 +265,9 @@ CameraGimbalConfig::~CameraGimbalConfig() void CameraGimbalConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "MNT_ANGMIN_TIL") //TILT { ui.tiltAngleMinSpinBox->setValue(value.toInt() / 100.0); diff --git a/src/ui/configuration/CompassConfig.cc b/src/ui/configuration/CompassConfig.cc index 610d354ed614465965a9f08fd247b30a1ffd7191..411cf79b6901211a1044ff18ba92c43952ffc129 100644 --- a/src/ui/configuration/CompassConfig.cc +++ b/src/ui/configuration/CompassConfig.cc @@ -46,6 +46,9 @@ CompassConfig::~CompassConfig() } void CompassConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "MAG_ENABLE") { if (value.toInt() == 0) diff --git a/src/ui/configuration/FailSafeConfig.cc b/src/ui/configuration/FailSafeConfig.cc index 9d177cc735ec12e004ac113e5c500fc1bf13e201..f032541b1c7e35f44a15ddf1c3b25a0fd1e681bb 100644 --- a/src/ui/configuration/FailSafeConfig.cc +++ b/src/ui/configuration/FailSafeConfig.cc @@ -278,6 +278,9 @@ void FailSafeConfig::activeUASSet(UASInterface *uas) } void FailSafeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + //Arducopter if (parameterName == "FS_THR_ENABLE") { @@ -414,6 +417,8 @@ void FailSafeConfig::remoteControlChannelRawChanges(int chan,float value) } void FailSafeConfig::hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8) { + Q_UNUSED(time); + ui.radio1Out->setValue(act1); ui.radio2Out->setValue(act2); ui.radio3Out->setValue(act3); @@ -425,6 +430,8 @@ void FailSafeConfig::hilActuatorsChanged(uint64_t time, float act1, float act2, } void FailSafeConfig::gpsStatusChanged(UASInterface* uas,int fixtype) { + Q_UNUSED(uas); + if (fixtype == 0 || fixtype == 1) { ui.gpsLabel->setText("

None

"); diff --git a/src/ui/configuration/FrameTypeConfig.cc b/src/ui/configuration/FrameTypeConfig.cc index 8c123c69fbb581de6e719b22676f1e0407ef6ec1..9d8803c264f76153dd4e0a411342e8775cbe68dc 100644 --- a/src/ui/configuration/FrameTypeConfig.cc +++ b/src/ui/configuration/FrameTypeConfig.cc @@ -52,6 +52,9 @@ FrameTypeConfig::~FrameTypeConfig() } void FrameTypeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "FRAME") { ui.xRadioButton->setEnabled(true); diff --git a/src/ui/configuration/OpticalFlowConfig.cc b/src/ui/configuration/OpticalFlowConfig.cc index 3e8bdb8b78b55ab58111f28ac837b652194720da..89f30558208e1cfcb8435c2ff438a7476a40a8c5 100644 --- a/src/ui/configuration/OpticalFlowConfig.cc +++ b/src/ui/configuration/OpticalFlowConfig.cc @@ -13,6 +13,9 @@ OpticalFlowConfig::~OpticalFlowConfig() } void OpticalFlowConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "FLOW_ENABLE") { if (value.toInt() == 0) diff --git a/src/ui/configuration/ParamWidget.cc b/src/ui/configuration/ParamWidget.cc index b9fb03c72671989e039a4bc732230974735b0083..aef3e3e3e783e833e3f985485313eab919752db9 100644 --- a/src/ui/configuration/ParamWidget.cc +++ b/src/ui/configuration/ParamWidget.cc @@ -48,6 +48,8 @@ ParamWidget::~ParamWidget() void ParamWidget::setupInt(QString title,QString description,int value,int min,int max) { + Q_UNUSED(value); + type = INT; ui.titleLabel->setText("

" + title + "

"); ui.descriptionLabel->setText(description); @@ -71,6 +73,8 @@ void ParamWidget::setupInt(QString title,QString description,int value,int min,i void ParamWidget::setupDouble(QString title,QString description,double value,double min,double max) { + Q_UNUSED(value); + type = DOUBLE; ui.titleLabel->setText("

" + title + "

"); ui.descriptionLabel->setText(description); diff --git a/src/ui/configuration/RadioCalibrationConfig.cc b/src/ui/configuration/RadioCalibrationConfig.cc index eb9db6fca9bfb4c71df52145f285616ed995c122..7dd5189af5d34f0261a60c29ae12742158de9377 100644 --- a/src/ui/configuration/RadioCalibrationConfig.cc +++ b/src/ui/configuration/RadioCalibrationConfig.cc @@ -119,7 +119,10 @@ void RadioCalibrationConfig::remoteControlChannelRawChanged(int chan,float val) void RadioCalibrationConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { - + Q_UNUSED(uas); + Q_UNUSED(component); + Q_UNUSED(parameterName); + Q_UNUSED(value); } void RadioCalibrationConfig::guiUpdateTimerTick() { @@ -153,10 +156,12 @@ void RadioCalibrationConfig::guiUpdateTimerTick() } void RadioCalibrationConfig::showEvent(QShowEvent *event) { + Q_UNUSED(event); guiUpdateTimer->start(100); } void RadioCalibrationConfig::hideEvent(QHideEvent *event) { + Q_UNUSED(event); guiUpdateTimer->stop(); } void RadioCalibrationConfig::calibrateButtonClicked() diff --git a/src/ui/configuration/SonarConfig.cc b/src/ui/configuration/SonarConfig.cc index fb8c4687b03dc6a2b69df6c398cee064de6f381f..2826804fbae9ff276605b62d24b357a04a7f8375 100644 --- a/src/ui/configuration/SonarConfig.cc +++ b/src/ui/configuration/SonarConfig.cc @@ -32,6 +32,8 @@ void SonarConfig::checkBoxToggled(bool enabled) } void SonarConfig::sonarTypeChanged(int index) { + Q_UNUSED(index); + if (!m_uas) { QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration")); @@ -42,6 +44,9 @@ void SonarConfig::sonarTypeChanged(int index) void SonarConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (parameterName == "SONAR_ENABLE") { if (value.toInt() == 0) diff --git a/src/ui/configuration/StandardParamConfig.cc b/src/ui/configuration/StandardParamConfig.cc index 0f43a922504a66928ca326e9e478525f35d58d44..509a109eea0d7df9c781bfcc451f647a43c7fd8a 100644 --- a/src/ui/configuration/StandardParamConfig.cc +++ b/src/ui/configuration/StandardParamConfig.cc @@ -31,6 +31,9 @@ void StandardParamConfig::addCombo(QString title,QString description,QString par } void StandardParamConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + if (paramToWidgetMap.contains(parameterName)) { if (value.type() == QVariant::Double) diff --git a/src/ui/configuration/terminalconsole.cpp b/src/ui/configuration/terminalconsole.cpp index 66ef5469112865cc60c6ecce7af3aaec22f9222b..86df9e4f8f16500a27ead0990c9d6e45646f04f7 100644 --- a/src/ui/configuration/terminalconsole.cpp +++ b/src/ui/configuration/terminalconsole.cpp @@ -257,6 +257,7 @@ void TerminalConsole::setBaudRate(int index) void TerminalConsole::setLink(int index) { + Q_UNUSED(index); m_settings.name = ui->linkComboBox->currentText(); qDebug() << "Changed Link to:" << m_settings.name; diff --git a/src/ui/designer/QGCRadioChannelDisplay.cpp b/src/ui/designer/QGCRadioChannelDisplay.cpp index 275afc28e7164b520f1870b92da11b1d3f3b9a44..b2d4b0dd075e15de8e23a2df8f52197e1ab25157 100644 --- a/src/ui/designer/QGCRadioChannelDisplay.cpp +++ b/src/ui/designer/QGCRadioChannelDisplay.cpp @@ -34,6 +34,8 @@ void QGCRadioChannelDisplay::setOrientation(Qt::Orientation orient) void QGCRadioChannelDisplay::paintEvent(QPaintEvent *event) { + Q_UNUSED(event); + //Values range from 0-3000. //1500 is the middle, static servo value. QPainter painter(this); diff --git a/src/ui/designer/QGCToolWidget.cc b/src/ui/designer/QGCToolWidget.cc index 2eeae5b26f3a963f71d66a83463b63492ef6608d..69dc906d0c4534b807bd38201d4946cc9aede426 100644 --- a/src/ui/designer/QGCToolWidget.cc +++ b/src/ui/designer/QGCToolWidget.cc @@ -192,6 +192,10 @@ QList QGCToolWidget::getParamList() } void QGCToolWidget::setParameterValue(int uas, int component, QString parameterName, const QVariant value) { + Q_UNUSED(uas); + Q_UNUSED(component); + Q_UNUSED(value); + QString widgetName = getTitle(); int size = settingsMap["count"].toInt(); if (paramToItemMap.contains(parameterName)) diff --git a/src/ui/linechart/IncrementalPlot.h b/src/ui/linechart/IncrementalPlot.h index cb9784ee7d15028c25d9a0841f5bb7510f4ec1c1..66f2b07347dc419a6e24b7b3b618d3f03bf34365 100644 --- a/src/ui/linechart/IncrementalPlot.h +++ b/src/ui/linechart/IncrementalPlot.h @@ -61,8 +61,6 @@ private: int d_count; QwtArray d_x; QwtArray d_y; - QTimer *d_timer; - int d_timerCount; }; /** diff --git a/src/ui/uas/UASQuickView.cc b/src/ui/uas/UASQuickView.cc index 668ae999e88e9340892940543fae8f93f4516e02..1054a3e40fb2a03cf7f5919873b3ac60d82496a6 100644 --- a/src/ui/uas/UASQuickView.cc +++ b/src/ui/uas/UASQuickView.cc @@ -190,6 +190,7 @@ void UASQuickView::sortItems(int columncount) } void UASQuickView::resizeEvent(QResizeEvent *evt) { + Q_UNUSED(evt); recalculateItemTextSizing(); } void UASQuickView::recalculateItemTextSizing() @@ -273,6 +274,8 @@ void UASQuickView::valueChanged(const int uasId, const QString& name, const QStr { Q_UNUSED(uasId); Q_UNUSED(unit); + Q_UNUSED(msec); + bool ok; double value = variant.toDouble(&ok); QMetaType::Type metaType = static_cast(variant.type()); diff --git a/src/ui/uas/UASQuickViewGaugeItem.cc b/src/ui/uas/UASQuickViewGaugeItem.cc index 0446e52807ea4cf4a191af42e275a34af5277d22..6fac0f2aef2238156d90b64fd958b1bd41c707de 100644 --- a/src/ui/uas/UASQuickViewGaugeItem.cc +++ b/src/ui/uas/UASQuickViewGaugeItem.cc @@ -15,6 +15,8 @@ void UASQuickViewGaugeItem::setTitle(QString title) } void UASQuickViewGaugeItem::resizeEvent(QResizeEvent *event) { + Q_UNUSED(event); + QFont valuefont = valueLabel->font(); QFont titlefont = titleLabel->font(); valuefont.setPixelSize(this->height() / 2.0); diff --git a/src/ui/uas/UASQuickViewItemSelect.cc b/src/ui/uas/UASQuickViewItemSelect.cc index 6536529cae513debfa7dc251e0e1489eff3c9fe1..124c635aecda34512f8d416ee392d8d4f109eca4 100644 --- a/src/ui/uas/UASQuickViewItemSelect.cc +++ b/src/ui/uas/UASQuickViewItemSelect.cc @@ -59,6 +59,8 @@ void UASQuickViewItemSelect::addItem(QString item,bool enabled) } void UASQuickViewItemSelect::resizeEvent(QResizeEvent *event) { + Q_UNUSED(event); + /*for (int i=0;iremoveWidget(m_checkBoxList[i]); diff --git a/src/ui/uas/UASQuickViewTextItem.cc b/src/ui/uas/UASQuickViewTextItem.cc index f5b89c1f9b7fb2b4a4a1b3e03744cbb90d3f74fc..f55dff6a15fc9c671b3959f406d19d6e463dd52f 100644 --- a/src/ui/uas/UASQuickViewTextItem.cc +++ b/src/ui/uas/UASQuickViewTextItem.cc @@ -119,7 +119,10 @@ void UASQuickViewTextItem::setValuePixelSize(int size) void UASQuickViewTextItem::resizeEvent(QResizeEvent *event) { + Q_UNUSED(event); return; +#if 0 + // code ifdef'ed out to silence warnings QFont valuefont = valueLabel->font(); QFont titlefont = titleLabel->font(); valuefont.setPixelSize(this->height()); @@ -158,4 +161,5 @@ titlefont.setPixelSize(valuefont.pixelSize() / 2.0); valueLabel->setFont(valuefont); titleLabel->setFont(titlefont); update(); +#endif } diff --git a/src/ui/uas/UASQuickViewTextItem.h b/src/ui/uas/UASQuickViewTextItem.h index 698c358f9120eecf2ba40eb37ae8cfa9740e5ec8..6f8946915411930a04b78aadf0381dd083d52646 100644 --- a/src/ui/uas/UASQuickViewTextItem.h +++ b/src/ui/uas/UASQuickViewTextItem.h @@ -17,7 +17,6 @@ protected: private: QLabel *titleLabel; QLabel *valueLabel; - QSpacerItem *spacerItem; }; #endif // UASQUICKVIEWTEXTITEM_H