Commit 3ecea9ef authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #509 from DonLakeFlyer/Warnings

Warnings fixes
parents 1feeda9a 20f9040b
#ifndef _MAVLINK_CONVERSIONS_H_
#define _MAVLINK_CONVERSIONS_H_
/* enable math defines on Windows */
#ifdef _MSC_VER
#ifndef _USE_MATH_DEFINES
#define _USE_MATH_DEFINES
#endif
#endif
#include <math.h>
#ifndef M_PI_2
#define M_PI_2 ((float)asin(1))
#define M_PI_2 ((float)asin(1.0f))
#endif
/**
......
......@@ -117,56 +117,16 @@ WindowsBuild {
}
#
# Warnings cleanup. Plan of attack is to turn off all existing warnings and turn on warnings as errors.
# Then we will clean up the warnings one type at a time, removing the override for that specific warning
# from the lists below. Eventually we will be left with no overlooked warnings and all future warnings
# generating an error and breaking the build.
#
# NEW WARNINGS SHOULD NOT BE ADDED TO THIS LIST. IF YOU GET AN ERROR, FIX IT BEFORE COMMITING.
# Warnings cleanup. Plan of attack is to turn on warnings as error once all warnings are fixed. Please
# do no change the warning level from what they are currently set to below.
#
MacBuild | LinuxBuild {
QMAKE_CXXFLAGS_WARN_ON += \
-Wall \
-Wno-unused-parameter \
-Wno-unused-variable \
-Wno-narrowing \
-Wno-unused-function
}
LinuxBuild {
QMAKE_CXXFLAGS_WARN_ON += \
-Wno-unused-but-set-variable \
-Wno-unused-local-typedefs
}
MacBuild {
QMAKE_CXXFLAGS_WARN_ON += \
-Wno-overloaded-virtual \
-Wno-unused-private-field
QMAKE_CXXFLAGS_WARN_ON += -Wall
}
WindowsBuild {
QMAKE_CXXFLAGS_WARN_ON += \
/W4 \
/WX \
/wd4005 \ # macro redefinition
/wd4100 \ # unrefernced formal parameter
/wd4101 \ # unreference local variable
/wd4127 \ # conditional expression constant
/wd4146 \ # unary minus operator applied to unsigned type
/wd4189 \ # local variable initialized but not used
/wd4201 \ # non standard extension: nameless struct/union
/wd4245 \ # signed/unsigned mismtach
/wd4290 \ # function declared using exception specification, but not supported
/wd4305 \ # truncation from double to float
/wd4309 \ # truncation of constant value
/wd4389 \ # == signed/unsigned mismatch
/wd4505 \ # unreferenced local function
/wd4512 \ # assignment operation could not be generated
/wd4701 \ # potentially uninitialized local variable
/wd4702 \ # unreachable code
/wd4996 # deprecated function
QMAKE_CXXFLAGS_WARN_ON += /W3
}
#
......
Subproject commit b8b885c610ee574140c7a6ad9bc007dcf28a74b7
Subproject commit 2db4b382b02c3822acd19e99bc57fa53f3f53d01
......@@ -55,7 +55,7 @@ This file is part of the QGROUNDCONTROL project
* @param writeFile The received messages are written to that file
* @param rate The rate at which the messages are sent (in intervals of milliseconds)
**/
MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile, int rate, QObject* parent) :
MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile, int rate) :
readyBytes(0),
timeOffset(0)
{
......@@ -677,6 +677,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
int streampointer = 0;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int bufferlength = 0;
// Initialize drop count to 0 so it isn't referenced uninitialized when returned at the bottom of this function
comm.packet_rx_drop_count = 0;
// Output all bytes as hex digits
for (int i=0; i<size; i++)
......
......@@ -48,7 +48,7 @@ class MAVLinkSimulationLink : public LinkInterface
{
Q_OBJECT
public:
MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5, QObject* parent = 0);
MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5);
~MAVLinkSimulationLink();
bool isConnected() const;
qint64 bytesAvailable();
......
......@@ -303,6 +303,11 @@ void MAVLinkSimulationMAV::mainloop()
timer25Hz--;
}
// Uncomment to turn on debug message printing
//#define DEBUG_PRINT_MESSAGE
#ifdef DEBUG_PRINT_MESSAGE
//static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
......@@ -376,17 +381,22 @@ static void print_field(const mavlink_message_t *msg, const mavlink_field_info_t
}
qDebug(" ");
}
#endif
static void print_message(const mavlink_message_t *msg)
{
#ifdef DEBUG_PRINT_MESSAGE
const mavlink_message_info_t *m = &message_info[msg->msgid];
const mavlink_field_info_t *f = m->fields;
unsigned i;
// qDebug("%s { ", m->name);
// for (i=0; i<m->num_fields; i++) {
// print_field(msg, &f[i]);
// }
// qDebug("}\n");
qDebug("%s { ", m->name);
for (i=0; i<m->num_fields; i++) {
print_field(msg, &f[i]);
}
qDebug("}\n");
#else
Q_UNUSED(msg);
#endif
}
void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
......
#include "MAVLinkSwarmSimulationLink.h"
MAVLinkSwarmSimulationLink::MAVLinkSwarmSimulationLink(QString readFile, QString writeFile, int rate, QObject *parent) :
MAVLinkSimulationLink(readFile, writeFile, rate, parent)
MAVLinkSwarmSimulationLink::MAVLinkSwarmSimulationLink(QString readFile, QString writeFile, int rate) :
MAVLinkSimulationLink(readFile, writeFile, rate)
{
}
......
......@@ -7,7 +7,7 @@ class MAVLinkSwarmSimulationLink : public MAVLinkSimulationLink
{
Q_OBJECT
public:
MAVLinkSwarmSimulationLink(QString readFile="", QString writeFile="", int rate=5, QObject *parent = 0);
MAVLinkSwarmSimulationLink(QString readFile="", QString writeFile="", int rate=5);
signals:
......
......@@ -353,8 +353,8 @@ void QGCFlightGearLink::readBytes()
// qDebug() << "sensorHilRawImuChanged " << xacc << yacc << zacc << rollspeed << pitchspeed << yawspeed << xmag << ymag << zmag << abs_pressure << diff_pressure << pressure_alt << temperature;
int gps_fix_type = 3;
float eph = 0.3;
float epv = 0.6;
float eph = 0.3f;
float epv = 0.6f;
float vel = sqrt(vx*vx + vy*vy + vz*vz);
float cog = yaw;
int satellites = 8;
......
......@@ -518,19 +518,19 @@ void QGCXPlaneLink::readBytes()
// X-Plane expresses yaw as 0..2 PI
if (yaw > M_PI) {
yaw -= 2.0 * M_PI;
yaw -= 2.0f * static_cast<float>(M_PI);
}
if (yaw < -M_PI) {
yaw += 2.0 * M_PI;
yaw += 2.0f * static_cast<float>(M_PI);
}
float yawmag = p.f[3] / 180.0f * M_PI;
if (yawmag > M_PI) {
yawmag -= 2.0 * M_PI;
yawmag -= 2.0f * static_cast<float>(M_PI);
}
if (yawmag < -M_PI) {
yawmag += 2.0 * M_PI;
yawmag += 2.0f * static_cast<float>(M_PI);
}
// Normal rotation matrix, but since we rotate the
......@@ -689,8 +689,8 @@ void QGCXPlaneLink::readBytes()
// XXX make these GUI-configurable and add randomness
int gps_fix_type = 3;
float eph = 0.3;
float epv = 0.6;
float eph = 0.3f;
float epv = 0.6f;
float vel = sqrt(vx*vx + vy*vy + vz*vz);
float cog = atan2(vy, vx);
int satellites = 8;
......
......@@ -154,7 +154,7 @@ public slots:
virtual void setLocalPositionSetpoint(float x, float y, float z, float yaw)
{ Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(z); Q_UNUSED(yaw); Q_ASSERT(false); };
virtual void setLocalPositionOffset(float x, float y, float z, float yaw) { Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(z); Q_UNUSED(yaw); Q_ASSERT(false); };
virtual void startRadioControlCalibration(int param) { Q_ASSERT(false); };
virtual void startRadioControlCalibration(int param) { Q_UNUSED(param); Q_ASSERT(false); };
virtual void endRadioControlCalibration() { Q_ASSERT(false); };
virtual void startMagnetometerCalibration() { Q_ASSERT(false); };
virtual void startGyroscopeCalibration() { Q_ASSERT(false); };
......
......@@ -3086,23 +3086,6 @@ void UAS::sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw
Q_UNUSED(yacc);
Q_UNUSED(zacc);
float q[4];
double cosPhi_2 = cos(double(roll) / 2.0);
double sinPhi_2 = sin(double(roll) / 2.0);
double cosTheta_2 = cos(double(pitch) / 2.0);
double sinTheta_2 = sin(double(pitch) / 2.0);
double cosPsi_2 = cos(double(yaw) / 2.0);
double sinPsi_2 = sin(double(yaw) / 2.0);
q[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
sinPhi_2 * sinTheta_2 * sinPsi_2);
q[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
cosPhi_2 * sinTheta_2 * sinPsi_2);
q[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
sinPhi_2 * cosTheta_2 * sinPsi_2);
q[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
sinPhi_2 * sinTheta_2 * cosPsi_2);
// Emit attitude for cross-check
emit valueChanged(uasId, "roll sim", "rad", roll, getUnixTime());
emit valueChanged(uasId, "pitch sim", "rad", pitch, getUnixTime());
......@@ -3215,7 +3198,7 @@ void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fi
float course = cog;
// map to 0..2pi
if (course < 0)
course += 2.0f * M_PI;
course += 2.0f * static_cast<float>(M_PI);
// scale from radians to degrees
course = (course / M_PI) * 180.0f;
......
......@@ -601,7 +601,7 @@ void HUD::paintHUD()
xImageFactor = width() / (float)glImage.width();
yImageFactor = height() / (float)glImage.height();
float imageFactor = qMin(xImageFactor, yImageFactor);
//float imageFactor = qMin(xImageFactor, yImageFactor);
// Resize to correct size and fill with image
// FIXME
......
......@@ -33,7 +33,7 @@ static const float PITCHTRANSLATION = 65;
// 5 degrees for each line
static const int PITCH_SCALE_RESOLUTION = 5;
static const float PITCH_SCALE_MAJORWIDTH = 0.1f;
static const float PITCH_SCALE_MINORWIDTH = 0.066;
static const float PITCH_SCALE_MINORWIDTH = 0.066f;
// Beginning from PITCH_SCALE_WIDTHREDUCTION_FROM degrees of +/- pitch, the
// width of the lines is reduced, down to PITCH_SCALE_WIDTHREDUCTION times
......@@ -49,18 +49,18 @@ static const int PITCH_SCALE_HALFRANGE = 15;
static const int COMPASS_DISK_MAJORTICK = 10;
static const int COMPASS_DISK_ARROWTICK = 45;
static const float COMPASS_DISK_MAJORLINEWIDTH = 0.006;
static const float COMPASS_DISK_MINORLINEWIDTH = 0.004;
static const float COMPASS_DISK_MAJORLINEWIDTH = 0.006f;
static const float COMPASS_DISK_MINORLINEWIDTH = 0.004f;
static const int COMPASS_DISK_RESOLUTION = 10;
static const float COMPASS_SEPARATE_DISK_RESOLUTION = 5;
static const float COMPASS_DISK_MARKERWIDTH = 0.2;
static const float COMPASS_DISK_MARKERHEIGHT = 0.133;
static const float COMPASS_SEPARATE_DISK_RESOLUTION = 5.0f;
static const float COMPASS_DISK_MARKERWIDTH = 0.2f;
static const float COMPASS_DISK_MARKERHEIGHT = 0.133f;
static const int CROSSTRACK_MAX = 1000;
static const float CROSSTRACK_RADIUS = 0.6;
static const float CROSSTRACK_RADIUS = 0.6f;
static const float TAPE_GAUGES_TICKWIDTH_MAJOR = 0.25;
static const float TAPE_GAUGES_TICKWIDTH_MINOR = 0.15;
static const float TAPE_GAUGES_TICKWIDTH_MAJOR = 0.25f;
static const float TAPE_GAUGES_TICKWIDTH_MINOR = 0.15f;
// The altitude difference between top and bottom of scale
static const int ALTIMETER_LINEAR_SPAN = 50;
......
......@@ -1836,13 +1836,13 @@ void QGCPX4VehicleConfig::parameterChanged(int uas, int component, QString param
else {
//Param recieved that we have no metadata for. Search to see if it belongs in a
//group with some other params
bool found = false;
//bool found = false;
for (int i=0;i<toolWidgets.size();i++) {
if (parameterName.startsWith(toolWidgets[i]->objectName())) {
//It should be grouped with this one, add it.
toolWidgets[i]->addParam(uas,component,parameterName,value);
libParamToWidgetMap.insert(parameterName,toolWidgets[i]);
found = true;
//found = true;
break;
}
}
......
......@@ -149,39 +149,39 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
}
void BatteryMonitorConfig::sensorCurrentIndexChanged(int index)
{
float maxvolt = 0.0;
float maxamps = 0.0;
float mvpervolt = 0.0;
float mvperamp = 0.0;
float topvolt = 0.0;
float topamps = 0.0;
float maxvolt = 0.0f;
float maxamps = 0.0f;
float mvpervolt = 0.0f;
float mvperamp = 0.0f;
float topvolt = 0.0f;
float topamps = 0.0f;
if (index == 1)
{
//atto 45 see https://www.sparkfun.com/products/10643
maxvolt = 13.6;
maxamps = 44.7;
maxvolt = 13.6f;
maxamps = 44.7f;
}
else if (index == 2)
{
//atto 90 see https://www.sparkfun.com/products/9028
maxvolt = 51.8;
maxamps = 89.4;
maxvolt = 51.8f;
maxamps = 89.4f;
}
else if (index == 3)
{
//atto 180 see https://www.sparkfun.com/products/10644
maxvolt = 51.8;
maxamps = 178.8;
maxvolt = 51.8f;
maxamps = 178.8f;
}
else if (index == 4)
{
//3dr
maxvolt = 50.0;
maxamps = 90.0;
maxvolt = 50.0f;
maxamps = 90.0f;
}
mvpervolt = calculatemVPerVolt(3.3,maxvolt);
mvperamp = calculatemVPerAmp(3.3,maxamps);
mvpervolt = calculatemVPerVolt(3.3f, maxvolt);
mvperamp = calculatemVPerAmp(3.3f, maxamps);
if (index == 0)
{
//Other
......
......@@ -222,7 +222,7 @@ void FlightModeConfig::remoteControlChannelRawChanged(int chan, float val)
if (chan == _modeSwitchRCChannel)
{
qDebug() << chan << val;
size_t highlightIndex;
size_t highlightIndex = _cModes; // initialize to unreachable index
for (size_t i=0; i<_cModes; i++) {
if (val < _rgModePWMBoundary[i]) {
......
......@@ -412,7 +412,7 @@ void LinechartPlot::setScaling(int scaling)
* @param id The string id of the curve
* @param visible The visibility: True to make it visible
**/
void LinechartPlot::setVisible(QString id, bool visible)
void LinechartPlot::setVisibleById(QString id, bool visible)
{
if(curves.contains(id)) {
curves.value(id)->setVisible(visible);
......@@ -437,7 +437,7 @@ void LinechartPlot::setVisible(QString id, bool visible)
**/
void LinechartPlot::hideCurve(QString id)
{
setVisible(id, false);
setVisibleById(id, false);
}
/**
......@@ -450,7 +450,7 @@ void LinechartPlot::hideCurve(QString id)
**/
void LinechartPlot::showCurve(QString id)
{
setVisible(id, true);
setVisibleById(id, true);
}
//void LinechartPlot::showCurve(QString id, int position)
......
......@@ -213,7 +213,7 @@ public slots:
void setActive(bool active);
// Functions referring to the currently active plot
void setVisible(QString id, bool visible);
void setVisibleById(QString id, bool visible);
/**
* @brief Set the color of a curve and its symbols.
......
......@@ -171,7 +171,7 @@ void LinechartWidget::selectAllCurves(bool all)
{
QMap<QString, QLabel*>::iterator i;
for (i = curveLabels->begin(); i != curveLabels->end(); ++i) {
activePlot->setVisible(i.key(), all);
activePlot->setVisibleById(i.key(), all);
}
}
......@@ -647,7 +647,7 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
// Set UI components to initial state
checkBox->setChecked(false);
plot->setVisible(curve+unit, false);
plot->setVisibleById(curve+unit, false);
}
/**
......@@ -952,7 +952,7 @@ void LinechartWidget::takeButtonClick(bool checked)
if(button != NULL)
{
activePlot->setVisible(button->objectName(), checked);
activePlot->setVisibleById(button->objectName(), checked);
QWidget* colorIcon = colorIcons.value(button->objectName(), 0);
if (colorIcon)
{
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment