Commit b3ba7ea3 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #210 from Susurrus/compile-fixes

Compilation warning fixes
parents 09fc4c2d ccc497b2
......@@ -207,7 +207,6 @@ void MAVLinkSimulationLink::mainloop()
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int bufferlength;
int messageSize;
mavlink_message_t msg;
// Timers
......@@ -458,7 +457,7 @@ void MAVLinkSimulationLink::mainloop()
chan.chan7_raw = (chan.chan4_raw + chan.chan2_raw) / 2.0f;
chan.chan8_raw = 0;
chan.rssi = 100;
messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -513,7 +512,7 @@ void MAVLinkSimulationLink::mainloop()
detectionCounter = 0;
}
detected.detected = 1;
messageSize = mavlink_msg_pattern_detected_encode(systemId, componentId, &msg, &detected);
mavlink_msg_pattern_detected_encode(systemId, componentId, &msg, &detected);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -528,7 +527,7 @@ void MAVLinkSimulationLink::mainloop()
status.load = 33 * detectionCounter % 1000;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
mavlink_msg_sys_status_encode(systemId, componentId, &msg, &status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -546,7 +545,7 @@ void MAVLinkSimulationLink::mainloop()
/*
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
mavlink_msg_boot_pack(systemId, componentId, &msg, version);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -568,7 +567,7 @@ void MAVLinkSimulationLink::mainloop()
typeCounter++;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK, system.base_mode, system.custom_mode, system.system_status);
mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK, system.base_mode, system.custom_mode, system.system_status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
......@@ -577,7 +576,7 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(systemId+1, componentId+1, &msg, mavType, MAV_AUTOPILOT_GENERIC, system.base_mode, system.custom_mode, system.system_status);
mavlink_msg_heartbeat_pack(systemId+1, componentId+1, &msg, mavType, MAV_AUTOPILOT_GENERIC, system.base_mode, system.custom_mode, system.system_status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
......@@ -597,7 +596,7 @@ void MAVLinkSimulationLink::mainloop()
// // HEARTBEAT VEHICLE 2
// // Pack message and get size of encoded byte string
// messageSize = mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_HELICOPTER, MAV_AUTOPILOT_ARDUPILOTMEGA);
// mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_HELICOPTER, MAV_AUTOPILOT_ARDUPILOTMEGA);
// // Allocate buffer with packet data
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// //add data into datastream
......@@ -607,23 +606,15 @@ void MAVLinkSimulationLink::mainloop()
// // HEARTBEAT VEHICLE 3
// // Pack message and get size of encoded byte string
// messageSize = mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// // Allocate buffer with packet data
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength);
// streampointer += bufferlength;
// STATUS VEHICLE 2
mavlink_sys_status_t status2;
mavlink_heartbeat_t system2;
system2.base_mode = MAV_MODE_PREFLIGHT;
status2.voltage_battery = voltage;
status2.load = 120;
system2.system_status = MAV_STATE_STANDBY;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -646,7 +637,7 @@ void MAVLinkSimulationLink::mainloop()
// Attitude
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......
......@@ -40,11 +40,11 @@ This file is part of the QGROUNDCONTROL project
#include "MainWindow.h"
QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) :
socket(NULL),
process(NULL),
terraSync(NULL),
socket(NULL),
startupArguments(startupArguments),
flightGearVersion(0)
flightGearVersion(0),
startupArguments(startupArguments)
{
this->host = host;
this->port = port+mav->getUASID();
......@@ -147,7 +147,15 @@ void QGCFlightGearLink::setRemoteHost(const QString& host)
void QGCFlightGearLink::updateActuators(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
{
Q_UNUSED(time);
Q_UNUSED(act1);
Q_UNUSED(act2);
Q_UNUSED(act3);
Q_UNUSED(act4);
Q_UNUSED(act5);
Q_UNUSED(act6);
Q_UNUSED(act7);
Q_UNUSED(act8);
}
void QGCFlightGearLink::updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode)
......@@ -232,13 +240,10 @@ void QGCFlightGearLink::readBytes()
}
// Parse string
double time;
float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
double lat, lon, alt;
double vx, vy, vz, xacc, yacc, zacc;
double airspeed;
time = values.at(0).toDouble();
lat = values.at(1).toDouble() * 1e7;
lon = values.at(2).toDouble() * 1e7;
alt = values.at(3).toDouble() * 1e3;
......@@ -257,8 +262,6 @@ void QGCFlightGearLink::readBytes()
vy = values.at(14).toDouble() * 1e2;
vz = values.at(15).toDouble() * 1e2;
airspeed = values.at(16).toDouble();
// Send updated state
emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
pitchspeed, yawspeed, lat, lon, alt,
......
......@@ -2432,6 +2432,9 @@ void UAS::disarmSystem()
*/
void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons)
{
Q_UNUSED(xHat);
Q_UNUSED(yHat);
// Scale values
double rollPitchScaling = 1.0f * 1000.0f;
double yawScaling = 1.0f * 1000.0f;
......@@ -2720,7 +2723,6 @@ void UAS::stopHil()
void UAS::shutdown()
{
bool result = false;
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Shutting down the UAS");
......@@ -2739,7 +2741,6 @@ void UAS::shutdown()
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0);
sendMessage(msg);
result = true;
}
}
......
......@@ -49,6 +49,8 @@ DebugConsole::DebugConsole(QWidget *parent) :
autoHold(true),
bytesToIgnore(0),
lastByte(-1),
escReceived(false),
escIndex(0),
sentBytes(),
holdBuffer(),
lineBuffer(""),
......@@ -61,8 +63,6 @@ DebugConsole::DebugConsole(QWidget *parent) :
lowpassDataRate(0.0f),
dataRateThreshold(400),
commandIndex(0),
escReceived(false),
escIndex(0),
m_ui(new Ui::DebugConsole)
{
// Setup basic user interface
......
......@@ -201,9 +201,7 @@ void HDDisplay::triggerUpdate()
void HDDisplay::paintEvent(QPaintEvent * event)
{
Q_UNUSED(event);
quint64 interval = 0;
//qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
interval = QGC::groundTimeMilliseconds();
renderOverlay();
}
......
......@@ -118,12 +118,6 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
visionFixKnown(false),
gpsFixKnown(false),
iruFixKnown(false),
setPointKnown(false),
positionSetPointKnown(false),
userSetPointSet(false),
userXYSetPointSet(false),
userZSetPointSet(false),
userYawSetPointSet(false),
gyroKnown(false),
gyroON(false),
gyroOK(false),
......@@ -150,7 +144,13 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
viconOK(false),
actuatorsKnown(false),
actuatorsON(false),
actuatorsOK(false)
actuatorsOK(false),
setPointKnown(false),
positionSetPointKnown(false),
userSetPointSet(false),
userXYSetPointSet(false),
userZSetPointSet(false),
userYawSetPointSet(false)
{
refreshTimer->setInterval(updateInterval);
......@@ -1075,12 +1075,13 @@ void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float az
{
Q_UNUSED(uasid);
// If slot is empty, insert object
if (satid != 0) // Satellite PRNs currently range from 1-32, but are never zero
if (satid != 0) { // Satellite PRNs currently range from 1-32, but are never zero
if (gpsSatellites.contains(satid)) {
gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
} else {
gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
}
}
}
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
......
......@@ -335,6 +335,7 @@ void HUD::updateAttitude(UASInterface* uas, int component, double roll, double p
void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
Q_UNUSED(uas);
Q_UNUSED(seconds);
fuelStatus = tr("BAT [%1% | %2V]").arg(percent, 2, 'f', 0, QChar('0')).arg(voltage, 4, 'f', 1, QChar('0'));
if (percent < 20.0f) {
fuelColor = warningColor;
......
......@@ -102,12 +102,10 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
{
bool isNull = false;
quint64 ret = 0;
if (time == 0)
{
ret = QGC::groundTimeMilliseconds() - onboardToGCSUnixTimeOffsetAndDelay[systemID];
isNull = true;
}
// Check if time is smaller than 40 years,
// assuming no system without Unix timestamp
......@@ -183,7 +181,6 @@ quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time)
{
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
// Store component ID
if (componentID[msg->msgid] == -1)
......@@ -196,7 +193,6 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
if (componentID[msg->msgid] != msg->compid)
{
componentMulti[msg->msgid] = true;
wrongComponent = true;
}
}
......
......@@ -19,8 +19,6 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
QWidget(parent),
mav(NULL),
chanCount(0),
changed(true),
rc_mode(RC_MODE_2),
rcRoll(0.0f),
rcPitch(0.0f),
rcYaw(0.0f),
......@@ -29,6 +27,8 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
rcAux1(0.0f),
rcAux2(0.0f),
rcAux3(0.0f),
changed(true),
rc_mode(RC_MODE_2),
calibrationEnabled(false),
ui(new Ui::QGCVehicleConfig)
{
......
......@@ -573,10 +573,6 @@ void UASView::refresh()
//qDebug() << "UPDATING UAS WIDGET!" << uas->getUASName();
quint64 lastupdate = 0;
//// qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
lastupdate = QGC::groundTimeMilliseconds();
if (generalUpdateCount == 4)
{
#if (QGC_EVENTLOOP_DEBUG)
......
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