From 4536782428a30527de1d3e7fc6fcd1018a9cc3ee Mon Sep 17 00:00:00 2001 From: ephy Date: Sun, 8 Aug 2010 06:45:16 +0000 Subject: [PATCH] GCS: Cleanup to allow -pedantic compile flag and changes to reduce the noise that it generates. git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@1243 ebee16cc-31ac-478f-84a7-5cbb03baadba --- .../src/libs/extensionsystem/pluginview.cpp | 2 +- ground/src/libs/glc_lib/PQP/PQP.cpp | 2 +- .../src/libs/glc_lib/geometry/glc_geomtools.h | 2 +- ground/src/libs/glc_lib/glc_enum.h | 2 +- ground/src/libs/glc_lib/glc_ext.h | 2 +- .../install/include/GLC_lib/glc_enum.h | 2 +- .../glc_lib/install/include/GLC_lib/glc_ext.h | 2 +- .../include/GLC_lib/maths/glc_utils_maths.h | 2 +- .../include/GLC_lib/maths/glc_vector4d.h | 2 +- ground/src/libs/glc_lib/lib3ds/mesh.h | 2 +- .../src/libs/glc_lib/maths/glc_utils_maths.h | 2 +- ground/src/libs/glc_lib/maths/glc_vector4d.h | 2 +- .../libs/libqxt/src/core/qxtcommandoptions.h | 4 +-- .../libs/libqxt/src/core/qxtserialdevice.h | 4 +-- .../libs/opmapcontrol/src/core/accessmode.h | 2 +- .../opmapcontrol/src/core/geodecoderstatus.h | 2 +- .../libs/opmapcontrol/src/core/languagetype.h | 2 +- .../src/libs/opmapcontrol/src/core/maptype.h | 2 +- .../libs/opmapcontrol/src/core/urlfactory.cpp | 3 ++ .../libs/opmapcontrol/src/core/urlfactory.h | 2 +- .../src/internals/mousewheelzoomtype.h | 2 +- .../src/internals/pureprojection.cpp | 11 ++++++++ .../src/internals/pureprojection.h | 18 ++++++------ ground/src/libs/qwt/src/qwt.h | 2 +- ground/src/libs/qymodem/src/qymodem.h | 2 +- .../libs/uavobjgenerator/uavobjectparser.cpp | 12 +++++--- .../coreplugin/dialogs/shortcutsettings.cpp | 2 +- .../src/plugins/coreplugin/mimedatabase.cpp | 8 +++--- ground/src/plugins/hitl/flightgearbridge.cpp | 4 +++ ground/src/plugins/hitl/flightgearbridge.h | 6 ++-- ground/src/plugins/hitlil2/il2bridge.cpp | 15 ++++++++++ ground/src/plugins/hitlil2/il2bridge.h | 28 +++++++++---------- 32 files changed, 96 insertions(+), 59 deletions(-) diff --git a/ground/src/libs/extensionsystem/pluginview.cpp b/ground/src/libs/extensionsystem/pluginview.cpp index b43c492f2..4fe0decef 100644 --- a/ground/src/libs/extensionsystem/pluginview.cpp +++ b/ground/src/libs/extensionsystem/pluginview.cpp @@ -63,7 +63,7 @@ using namespace ExtensionSystem; -Q_DECLARE_METATYPE(ExtensionSystem::PluginSpec*); +Q_DECLARE_METATYPE(ExtensionSystem::PluginSpec*) /*! \fn PluginView::PluginView(PluginManager *manager, QWidget *parent) diff --git a/ground/src/libs/glc_lib/PQP/PQP.cpp b/ground/src/libs/glc_lib/PQP/PQP.cpp index 542e003bc..0247542c5 100755 --- a/ground/src/libs/glc_lib/PQP/PQP.cpp +++ b/ground/src/libs/glc_lib/PQP/PQP.cpp @@ -250,7 +250,7 @@ PQP_Model::MemUsage(int msg) if (msg) { - fprintf(stderr,"Total for model %p: %d bytes\n", this, total_mem); + fprintf(stderr,"Total for model %p: %d bytes\n", (void*)this, total_mem); fprintf(stderr,"BVs: %d alloced, take %d bytes each\n", num_bvs, sizeof(BV)); fprintf(stderr,"Tris: %d alloced, take %d bytes each\n", diff --git a/ground/src/libs/glc_lib/geometry/glc_geomtools.h b/ground/src/libs/glc_lib/geometry/glc_geomtools.h index 3268723a1..a02143a49 100755 --- a/ground/src/libs/glc_lib/geometry/glc_geomtools.h +++ b/ground/src/libs/glc_lib/geometry/glc_geomtools.h @@ -80,6 +80,6 @@ namespace glc //@} -}; +} #endif /*GLC_GEOMTOOLS_H_*/ diff --git a/ground/src/libs/glc_lib/glc_enum.h b/ground/src/libs/glc_lib/glc_enum.h index ffe3b29ea..2731877c3 100755 --- a/ground/src/libs/glc_lib/glc_enum.h +++ b/ground/src/libs/glc_lib/glc_enum.h @@ -49,7 +49,7 @@ namespace glc extern QMutex iDMutex; extern QMutex geomIdMutex; extern QMutex userIdMutex; -}; +} // GLC_Lib version diff --git a/ground/src/libs/glc_lib/glc_ext.h b/ground/src/libs/glc_lib/glc_ext.h index 12ed9b679..2c9e33159 100755 --- a/ground/src/libs/glc_lib/glc_ext.h +++ b/ground/src/libs/glc_lib/glc_ext.h @@ -83,5 +83,5 @@ namespace glc //! Load Point Sprite extension bool loadPointSpriteExtension(); -}; +} #endif /*GLC_EXT_H_*/ diff --git a/ground/src/libs/glc_lib/install/include/GLC_lib/glc_enum.h b/ground/src/libs/glc_lib/install/include/GLC_lib/glc_enum.h index ffe3b29ea..2731877c3 100755 --- a/ground/src/libs/glc_lib/install/include/GLC_lib/glc_enum.h +++ b/ground/src/libs/glc_lib/install/include/GLC_lib/glc_enum.h @@ -49,7 +49,7 @@ namespace glc extern QMutex iDMutex; extern QMutex geomIdMutex; extern QMutex userIdMutex; -}; +} // GLC_Lib version diff --git a/ground/src/libs/glc_lib/install/include/GLC_lib/glc_ext.h b/ground/src/libs/glc_lib/install/include/GLC_lib/glc_ext.h index 12ed9b679..2c9e33159 100755 --- a/ground/src/libs/glc_lib/install/include/GLC_lib/glc_ext.h +++ b/ground/src/libs/glc_lib/install/include/GLC_lib/glc_ext.h @@ -83,5 +83,5 @@ namespace glc //! Load Point Sprite extension bool loadPointSpriteExtension(); -}; +} #endif /*GLC_EXT_H_*/ diff --git a/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_utils_maths.h b/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_utils_maths.h index 737324716..c1465e721 100755 --- a/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_utils_maths.h +++ b/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_utils_maths.h @@ -39,6 +39,6 @@ namespace glc /*! \def PI * \brief Define the magic number PI */ const double PI= acos(-1.0); -}; +} #endif /*GLC_UTILS_MATHS_H_*/ diff --git a/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_vector4d.h b/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_vector4d.h index 9cf2a3774..95836036f 100755 --- a/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_vector4d.h +++ b/ground/src/libs/glc_lib/install/include/GLC_lib/maths/glc_vector4d.h @@ -397,7 +397,7 @@ namespace glc /*! \var Z_AXIS * \brief Z axis Vector*/ const GLC_Vector4d Z_AXIS(0.0, 0.0, 1.0); -}; +} //! Define GLC_Point4D typedef GLC_Vector4d GLC_Point4d; diff --git a/ground/src/libs/glc_lib/lib3ds/mesh.h b/ground/src/libs/glc_lib/lib3ds/mesh.h index dd75399cc..ceaae5811 100755 --- a/ground/src/libs/glc_lib/lib3ds/mesh.h +++ b/ground/src/libs/glc_lib/lib3ds/mesh.h @@ -70,7 +70,7 @@ typedef enum { /* Bit 11-12: Unused ? */ LIB3DS_FACE_FLAG_SELECT_3 = (1<<13), /*!< Bit 13: Selection of the face in selection 3*/ LIB3DS_FACE_FLAG_SELECT_2 = (1<<14), /*!< Bit 14: Selection of the face in selection 2*/ - LIB3DS_FACE_FLAG_SELECT_1 = (1<<15), /*!< Bit 15: Selection of the face in selection 1*/ + LIB3DS_FACE_FLAG_SELECT_1 = (1<<15) /*!< Bit 15: Selection of the face in selection 1*/ } Lib3dsFaceFlag; /** diff --git a/ground/src/libs/glc_lib/maths/glc_utils_maths.h b/ground/src/libs/glc_lib/maths/glc_utils_maths.h index 737324716..c1465e721 100755 --- a/ground/src/libs/glc_lib/maths/glc_utils_maths.h +++ b/ground/src/libs/glc_lib/maths/glc_utils_maths.h @@ -39,6 +39,6 @@ namespace glc /*! \def PI * \brief Define the magic number PI */ const double PI= acos(-1.0); -}; +} #endif /*GLC_UTILS_MATHS_H_*/ diff --git a/ground/src/libs/glc_lib/maths/glc_vector4d.h b/ground/src/libs/glc_lib/maths/glc_vector4d.h index 9cf2a3774..95836036f 100755 --- a/ground/src/libs/glc_lib/maths/glc_vector4d.h +++ b/ground/src/libs/glc_lib/maths/glc_vector4d.h @@ -397,7 +397,7 @@ namespace glc /*! \var Z_AXIS * \brief Z axis Vector*/ const GLC_Vector4d Z_AXIS(0.0, 0.0, 1.0); -}; +} //! Define GLC_Point4D typedef GLC_Vector4d GLC_Point4d; diff --git a/ground/src/libs/libqxt/src/core/qxtcommandoptions.h b/ground/src/libs/libqxt/src/core/qxtcommandoptions.h index 2b034e3fe..947c9602d 100644 --- a/ground/src/libs/libqxt/src/core/qxtcommandoptions.h +++ b/ground/src/libs/libqxt/src/core/qxtcommandoptions.h @@ -32,8 +32,8 @@ #include #include class QxtCommandOptionsPrivate; -QT_FORWARD_DECLARE_CLASS(QTextStream); -QT_FORWARD_DECLARE_CLASS(QIODevice); +QT_FORWARD_DECLARE_CLASS(QTextStream) +QT_FORWARD_DECLARE_CLASS(QIODevice) class QXT_CORE_EXPORT QxtCommandOptions diff --git a/ground/src/libs/libqxt/src/core/qxtserialdevice.h b/ground/src/libs/libqxt/src/core/qxtserialdevice.h index 07c6b9ba7..61d83c6b8 100644 --- a/ground/src/libs/libqxt/src/core/qxtserialdevice.h +++ b/ground/src/libs/libqxt/src/core/qxtserialdevice.h @@ -56,7 +56,7 @@ public: Stop2 = 128, StopMask = 128 }; - Q_DECLARE_FLAGS(PortSettings, PortSetting); + Q_DECLARE_FLAGS(PortSettings, PortSetting) explicit QxtSerialDevice(const QString& device, QObject* parent = 0); QxtSerialDevice(QObject* parent = 0); @@ -91,6 +91,6 @@ private: QXT_DECLARE_PRIVATE(QxtSerialDevice) }; -Q_DECLARE_OPERATORS_FOR_FLAGS(QxtSerialDevice::PortSettings); +Q_DECLARE_OPERATORS_FOR_FLAGS(QxtSerialDevice::PortSettings) #endif diff --git a/ground/src/libs/opmapcontrol/src/core/accessmode.h b/ground/src/libs/opmapcontrol/src/core/accessmode.h index 1412006dc..d152936f2 100644 --- a/ground/src/libs/opmapcontrol/src/core/accessmode.h +++ b/ground/src/libs/opmapcontrol/src/core/accessmode.h @@ -53,7 +53,7 @@ namespace core { /// /// access only cache /// - CacheOnly, + CacheOnly }; static QString StrByType(Types const& value) { diff --git a/ground/src/libs/opmapcontrol/src/core/geodecoderstatus.h b/ground/src/libs/opmapcontrol/src/core/geodecoderstatus.h index 1c7184c56..58b653dee 100644 --- a/ground/src/libs/opmapcontrol/src/core/geodecoderstatus.h +++ b/ground/src/libs/opmapcontrol/src/core/geodecoderstatus.h @@ -97,7 +97,7 @@ namespace core { /// The given key has gone over the requests limit in the 24 hour period or has submitted too many requests in too short a period of time. /// If you're sending multiple requests in parallel or in a tight loop, use a timer or pause in your code to make sure you don't send the requests too quickly. /// - G_GEO_TOO_MANY_QUERIES=620, + G_GEO_TOO_MANY_QUERIES=620 }; static QString StrByType(Types const& value) diff --git a/ground/src/libs/opmapcontrol/src/core/languagetype.h b/ground/src/libs/opmapcontrol/src/core/languagetype.h index e511a3a52..4b8411e45 100644 --- a/ground/src/libs/opmapcontrol/src/core/languagetype.h +++ b/ground/src/libs/opmapcontrol/src/core/languagetype.h @@ -94,7 +94,7 @@ namespace core { Ukrainian, Vietnamese, ChineseSimplified, - ChineseTraditional, + ChineseTraditional }; static QString StrByType(Types const& value) diff --git a/ground/src/libs/opmapcontrol/src/core/maptype.h b/ground/src/libs/opmapcontrol/src/core/maptype.h index 5c9a27ee6..741832abc 100644 --- a/ground/src/libs/opmapcontrol/src/core/maptype.h +++ b/ground/src/libs/opmapcontrol/src/core/maptype.h @@ -96,7 +96,7 @@ namespace core { GoogleLabelsKorea=4003, GoogleHybridKorea=4005, - YandexMapRu = 5000, + YandexMapRu = 5000 }; static QString StrByType(Types const& value) { diff --git a/ground/src/libs/opmapcontrol/src/core/urlfactory.cpp b/ground/src/libs/opmapcontrol/src/core/urlfactory.cpp index e36e27671..07eb3664a 100644 --- a/ground/src/libs/opmapcontrol/src/core/urlfactory.cpp +++ b/ground/src/libs/opmapcontrol/src/core/urlfactory.cpp @@ -28,6 +28,9 @@ namespace core { + +const double UrlFactory::EarthRadiusKm = 6378.137; // WGS-84 + UrlFactory::UrlFactory() { /// diff --git a/ground/src/libs/opmapcontrol/src/core/urlfactory.h b/ground/src/libs/opmapcontrol/src/core/urlfactory.h index 760459b64..e886a5410 100644 --- a/ground/src/libs/opmapcontrol/src/core/urlfactory.h +++ b/ground/src/libs/opmapcontrol/src/core/urlfactory.h @@ -69,7 +69,7 @@ namespace core { bool CorrectGoogleVersions; bool UseGeocoderCache; //TODO GetSet bool UsePlacemarkCache;//TODO GetSet - static const double EarthRadiusKm = 6378.137; // WGS-84 + static const double EarthRadiusKm; double GetDistance(internals::PointLatLng p1,internals::PointLatLng p2); protected: diff --git a/ground/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h b/ground/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h index 26d80c758..218815c36 100644 --- a/ground/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h +++ b/ground/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h @@ -53,7 +53,7 @@ namespace internals { /// /// zooms map to current view center /// - ViewCenter, + ViewCenter }; static QString StrByType(Types const& value) { diff --git a/ground/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/src/libs/opmapcontrol/src/internals/pureprojection.cpp index b60e61e3d..e19f33f11 100644 --- a/ground/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -32,6 +32,17 @@ namespace internals { + +const double PureProjection::PI = M_PI; +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::DBLLONG= 4.61168601e18; +const double PureProjection::R2D=180/M_PI; +const double PureProjection::D2R=M_PI/180; + Point PureProjection::FromLatLngToPixel(const PointLatLng::PointLatLng &p,const int &zoom) { return FromLatLngToPixel(p.Lat(), p.Lng(), zoom); diff --git a/ground/src/libs/opmapcontrol/src/internals/pureprojection.h b/ground/src/libs/opmapcontrol/src/internals/pureprojection.h index 322e6b45c..4ab806a62 100644 --- a/ground/src/libs/opmapcontrol/src/internals/pureprojection.h +++ b/ground/src/libs/opmapcontrol/src/internals/pureprojection.h @@ -83,15 +83,15 @@ public: protected: - static const double PI = M_PI; - static const double HALF_PI = (M_PI * 0.5); - static const double TWO_PI= (M_PI * 2.0); - static const double EPSLoN= 1.0e-10; - static const double MAX_VAL= 4; - static const double MAXLONG= 2147483647; - static const double DBLLONG= 4.61168601e18; - static const double R2D=180/M_PI; - static const double D2R=M_PI/180; + static const double PI; + static const double HALF_PI; + static const double TWO_PI; + static const double EPSLoN; + static const double MAX_VAL; + static const double MAXLONG; + static const double DBLLONG; + static const double R2D; + static const double D2R; static double Sign(const double &x); diff --git a/ground/src/libs/qwt/src/qwt.h b/ground/src/libs/qwt/src/qwt.h index 1140d7729..394bbb2bf 100644 --- a/ground/src/libs/qwt/src/qwt.h +++ b/ground/src/libs/qwt/src/qwt.h @@ -17,6 +17,6 @@ */ namespace Qwt { -}; +} #endif diff --git a/ground/src/libs/qymodem/src/qymodem.h b/ground/src/libs/qymodem/src/qymodem.h index b11f5c452..de538b6b5 100644 --- a/ground/src/libs/qymodem/src/qymodem.h +++ b/ground/src/libs/qymodem/src/qymodem.h @@ -137,7 +137,7 @@ protected: enum Error { ErrorTimeout = -200, /**< Timed out trying to communicate with other device */ - ErrorBlockRetriesExceded = -201, /**< A block could not be sent */ + ErrorBlockRetriesExceded = -201 /**< A block could not be sent */ }; diff --git a/ground/src/libs/uavobjgenerator/uavobjectparser.cpp b/ground/src/libs/uavobjgenerator/uavobjectparser.cpp index 6a32b4b73..1b6ab6cfa 100644 --- a/ground/src/libs/uavobjgenerator/uavobjectparser.cpp +++ b/ground/src/libs/uavobjgenerator/uavobjectparser.cpp @@ -699,7 +699,8 @@ bool UAVObjectParser::generateFlightObject(int objIndex, const QString& template QStringList options = info->fields[n]->options; for (int m = 0; m < options.length(); ++m) { - enums.append( QString("%1_%2_%3=%4, ") + QString s = (m == (options.length()-1)) ? "%1_%2_%3=%4" : "%1_%2_%3=%4, "; + enums.append( s .arg( info->name.toUpper() ) .arg( info->fields[n]->name.toUpper() ) .arg( options[m].toUpper() ) @@ -719,7 +720,8 @@ bool UAVObjectParser::generateFlightObject(int objIndex, const QString& template QStringList elemNames = info->fields[n]->elementNames; for (int m = 0; m < elemNames.length(); ++m) { - enums.append( QString("%1_%2_%3=%4, ") + QString s = (m != (elemNames.length()-1)) ? "%1_%2_%3=%4, " : "%1_%2_%3=%4"; + enums.append( s .arg( info->name.toUpper() ) .arg( info->fields[n]->name.toUpper() ) .arg( elemNames[m].toUpper() ) @@ -903,7 +905,8 @@ bool UAVObjectParser::generateGCSObject(int objIndex, const QString& templateInc QStringList options = info->fields[n]->options; for (int m = 0; m < options.length(); ++m) { - enums.append( QString("%1_%2=%3, ") + QString s = (m != (options.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s .arg( info->fields[n]->name.toUpper() ) .arg( options[m].toUpper() ) .arg(m) ); @@ -921,7 +924,8 @@ bool UAVObjectParser::generateGCSObject(int objIndex, const QString& templateInc QStringList elemNames = info->fields[n]->elementNames; for (int m = 0; m < elemNames.length(); ++m) { - enums.append( QString("%1_%2=%3, ") + QString s = (m != (elemNames.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s .arg( info->fields[n]->name.toUpper() ) .arg( elemNames[m].toUpper() ) .arg(m) ); diff --git a/ground/src/plugins/coreplugin/dialogs/shortcutsettings.cpp b/ground/src/plugins/coreplugin/dialogs/shortcutsettings.cpp index e0b8ed535..dba385ccd 100644 --- a/ground/src/plugins/coreplugin/dialogs/shortcutsettings.cpp +++ b/ground/src/plugins/coreplugin/dialogs/shortcutsettings.cpp @@ -44,7 +44,7 @@ #include #include -Q_DECLARE_METATYPE(Core::Internal::ShortcutItem*); +Q_DECLARE_METATYPE(Core::Internal::ShortcutItem*) using namespace Core; using namespace Core::Internal; diff --git a/ground/src/plugins/coreplugin/mimedatabase.cpp b/ground/src/plugins/coreplugin/mimedatabase.cpp index 6b19e3cfb..4f55a9e3e 100644 --- a/ground/src/plugins/coreplugin/mimedatabase.cpp +++ b/ground/src/plugins/coreplugin/mimedatabase.cpp @@ -100,7 +100,7 @@ namespace Internal { // and read while checking). class FileMatchContext { - Q_DISABLE_COPY(FileMatchContext); + Q_DISABLE_COPY(FileMatchContext) public: // Max data to be read from a file enum { MaxData = 2048 }; @@ -151,7 +151,7 @@ QByteArray FileMatchContext::data() // The binary fallback matcher for "application/octet-stream". class BinaryMatcher : public IMagicMatcher { - Q_DISABLE_COPY(BinaryMatcher); + Q_DISABLE_COPY(BinaryMatcher) public: BinaryMatcher() {} virtual bool matches(const QByteArray & /*data*/) const { return true; } @@ -161,7 +161,7 @@ public: // A heuristic text file matcher: If the data do not contain any character // below tab (9), detect as text. class HeuristicTextMagicMatcher : public IMagicMatcher { - Q_DISABLE_COPY(HeuristicTextMagicMatcher); + Q_DISABLE_COPY(HeuristicTextMagicMatcher) public: HeuristicTextMagicMatcher() {} virtual bool matches(const QByteArray &data) const; @@ -539,7 +539,7 @@ namespace Internal { // MimeDatabase helpers: Generic parser for a sequence of . // Calls abstract handler function process for MimeType it finds. class BaseMimeTypeParser { - Q_DISABLE_COPY(BaseMimeTypeParser); + Q_DISABLE_COPY(BaseMimeTypeParser) public: BaseMimeTypeParser(); virtual ~BaseMimeTypeParser() {} diff --git a/ground/src/plugins/hitl/flightgearbridge.cpp b/ground/src/plugins/hitl/flightgearbridge.cpp index c055eafd2..64e5a4e61 100644 --- a/ground/src/plugins/hitl/flightgearbridge.cpp +++ b/ground/src/plugins/hitl/flightgearbridge.cpp @@ -30,6 +30,10 @@ #include "coreplugin/icore.h" #include "coreplugin/threadmanager.h" +const float FlightGearBridge::FT2M = 0.3048; +const float FlightGearBridge::KT2MPS = 0.514444444; +const float FlightGearBridge::INHG2KPA = 3.386; + FlightGearBridge::FlightGearBridge() { // move to thread diff --git a/ground/src/plugins/hitl/flightgearbridge.h b/ground/src/plugins/hitl/flightgearbridge.h index ca6b0ea4d..b5663669a 100644 --- a/ground/src/plugins/hitl/flightgearbridge.h +++ b/ground/src/plugins/hitl/flightgearbridge.h @@ -68,9 +68,9 @@ private slots: void telStatsUpdated(UAVObject* obj); private: - static const float FT2M = 0.3048; - static const float KT2MPS = 0.514444444; - static const float INHG2KPA = 3.386; + static const float FT2M; + static const float KT2MPS; + static const float INHG2KPA; QUdpSocket* inSocket; QUdpSocket* outSocket; diff --git a/ground/src/plugins/hitlil2/il2bridge.cpp b/ground/src/plugins/hitlil2/il2bridge.cpp index a1e6f7e4f..247892871 100644 --- a/ground/src/plugins/hitlil2/il2bridge.cpp +++ b/ground/src/plugins/hitlil2/il2bridge.cpp @@ -65,6 +65,21 @@ #include #include +const float Il2Bridge::FT2M = 0.3048; +const float Il2Bridge::KT2MPS = 0.514444444; +const float Il2Bridge::MPS2KMH = 3.6; +const float Il2Bridge::KMH2MPS = (1.0/3.6); +const float Il2Bridge::INHG2KPA = 3.386; +const float Il2Bridge::RAD2DEG = (180.0/M_PI); +const float Il2Bridge::DEG2RAD = (M_PI/180.0); +const float Il2Bridge::M2DEG = 60.*1852.; // 60 miles per degree times 1852 meters per mile +const float Il2Bridge::DEG2M = (1.0/(60.*1852.)); +const float Il2Bridge::AIR_CONST = 287.058; // J/(kg*K) +const float Il2Bridge::GROUNDDENSITY = 1.225; // kg/m³ ;) +const float Il2Bridge::TEMP_GROUND = (15.0 + 273.0); // 15°C in Kelvin +const float Il2Bridge::TEMP_LAPSE_RATE = -0.0065; //degrees per meter +const float Il2Bridge::AIR_CONST_FACTOR = -0.0341631947363104; //several nature constants calculated into one + Il2Bridge::Il2Bridge(QString il2HostName, int il2Port, QString il2Latitude, QString il2Longitude) { // Init fields diff --git a/ground/src/plugins/hitlil2/il2bridge.h b/ground/src/plugins/hitlil2/il2bridge.h index db4138fd0..7e43208e0 100644 --- a/ground/src/plugins/hitlil2/il2bridge.h +++ b/ground/src/plugins/hitlil2/il2bridge.h @@ -103,20 +103,20 @@ private slots: void telStatsUpdated(UAVObject* obj); private: - static const float FT2M = 0.3048; - static const float KT2MPS = 0.514444444; - static const float MPS2KMH = 3.6; - static const float KMH2MPS = (1.0/3.6); - static const float INHG2KPA = 3.386; - static const float RAD2DEG = (180.0/M_PI); - static const float DEG2RAD = (M_PI/180.0); - static const float M2DEG = 60.*1852.; // 60 miles per degree times 1852 meters per mile - static const float DEG2M = (1.0/(60.*1852.)); - static const float AIR_CONST = 287.058; // J/(kg*K) - static const float GROUNDDENSITY = 1.225; // kg/m³ ;) - static const float TEMP_GROUND = (15.0 + 273.0); // 15°C in Kelvin - static const float TEMP_LAPSE_RATE = -0.0065; //degrees per meter - static const float AIR_CONST_FACTOR = -0.0341631947363104; //several nature constants calculated into one + static const float FT2M; + static const float KT2MPS; + static const float MPS2KMH; + static const float KMH2MPS; + static const float INHG2KPA; + static const float RAD2DEG; + static const float DEG2RAD; + static const float M2DEG; + static const float DEG2M; + static const float AIR_CONST; + static const float GROUNDDENSITY; + static const float TEMP_GROUND; + static const float TEMP_LAPSE_RATE; + static const float AIR_CONST_FACTOR; struct flightParams current; struct flightParams old;