Unverified Commit 55dd50c1 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8811 from patrickelectric/qt_5_15

Help with Qt 5.15 and 5.14 integration
parents 6db84fcc d111e784
......@@ -1274,17 +1274,26 @@ QGCCameraControl::_processConditionTest(const QString conditionTest)
qCDebug(CameraControlVerboseLog) << "_processConditionTest(" << conditionTest << ")";
int op = TEST_NONE;
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("!=")) {
test = conditionTest.split("!=", QString::SkipEmptyParts);
test = split("!=");
op = TEST_NOT_EQUAL;
} else if(conditionTest.contains("=")) {
test = conditionTest.split("=", QString::SkipEmptyParts);
test = split("=");
op = TEST_EQUAL;
} else if(conditionTest.contains(">")) {
test = conditionTest.split(">", QString::SkipEmptyParts);
test = split(">");
op = TEST_GREATER;
} else if(conditionTest.contains("<")) {
test = conditionTest.split("<", QString::SkipEmptyParts);
test = split("<");
op = TEST_SMALLER;
}
if(test.size() == 2) {
......@@ -1319,7 +1328,11 @@ 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();
......
This diff is collapsed.
......@@ -200,6 +200,62 @@ private:
QVariant _maxForType(void) const;
void _setAppSettingsTranslators(void);
/**
* @brief Clamp a value based in the cookedMin and CookedMax values
*
* @tparam T
* @param variantValue
*/
template<class T>
void clamp(QVariant& variantValue) const {
if (cookedMin().value<T>() > variantValue.value<T>()) {
variantValue = cookedMin();
} else if(variantValue.value<T>() > cookedMax().value<T>()) {
variantValue = cookedMax();
}
}
/**
* @brief Check if value is inside cooked limits
*
* @tparam T
* @param variantValue
*/
template<class T>
bool isInCookedLimit(const QVariant& variantValue) const {
return cookedMin().value<T>() < variantValue.value<T>() && variantValue.value<T>() < cookedMax().value<T>();
}
/**
* @brief Check if value is inside raw limits
*
* @tparam T
* @param variantValue
*/
template<class T>
bool isInRawLimit(const QVariant& variantValue) const {
return rawMin().value<T>() <= variantValue.value<T>() && variantValue.value<T>() < rawMax().value<T>();
}
/**
* @brief Check if value if over min limit
*
* @param variantValue
* @return true
* @return false
*/
bool isInRawMinLimit(const QVariant& variantValue) const;
/**
* @brief Check if value is lower than upper limit
*
* @param variantValue
* @return true
* @return false
*/
bool isInRawMaxLimit(const QVariant& variantValue) const;
// Built in translators
static QVariant _defaultTranslator(const QVariant& from) { return from; }
static QVariant _degreesToRadians(const QVariant& degrees);
......
......@@ -793,7 +793,11 @@ void APMFirmwarePlugin::_soloVideoHandshake(Vehicle* vehicle, bool originalSoloF
socket->connectToHost(_artooIP, _artooVideoHandshakePort);
if (originalSoloFirmware) {
#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
}
}
......
......@@ -170,7 +170,11 @@ bool JsonHelper::_parseEnumWorker(const QJsonObject& jsonObject, QMap<QString, Q
} else {
// "enumStrings": "Auto,Manual,Shutter Priority,Aperture Priority",
QString value = jsonObject.value(_enumStringsJsonKey).toString();
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
enumStrings = defineMap.value(value, value).split(",", QString::SkipEmptyParts);
#else
enumStrings = defineMap.value(value, value).split(",", Qt::SkipEmptyParts);
#endif
}
if(jsonObject.value(_enumValuesJsonKey).isArray()) {
......@@ -186,7 +190,11 @@ bool JsonHelper::_parseEnumWorker(const QJsonObject& jsonObject, QMap<QString, Q
} else {
// "enumValues": "0,1,2,3,4,5",
QString value = jsonObject.value(_enumValuesJsonKey).toString();
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
enumValues = defineMap.value(value, value).split(",", QString::SkipEmptyParts);
#else
enumValues = defineMap.value(value, value).split(",", Qt::SkipEmptyParts);
#endif
}
if (enumStrings.count() != enumValues.count()) {
......
......@@ -55,7 +55,11 @@ 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");
......
......@@ -15,6 +15,7 @@
#include "FlightPathSegment.h"
#include "MissionController.h"
#include <QCborValue>
#include <QSettings>
const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType";
......@@ -78,7 +79,7 @@ void ComplexMissionItem::_savePresetJson(const QString& name, QJsonObject& prese
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
settings.setValue(name, QJsonDocument(presetObject).toBinaryData());
settings.setValue(name, QCborMap::fromJsonObject(presetObject).toCborValue().toByteArray());
// 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.
......@@ -107,7 +108,7 @@ QJsonObject ComplexMissionItem::_loadPresetJson(const QString& name)
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
return QJsonDocument::fromBinaryData(settings.value(name).toByteArray()).object();
return QCborValue(settings.value(name).toByteArray()).toMap().toJsonObject();
}
void ComplexMissionItem::addKMLVisuals(KMLPlanDomDocument& /* domDocument */)
......
......@@ -384,10 +384,14 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
paramInfo->_label = paramObject.value(_labelJsonKey).toString();
paramInfo->_decimalPlaces = paramObject.value(_decimalPlacesJsonKey).toInt(FactMetaData::kUnknownDecimalPlaces);
paramInfo->_enumStrings = paramObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
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) {
......@@ -402,8 +406,11 @@ 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);
......
......@@ -453,7 +453,12 @@ 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 (rgOffsetEdges[prevIndex].intersect(rgOffsetEdges[i], &newVertex) == QLineF::NoIntersection) {
#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");
return;
......
......@@ -329,7 +329,12 @@ 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 (rgOffsetEdges[i - 1].intersect(rgOffsetEdges[i], &newVertex) == QLineF::NoIntersection) {
#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();
}
......
......@@ -520,12 +520,20 @@ void SurveyComplexItem::_intersectLinesWithRect(const QList<QLineF>& lineList, c
QLineF intersectLine;
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;
if (line.intersect(topLine, &intersectPoint) == QLineF::BoundedIntersection) {
if (isLineBoundedIntersect(topLine)) {
intersectLine.setP1(intersectPoint);
foundCount++;
}
if (line.intersect(rightLine, &intersectPoint) == QLineF::BoundedIntersection) {
if (isLineBoundedIntersect(rightLine)) {
if (foundCount == 0) {
intersectLine.setP1(intersectPoint);
} else {
......@@ -536,7 +544,7 @@ void SurveyComplexItem::_intersectLinesWithRect(const QList<QLineF>& lineList, c
}
foundCount++;
}
if (line.intersect(bottomLine, &intersectPoint) == QLineF::BoundedIntersection) {
if (isLineBoundedIntersect(bottomLine)) {
if (foundCount == 0) {
intersectLine.setP1(intersectPoint);
} else {
......@@ -547,7 +555,7 @@ void SurveyComplexItem::_intersectLinesWithRect(const QList<QLineF>& lineList, c
}
foundCount++;
}
if (line.intersect(leftLine, &intersectPoint) == QLineF::BoundedIntersection) {
if (isLineBoundedIntersect(leftLine)) {
if (foundCount == 0) {
intersectLine.setP1(intersectPoint);
} else {
......@@ -577,7 +585,13 @@ void SurveyComplexItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList
for (int j=0; j<polygon.count()-1; j++) {
QPointF intersectPoint;
QLineF polygonLine = QLineF(polygon[j], polygon[j+1]);
if (line.intersect(polygonLine, &intersectPoint) == QLineF::BoundedIntersection) {
#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);
}
......@@ -1102,7 +1116,12 @@ bool SurveyComplexItem::_VertexCanSeeOther(const QPolygonF& polygon, const QPoin
if (vertexD == vertexB) continue;
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());
......
......@@ -24,5 +24,9 @@ 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
}
......@@ -83,9 +83,12 @@ 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;
}
......
......@@ -18,6 +18,7 @@
#include "QGCTemporaryFile.h"
#include <QDir>
#include <QRandomGenerator>
#include <QStandardPaths>
QGCTemporaryFile::QGCTemporaryFile(const QString& fileTemplate, QObject* parent) :
......@@ -40,7 +41,7 @@ bool QGCTemporaryFile::open(QFile::OpenMode openMode)
do {
QString uniqueStr;
for (int i=0; i<6; i++) {
uniqueStr += rgDigits[qrand() % 10];
uniqueStr += rgDigits[QRandomGenerator::global()->generate() % 10];
}
if (_template.contains("XXXXXX")) {
......
......@@ -168,7 +168,12 @@ bool ParameterEditorController::_shouldShow(Fact* fact)
void ParameterEditorController::_updateParameters(void)
{
QObjectList newParameterList;
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
QStringList searchItems = _searchText.split(' ', QString::SkipEmptyParts);
#else
QStringList searchItems = _searchText.split(' ', Qt::SkipEmptyParts);
#endif
if (searchItems.isEmpty() && !_showModifiedOnly) {
int compId = _parameterMgr->getComponentId(_currentCategory);
......
......@@ -221,7 +221,13 @@ bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPo
{
QPointF intersectPoint;
return QLineF(line1A, line1B).intersect(QLineF(line2A, line2B), &intersectPoint) == QLineF::BoundedIntersection &&
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 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;
}
......
......@@ -116,7 +116,11 @@ 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);
}
}
......
......@@ -250,7 +250,11 @@ 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);
......
......@@ -243,7 +243,13 @@ MAV_TYPE AppSettings::offlineEditingVehicleTypeFromVehicleType(MAV_TYPE vehicleT
QList<int> AppSettings::firstRunPromptsIdsVariantToList(const QVariant& firstRunPromptIds)
{
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());
}
......
......@@ -127,7 +127,12 @@ 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)
......
......@@ -150,7 +150,7 @@ MAVLinkLogProcessor::valid()
bool
MAVLinkLogProcessor::create(MAVLinkLogManager* manager, const QString path, uint8_t id)
{
_fileName.sprintf("%s/%03d-%s%s",
_fileName.asprintf("%s/%03d-%s%s",
path.toLatin1().data(),
id,
QDateTime::currentDateTime().toString("yyyy-MM-dd-hh-mm-ss-zzz").toLocal8Bit().data(),
......
......@@ -1535,7 +1535,7 @@ QString Vehicle::vehicleUIDStr()
{
QString uid;
uint8_t* pUid = (uint8_t*)(void*)&_uid;
uid.sprintf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
uid.asprintf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
pUid[0] & 0xff,
pUid[1] & 0xff,
pUid[2] & 0xff,
......@@ -4102,8 +4102,7 @@ QString Vehicle::hobbsMeter()
int hours = hobbsTimeSeconds / 3600;
int minutes = (hobbsTimeSeconds % 3600) / 60;
int seconds = hobbsTimeSeconds % 60;
QString timeStr;
timeStr.sprintf("%04d:%02d:%02d", hours, minutes, seconds);
QString timeStr = QString::asprintf("%04d:%02d:%02d", hours, minutes, seconds);
qCDebug(VehicleLog) << "Hobbs Meter:" << timeStr << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
return timeStr;
}
......
......@@ -150,12 +150,21 @@ bool TCPLink::_hardwareConnect()
Q_ASSERT(_socket == nullptr);
_socket = new QTcpSocket();
#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
_socket->connectToHost(_tcpConfig->address(), _tcpConfig->port());
QObject::connect(_socket, &QTcpSocket::readyRead, this, &TCPLink::readBytes);
#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
// Give the socket a second to connect to the other side otherwise error out
if (!_socket->waitForConnected(1000))
......@@ -320,7 +329,7 @@ void TCPConfiguration::loadSettings(QSettings& settings, const QString& root)
settings.beginGroup(root);
_port = (quint16)settings.value("port", QGC_TCP_PORT).toUInt();
QString address = settings.value("host", _address.toString()).toString();
_address = address;
_address = QHostAddress(address);
settings.endGroup();
}
......
......@@ -20,6 +20,7 @@
#include "AppSettings.h"
#include "SettingsManager.h"
#include <QRandomGenerator>
#include <QTemporaryFile>
#include <QTime>
......@@ -464,12 +465,12 @@ QString UnitTest::createRandomFile(uint32_t byteCount)
QTemporaryFile tempFile;
QTime time = QTime::currentTime();
qsrand((uint)time.msec());
QRandomGenerator::global()->seed(time.msec());
tempFile.setAutoRemove(false);
if (tempFile.open()) {
for (uint32_t bytesWritten=0; bytesWritten<byteCount; bytesWritten++) {
unsigned char byte = (qrand() * 0xFF) / RAND_MAX;
unsigned char byte = (QRandomGenerator::global()->generate() * 0xFF) / RAND_MAX;
tempFile.write((char *)&byte, 1);
}
tempFile.close();
......
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