diff --git a/src/uas/ArduPilotMegaMAV.cc b/src/uas/ArduPilotMegaMAV.cc index b1d7c84278f50afa11724f29edcbc9d5597f32f8..c3c34c5e859e140618e3567c0e2039a351e99895 100644 --- a/src/uas/ArduPilotMegaMAV.cc +++ b/src/uas/ArduPilotMegaMAV.cc @@ -28,12 +28,12 @@ This file is part of the QGROUNDCONTROL project #include "ArduPilotMegaMAV.h" -#ifndef mavlink_mount_configure_t +#ifndef MAVLINK_MSG_ID_MOUNT_CONFIGURE #include "ardupilotmega/mavlink_msg_mount_configure.h" #endif -#ifndef mavlink_mount_control_t -#include "ardupilotmega/mavlink_msg_mount_control.h"; +#ifndef MAVLINK_MSG_ID_MOUNT_CONTROL +#include "ardupilotmega/mavlink_msg_mount_control.h" #endif ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) : diff --git a/src/ui/PrimaryFlightDisplay.cpp b/src/ui/PrimaryFlightDisplay.cpp index b5a732bf37b0dc2c78fea88b089dc5263895a2dc..2c595b45a15ae1290225151d28faa5b8857b12e9 100644 --- a/src/ui/PrimaryFlightDisplay.cpp +++ b/src/ui/PrimaryFlightDisplay.cpp @@ -112,7 +112,7 @@ */ double PrimaryFlightDisplay_round(double value, int digits=0) { - return floor(value * pow(10, digits) + 0.5) / pow(10, digits); + return floor(value * pow(10.0f, digits) + 0.5f) / pow(10.0f, digits); } const int PrimaryFlightDisplay::tickValues[] = {10, 20, 30, 45, 60}; @@ -546,17 +546,17 @@ void PrimaryFlightDisplay::drawAIAirframeFixedFeatures(QPainter& painter, QRectF qreal h = area.height(); QPen pen; - pen.setWidthF(lineWidth * 1.5); + pen.setWidthF(lineWidth * 1.5f); pen.setColor(redColor); painter.setPen(pen); - float length = 0.15; - float side = 0.5; + float length = 0.15f; + float side = 0.5f; // The 2 lines at sides. painter.drawLine(QPointF(-side*w, 0), QPointF(-(side-length)*w, 0)); painter.drawLine(QPointF(side*w, 0), QPointF((side-length)*w, 0)); - float rel = length/qSqrt(2); + float rel = length/qSqrt(2.0f); // The gull painter.drawLine(QPointF(rel*w, rel*w/2), QPoint(0, 0)); painter.drawLine(QPointF(-rel*w, rel*w/2), QPoint(0, 0));