Browse Source

Remove back compat for < Qt 5.15

QGC4.4
Don Gagne 4 years ago committed by Don Gagne
parent
commit
07259f7f02
  1. 8
      src/Camera/QGCCameraControl.cc
  2. 8
      src/FactSystem/FactMetaData.cc
  3. 4
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  4. 4
      src/LogCompressor.cc
  5. 8
      src/MissionManager/ComplexMissionItem.cc
  6. 8
      src/MissionManager/MissionCommandUIInfo.cc
  7. 4
      src/MissionManager/QGCMapPolygon.cc
  8. 4
      src/MissionManager/QGCMapPolyline.cc
  9. 12
      src/MissionManager/SurveyComplexItem.cc
  10. 4
      src/QGCComboBox.cc
  11. 4
      src/QGCFileDownload.cc
  12. 5
      src/QmlControls/ParameterEditorController.cc
  13. 4
      src/QmlControls/QGroundControlQmlGlobal.cc
  14. 4
      src/QtLocationPlugin/GoogleMapProvider.cpp
  15. 4
      src/QtLocationPlugin/QGCMapTileSet.cpp
  16. 4
      src/QtLocationPlugin/QGCTileCacheWorker.cpp
  17. 4
      src/Settings/AppSettings.cc
  18. 4
      src/Terrain/TerrainQuery.cc
  19. 4
      src/Vehicle/FTPManagerTest.h
  20. 2
      src/Vehicle/MAVLinkLogManager.cc
  21. 6
      src/comm/MockLinkFTP.cc
  22. 9
      src/comm/TCPLink.cc

8
src/Camera/QGCCameraControl.cc

