Commit 25e35803 authored by oberion's avatar oberion Committed by LM

Fixed windows build bug and div. compile warnings

parent ce0bd4d2
......@@ -64,7 +64,7 @@ float limitAngleToPMPIf(float angle)
else
{
// Approximate
angle = fmodf(angle, M_PI);
angle = fmodf(angle, (float) M_PI);
}
return angle;
......
......@@ -47,7 +47,7 @@ inline bool isnan(T value)
template<typename T>
inline bool isinf(T value)
{
return std::numeric_limits<T>::has_infinity && (value == std::numeric_limits<T>::infinity() || (-1*value) == std::numeric_limits<T>::infinity());
return (value == std::numeric_limits<T>::infinity() || (-1*value) == std::numeric_limits<T>::infinity()) && std::numeric_limits<T>::has_infinity;
}
#else
#include <cmath>
......
......@@ -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
......
......@@ -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));
......
......@@ -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);
......
......@@ -6,6 +6,9 @@
#include <QDebug>
const float QGCMAVLinkInspector::updateHzLowpass = 0.2f;
const unsigned int QGCMAVLinkInspector::updateInterval = 1000U;
QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMAVLinkInspector)
......
......@@ -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;
......
......@@ -265,5 +265,7 @@ void QGCRGBDView::updateData(UASInterface *uas)
}
glImage = QGLWidget::convertToGLFormat(fill);
#else
Q_UNUSED(uas);
#endif
}
......@@ -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),
......
......@@ -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();
......
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