Commit da2aaa92 authored by pixhawk's avatar pixhawk

Fixed windows visual studio compile warnings.

parent 27618df8
......@@ -182,10 +182,10 @@ void MAVLinkSimulationLink::mainloop()
// Fake system values
static float fullVoltage = 4.2 * 3;
static float emptyVoltage = 3.35 * 3;
static float fullVoltage = 4.2f * 3.0f;
static float emptyVoltage = 3.35f * 3.0f;
static float voltage = fullVoltage;
static float drainRate = 0.025; // x.xx% of the capacity is linearly drained per second
static float drainRate = 0.025f; // x.xx% of the capacity is linearly drained per second
mavlink_attitude_t attitude;
memset(&attitude, 0, sizeof(mavlink_attitude_t));
......@@ -212,7 +212,7 @@ void MAVLinkSimulationLink::mainloop()
// VOLTAGE
// The battery is drained constantly
voltage = voltage - ((fullVoltage - emptyVoltage) * drainRate / rate);
if (voltage < 3.550 * 3) voltage = 3.550 * 3;
if (voltage < 3.550f * 3.0f) voltage = 3.550f * 3.0f;
static int state = 0;
......
......@@ -584,7 +584,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
// FIXME big hack for simulation!
//float oneDegreeOfLatMeters = 111131.745f;
float orbit = 0.00008;
float orbit = 0.00008f;
// compare current position (given in message) with current waypoint
//float orbit = wp->param1;
......
......@@ -64,11 +64,12 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (message.sysid == uasId)
{
// Handle your special messages mavlink_message_t* msg = &message;
#ifdef MAVLINK_ENABLED_SLUGS
// Handle your special messages mavlink_message_t* msg = &message;
switch (message.msgid)
{
#ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_RAW_IMU:
mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
......@@ -151,12 +152,11 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
#endif
default:
// qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
break;
}
#endif
}
}
......
......@@ -338,7 +338,7 @@ void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int s
// this->timeRemaining = seconds;
// this->percentRemaining = percent;
fuelStatus.sprintf("BAT [%02.0f \%% | %05.2fV] (%02dm:%02ds)", percent, voltage, seconds/60, seconds%60);
fuelStatus.sprintf("BAT [%02.0f % | %05.2fV] (%02dm:%02ds)", percent, voltage, seconds/60, seconds%60);
if (percent < 20.0f)
{
......@@ -647,10 +647,10 @@ void HUD::paintHUD()
yawInt += newYawDiff;
if (yawInt > M_PI) yawInt = M_PI;
if (yawInt < -M_PI) yawInt = -M_PI;
if (yawInt > M_PI) yawInt = (float)M_PI;
if (yawInt < -M_PI) yawInt = (float)-M_PI;
float yawTrans = yawInt * (double)maxYawTrans;
float yawTrans = yawInt * (float)maxYawTrans;
yawInt *= 0.6f;
if ((yawTrans < 5.0) && (yawTrans > -5.0)) yawTrans = 0;
......@@ -836,7 +836,7 @@ void HUD::paintHUD()
// Rotate view and draw all roll-dependent indicators
painter.rotate((rollLP/M_PI)* -180.0f);
painter.translate(0, (-pitchLP/M_PI)* -180.0f * refToScreenY(1.8));
painter.translate(0, (-pitchLP/(float)M_PI)* -180.0f * refToScreenY(1.8f));
//qDebug() << "ROLL" << roll << "PITCH" << pitch << "YAW DIFF" << valuesDot.value("roll", 0.0f);
......
......@@ -67,8 +67,12 @@ public:
};
const float* operator[](int i) const;
#ifdef _MSC_VER
const QVector<float>& operator()(int i) const;
#else
const QVector<float>& operator()(int i) const throw(std::out_of_range);
void set(int element, int index, float value) {(*data)[element][index] = value;}
#endif
void set(int element, int index, float value) {(*data)[element][index] = value;}
public slots:
void setAileron(int index, float value) {set(AILERON, index, value);}
......
......@@ -57,12 +57,12 @@ void MAV2DIcon::setYaw(float yaw)
{
//qDebug() << "MAV2Icon" << yaw;
float diff = fabs(yaw - this->yaw);
while (diff > M_PI)
while (diff > (float)M_PI)
{
diff -= M_PI;
diff -= (float)M_PI;
}
if (diff > 0.1)
if (diff > 0.1f)
{
this->yaw = yaw;
drawIcon(mypen);
......
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