@ -1278,11 +1278,7 @@ QGCCameraControl::_processConditionTest(const QString conditionTest) @@ -1278,11 +1278,7 @@ QGCCameraControl::_processConditionTest(const QString conditionTest)
QStringList test;
auto split = [&conditionTest](const QString& sep ) {
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
return conditionTest.split(sep, QString::SkipEmptyParts);
#else
return conditionTest.split(sep, Qt::SkipEmptyParts);
#endif
};
if(conditionTest.contains("!=")) {
@ -1330,11 +1326,7 @@ QGCCameraControl::_processCondition(const QString condition) @@ -1330,11 +1326,7 @@ QGCCameraControl::_processCondition(const QString condition)
bool result = true;
bool andOp = true;
if(!condition.isEmpty()) {
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QStringList scond = condition.split(" ", QString::SkipEmptyParts);
#else
QStringList scond = condition.split(" ", Qt::SkipEmptyParts);
#endif
while(scond.size()) {
QString test = scond.first();
scond.removeFirst();

8
src/FactSystem/FactMetaData.cc

@ -1531,18 +1531,10 @@ bool FactMetaData::_parseEnum(const QJsonObject& jsonObject, DefineMap_t defineM @@ -1531,18 +1531,10 @@ bool FactMetaData::_parseEnum(const QJsonObject& jsonObject, DefineMap_t defineM
}
QString strings = jsonObject.value(_enumStringsJsonKey).toString();
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
rgDescriptions = defineMap.value(strings, strings).split(",", QString::SkipEmptyParts);
#else
rgDescriptions = defineMap.value(strings, strings).split(",", Qt::SkipEmptyParts);
#endif
QString values = jsonObject.value(_enumValuesJsonKey).toString();
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
rgValues = defineMap.value(values, values).split(",", QString::SkipEmptyParts);
#else
rgValues = defineMap.value(values, values).split(",", Qt::SkipEmptyParts);
#endif
if (rgDescriptions.count() != rgValues.count()) {
errorString = QStringLiteral("Enum strings/values count mismatch - strings:values %1:%2").arg(rgDescriptions.count()).arg(rgValues.count());

4
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -639,11 +639,7 @@ void APMFirmwarePlugin::_soloVideoHandshake(void) @@ -639,11 +639,7 @@ void APMFirmwarePlugin::_soloVideoHandshake(void)
{
QTcpSocket* socket = new QTcpSocket(this);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QObject::connect(socket, static_cast<void (QTcpSocket::*)(QAbstractSocket::SocketError)>(&QTcpSocket::error), this, &APMFirmwarePlugin::_artooSocketError);
#else
QObject::connect(socket, &QAbstractSocket::errorOccurred, this, &APMFirmwarePlugin::_artooSocketError);
#endif
socket->connectToHost(_artooIP, _artooVideoHandshakePort);
}

4
src/LogCompressor.cc

@ -55,11 +55,7 @@ void LogCompressor::run() @@ -55,11 +55,7 @@ void LogCompressor::run()
QString outFileName;
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QStringList parts = QFileInfo(infile.fileName()).absoluteFilePath().split(".", QString::SkipEmptyParts);
#else
QStringList parts = QFileInfo(infile.fileName()).absoluteFilePath().split(".", Qt::SkipEmptyParts);
#endif
parts.replace(0, parts.first() + "_compressed");
parts.replace(parts.size()-1, "txt");

8
src/MissionManager/ComplexMissionItem.cc

@ -82,11 +82,7 @@ void ComplexMissionItem::_savePresetJson(const QString& name, QJsonObject& prese @@ -82,11 +82,7 @@ void ComplexMissionItem::_savePresetJson(const QString& name, QJsonObject& prese
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
settings.setValue(name, QJsonDocument(presetObject).toBinaryData());
#else
settings.setValue(name, QCborMap::fromJsonObject(presetObject).toCborValue().toVariant());
#endif
// Use this to save a survey preset as a JSON file to be included in the build
// as a built-in survey preset that cannot be deleted.
@ -115,11 +111,7 @@ QJsonObject ComplexMissionItem::_loadPresetJson(const QString& name) @@ -115,11 +111,7 @@ QJsonObject ComplexMissionItem::_loadPresetJson(const QString& name)
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
return QJsonDocument::fromBinaryData(settings.value(name).toByteArray()).object();
#else
return QCborValue::fromVariant(settings.value(name)).toMap().toJsonObject();
#endif
}
void ComplexMissionItem::addKMLVisuals(KMLPlanDomDocument& /* domDocument */)

8
src/MissionManager/MissionCommandUIInfo.cc

@ -403,11 +403,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ @@ -403,11 +403,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
paramInfo->_param = i;
paramInfo->_units = paramObject.value(_unitsJsonKey).toString();
paramInfo->_nanUnchanged = paramObject.value(_nanUnchangedJsonKey).toBool(false);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
paramInfo->_enumStrings = paramObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
#else
paramInfo->_enumStrings = paramObject.value(_enumStringsJsonKey).toString().split(",", Qt::SkipEmptyParts);
#endif
if (paramObject.contains(_defaultJsonKey)) {
if (paramInfo->_nanUnchanged) {
@ -422,11 +418,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ @@ -422,11 +418,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
} else {
paramInfo->_defaultValue = paramInfo->_nanUnchanged ? std::numeric_limits<double>::quiet_NaN() : 0;
}
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
#else
QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", Qt::SkipEmptyParts);
#endif
for (const QString &enumValue: enumValues) {
bool convertOk;
double value = enumValue.toDouble(&convertOk);

4
src/MissionManager/QGCMapPolygon.cc

@ -462,11 +462,7 @@ void QGCMapPolygon::offset(double distance) @@ -462,11 +462,7 @@ void QGCMapPolygon::offset(double distance)
QGeoCoordinate tangentOrigin = vertexCoordinate(0);
for (int i=0; i<rgOffsetEdges.count(); i++) {
int prevIndex = i == 0 ? rgOffsetEdges.count() - 1 : i - 1;
#if QT_VERSION < QT_VERSION_CHECK(5, 14, 0)
auto intersect = rgOffsetEdges[prevIndex].intersect(rgOffsetEdges[i], &newVertex);
#else
auto intersect = rgOffsetEdges[prevIndex].intersects(rgOffsetEdges[i], &newVertex);
#endif
if (intersect == QLineF::NoIntersection) {
// FIXME: Better error handling?
qWarning("Intersection failed");

4
src/MissionManager/QGCMapPolyline.cc

@ -334,11 +334,7 @@ QList<QGeoCoordinate> QGCMapPolyline::offsetPolyline(double distance) @@ -334,11 +334,7 @@ QList<QGeoCoordinate> QGCMapPolyline::offsetPolyline(double distance)
// Intersect the offset edges to generate new central vertices
QPointF newVertex;
for (int i=1; i<rgOffsetEdges.count(); i++) {
#if QT_VERSION < QT_VERSION_CHECK(5, 14, 0)
auto intersect = rgOffsetEdges[i - 1].intersect(rgOffsetEdges[i], &newVertex);
#else
auto intersect = rgOffsetEdges[i - 1].intersects(rgOffsetEdges[i], &newVertex);
#endif
if (intersect == QLineF::NoIntersection) {
// Two lines are colinear
newVertex = rgOffsetEdges[i].p2();

12
src/MissionManager/SurveyComplexItem.cc

@ -521,11 +521,7 @@ void SurveyComplexItem::_intersectLinesWithRect(const QList<QLineF>& lineList, c @@ -521,11 +521,7 @@ void SurveyComplexItem::_intersectLinesWithRect(const QList<QLineF>& lineList, c
const QLineF& line = lineList[i];
auto isLineBoundedIntersect = [&line, &intersectPoint](const QLineF& linePosition) {
#if QT_VERSION < QT_VERSION_CHECK(5, 14, 0)
return line.intersect(linePosition, &intersectPoint) == QLineF::BoundedIntersection;
#else
return line.intersects(linePosition, &intersectPoint) == QLineF::BoundedIntersection;
#endif
};
int foundCount = 0;
@ -586,11 +582,7 @@ void SurveyComplexItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList @@ -586,11 +582,7 @@ void SurveyComplexItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList
QPointF intersectPoint;
QLineF polygonLine = QLineF(polygon[j], polygon[j+1]);
#if QT_VERSION < QT_VERSION_CHECK(5, 14, 0)
auto intersect = line.intersect(polygonLine, &intersectPoint);
#else
auto intersect = line.intersects(polygonLine, &intersectPoint);
#endif
if (intersect == QLineF::BoundedIntersection) {
if (!intersections.contains(intersectPoint)) {
intersections.append(intersectPoint);
@ -1105,11 +1097,7 @@ bool SurveyComplexItem::_VertexCanSeeOther(const QPolygonF& polygon, const QPoin @@ -1105,11 +1097,7 @@ bool SurveyComplexItem::_VertexCanSeeOther(const QPolygonF& polygon, const QPoin
QLineF lineCD(*vertexC, *vertexD);
QPointF intersection{};
#if QT_VERSION < QT_VERSION_CHECK(5, 14, 0)
auto intersects = lineAB.intersect(lineCD, &intersection);
#else
auto intersects = lineAB.intersects(lineCD, &intersection);
#endif
if (intersects == QLineF::IntersectType::BoundedIntersection) {
// auto diffIntersection = *vertexA - intersection;
// auto distanceIntersection = sqrtf(diffIntersection.x() * diffIntersection.x() + diffIntersection.y()*diffIntersection.y());

4
src/QGCComboBox.cc

@ -24,9 +24,5 @@ void QGCComboBox::simulateUserSetCurrentIndex(int index) @@ -24,9 +24,5 @@ void QGCComboBox::simulateUserSetCurrentIndex(int index)
// We have to manually signal activated
emit activated(index);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
emit activated(itemText(index));
#else
emit textActivated(itemText(index));
#endif
}

4
src/QGCFileDownload.cc

@ -57,11 +57,7 @@ bool QGCFileDownload::download(const QString& remoteFile, bool redirect) @@ -57,11 +57,7 @@ bool QGCFileDownload::download(const QString& remoteFile, bool redirect)
connect(networkReply, &QNetworkReply::downloadProgress, this, &QGCFileDownload::downloadProgress);
connect(networkReply, &QNetworkReply::finished, this, &QGCFileDownload::_downloadFinished);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
connect(networkReply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &QGCFileDownload::_downloadError);
#else
connect(networkReply, &QNetworkReply::errorOccurred, this, &QGCFileDownload::_downloadError);
#endif
return true;
}

5
src/QmlControls/ParameterEditorController.cc

@ -365,12 +365,7 @@ void ParameterEditorController::_searchTextChanged(void) @@ -365,12 +365,7 @@ void ParameterEditorController::_searchTextChanged(void)
{
QObjectList newParameterList;
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QStringList rgSearchStrings = _searchText.split(' ', QString::SkipEmptyParts);
#else
QStringList rgSearchStrings = _searchText.split(' ', Qt::SkipEmptyParts);
#endif
if (rgSearchStrings.isEmpty() && !_showModifiedOnly) {
ParameterEditorCategory* category = _categories.count() ? _categories.value<ParameterEditorCategory*>(0) : nullptr;

4
src/QmlControls/QGroundControlQmlGlobal.cc

@ -209,11 +209,7 @@ bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPo @@ -209,11 +209,7 @@ bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPo
{
QPointF intersectPoint;
#if QT_VERSION < QT_VERSION_CHECK(5, 14, 0)
auto intersect = QLineF(line1A, line1B).intersect(QLineF(line2A, line2B), &intersectPoint);
#else
auto intersect = QLineF(line1A, line1B).intersects(QLineF(line2A, line2B), &intersectPoint);
#endif
return intersect == QLineF::BoundedIntersection &&
intersectPoint != line1A && intersectPoint != line1B;

4
src/QtLocationPlugin/GoogleMapProvider.cpp

@ -116,11 +116,7 @@ void GoogleMapProvider::_tryCorrectGoogleVersions(QNetworkAccessManager* network @@ -116,11 +116,7 @@ void GoogleMapProvider::_tryCorrectGoogleVersions(QNetworkAccessManager* network
_googleReply = networkManager->get(qheader);
connect(_googleReply, &QNetworkReply::finished, this, &GoogleMapProvider::_googleVersionCompleted);
connect(_googleReply, &QNetworkReply::destroyed, this, &GoogleMapProvider::_replyDestroyed);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
connect(_googleReply, QOverload<QNetworkReply::NetworkError>::of(&QNetworkReply::error), this, &GoogleMapProvider::_networkReplyError);
#else
connect(_googleReply, &QNetworkReply::errorOccurred, this, &GoogleMapProvider::_networkReplyError);
#endif
networkManager->setProxy(proxy);
}
}

4
src/QtLocationPlugin/QGCMapTileSet.cpp

@ -250,11 +250,7 @@ void QGCCachedTileSet::_prepareDownload() @@ -250,11 +250,7 @@ void QGCCachedTileSet::_prepareDownload()
QNetworkReply* reply = _networkManager->get(request);
reply->setParent(0);
connect(reply, &QNetworkReply::finished, this, &QGCCachedTileSet::_networkReplyFinished);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
connect(reply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &QGCCachedTileSet::_networkReplyError);
#else
connect(reply, &QNetworkReply::errorOccurred, this, &QGCCachedTileSet::_networkReplyError);
#endif
_replies.insert(tile->hash(), reply);
#if !defined(__mobile__)
_networkManager->setProxy(proxy);

4
src/QtLocationPlugin/QGCTileCacheWorker.cpp

@ -1194,11 +1194,7 @@ QGCCacheWorker::_lookupReady(QHostInfo info) @@ -1194,11 +1194,7 @@ QGCCacheWorker::_lookupReady(QHostInfo info)
emit internetStatus(true);
socket->deleteLater();
});
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
connect(socket, QOverload<QAbstractSocket::SocketError>::of(&QAbstractSocket::error), this, [this, socket](QAbstractSocket::SocketError error) {
#else
connect(socket, &QAbstractSocket::errorOccurred, this, [this, socket](QAbstractSocket::SocketError error) {
#endif
qCDebug(QGCTileCacheLog) << "No internet connection, reason:" << error;
emit internetStatus(false);
socket->deleteLater();

4
src/Settings/AppSettings.cc

@ -249,11 +249,7 @@ QList<int> AppSettings::firstRunPromptsIdsVariantToList(const QVariant& firstRun @@ -249,11 +249,7 @@ QList<int> AppSettings::firstRunPromptsIdsVariantToList(const QVariant& firstRun
{
QList<int> rgIds;
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QStringList strIdList = firstRunPromptIds.toString().split(",", QString::SkipEmptyParts);
#else
QStringList strIdList = firstRunPromptIds.toString().split(",", Qt::SkipEmptyParts);
#endif
for (const QString& strId: strIdList) {
rgIds.append(strId.toInt());

4
src/Terrain/TerrainQuery.cc

@ -128,11 +128,7 @@ void TerrainAirMapQuery::_sendQuery(const QString& path, const QUrlQuery& urlQue @@ -128,11 +128,7 @@ void TerrainAirMapQuery::_sendQuery(const QString& path, const QUrlQuery& urlQue
connect(networkReply, &QNetworkReply::finished, this, &TerrainAirMapQuery::_requestFinished);
connect(networkReply, &QNetworkReply::sslErrors, this, &TerrainAirMapQuery::_sslErrors);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
connect(networkReply, QOverload<QNetworkReply::NetworkError>::of(&QNetworkReply::error), this, &TerrainAirMapQuery::_requestError);
#else
connect(networkReply, &QNetworkReply::errorOccurred, this, &TerrainAirMapQuery::_requestError);
#endif
}
void TerrainAirMapQuery::_requestError(QNetworkReply::NetworkError code)

4
src/Vehicle/FTPManagerTest.h

@ -16,14 +16,14 @@ class FTPManagerTest : public UnitTest @@ -16,14 +16,14 @@ class FTPManagerTest : public UnitTest
Q_OBJECT
private slots:
void _performSizeBasedTestCases (void);
void _performTestCases (void);
void _testLostPackets (void);
// Overrides from UnitTest
void cleanup(void) override;
private:
void _performSizeBasedTestCases (void);
void _performTestCases (void);
typedef struct {
const char* file;
} TestCase_t;

2
src/Vehicle/MAVLinkLogManager.cc

@ -742,9 +742,7 @@ MAVLinkLogManager::_sendLog(const QString& logFile) @@ -742,9 +742,7 @@ MAVLinkLogManager::_sendLog(const QString& logFile)
multiPart->append(logPart);
file->setParent(multiPart);
QNetworkRequest request(_uploadURL);
#if QT_VERSION > 0x050600
request.setAttribute(QNetworkRequest::RedirectPolicyAttribute, true);
#endif
QNetworkReply* reply = _nam->post(request, multiPart);
connect(reply, &QNetworkReply::finished, this, &MAVLinkLogManager::_uploadFinished);
connect(this, &MAVLinkLogManager::abortUpload, reply, &QNetworkReply::abort);

6
src/comm/MockLinkFTP.cc

@ -281,7 +281,8 @@ void MockLinkFTP::mavlinkMessageReceived(const mavlink_message_t& message) @@ -281,7 +281,8 @@ void MockLinkFTP::mavlinkMessageReceived(const mavlink_message_t& message)
MavlinkFTP::Request* request = (MavlinkFTP::Request*)&requestFTP.payload[0];
if (_randomDropsEnabled) {
// kCmdOpenFileRO and kCmdResetSessions don't support retry so we can't drop those
if (_randomDropsEnabled && request->hdr.opcode != MavlinkFTP::kCmdOpenFileRO && request->hdr.opcode != MavlinkFTP::kCmdResetSessions) {
if ((rand() % 5) == 0) {
qDebug() << "MockLinkFTP: Random drop of incoming packet";
return;
@ -406,7 +407,8 @@ void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentI @@ -406,7 +407,8 @@ void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentI
targetComponentId,
(uint8_t*)request); // Payload
if (_randomDropsEnabled) {
// kCmdOpenFileRO and kCmdResetSessions don't support retry so we can't drop those
if (_randomDropsEnabled && request->hdr.req_opcode != MavlinkFTP::kCmdOpenFileRO && request->hdr.req_opcode != MavlinkFTP::kCmdResetSessions) {
if ((rand() % 5) == 0) {
qDebug() << "MockLinkFTP: Random drop of outgoing packet";
return;

9
src/comm/TCPLink.cc

@ -114,17 +114,8 @@ bool TCPLink::_hardwareConnect() @@ -114,17 +114,8 @@ bool TCPLink::_hardwareConnect()
_socket = new QTcpSocket();
QObject::connect(_socket, &QIODevice::readyRead, this, &TCPLink::_readBytes);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QSignalSpy errorSpy(_socket, static_cast<void (QTcpSocket::*)(QAbstractSocket::SocketError)>(&QTcpSocket::error));
#else
QSignalSpy errorSpy(_socket, &QAbstractSocket::errorOccurred);
#endif
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QObject::connect(_socket,static_cast<void (QTcpSocket::*)(QAbstractSocket::SocketError)>(&QTcpSocket::error),
this, &TCPLink::_socketError);
#else
QObject::connect(_socket, &QAbstractSocket::errorOccurred, this, &TCPLink::_socketError);
#endif
_socket->connectToHost(_tcpConfig->address(), _tcpConfig->port());

Loading…
Cancel
Save