From b8a41f1ff158c156b1569c5600b0b17501632031 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 27 Aug 2012 14:16:05 +0200 Subject: [PATCH] Fixed a number of compile warnings --- src/LogCompressor.cc | 4 +-- src/ui/DebugConsole.cc | 2 +- src/ui/HSIDisplay.cc | 27 +++++++++++++++----- src/ui/HSIDisplay.h | 31 ++++++++++++----------- src/ui/QGCDataPlot2D.cc | 3 ++- src/ui/QGCWaypointListMulti.cc | 4 +-- src/ui/WaypointList.cc | 1 + src/ui/WaypointViewOnlyView.cc | 1 + src/ui/mavlink/QGCMAVLinkMessageSender.cc | 3 ++- 9 files changed, 48 insertions(+), 28 deletions(-) diff --git a/src/LogCompressor.cc b/src/LogCompressor.cc index 5d41d08c8..094199a4f 100644 --- a/src/LogCompressor.cc +++ b/src/LogCompressor.cc @@ -46,8 +46,8 @@ LogCompressor::LogCompressor(QString logFileName, QString outFileName, QString d outFileName(outFileName), running(true), currentDataLine(0), - holeFillingEnabled(true), - delimiter(delimiter) + delimiter(delimiter), + holeFillingEnabled(true) { } diff --git a/src/ui/DebugConsole.cc b/src/ui/DebugConsole.cc index b8ccb9d40..0d27f3770 100644 --- a/src/ui/DebugConsole.cc +++ b/src/ui/DebugConsole.cc @@ -395,7 +395,7 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes) { if (escReceived) { - if (escIndex < sizeof(escBytes)) + if (escIndex < static_cast(sizeof(escBytes))) { escBytes[escIndex] = byte; //qDebug() << "GOT BYTE ESC:" << byte; diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index f43292a67..2a241a28c 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -49,6 +49,13 @@ This file is part of the QGROUNDCONTROL project HSIDisplay::HSIDisplay(QWidget *parent) : HDDisplay(NULL, "HSI", parent), + dragStarted(false), + leftDragStarted(false), + mouseHasMoved(false), + startX(0.0f), + startY(0.0f), + actionPending(false), + directSending(false), gpsSatellites(), satellitesUsed(0), attXSet(0.0f), @@ -88,6 +95,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) : uiZSetCoordinate(0.0f), uiYawSet(0.0f), metricWidth(4.0), + xCenterPos(0), + yCenterPos(0), positionLock(false), attControlEnabled(false), xyControlEnabled(false), @@ -97,14 +106,20 @@ HSIDisplay::HSIDisplay(QWidget *parent) : gpsFix(0), visionFix(0), laserFix(0), + iruFix(0), mavInitialized(false), - bottomMargin(10.0f), - dragStarted(false), topMargin(12.0f), - leftDragStarted(false), - mouseHasMoved(false), - actionPending(false), - directSending(false), + bottomMargin(10.0f), + attControlKnown(false), + xyControlKnown(false), + zControlKnown(false), + yawControlKnown(false), + positionFixKnown(false), + visionFixKnown(false), + gpsFixKnown(false), + iruFixKnown(false), + setPointKnown(false), + positionSetPointKnown(false), userSetPointSet(false), userXYSetPointSet(false), userZSetPointSet(false), diff --git a/src/ui/HSIDisplay.h b/src/ui/HSIDisplay.h index 7a35dbc6d..b23075e61 100644 --- a/src/ui/HSIDisplay.h +++ b/src/ui/HSIDisplay.h @@ -162,20 +162,6 @@ protected: double refToMetric(double ref); /** @brief Metric body coordinates to screen coordinates */ QPointF metricBodyToScreen(QPointF metric); - QMap objectNames; - QMap objectTypes; - QMap objectQualities; - QMap objectBearings; - QMap objectDistances; - bool dragStarted; - bool leftDragStarted; - bool mouseHasMoved; - float startX; - float startY; - QTimer statusClearTimer; - QString statusMessage; - bool actionPending; - bool directSending; /** * @brief Private data container class to be used within the HSI widget @@ -212,6 +198,21 @@ protected: friend class HSIDisplay; }; + QMap objectNames; + QMap objectTypes; + QMap objectQualities; + QMap objectBearings; + QMap objectDistances; + bool dragStarted; + bool leftDragStarted; + bool mouseHasMoved; + float startX; + float startY; + QTimer statusClearTimer; + QString statusMessage; + bool actionPending; + bool directSending; + QMap gpsSatellites; unsigned int satellitesUsed; @@ -275,8 +276,8 @@ protected: int laserFix; ///< Localization dimensions based on laser int iruFix; ///< Localization dimensions based on ultrasound bool mavInitialized; ///< The MAV is initialized once the setpoint has been received - float bottomMargin; ///< Margin on the bottom of the page, in virtual coordinates float topMargin; ///< Margin on top of the page, in virtual coordinates + float bottomMargin; ///< Margin on the bottom of the page, in virtual coordinates bool attControlKnown; ///< Attitude control status known flag bool xyControlKnown; ///< XY control status known flag diff --git a/src/ui/QGCDataPlot2D.cc b/src/ui/QGCDataPlot2D.cc index 9013ea3fd..f3dbeb403 100644 --- a/src/ui/QGCDataPlot2D.cc +++ b/src/ui/QGCDataPlot2D.cc @@ -613,7 +613,8 @@ bool QGCDataPlot2D::calculateRegression(QString xName, QString yName, QString me function = tr("Regression method %1 not found").arg(method); } - delete x, y; + delete x; + delete y; } else { // xName == yName function = tr("Please select different X and Y dimensions, not %1 = %2").arg(xName, yName); diff --git a/src/ui/QGCWaypointListMulti.cc b/src/ui/QGCWaypointListMulti.cc index 2bf3462c8..53a0065df 100644 --- a/src/ui/QGCWaypointListMulti.cc +++ b/src/ui/QGCWaypointListMulti.cc @@ -4,8 +4,8 @@ QGCWaypointListMulti::QGCWaypointListMulti(QWidget *parent) : QWidget(parent), - ui(new Ui::QGCWaypointListMulti), - offline_uas_id(0) + offline_uas_id(0), + ui(new Ui::QGCWaypointListMulti) { ui->setupUi(this); setMinimumSize(600, 80); diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index 44a5be0db..e9ec70bba 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -338,6 +338,7 @@ int WaypointList::addCurrentPositionWaypoint() return 1; } } + return 1; } void WaypointList::updateStatusLabel(const QString &string) diff --git a/src/ui/WaypointViewOnlyView.cc b/src/ui/WaypointViewOnlyView.cc index b7858944c..3ae64851b 100644 --- a/src/ui/WaypointViewOnlyView.cc +++ b/src/ui/WaypointViewOnlyView.cc @@ -28,6 +28,7 @@ void WaypointViewOnlyView::changedAutoContinue(int state) void WaypointViewOnlyView::changedCurrent(int state) //This is a slot receiving signals from QCheckBox m_ui->current. The state given here is whatever the user has clicked and not the true "current" value onboard. { + Q_UNUSED(state); //qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->getId(); m_ui->current->blockSignals(true); diff --git a/src/ui/mavlink/QGCMAVLinkMessageSender.cc b/src/ui/mavlink/QGCMAVLinkMessageSender.cc index 404847e2d..fabf24997 100644 --- a/src/ui/mavlink/QGCMAVLinkMessageSender.cc +++ b/src/ui/mavlink/QGCMAVLinkMessageSender.cc @@ -44,7 +44,8 @@ bool QGCMAVLinkMessageSender::sendMessage() bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) { - if (msgid == 0 || msgid > 255 || messageInfo[msgid].name == "" || messageInfo[msgid].name == "EMPTY") + QString msgname(messageInfo[msgid].name); + if (msgid == 0 || msgid > 255 || messageInfo[msgid].name == NULL || msgname.compare(QString("EMPTY"))) { return false; } -- 2.22.0