nixpkgs-suyu/pkgs/applications/science/robotics/qgroundcontrol/0001-fix-gcc-cmath-namespace-issues.patch
2016-03-24 20:06:31 -07:00

140 lines
6.8 KiB
Diff

From fffc383c10c7c194e427d78c83802c3b910fa1c2 Mon Sep 17 00:00:00 2001
From: Patrick Callahan <pxcallahan@gmail.com>
Date: Thu, 24 Mar 2016 18:17:57 -0700
Subject: [PATCH] fix gcc cmath namespace issues
---
src/Vehicle/Vehicle.cc | 6 +++---
src/comm/QGCFlightGearLink.cc | 4 ++--
src/comm/QGCJSBSimLink.cc | 4 ++--
src/uas/UAS.cc | 8 ++++----
src/ui/QGCDataPlot2D.cc | 4 ++--
5 files changed, 13 insertions(+), 13 deletions(-)
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index a0d3605..205b1de 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -638,17 +638,17 @@ void Vehicle::setLongitude(double longitude){
void Vehicle::_updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64)
{
- if (isinf(roll)) {
+ if (std::isinf(roll)) {
_rollFact.setRawValue(0);
} else {
_rollFact.setRawValue(roll * (180.0 / M_PI));
}
- if (isinf(pitch)) {
+ if (std::isinf(pitch)) {
_pitchFact.setRawValue(0);
} else {
_pitchFact.setRawValue(pitch * (180.0 / M_PI));
}
- if (isinf(yaw)) {
+ if (std::isinf(yaw)) {
_headingFact.setRawValue(0);
} else {
yaw = yaw * (180.0 / M_PI);
diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc
index 2a520fb..886aecf 100644
--- a/src/comm/QGCFlightGearLink.cc
+++ b/src/comm/QGCFlightGearLink.cc
@@ -230,7 +230,7 @@ void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float p
Q_UNUSED(systemMode);
Q_UNUSED(navMode);
- if(!isnan(rollAilerons) && !isnan(pitchElevator) && !isnan(yawRudder) && !isnan(throttle))
+ if(!std::isnan(rollAilerons) && !std::isnan(pitchElevator) && !std::isnan(yawRudder) && !std::isnan(throttle))
{
QString state("%1\t%2\t%3\t%4\t%5\n");
state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle);
@@ -240,7 +240,7 @@ void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float p
}
else
{
- qDebug() << "HIL: Got NaN values from the hardware: isnan output: roll: " << isnan(rollAilerons) << ", pitch: " << isnan(pitchElevator) << ", yaw: " << isnan(yawRudder) << ", throttle: " << isnan(throttle);
+ qDebug() << "HIL: Got NaN values from the hardware: std::isnan output: roll: " << std::isnan(rollAilerons) << ", pitch: " << std::isnan(pitchElevator) << ", yaw: " << std::isnan(yawRudder) << ", throttle: " << std::isnan(throttle);
}
}
diff --git a/src/comm/QGCJSBSimLink.cc b/src/comm/QGCJSBSimLink.cc
index 1210621..89db371 100644
--- a/src/comm/QGCJSBSimLink.cc
+++ b/src/comm/QGCJSBSimLink.cc
@@ -242,7 +242,7 @@ void QGCJSBSimLink::updateControls(quint64 time, float rollAilerons, float pitch
Q_UNUSED(systemMode);
Q_UNUSED(navMode);
- if(!isnan(rollAilerons) && !isnan(pitchElevator) && !isnan(yawRudder) && !isnan(throttle))
+ if(!std::isnan(rollAilerons) && !std::isnan(pitchElevator) && !std::isnan(yawRudder) && !std::isnan(throttle))
{
QString state("%1\t%2\t%3\t%4\t%5\n");
state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle);
@@ -250,7 +250,7 @@ void QGCJSBSimLink::updateControls(quint64 time, float rollAilerons, float pitch
}
else
{
- qDebug() << "HIL: Got NaN values from the hardware: isnan output: roll: " << isnan(rollAilerons) << ", pitch: " << isnan(pitchElevator) << ", yaw: " << isnan(yawRudder) << ", throttle: " << isnan(throttle);
+ qDebug() << "HIL: Got NaN values from the hardware: isnan output: roll: " << std::isnan(rollAilerons) << ", pitch: " << std::isnan(pitchElevator) << ", yaw: " << std::isnan(yawRudder) << ", throttle: " << std::isnan(throttle);
}
//qDebug() << "Updated controls" << state;
}
diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc
index 4d5c1c2..ac88852 100644
--- a/src/uas/UAS.cc
+++ b/src/uas/UAS.cc
@@ -558,7 +558,7 @@ void UAS::receiveMessage(mavlink_message_t message)
setAltitudeAMSL(hud.alt);
setGroundSpeed(hud.groundspeed);
- if (!isnan(hud.airspeed))
+ if (!std::isnan(hud.airspeed))
setAirSpeed(hud.airspeed);
speedZ = -hud.climb;
emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
@@ -654,7 +654,7 @@ void UAS::receiveMessage(mavlink_message_t message)
float vel = pos.vel/100.0f;
// Smaller than threshold and not NaN
- if ((vel < 1000000) && !isnan(vel) && !isinf(vel)) {
+ if ((vel < 1000000) && !std::isnan(vel) && !std::isinf(vel)) {
setGroundSpeed(vel);
emit speedChanged(this, groundSpeed, airSpeed, time);
} else {
@@ -1439,8 +1439,8 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
if (countSinceLastTransmission++ >= 5) {
sendCommand = true;
countSinceLastTransmission = 0;
- } else if ((!isnan(roll) && roll != manualRollAngle) || (!isnan(pitch) && pitch != manualPitchAngle) ||
- (!isnan(yaw) && yaw != manualYawAngle) || (!isnan(thrust) && thrust != manualThrust) ||
+ } else if ((!std::isnan(roll) && roll != manualRollAngle) || (!std::isnan(pitch) && pitch != manualPitchAngle) ||
+ (!std::isnan(yaw) && yaw != manualYawAngle) || (!std::isnan(thrust) && thrust != manualThrust) ||
buttons != manualButtons) {
sendCommand = true;
diff --git a/src/ui/QGCDataPlot2D.cc b/src/ui/QGCDataPlot2D.cc
index 2e530b2..9d5a774 100644
--- a/src/ui/QGCDataPlot2D.cc
+++ b/src/ui/QGCDataPlot2D.cc
@@ -535,7 +535,7 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil
{
bool okx = true;
x = text.toDouble(&okx);
- if (okx && !isnan(x) && !isinf(x))
+ if (okx && !std::isnan(x) && !std::isinf(x))
{
headerfound = true;
}
@@ -561,7 +561,7 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil
y = text.toDouble(&oky);
// Only INF is really an issue for the plot
// NaN is fine
- if (oky && !isnan(y) && !isinf(y) && text.length() > 0 && text != " " && text != "\n" && text != "\r" && text != "\t")
+ if (oky && !std::isnan(y) && !std::isinf(y) && text.length() > 0 && text != " " && text != "\n" && text != "\r" && text != "\t")
{
// Only append definitely valid values
xValues.value(curveName)->append(x);
--
2.7.4