Commit 16a68ab5 authored by pixhawk's avatar pixhawk

Fixed a whole bunch of compile warnings

parent 74c36838
......@@ -99,9 +99,10 @@ namespace qmapcontrol
Geometry* Layer::get_Geometry(int index)
{
Geometry* geo = NULL;
if(geometrySelected)
{
return geometrySelected;
geo = geometrySelected;
}
else
{
......@@ -110,7 +111,7 @@ namespace qmapcontrol
Geometry *geometry = geometries[i];
if(geometry->name() == QString::number(index))
{
return geometry;
geo = geometry;
}
}
......@@ -124,7 +125,7 @@ namespace qmapcontrol
// }
}
return geo;
}
bool Layer::isVisible() const
......
......@@ -122,6 +122,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
#endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt");
simulationLink->disconnect();
//mainWindow->addLink(simulationLink);
mainWindow = MainWindow::instance();
......
......@@ -496,7 +496,7 @@ bool MAVLinkXMLParser::generate()
if (fieldType == "uint8_t_mavlink_version")
{
unpackingCode = QString("\treturn %1;").arg(mavlinkVersion);
unpackingCode = QString("\treturn (%1)(msg->payload%2)[0];").arg("uint8_t", prepends);
}
else if (fieldType == "uint8_t" || fieldType == "int8_t")
{
......@@ -531,7 +531,7 @@ bool MAVLinkXMLParser::generate()
// Generate the message decoding function
if (fieldType.contains("uint8_t_mavlink_version"))
{
unpacking += unpackingComment + QString("static inline uint8_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg)\n{\n\treturn %3;\n}\n\n").arg(messageName, fieldName).arg(mavlinkVersion);
unpacking += unpackingComment + QString("static inline %1 mavlink_msg_%2_get_%3(const mavlink_message_t* msg)\n{\n%4\n}\n\n").arg("uint8_t", messageName, fieldName, unpackingCode);
decodeLines += "";
prepends += "+sizeof(uint8_t)";
}
......
......@@ -394,11 +394,14 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
void UASWaypointManager::globalAddWaypoint(Waypoint *wp)
{
// FIXME Will be removed
Q_UNUSED(wp);
}
int UASWaypointManager::globalRemoveWaypoint(quint16 seq)
{
// FIXME Will be removed
Q_UNUSED(seq);
return 0;
}
......
This diff is collapsed.
......@@ -640,6 +640,8 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
}
}
#else
Q_UNUSED(PIDtype);
#endif // MAVLINK_ENABLED_SLUG
}
......
......@@ -221,7 +221,8 @@ double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2)
*/
QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2)
{
double cateto_opuesto,cateto_adyacente, hipotenusa, distancia, marcacion;
double cateto_opuesto,cateto_adyacente, hipotenusa, distancia;
double marcacion = 0.0;
//latitude and longitude first point
......@@ -234,7 +235,7 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl
cateto_adyacente = abs((lon1-lon2));
hipotenusa = sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
distancia = hipotenusa*60;
distancia = hipotenusa*60.0;
if ((lat1 < lat2) && (lon1 > lon2)) //primer cuadrante
......
......@@ -75,7 +75,7 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
return;
}
double tileResolution;
double tileResolution = 1.0;
if (currentImageryType == GOOGLE_SATELLITE ||
currentImageryType == GOOGLE_MAP)
{
......@@ -131,7 +131,7 @@ Imagery::draw2D(double windowWidth, double windowHeight,
return;
}
double tileResolution;
double tileResolution = 1.0;
if (currentImageryType == GOOGLE_SATELLITE ||
currentImageryType == GOOGLE_MAP)
{
......
......@@ -241,7 +241,7 @@ Pixhawk3DWidget::insertWaypoint(void)
{
if (uas)
{
Waypoint* wp;
Waypoint* wp = NULL;
if (frame == MAV_FRAME_GLOBAL)
{
double latitude = uas->getLatitude();
......
......@@ -59300,9 +59300,10 @@ static GLfloat normals [22155][3] = {
GLfloat textures[1][2]={{0.0f,0.0f}};
/*Material indicies*/
/*{material index,face count}*/
static int material_ref [1][2] = {
{0,77848}
};
//static int material_ref [1][2] = {
//{0,77848}
//};
void MyMaterial(GLenum mode, GLfloat * f, GLfloat alpha)
{
GLfloat d[4];
......@@ -53,7 +53,9 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
{
if (uas)
{
double robotX, robotY, robotZ;
double robotX = 0.0;
double robotY = 0.0;
double robotZ = 0.0;
if (frame == MAV_FRAME_GLOBAL)
{
double latitude = uas->getLatitude();
......
......@@ -215,6 +215,7 @@ void UASView::hideEvent(QHideEvent* event)
void UASView::receiveHeartbeat(UASInterface* uas)
{
Q_UNUSED(uas);
QString colorstyle;
heartbeatColor = QColor(20, 200, 20);
colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}",
......
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