From 01fd0113f9f03b76f18ffc52498f9243d4da63e6 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 29 Sep 2014 12:23:11 -0700 Subject: [PATCH] Fix Windows 64 bit warnings --- src/comm/MAVLinkSimulationWaypointPlanner.cc | 4 ++-- src/qgcunittest/MockMavlinkFileServer.cc | 4 ++-- src/uas/QGCUASFileManager.cc | 5 +++-- src/uas/UAS.cc | 2 +- src/ui/QGCMAVLinkInspector.cc | 2 +- src/ui/configuration/FlightModeConfig.cc | 8 ++++---- src/ui/configuration/FlightModeConfig.h | 4 ++-- 7 files changed, 15 insertions(+), 14 deletions(-) diff --git a/src/comm/MAVLinkSimulationWaypointPlanner.cc b/src/comm/MAVLinkSimulationWaypointPlanner.cc index c4cc5fee3..aa6384166 100644 --- a/src/comm/MAVLinkSimulationWaypointPlanner.cc +++ b/src/comm/MAVLinkSimulationWaypointPlanner.cc @@ -890,7 +890,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* } else { if (verbose) qDebug("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid); } - protocol_current_count = waypoints->size(); + protocol_current_count = static_cast(waypoints->size()); send_waypoint_count(msg->sysid,msg->compid, protocol_current_count); } else { if (verbose) qDebug("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST because i'm doing something else already (state=%i).\n", current_state); @@ -999,7 +999,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* send_waypoint_ack(protocol_current_partner_systemid, protocol_current_partner_compid, 0); if (current_active_wp_id > waypoints_receive_buffer->size()-1) { - current_active_wp_id = waypoints_receive_buffer->size() - 1; + current_active_wp_id = static_cast(waypoints_receive_buffer->size()) - 1; } // switch the waypoints list diff --git a/src/qgcunittest/MockMavlinkFileServer.cc b/src/qgcunittest/MockMavlinkFileServer.cc index b52674a25..87f8016d7 100644 --- a/src/qgcunittest/MockMavlinkFileServer.cc +++ b/src/qgcunittest/MockMavlinkFileServer.cc @@ -86,8 +86,8 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request, ui char *bufPtr = (char *)&ackResponse.data[0]; for (int i=0; i<_fileList.size(); i++) { strcpy(bufPtr, _fileList[i].toStdString().c_str()); - size_t cchFilename = strlen(bufPtr); - Q_ASSERT(cchFilename); + uint8_t cchFilename = static_cast(strlen(bufPtr)); + Q_ASSERT(cchFilename); ackResponse.hdr.size += cchFilename + 1; bufPtr += cchFilename + 1; } diff --git a/src/uas/QGCUASFileManager.cc b/src/uas/QGCUASFileManager.cc index cf19f508c..f8b1013e3 100644 --- a/src/uas/QGCUASFileManager.cc +++ b/src/uas/QGCUASFileManager.cc @@ -159,8 +159,9 @@ void QGCUASFileManager::_listAckResponse(Request* listAck) // get the length of the name uint8_t cBytesLeft = cBytes - offset; - size_t nlen = strnlen(ptr, cBytesLeft); + uint8_t nlen = static_cast(strnlen(ptr, cBytesLeft)); if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) { + if (nlen < 2) { _currentOperation = kCOIdle; _emitErrorMessage(tr("Incorrectly formed list entry: '%1'").arg(ptr)); return; @@ -315,7 +316,7 @@ void QGCUASFileManager::listDirectory(const QString& dirPath) void QGCUASFileManager::_fillRequestWithString(Request* request, const QString& str) { strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data)); - request->hdr.size = strnlen((const char *)&request->data[0], sizeof(request->data)); + request->hdr.size = static_cast(strnlen((const char *)&request->data[0], sizeof(request->data))); } void QGCUASFileManager::_sendListCommand(void) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 32143d5cd..692d1b1fa 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1953,7 +1953,7 @@ QImage UAS::getImage() QString header("P5\n%1 %2\n%3\n"); header = header.arg(imageWidth).arg(imageHeight).arg(imgColors); - QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size()); + QByteArray tmpImage(header.toStdString().c_str(), header.length()); tmpImage.append(imageRecBuffer); //qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header; diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index 73f3955e3..fe3c6bb49 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -293,7 +293,7 @@ void QGCMAVLinkInspector::refreshView() { const char* msgname = messageInfo[i].name; - int namelen = strnlen(msgname, 5); + size_t namelen = strnlen(msgname, 5); if (namelen < 3) { continue; diff --git a/src/ui/configuration/FlightModeConfig.cc b/src/ui/configuration/FlightModeConfig.cc index 62a46c7ca..7939fac5b 100644 --- a/src/ui/configuration/FlightModeConfig.cc +++ b/src/ui/configuration/FlightModeConfig.cc @@ -181,9 +181,9 @@ void FlightModeConfig::activeUASSet(UASInterface *uas) } // Set up the combo boxes - for (size_t i=0; i<_cModes; i++) { + for (int i=0; i<_cModes; i++) { // Fill each combo box with the available flight modes - for (size_t j=0; j<_cModeInfo; j++) { + for (int j=0; j<_cModeInfo; j++) { _rgCombo[i]->addItem(_rgModeInfo[j].label, QVariant(QChar((char)_rgModeInfo[j].value))); } @@ -260,13 +260,13 @@ void FlightModeConfig::parameterChanged(int uas, int component, QString paramete } } else { // Loop over the flight mode params looking for a match - for (size_t i=0; i<_cModes; i++) { + for (int i=0; i<_cModes; i++) { if (parameterName == _rgModeParam[i]) { // We found a match, i is now the index of the combo box which displays that mode slot // Loop over the mode info till we find the matching value, this tells us which row in the // combo box to select. QComboBox* combo = _rgCombo[i]; - for (size_t j=0; j<_cModeInfo; j++) { + for (int j=0; j<_cModeInfo; j++) { if (_rgModeInfo[j].value == iValue) { combo->setCurrentIndex(j); return; diff --git a/src/ui/configuration/FlightModeConfig.h b/src/ui/configuration/FlightModeConfig.h index 27cb23a47..81ee2939f 100644 --- a/src/ui/configuration/FlightModeConfig.h +++ b/src/ui/configuration/FlightModeConfig.h @@ -58,9 +58,9 @@ private: static const FlightModeInfo_t _rgModeInfoRotor[]; static const FlightModeInfo_t _rgModeInfoRover[]; const FlightModeInfo_t* _rgModeInfo; - size_t _cModeInfo; + int _cModeInfo; - static const size_t _cModes = 6; + static const int _cModes = 6; static const char* _rgModeParamFixedWing[_cModes]; static const char* _rgModeParamRotor[_cModes]; -- 2.22.0