From 9b657f8e1cd6c881702b71d16cfef0bab330f5ee Mon Sep 17 00:00:00 2001 From: LM Date: Thu, 14 Jul 2011 08:28:26 +0200 Subject: [PATCH] Adjusted a large number of files to work with VS2008 compiler --- src/comm/SerialLink.cc | 21 ++- src/libs/opmapcontrol/src/core/point.cpp | 13 +- src/libs/opmapcontrol/src/core/point.h | 12 +- src/libs/opmapcontrol/src/core/urlfactory.cpp | 1 + .../internals/projections/lks94projection.cpp | 11 +- .../projections/mercatorprojection.cpp | 2 +- .../projections/mercatorprojectionyandex.cpp | 4 +- .../projections/platecarreeprojection.cpp | 2 +- .../platecarreeprojectionpergo.cpp | 2 +- .../src/internals/pureprojection.cpp | 11 +- .../src/internals/pureprojection.h | 2 +- .../opmapcontrol/src/internals/rectlatlng.h | 16 +- .../opmapcontrol/src/mapwidget/gpsitem.cpp | 2 +- .../opmapcontrol/src/mapwidget/uavitem.cpp | 2 +- src/libs/utils/coordinateconversions.cpp | 1 + src/libs/utils/qtcolorbutton.cpp | 2 +- src/libs/utils/utils_external.pri | 158 +++++++++--------- src/libs/utils/worldmagmodel.cpp | 1 + src/uas/UAS.cc | 2 + src/uas/UASManager.cc | 3 +- src/ui/HSIDisplay.cc | 2 + src/ui/SerialConfigurationWindow.cc | 2 +- src/ui/mavlink/QGCMAVLinkTextEdit.cc | 2 + 23 files changed, 150 insertions(+), 124 deletions(-) diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 21e91563d..db53054b0 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -344,6 +344,7 @@ qint64 SerialLink::getNominalDataRate() { qint64 dataRate = 0; switch (portSettings.baudRate()) { +#ifndef Q_OS_WIN case QPortSettings::BAUDR_50: dataRate = 50; break; @@ -362,6 +363,7 @@ qint64 SerialLink::getNominalDataRate() case QPortSettings::BAUDR_200: dataRate = 200; break; +#endif case QPortSettings::BAUDR_300: dataRate = 300; break; @@ -371,9 +373,11 @@ qint64 SerialLink::getNominalDataRate() case QPortSettings::BAUDR_1200: dataRate = 1200; break; +#ifndef Q_OS_WIN case QPortSettings::BAUDR_1800: dataRate = 1800; break; +#endif case QPortSettings::BAUDR_2400: dataRate = 2400; break; @@ -402,7 +406,7 @@ qint64 SerialLink::getNominalDataRate() case QPortSettings::BAUDR_57600: dataRate = 57600; break; -#ifdef Q_OS_WIN +#ifdef Q_OS_WIN_XXXX // FIXME case QPortSettings::BAUDR_76800: dataRate = 76800; break; @@ -598,7 +602,13 @@ bool SerialLink::setBaudRateType(int rateIndex) if(isConnected()) reconnect = true; disconnect(); - if (rateIndex >= (int)QPortSettings::BAUDR_50 && rateIndex <= (int)QPortSettings::BAUDR_921600) +#ifdef Q_OS_WIN + const int minBaud = (int)QPortSettings::BAUDR_14400; +#else + const int minBaud = (int)QPortSettings::BAUDR_50; +#endif + + if (rateIndex >= minBaud && rateIndex <= (int)QPortSettings::BAUDR_921600) { portSettings.setBaudRate((QPortSettings::BaudRate)rateIndex); } @@ -627,6 +637,8 @@ bool SerialLink::setBaudRate(int rate) disconnect(); switch (rate) { + +#ifndef Q_OS_WIN case 50: portSettings.setBaudRate(QPortSettings::BAUDR_50); break; @@ -645,6 +657,7 @@ bool SerialLink::setBaudRate(int rate) case 200: portSettings.setBaudRate(QPortSettings::BAUDR_200); break; +#endif case 300: portSettings.setBaudRate(QPortSettings::BAUDR_300); break; @@ -654,9 +667,11 @@ bool SerialLink::setBaudRate(int rate) case 1200: portSettings.setBaudRate(QPortSettings::BAUDR_1200); break; +#ifndef Q_OS_WIN case 1800: portSettings.setBaudRate(QPortSettings::BAUDR_1800); break; +#endif case 2400: portSettings.setBaudRate(QPortSettings::BAUDR_2400); break; @@ -685,7 +700,7 @@ bool SerialLink::setBaudRate(int rate) case 57600: portSettings.setBaudRate(QPortSettings::BAUDR_57600); break; -#ifdef Q_OS_WIN +#ifdef Q_OS_WIN_XXXX // FIXME CHECK THIS case 76800: portSettings.setBaudRate(QPortSettings::BAUDR_76800); break; diff --git a/src/libs/opmapcontrol/src/core/point.cpp b/src/libs/opmapcontrol/src/core/point.cpp index 269a20edf..fd12396f4 100644 --- a/src/libs/opmapcontrol/src/core/point.cpp +++ b/src/libs/opmapcontrol/src/core/point.cpp @@ -30,8 +30,8 @@ namespace core { Point::Point(int dw) { - this->x=(short)Point::LOWORD(dw); - this->y=(short)Point::HIWORD(dw); + this->x=(short)Point::loWord(dw); + this->y=(short)Point::hiWord(dw); empty=false; } Point::Point(Size sz) @@ -60,15 +60,6 @@ namespace core { { return !(lhs==rhs); } - int Point::HIWORD(int n) - { - return (n >> 16) & 0xffff; - } - - int Point::LOWORD(int n) - { - return n & 0xffff; - } Point Point::Empty=Point(); } diff --git a/src/libs/opmapcontrol/src/core/point.h b/src/libs/opmapcontrol/src/core/point.h index ed64e55df..b28146043 100644 --- a/src/libs/opmapcontrol/src/core/point.h +++ b/src/libs/opmapcontrol/src/core/point.h @@ -27,7 +27,6 @@ #ifndef OPOINT_H #define OPOINT_H - #include namespace core { @@ -60,8 +59,15 @@ namespace core { { Offset(p.x, p.y); } - static int HIWORD(int n); - static int LOWORD(int n); + static int hiWord(int n) + { + return (n >> 16) & 0xffff; + } + + static int loWord(int n) + { + return n & 0xffff; + } private: int x; diff --git a/src/libs/opmapcontrol/src/core/urlfactory.cpp b/src/libs/opmapcontrol/src/core/urlfactory.cpp index ca250228b..d6d0dc473 100644 --- a/src/libs/opmapcontrol/src/core/urlfactory.cpp +++ b/src/libs/opmapcontrol/src/core/urlfactory.cpp @@ -26,6 +26,7 @@ */ #include "urlfactory.h" #include +#include namespace core { diff --git a/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp b/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp index c10b161c6..f8a37c0be 100644 --- a/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp +++ b/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp @@ -25,6 +25,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "lks94projection.h" +#include @@ -105,7 +106,7 @@ QVector LKS94Projection::DTM10(const QVector & lonlat) double lon = DegreesToRadians(lonlat[0]); double lat = DegreesToRadians(lonlat[1]); - double h = lonlat.count() < 3 ? 0 : std::isnan(lonlat[2]) ? 0 : lonlat[2];//TODO NAN + double h = lonlat.count() < 3 ? 0 : (lonlat[2] != lonlat[2]) ? 0 : lonlat[2];//TODO NAN double v = semiMajor / sqrt(1 - es * pow(sin(lat), 2)); double x = (v + h) * cos(lat) * cos(lon); double y = (v + h) * cos(lat) * sin(lon); @@ -137,7 +138,7 @@ QVector LKS94Projection::MTD10(QVector & pnt) // ... bool AtPole = false; // is location in polar region - double Z = pnt.count() < 3 ? 0 : std::isnan(pnt[2]) ? 0 : pnt[2];//TODO NaN + double Z = pnt.count() < 3 ? 0 : (pnt[2] != pnt[2]) ? 0 : pnt[2];//TODO NaN double lon = 0; double lat = 0; @@ -304,8 +305,8 @@ QVector LKS94Projection::DTM01(QVector & lonlat) double lon = DegreesToRadians(lonlat[0]); double lat = DegreesToRadians(lonlat[1]); - double h = lonlat.count() < 3 ? 0 : std::isnan(lonlat[2]) ? 0 : lonlat[2];//TODO NaN - double v = semiMajor / sqrt(1 - es * pow(sin(lat), 2)); + double h = lonlat.count() < 3 ? 0 : (lonlat[2] != lonlat[2]) ? 0 : lonlat[2];//TODO NaN + double v = semiMajor / sqrt(1 - es * pow(sin(lat), 2.0)); double x = (v + h) * cos(lat) * cos(lon); double y = (v + h) * cos(lat) * sin(lon); double z = ((1 - es) * v + h) * sin(lat); @@ -335,7 +336,7 @@ QVector LKS94Projection::MTD01(QVector & pnt) // ... bool At_Pole = false; // is location in polar region - double Z = pnt.count() < 3 ? 0 : std::isnan(pnt[2]) ? 0 : pnt[2];//TODO NaN + double Z = pnt.count() < 3 ? 0 : (pnt[2] != pnt[2]) ? 0 : pnt[2];//TODO NaN double lon = 0; double lat = 0; diff --git a/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp b/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp index 848b499c4..aa286ca20 100644 --- a/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp +++ b/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp @@ -25,7 +25,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "mercatorprojection.h" - +#include namespace projections { MercatorProjection::MercatorProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177), diff --git a/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp b/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp index ad0b7a1b6..a6a2ba306 100644 --- a/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp +++ b/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp @@ -25,7 +25,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "mercatorprojectionyandex.h" - +#include namespace projections { @@ -45,7 +45,7 @@ Point MercatorProjectionYandex::FromLatLngToPixel(double lat, double lng, const double k = 0.0818191908426; double z = tan(MathPiDiv4 + rLat / 2) / pow((tan(MathPiDiv4 + asin(k * sin(rLat)) / 2)), k); - double z1 = pow(2, 23 - zoom); + double z1 = pow(2.0, 23 - zoom); double DX = ((20037508.342789 + a * rLon) * 53.5865938 / z1); double DY = ((20037508.342789 - a * log(z)) * 53.5865938 / z1); diff --git a/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp b/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp index 29dc7f65d..cdd3dfab3 100644 --- a/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp +++ b/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp @@ -85,7 +85,7 @@ double PlateCarreeProjection::Flattening() const } Size PlateCarreeProjection::GetTileMatrixMaxXY(const int &zoom) { - int y = (int) pow(2, zoom); + int y = (int) pow(2.0f, zoom); return Size((2*y) - 1, y - 1); } diff --git a/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp b/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp index 009c283b2..d1d24c5cc 100644 --- a/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp +++ b/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp @@ -84,7 +84,7 @@ double PlateCarreeProjectionPergo::Flattening() const } Size PlateCarreeProjectionPergo::GetTileMatrixMaxXY(const int &zoom) { - int y = (int) pow(2, zoom); + int y = (int) pow(2.0f, zoom); return Size((2*y) - 1, y - 1); } diff --git a/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/src/libs/opmapcontrol/src/internals/pureprojection.cpp index 56aefafbd..d86bf26ae 100644 --- a/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -25,6 +25,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "pureprojection.h" +#include @@ -38,7 +39,7 @@ const double PureProjection::HALF_PI = (M_PI * 0.5); const double PureProjection::TWO_PI= (M_PI * 2.0); const double PureProjection::EPSLoN= 1.0e-10; const double PureProjection::MAX_VAL= 4; -const double PureProjection::MAXLONG= 2147483647; +const double PureProjection::maxLong= 2147483647; const double PureProjection::DBLLONG= 4.61168601e18; const double PureProjection::R2D=180/M_PI; const double PureProjection::D2R=M_PI/180; @@ -128,17 +129,17 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) x = x - (Sign(x) * TWO_PI); else - if(((qlonglong) qAbs(x / TWO_PI)) < MAXLONG) + if(((qlonglong) qAbs(x / TWO_PI)) < maxLong) { x = x - (((qlonglong) (x / TWO_PI)) * TWO_PI); } else - if(((qlonglong) qAbs(x / (MAXLONG * TWO_PI))) < MAXLONG) + if(((qlonglong) qAbs(x / (maxLong * TWO_PI))) < maxLong) { - x = x - (((qlonglong) (x / (MAXLONG * TWO_PI))) * (TWO_PI * MAXLONG)); + x = x - (((qlonglong) (x / (maxLong * TWO_PI))) * (TWO_PI * maxLong)); } else - if(((qlonglong) qAbs(x / (DBLLONG * TWO_PI))) < MAXLONG) + if(((qlonglong) qAbs(x / (DBLLONG * TWO_PI))) < maxLong) { x = x - (((qlonglong) (x / (DBLLONG * TWO_PI))) * (TWO_PI * DBLLONG)); } diff --git a/src/libs/opmapcontrol/src/internals/pureprojection.h b/src/libs/opmapcontrol/src/internals/pureprojection.h index 5b600fc5a..77f795d31 100644 --- a/src/libs/opmapcontrol/src/internals/pureprojection.h +++ b/src/libs/opmapcontrol/src/internals/pureprojection.h @@ -88,7 +88,7 @@ protected: static const double TWO_PI; static const double EPSLoN; static const double MAX_VAL; - static const double MAXLONG; + static const double maxLong; static const double DBLLONG; static const double R2D; static const double D2R; diff --git a/src/libs/opmapcontrol/src/internals/rectlatlng.h b/src/libs/opmapcontrol/src/internals/rectlatlng.h index bdf256f59..a951cf1e6 100644 --- a/src/libs/opmapcontrol/src/internals/rectlatlng.h +++ b/src/libs/opmapcontrol/src/internals/rectlatlng.h @@ -203,11 +203,11 @@ public: } static RectLatLng Intersect(RectLatLng const& a, RectLatLng const& b) { - double lng = std::max(a.Lng(), b.Lng()); - double num2 = std::min((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); + double lng = qMax(a.Lng(), b.Lng()); + double num2 = qMin((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); - double lat = std::max(a.Lat(), b.Lat()); - double num4 = std::min((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); + double lat = qMax(a.Lat(), b.Lat()); + double num4 = qMin((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); if((num2 >= lng) && (num4 >= lat)) { @@ -222,10 +222,10 @@ public: static RectLatLng Union(RectLatLng const& a, RectLatLng const& b) { - double lng = std::min(a.Lng(), b.Lng()); - double num2 = std::max((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); - double lat = std::min(a.Lat(), b.Lat()); - double num4 = std::max((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); + double lng = qMin(a.Lng(), b.Lng()); + double num2 = qMax((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); + double lat = qMin(a.Lat(), b.Lat()); + double num4 = qMax((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); return RectLatLng(lng, lat, num2 - lng, num4 - lat); } void Offset(PointLatLng const& pos) diff --git a/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp b/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp index aeb9055c3..c13a1f50a 100644 --- a/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp +++ b/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp @@ -210,7 +210,7 @@ namespace mapcontrol double GPSItem::Distance3D(const internals::PointLatLng &coord, const int &altitude) { return sqrt(pow(internals::PureProjection::DistanceBetweenLatLng(this->coord,coord)*1000,2)+ - pow(this->altitude-altitude,2)); + pow(static_cast(this->altitude-altitude),2)); } void GPSItem::SetUavPic(QString UAVPic) diff --git a/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 9dbea84e4..84620ad22 100644 --- a/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -211,7 +211,7 @@ namespace mapcontrol double UAVItem::Distance3D(const internals::PointLatLng &coord, const int &altitude) { return sqrt(pow(internals::PureProjection::DistanceBetweenLatLng(this->coord,coord)*1000,2)+ - pow(this->altitude-altitude,2)); + pow(static_cast(this->altitude-altitude),2)); } void UAVItem::SetUavPic(QString UAVPic) { diff --git a/src/libs/utils/coordinateconversions.cpp b/src/libs/utils/coordinateconversions.cpp index ba67d8ab5..19c5dc2b0 100644 --- a/src/libs/utils/coordinateconversions.cpp +++ b/src/libs/utils/coordinateconversions.cpp @@ -31,6 +31,7 @@ #include #include #include +#include #define RAD2DEG (180.0/M_PI) #define DEG2RAD (M_PI/180.0) diff --git a/src/libs/utils/qtcolorbutton.cpp b/src/libs/utils/qtcolorbutton.cpp index aab8d71c0..730a0b6db 100644 --- a/src/libs/utils/qtcolorbutton.cpp +++ b/src/libs/utils/qtcolorbutton.cpp @@ -282,4 +282,4 @@ void QtColorButton::dropEvent(QDropEvent *event) } // namespace Utils -#include "moc_qtcolorbutton.cpp" +//#include "moc_qtcolorbutton.cpp" diff --git a/src/libs/utils/utils_external.pri b/src/libs/utils/utils_external.pri index 07c09feda..7c7a85cb6 100644 --- a/src/libs/utils/utils_external.pri +++ b/src/libs/utils/utils_external.pri @@ -12,48 +12,49 @@ DEFINES += EXTERNAL_USE DEFINES += QTCREATOR_UTILS_LIB +# submiteditorwidget.h \ + # Input -HEADERS += abstractprocess.h \ - basevalidatinglineedit.h \ - checkablemessagebox.h \ - classnamevalidatinglineedit.h \ - codegeneration.h \ - consoleprocess.h \ - coordinateconversions.h \ - detailsbutton.h \ - detailswidget.h \ - fancylineedit.h \ - fancymainwindow.h \ - filenamevalidatinglineedit.h \ - filesearch.h \ - filewizarddialog.h \ - filewizardpage.h \ - homelocationutil.h \ - iwelcomepage.h \ - linecolumnlabel.h \ - listutils.h \ - newclasswidget.h \ - parameteraction.h \ - pathchooser.h \ - pathlisteditor.h \ - pathutils.h \ - projectintropage.h \ - projectnamevalidatinglineedit.h \ - qtcassert.h \ - qtcolorbutton.h \ - reloadpromptutils.h \ - savedaction.h \ - settingsutils.h \ - styledbar.h \ - stylehelper.h \ - submiteditorwidget.h \ - submitfieldwidget.h \ - synchronousprocess.h \ - treewidgetcolumnstretcher.h \ - uncommentselection.h \ - utils_global.h \ - welcomemodetreewidget.h \ - worldmagmodel.h \ +HEADERS += utils_global.h \ + reloadpromptutils.h \ + settingsutils.h \ + filesearch.h \ + listutils.h \ + pathchooser.h \ + pathlisteditor.h \ + filewizardpage.h \ + filewizarddialog.h \ + projectintropage.h \ + basevalidatinglineedit.h \ + filenamevalidatinglineedit.h \ + projectnamevalidatinglineedit.h \ + codegeneration.h \ + newclasswidget.h \ + classnamevalidatinglineedit.h \ + linecolumnlabel.h \ + fancylineedit.h \ + qtcolorbutton.h \ + savedaction.h \ + abstractprocess.h \ + consoleprocess.h \ + synchronousprocess.h \ + submitfieldwidget.h \ + uncommentselection.h \ + parameteraction.h \ + treewidgetcolumnstretcher.h \ + checkablemessagebox.h \ + qtcassert.h \ + styledbar.h \ + stylehelper.h \ + welcomemodetreewidget.h \ + iwelcomepage.h \ + fancymainwindow.h \ + detailsbutton.h \ + detailswidget.h \ + coordinateconversions.h \ + pathutils.h \ + worldmagmodel.h \ + homelocationutil.h \ xmlconfig.h win32 { @@ -80,42 +81,43 @@ linux-g++ { SOURCES += consoleprocess_unix.cpp } -SOURCES += basevalidatinglineedit.cpp \ - checkablemessagebox.cpp \ - classnamevalidatinglineedit.cpp \ - codegeneration.cpp \ - consoleprocess.cpp \ - coordinateconversions.cpp \ - detailsbutton.cpp \ - detailswidget.cpp \ - fancylineedit.cpp \ - fancymainwindow.cpp \ - filenamevalidatinglineedit.cpp \ - filesearch.cpp \ - filewizarddialog.cpp \ - filewizardpage.cpp \ - homelocationutil.cpp \ - iwelcomepage.cpp \ - linecolumnlabel.cpp \ - newclasswidget.cpp \ - parameteraction.cpp \ - pathchooser.cpp \ - pathlisteditor.cpp \ - pathutils.cpp \ - projectintropage.cpp \ - projectnamevalidatinglineedit.cpp \ - qtcolorbutton.cpp \ - reloadpromptutils.cpp \ - savedaction.cpp \ - settingsutils.cpp \ - styledbar.cpp \ - stylehelper.cpp \ - submiteditorwidget.cpp \ - submitfieldwidget.cpp \ - synchronousprocess.cpp \ - treewidgetcolumnstretcher.cpp \ - uncommentselection.cpp \ - welcomemodetreewidget.cpp \ - worldmagmodel.cpp \ +# submiteditorwidget.cpp \ + +SOURCES += reloadpromptutils.cpp \ + settingsutils.cpp \ + filesearch.cpp \ + pathchooser.cpp \ + pathlisteditor.cpp \ + filewizardpage.cpp \ + filewizarddialog.cpp \ + projectintropage.cpp \ + basevalidatinglineedit.cpp \ + filenamevalidatinglineedit.cpp \ + projectnamevalidatinglineedit.cpp \ + codegeneration.cpp \ + newclasswidget.cpp \ + classnamevalidatinglineedit.cpp \ + linecolumnlabel.cpp \ + fancylineedit.cpp \ + qtcolorbutton.cpp \ + savedaction.cpp \ + synchronousprocess.cpp \ + submitfieldwidget.cpp \ + consoleprocess.cpp \ + uncommentselection.cpp \ + parameteraction.cpp \ + treewidgetcolumnstretcher.cpp \ + checkablemessagebox.cpp \ + styledbar.cpp \ + stylehelper.cpp \ + welcomemodetreewidget.cpp \ + iwelcomepage.cpp \ + fancymainwindow.cpp \ + detailsbutton.cpp \ + detailswidget.cpp \ + coordinateconversions.cpp \ + pathutils.cpp \ + worldmagmodel.cpp \ + homelocationutil.cpp \ xmlconfig.cpp RESOURCES += utils.qrc diff --git a/src/libs/utils/worldmagmodel.cpp b/src/libs/utils/worldmagmodel.cpp index ce8201ece..fe969dc0e 100644 --- a/src/libs/utils/worldmagmodel.cpp +++ b/src/libs/utils/worldmagmodel.cpp @@ -48,6 +48,7 @@ #include #include #include +#include #define RAD2DEG(rad) ((rad) * (180.0 / M_PI)) #define DEG2RAD(deg) ((deg) * (M_PI / 180.0)) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 679ab0fb4..f989e709c 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1383,6 +1383,8 @@ QImage UAS::getImage() imagePacketsArrived = 0; //imageRecBuffer.clear(); return image; +#else + return QImage(); #endif } diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc index f43b08708..16094222d 100644 --- a/src/uas/UASManager.cc +++ b/src/uas/UASManager.cc @@ -76,7 +76,8 @@ void UASManager::loadSettings() bool UASManager::setHomePosition(double lat, double lon, double alt) { // Checking for NaN and infitiny - if (lat == lat && lon == lon && alt == alt && !std::isinf(lat) && !std::isinf(lon) && !std::isinf(alt) + // FIXME does not work with MSVC: && !std::isinf(lat) && !std::isinf(lon) && !std::isinf(alt) + if (lat == lat && lon == lon && alt == alt && lat <= 90.0 && lat >= -90.0 && lon <= 180.0 && lon >= -180.0) { bool changed = false; diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index d48841280..27f40b849 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -40,11 +40,13 @@ This file is part of the QGROUNDCONTROL project #include "QGC.h" #include "Waypoint.h" #include "UASWaypointManager.h" +#include //#include "Waypoint2DIcon.h" //#include "MAV2DIcon.h" #include + HSIDisplay::HSIDisplay(QWidget *parent) : HDDisplay(NULL, "HSI", parent), gpsSatellites(), diff --git a/src/ui/SerialConfigurationWindow.cc b/src/ui/SerialConfigurationWindow.cc index 60d186f20..f9121c98b 100644 --- a/src/ui/SerialConfigurationWindow.cc +++ b/src/ui/SerialConfigurationWindow.cc @@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project #include #include #ifdef _WIN32 -#include +#include #endif #if defined (__APPLE__) && defined (__MACH__) #include diff --git a/src/ui/mavlink/QGCMAVLinkTextEdit.cc b/src/ui/mavlink/QGCMAVLinkTextEdit.cc index 89721e0b2..f3f2172c7 100644 --- a/src/ui/mavlink/QGCMAVLinkTextEdit.cc +++ b/src/ui/mavlink/QGCMAVLinkTextEdit.cc @@ -75,10 +75,12 @@ bool QGCMAVLinkTextEdit::syntaxcheck() QMessageBox::information(0, tr("XML not found!"),tr("Null size xml document!")); error = true; } + return error; } void QGCMAVLinkTextEdit::contextMenuEvent ( QContextMenuEvent * e ) { + Q_UNUSED(e); QMenu *RContext = createOwnStandardContextMenu(); RContext->exec(QCursor::pos()); delete RContext; -- 2.22.0