diff --git a/CMakeLists.txt b/CMakeLists.txt index cee5158b395..07cc433d411 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -158,7 +158,7 @@ include(Qt6QGCConfiguration) set(QT_QML_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/qml" CACHE PATH "Install path for QML" FORCE) set(QML_IMPORT_PATH ${CMAKE_SOURCE_DIR}/src ${CMAKE_SOURCE_DIR}/qml ${CMAKE_BINARY_DIR}/imports CACHE STRING "Extra QML Import Paths" FORCE) -add_compile_definitions(QT_DISABLE_DEPRECATED_UP_TO=0x060700) +add_compile_definitions(QT_DISABLE_DEPRECATED_UP_TO=0x060800) if(CMAKE_BUILD_TYPE STREQUAL "Release") add_compile_definitions( diff --git a/src/AnalyzeView/MAVLinkMessage.cc b/src/AnalyzeView/MAVLinkMessage.cc index 29c4d04ce31..03809ecc4c2 100644 --- a/src/AnalyzeView/MAVLinkMessage.cc +++ b/src/AnalyzeView/MAVLinkMessage.cc @@ -12,6 +12,8 @@ #include "QGCLoggingCategory.h" #include "QmlObjectListModel.h" +#include + QGC_LOGGING_CATEGORY(MAVLinkMessageLog, "qgc.analyzeview.mavlinkmessage") QGCMAVLinkMessage::QGCMAVLinkMessage(const mavlink_message_t &message, QObject *parent) @@ -232,7 +234,7 @@ void QGCMAVLinkMessage::_updateFields() uint32_t n; (void) memcpy(&n, msg + offset, sizeof(uint32_t)); if (_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) { - const QDateTime d = QDateTime::fromMSecsSinceEpoch(static_cast(n), Qt::UTC,0); + const QDateTime d = QDateTime::fromMSecsSinceEpoch(static_cast(n), QTimeZone::utc()); field->updateValue(d.toString("HH:mm:ss"), static_cast(n)); } else { field->updateValue(QString::number(n), static_cast(n)); @@ -305,7 +307,7 @@ void QGCMAVLinkMessage::_updateFields() uint64_t n; (void) memcpy(&n, msg + offset, sizeof(uint64_t)); if(_message.msgid == MAVLINK_MSG_ID_SYSTEM_TIME) { - const QDateTime d = QDateTime::fromMSecsSinceEpoch(n / 1000, Qt::UTC, 0); + const QDateTime d = QDateTime::fromMSecsSinceEpoch(n / 1000, QTimeZone::utc()); field->updateValue(d.toString("yyyy MM dd HH:mm:ss"), static_cast(n)); } else { field->updateValue(QString::number(n), static_cast(n)); diff --git a/src/Camera/VehicleCameraControl.cc b/src/Camera/VehicleCameraControl.cc index a77a3952f90..d35af36a277 100644 --- a/src/Camera/VehicleCameraControl.cc +++ b/src/Camera/VehicleCameraControl.cc @@ -780,12 +780,12 @@ VehicleCameraControl::_loadCameraDefinitionFile(QByteArray& bytes) if(!_handleLocalization(bytes)) { return false; } - int errorLine; - QString errorMsg; + QDomDocument doc; - if(!doc.setContent(bytes, false, &errorMsg, &errorLine)) { - qCCritical(CameraControlLog) << "Unable to parse camera definition file on line:" << errorLine; - qCCritical(CameraControlLog) << errorMsg; + const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default); + if (!result) { + qCCritical(CameraControlLog) << "Unable to parse camera definition file on line:" << result.errorLine; + qCCritical(CameraControlLog) << result.errorMessage; return false; } //-- Load camera constants @@ -1059,13 +1059,12 @@ VehicleCameraControl::_loadSettings(const QDomNodeList nodeList) //----------------------------------------------------------------------------- bool VehicleCameraControl::_handleLocalization(QByteArray& bytes) -{ - QString errorMsg; - int errorLine; +{ QDomDocument doc; - if(!doc.setContent(bytes, false, &errorMsg, &errorLine)) { - qCritical() << "Unable to parse camera definition file on line:" << errorLine; - qCritical() << errorMsg; + const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default); + if (!result) { + qCritical() << "Unable to parse camera definition file on line:" << result.errorLine; + qCritical() << result.errorMessage; return false; } //-- Find out where we are @@ -1657,34 +1656,32 @@ VehicleCameraControl::handleTrackingImageStatus(const mavlink_camera_tracking_im void VehicleCameraControl::setCurrentStream(int stream) { - if(stream != _currentStream && stream >= 0 && stream < _streamLabels.count()) { - if(_currentStream != stream) { - QGCVideoStreamInfo* pInfo = currentStreamInstance(); - if(pInfo) { - qCDebug(CameraControlLog) << "Stopping stream:" << pInfo->uri(); - //-- Stop current stream - _vehicle->sendMavCommand( - _compID, // Target component - MAV_CMD_VIDEO_STOP_STREAMING, // Command id - false, // ShowError - pInfo->streamID()); // Stream ID - } - _currentStream = stream; - pInfo = currentStreamInstance(); - if(pInfo) { - //-- Start new stream - qCDebug(CameraControlLog) << "Starting stream:" << pInfo->uri(); - _vehicle->sendMavCommand( - _compID, // Target component - MAV_CMD_VIDEO_START_STREAMING, // Command id - false, // ShowError - pInfo->streamID()); // Stream ID - //-- Update stream status - _requestStreamStatus(static_cast(pInfo->streamID())); - } - emit currentStreamChanged(); - emit _vehicle->cameraManager()->streamChanged(); + if (stream != _currentStream && stream >= 0 && stream < _streamLabels.count()) { + QGCVideoStreamInfo* pInfo = currentStreamInstance(); + if(pInfo) { + qCDebug(CameraControlLog) << "Stopping stream:" << pInfo->uri(); + //-- Stop current stream + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_STOP_STREAMING, // Command id + false, // ShowError + pInfo->streamID()); // Stream ID + } + _currentStream = stream; + pInfo = currentStreamInstance(); + if(pInfo) { + //-- Start new stream + qCDebug(CameraControlLog) << "Starting stream:" << pInfo->uri(); + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_START_STREAMING, // Command id + false, // ShowError + pInfo->streamID()); // Stream ID + //-- Update stream status + _requestStreamStatus(static_cast(pInfo->streamID())); } + emit currentStreamChanged(); + emit _vehicle->cameraManager()->streamChanged(); } } @@ -2056,7 +2053,8 @@ VehicleCameraControl::_handleDefinitionFile(const QString &url) } QByteArray bytes = xmlFile.readAll(); QDomDocument doc; - if(!doc.setContent(bytes, false)) { + const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default); + if (!result) { qWarning() << "Could not parse cached camera definition file:" << _cacheFile; _httpRequest(url); return; diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc index 416b1946b71..a195ddb3148 100644 --- a/src/MissionManager/CameraSection.cc +++ b/src/MissionManager/CameraSection.cc @@ -257,7 +257,7 @@ bool CameraSection::_scanGimbal(QmlObjectListModel* visualItems, int scanIndex) if (item) { MissionItem& missionItem = item->missionItem(); if ((MAV_CMD)item->command() == MAV_CMD_DO_MOUNT_CONTROL) { - if (missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) { + if (missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == static_cast(MAV_MOUNT_MODE_MAVLINK_TARGETING)) { setSpecifyGimbal(true); gimbalPitch()->setRawValue(missionItem.param1()); gimbalYaw()->setRawValue(missionItem.param3()); @@ -434,7 +434,7 @@ bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scan MissionItem& missionItem = item->missionItem(); if ((MAV_CMD)item->command() == MAV_CMD_SET_CAMERA_MODE) { // We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields - if (missionItem.param1() == 0 && (missionItem.param2() == CAMERA_MODE_IMAGE || missionItem.param2() == CAMERA_MODE_VIDEO || missionItem.param2() == CAMERA_MODE_IMAGE_SURVEY) && qIsNaN(missionItem.param3())) { + if (missionItem.param1() == 0 && (missionItem.param2() == static_cast(CAMERA_MODE_IMAGE) || missionItem.param2() == static_cast(CAMERA_MODE_VIDEO) || missionItem.param2() == static_cast(CAMERA_MODE_IMAGE_SURVEY)) && qIsNaN(missionItem.param3())) { setSpecifyCameraMode(true); cameraMode()->setRawValue(missionItem.param2()); visualItems->removeAt(scanIndex)->deleteLater(); diff --git a/src/MissionManager/LandingComplexItem.cc b/src/MissionManager/LandingComplexItem.cc index 0ed8af728b8..a30e1662bd7 100644 --- a/src/MissionManager/LandingComplexItem.cc +++ b/src/MissionManager/LandingComplexItem.cc @@ -447,7 +447,7 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV if (item) { MissionItem& missionItemChangeSpeed = item->missionItem(); if (missionItemChangeSpeed.command() == MAV_CMD_DO_CHANGE_SPEED && - missionItemChangeSpeed.param1() == SPEED_TYPE_AIRSPEED && + missionItemChangeSpeed.param1() == static_cast(SPEED_TYPE_AIRSPEED) && missionItemChangeSpeed.param2() >= -2 && missionItemChangeSpeed.param3() == -1 && missionItemChangeSpeed.param4() == 0) { diff --git a/src/Utilities/KMLHelper.cc b/src/Utilities/KMLHelper.cc index ad9caa64099..46de4e062de 100644 --- a/src/Utilities/KMLHelper.cc +++ b/src/Utilities/KMLHelper.cc @@ -28,10 +28,9 @@ QDomDocument KMLHelper::_loadFile(const QString& kmlFile, QString& errorString) } QDomDocument doc; - QString errorMessage; - int errorLine; - if (!doc.setContent(&file, &errorMessage, &errorLine)) { - errorString = QString(_errorPrefix).arg(tr("Unable to parse KML file: %1 error: %2 line: %3").arg(kmlFile).arg(errorMessage).arg(errorLine)); + const QDomDocument::ParseResult result = doc.setContent(&file, QDomDocument::ParseOption::Default); + if (!result) { + errorString = QString(_errorPrefix).arg(tr("Unable to parse KML file: %1 error: %2 line: %3").arg(kmlFile).arg(result.errorMessage).arg(result.errorLine)); return QDomDocument(); } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 728a123d24b..ab6c8576384 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2382,7 +2382,7 @@ void Vehicle::sendMavCommand(int compId, MAV_CMD command, bool showError, float void Vehicle::sendMavCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1, float param2, float param3, float param4, float param5, float param6, float param7) { - QTimer::singleShot(milliseconds, this, [=] { sendMavCommand(compId, command, showError, param1, param2, param3, param4, param5, param6, param7); }); + QTimer::singleShot(milliseconds, this, [=, this] { sendMavCommand(compId, command, showError, param1, param2, param3, param4, param5, param6, param7); }); } void Vehicle::sendCommand(int compId, int command, bool showError, double param1, double param2, double param3, double param4, double param5, double param6, double param7) diff --git a/test/MissionManager/SimpleMissionItemTest.cc b/test/MissionManager/SimpleMissionItemTest.cc index 77f7eadab68..80b7cc14892 100644 --- a/test/MissionManager/SimpleMissionItemTest.cc +++ b/test/MissionManager/SimpleMissionItemTest.cc @@ -73,7 +73,6 @@ const ItemExpected_t _rgItemExpected[] = { }; SimpleMissionItemTest::SimpleMissionItemTest(void) - : _simpleItem(nullptr) { rgSimpleItemSignals[commandChangedIndex] = SIGNAL(commandChanged(int)); rgSimpleItemSignals[altitudeModeChangedIndex] = SIGNAL(altitudeModeChanged()); diff --git a/test/MissionManager/SimpleMissionItemTest.h b/test/MissionManager/SimpleMissionItemTest.h index 5b476b805e8..6487c0b1c3b 100644 --- a/test/MissionManager/SimpleMissionItemTest.h +++ b/test/MissionManager/SimpleMissionItemTest.h @@ -84,7 +84,7 @@ private slots: void _testEditorFactsWorker (QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t vtolMode, const ItemExpected_t* rgExpected); bool _classMatch (QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t testClass); - SimpleMissionItem* _simpleItem; + SimpleMissionItem* _simpleItem = nullptr; MultiSignalSpy* _spySimpleItem = nullptr; MultiSignalSpy* _spyVisualItem = nullptr; };