diff --git a/src/QGC.cc b/src/QGC.cc index 179d54f5905c1c1c06006a2a68f31fc01bba2f90..c30209f83b0ceb8ea992d4d465dd9f385838f53c 100644 --- a/src/QGC.cc +++ b/src/QGC.cc @@ -64,7 +64,7 @@ float limitAngleToPMPIf(float angle) else { // Approximate - angle = fmodf(angle, M_PI); + angle = fmodf(angle, (float) M_PI); } return angle; diff --git a/src/QGC.h b/src/QGC.h index 9a1b442d176de3bc7818d086c4cc2f8fa705880f..7f17bd143cb4ef2a6641e6120d56f3aec214252e 100644 --- a/src/QGC.h +++ b/src/QGC.h @@ -47,7 +47,7 @@ inline bool isnan(T value) template inline bool isinf(T value) { - return std::numeric_limits::has_infinity && (value == std::numeric_limits::infinity() || (-1*value) == std::numeric_limits::infinity()); + return (value == std::numeric_limits::infinity() || (-1*value) == std::numeric_limits::infinity()) && std::numeric_limits::has_infinity; } #else #include diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 519924400295bc10ae00d3200cb5aaeec0beca83..948fcecbd4cdf5cc7889159e41c223b2cfc8fafe 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -221,10 +221,10 @@ void MAVLinkSimulationMAV::mainloop() if (sys_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL) { mavlink_hil_controls_t hil; - hil.roll_ailerons = 0.0; - hil.pitch_elevator = 0.05; - hil.yaw_rudder = 0.05; - hil.throttle = 0.6; + hil.roll_ailerons = 0.0f; + hil.pitch_elevator = 0.05f; + hil.yaw_rudder = 0.05f; + hil.throttle = 0.6f; // Encode the data (adding header and checksums, etc.) mavlink_msg_hil_controls_encode(systemid, MAV_COMP_ID_IMU, &ret, &hil); // And send it diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index e37bd25df5e7a997154785880dbc7e9fb7de8faa..4a274b4e6b06454f95c9087cce77a500930716b0 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -114,6 +114,9 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l { Q_UNUSED(mav); Q_UNUSED(time); + Q_UNUSED(alt); + Q_UNUSED(lon); + Q_UNUSED(lat); if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) { // TODO FIXME Calculate distance @@ -239,6 +242,7 @@ void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, m void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr) { + Q_UNUSED(compId); if (!uas) return; if (systemId == uasid) { emit updateStatusString(QString("Reached waypoint %1").arg(wpr->seq)); diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 296e25d3e08e16c7335a5fc65bf7f1bfd0d1f3f2..0e260bf1af20886478237cad56b3ae7cfa1641a4 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -486,6 +486,11 @@ void HSIDisplay::updatePositionZControllerEnabled(bool enabled) void HSIDisplay::updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance) { + Q_UNUSED(quality); + Q_UNUSED(name); + Q_UNUSED(type); + Q_UNUSED(id); + Q_UNUSED(time); // FIXME add multi-object support QPainter painter(this); QColor color(Qt::yellow); diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index 691f8bcceb8ca92dbbbfb64ba3e3b5bfb46317a3..d4c353c3b01d0bbd542d44fd12fc7906d4f76166 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -6,6 +6,9 @@ #include +const float QGCMAVLinkInspector::updateHzLowpass = 0.2f; +const unsigned int QGCMAVLinkInspector::updateInterval = 1000U; + QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *parent) : QWidget(parent), ui(new Ui::QGCMAVLinkInspector) diff --git a/src/ui/QGCMAVLinkInspector.h b/src/ui/QGCMAVLinkInspector.h index f4751dd659a300fdc3c026bdf6c18cd0b947ab2f..4623b2436d273f2f059c4163fe2b85c1e3ac16ee 100644 --- a/src/ui/QGCMAVLinkInspector.h +++ b/src/ui/QGCMAVLinkInspector.h @@ -37,8 +37,8 @@ protected: // Update one message field void updateField(int msgid, int fieldid, QTreeWidgetItem* item); - static const unsigned int updateInterval = 1000; - static const float updateHzLowpass = 0.2f; + static const unsigned int updateInterval; + static const float updateHzLowpass; private: Ui::QGCMAVLinkInspector *ui; diff --git a/src/ui/QGCRGBDView.cc b/src/ui/QGCRGBDView.cc index de45d8065374e7e9ffc0267024b9cfb490a49405..ded4a4edac8b2a3808e8d99f0d8e364d36232f8b 100644 --- a/src/ui/QGCRGBDView.cc +++ b/src/ui/QGCRGBDView.cc @@ -265,5 +265,7 @@ void QGCRGBDView::updateData(UASInterface *uas) } glImage = QGLWidget::convertToGLFormat(fill); +#else + Q_UNUSED(uas); #endif } diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index ed1b371c1f3093e301274e64d7cce05ba22021f4..2c5a7aa3e7e3034170388080c187bebc11b79f97 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -10,7 +10,7 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : mapcontrol::OPMapWidget(parent), currWPManager(NULL), firingWaypointChange(NULL), - maxUpdateInterval(2.1), // 2 seconds + maxUpdateInterval(2.1f), // 2 seconds followUAVEnabled(false), trailType(mapcontrol::UAVTrailType::ByTimeElapsed), trailInterval(2.0f), diff --git a/src/ui/uas/UASListWidget.cc b/src/ui/uas/UASListWidget.cc index faa136d3b0db284afd126956af5b3adb1257ef19..33bac7a584256d421e518c739cdde638db1d80f1 100644 --- a/src/ui/uas/UASListWidget.cc +++ b/src/ui/uas/UASListWidget.cc @@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas) void UASListWidget::removeUAS(UASInterface* uas) { + Q_UNUSED(uas); // uasViews.remove(uas); // listLayout->removeWidget(uasViews.value(uas)); // uasViews.value(uas)->deleteLater();