diff --git a/src/ADSB/ADSBVehicleManager.cc b/src/ADSB/ADSBVehicleManager.cc index f275de94075fc58dcbad7864ebd8327ec8785379..bd5aaf655ab2d11867aaa9f72918cd130f86a0cb 100644 --- a/src/ADSB/ADSBVehicleManager.cc +++ b/src/ADSB/ADSBVehicleManager.cc @@ -66,7 +66,7 @@ void ADSBVehicleManager::adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehi void ADSBVehicleManager::_tcpError(const QString errorMsg) { - qgcApp()->showMessage(tr("ADSB Server Error: %1").arg(errorMsg)); + qgcApp()->showAppMessage(tr("ADSB Server Error: %1").arg(errorMsg)); } diff --git a/src/Airmap/AirMapManager.cc b/src/Airmap/AirMapManager.cc index b3cb121863deb53d05600b05bb5d1cf9e458d60d..56681fa338e63cef8ddff95b167d1248f7f34b3a 100644 --- a/src/Airmap/AirMapManager.cc +++ b/src/Airmap/AirMapManager.cc @@ -89,7 +89,7 @@ void AirMapManager::_error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails) { qCDebug(AirMapManagerLog) << "Error: "<showMessage(QString("Error: %1. %2").arg(what).arg(airmapdMessage)); + qgcApp()->showAppMessage(QString("Error: %1. %2").arg(what).arg(airmapdMessage)); } //----------------------------------------------------------------------------- diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc index 1823c3eac362c82d080749453fc450a36b774f41..84cce217fbf51234ac26ce9fc212ffc53e129449 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc @@ -254,7 +254,7 @@ void APMAirframeComponentController::_githubJsonDownloadFinished(QString remoteF void APMAirframeComponentController::_githubJsonDownloadError(QString errorMsg) { - qgcApp()->showMessage(tr("Param file github json download failed: %1").arg(errorMsg)); + qgcApp()->showAppMessage(tr("Param file github json download failed: %1").arg(errorMsg)); qgcApp()->restoreOverrideCursor(); } @@ -267,7 +267,7 @@ void APMAirframeComponentController::_paramFileDownloadFinished(QString remoteFi void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg) { - qgcApp()->showMessage(tr("Param file download failed: %1").arg(errorMsg)); + qgcApp()->showAppMessage(tr("Param file download failed: %1").arg(errorMsg)); qgcApp()->restoreOverrideCursor(); } diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index 5209e106597d2d04e1e3956148eec0e45359c595..8accdb18e28527758cd94091c41825d4c67ecec6 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -218,7 +218,7 @@ void APMAutoPilotPlugin::_checkForBadCubeBlack(void) if (paramMgr->parameterExists(-1, paramAcc3) && paramMgr->getParameter(-1, paramAcc3)->rawValue().toInt() == 0 && paramMgr->parameterExists(-1, paramGyr3) && paramMgr->getParameter(-1, paramGyr3)->rawValue().toInt() == 0 && paramMgr->parameterExists(-1, paramEnableMask) && paramMgr->getParameter(-1, paramEnableMask)->rawValue().toInt() >= 7) { - qgcApp()->showMessage(tr("WARNING: The flight board you are using has a critical service bulletin against it which advises against flying. For details see: https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406")); + qgcApp()->showAppMessage(tr("WARNING: The flight board you are using has a critical service bulletin against it which advises against flying. For details see: https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406")); } } diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index 197c1a6841e1f3cd890476498473e51572ad5d69..2bd404b5d581e7ccda95d58dbbbf883bb462e1d0 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -196,7 +196,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll default: // Assume failed _hideAllCalAreas(); - qgcApp()->showMessage(tr("Calibration failed. Calibration log will be displayed.")); + qgcApp()->showAppMessage(tr("Calibration failed. Calibration log will be displayed.")); break; } diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index cdae620b9ba179d1e88e5c83aa41b632491e0c54..6c1d860f72881a26d99d45e555b2ce9b1a1cdcb8 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -71,7 +71,7 @@ void AutoPilotPlugin::parametersReadyPreChecks(void) } if (!_setupComplete) { - qgcApp()->showMessage(tr("One or more vehicle components require setup prior to flight.")); + qgcApp()->showAppMessage(tr("One or more vehicle components require setup prior to flight.")); // Take the user to Vehicle Summary qgcApp()->showSetupView(); diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.cc b/src/AutoPilotPlugins/Common/RadioComponentController.cc index 59864def032c5ee1475a8f2fcf46c36cf1612b8f..3598f99031a19af334a8380afe88ff9641e99730 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.cc +++ b/src/AutoPilotPlugins/Common/RadioComponentController.cc @@ -288,7 +288,7 @@ void RadioComponentController::nextButtonClicked(void) if (_unitTestMode) { emit nextButtonMessageBoxDisplayed(); } else { - qgcApp()->showMessage(QString("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); + qgcApp()->showAppMessage(QString("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); } return; } diff --git a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc index cd3f3d88b9493b4f7703f88ab076b2ab98424f3a..b57f86dd130a5de8ab42deeb47e99559a15ad160 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc @@ -85,7 +85,7 @@ AirframeComponentController::~AirframeComponentController() void AirframeComponentController::changeAutostart(void) { if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) { - qgcApp()->showMessage(tr("You cannot change airframe configuration while connected to multiple vehicles.")); + qgcApp()->showAppMessage(tr("You cannot change airframe configuration while connected to multiple vehicles.")); return; } diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc index 9f9036affd5377e9656fac8393b1a4c9fd07ff38..30b83158c1eda67b3b770670d7e6f4db887ce3d4 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc @@ -132,7 +132,7 @@ void PX4AutoPilotPlugin::parametersReadyPreChecks(void) QString hitlParam("SYS_HITL"); if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, hitlParam) && _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, hitlParam)->rawValue().toBool()) { - qgcApp()->showMessage(tr("Warning: Hardware In The Loop (HITL) simulation is enabled for this vehicle.")); + qgcApp()->showAppMessage(tr("Warning: Hardware In The Loop (HITL) simulation is enabled for this vehicle.")); } } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index ec5110bbe2112d257422be4bf5feff69d15ccf84..590196f1bc351c746b51194b1a05c95c0e3c4be4 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -179,7 +179,7 @@ void SensorsComponentController::_stopCalibration(SensorsComponentController::St default: // Assume failed _hideAllCalAreas(); - qgcApp()->showMessage(tr("Calibration failed. Calibration log will be displayed.")); + qgcApp()->showAppMessage(tr("Calibration failed. Calibration log will be displayed.")); break; } diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index a57beaed25c762b867492b047cfb7f7f04b8c95a..d080b9f5e3296c2103ec0a85067231e50fcff24a 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -742,9 +742,9 @@ void Fact::_checkForRebootMessaging(void) if(qgcApp()) { if (!qgcApp()->runningUnitTests()) { if (vehicleRebootRequired()) { - qgcApp()->showMessage(tr("Change of parameter %1 requires a Vehicle reboot to take effect.").arg(name())); + qgcApp()->showAppMessage(tr("Change of parameter %1 requires a Vehicle reboot to take effect.").arg(name())); } else if (qgcRebootRequired()) { - qgcApp()->showMessage(tr("Change of '%1' value requires restart of %2 to take effect.").arg(shortDescription()).arg(qgcApp()->applicationName())); + qgcApp()->showAppMessage(tr("Change of '%1' value requires restart of %2 to take effect.").arg(shortDescription()).arg(qgcApp()->applicationName())); } } } diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index 5bf6a77185679484a06a0f170ac69d8f87407602..bb035de9da56523b21a4609770b9fcafe383b036 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -120,7 +120,7 @@ void FactPanelController::_showInternalError(const QString& errorMsg) { _notifyPanelErrorMsg(tr("Internal Error: %1").arg(errorMsg)); qCWarning(FactPanelControllerLog) << "Internal Error" << errorMsg; - qgcApp()->showMessage(errorMsg); + qgcApp()->showAppMessage(errorMsg); } void FactPanelController::getMissingParameters(QStringList rgNames) diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 9cb48e481aa8b951964f31911b98170aa609c35c..aa282babc0d8ec54c010256880a9343ed572a77d 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -782,7 +782,7 @@ void ParameterManager::_waitingParamTimeout(void) _waitingWriteParamNameMap[componentId].remove(paramName); QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName); qCDebug(ParameterManagerLog) << errorMsg; - qgcApp()->showMessage(errorMsg); + qgcApp()->showAppMessage(errorMsg); } } } @@ -804,7 +804,7 @@ void ParameterManager::_waitingParamTimeout(void) _waitingReadParamNameMap[componentId].remove(paramName); QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName); qCDebug(ParameterManagerLog) << errorMsg; - qgcApp()->showMessage(errorMsg); + qgcApp()->showAppMessage(errorMsg); } } } @@ -1029,7 +1029,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian for (const QString& name: cacheMap.keys()) { _debugCacheParamSeen[componentId][name] = false; } - qgcApp()->showMessage(tr("Parameter cache CRC match failed")); + qgcApp()->showAppMessage(tr("Parameter cache CRC match failed")); } } } @@ -1296,7 +1296,7 @@ void ParameterManager::_checkInitialLoadComplete(void) "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. " "If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.").arg(qgcApp()->applicationName()).arg(_vehicle->id()); qCDebug(ParameterManagerLog) << errorMsg; - qgcApp()->showMessage(errorMsg); + qgcApp()->showAppMessage(errorMsg); if (!qgcApp()->runningUnitTests()) { qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList; } @@ -1320,7 +1320,7 @@ void ParameterManager::_initialRequestTimeout(void) QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. " "This will cause %2 to be unable to display its full user interface.").arg(_vehicle->id()).arg(qgcApp()->applicationName()); qCDebug(ParameterManagerLog) << errorMsg; - qgcApp()->showMessage(errorMsg); + qgcApp()->showAppMessage(errorMsg); } } } diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index e000ac8c29413a471f09e94a21c3e59a60a2cccf..9a035ce5594355a5794f4ef88a9539d2b06eaf8d 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -397,7 +397,7 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess if (supportedMajorNumber != -1) { if (firmwareVersion.majorNumber() < supportedMajorNumber || (firmwareVersion.majorNumber() == supportedMajorNumber && firmwareVersion.minorNumber() < supportedMinorNumber)) { - qgcApp()->showMessage(tr("QGroundControl fully supports Version %1.%2 and above. You are using a version prior to that. This combination is untested, you may run into unpredictable results.").arg(supportedMajorNumber).arg(supportedMinorNumber)); + qgcApp()->showAppMessage(tr("QGroundControl fully supports Version %1.%2 and above. You are using a version prior to that. This combination is untested, you may run into unpredictable results.").arg(supportedMajorNumber).arg(supportedMinorNumber)); } } } @@ -798,7 +798,7 @@ void APMFirmwarePlugin::_soloVideoHandshake(Vehicle* vehicle, bool originalSoloF void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketError) { - qgcApp()->showMessage(tr("Error during Solo video link setup: %1").arg(socketError)); + qgcApp()->showAppMessage(tr("Error during Solo video link setup: %1").arg(socketError)); } QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) @@ -888,7 +888,7 @@ void APMFirmwarePlugin::pauseVehicle(Vehicle* vehicle) void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) { if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) { - qgcApp()->showMessage(QStringLiteral("Unable to go to location, vehicle position not known.")); + qgcApp()->showAppMessage(QStringLiteral("Unable to go to location, vehicle position not known.")); return; } @@ -908,7 +908,7 @@ void APMFirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL) void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) { if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) { - qgcApp()->showMessage(tr("Unable to change altitude, vehicle altitude not known.")); + qgcApp()->showAppMessage(tr("Unable to change altitude, vehicle altitude not known.")); return; } @@ -968,13 +968,13 @@ double APMFirmwarePlugin::minimumTakeoffAltitude(Vehicle* vehicle) bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel) { if (!vehicle->multiRotor() && !vehicle->vtol()) { - qgcApp()->showMessage(tr("Vehicle does not support guided takeoff")); + qgcApp()->showAppMessage(tr("Vehicle does not support guided takeoff")); return false; } double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble(); if (qIsNaN(vehicleAltitudeAMSL)) { - qgcApp()->showMessage(tr("Unable to takeoff, vehicle position not known.")); + qgcApp()->showAppMessage(tr("Unable to takeoff, vehicle position not known.")); return false; } @@ -984,12 +984,12 @@ bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel) } if (!_setFlightModeAndValidate(vehicle, "Guided")) { - qgcApp()->showMessage(tr("Unable to takeoff: Vehicle failed to change to Guided mode.")); + qgcApp()->showAppMessage(tr("Unable to takeoff: Vehicle failed to change to Guided mode.")); return false; } if (!_armVehicleAndValidate(vehicle)) { - qgcApp()->showMessage(tr("Unable to takeoff: Vehicle failed to arm.")); + qgcApp()->showAppMessage(tr("Unable to takeoff: Vehicle failed to arm.")); return false; } @@ -1007,7 +1007,7 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle) if (vehicle->flying()) { // Vehicle already in the air, we just need to switch to auto if (!_setFlightModeAndValidate(vehicle, "Auto")) { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode.")); + qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode.")); } return; } @@ -1015,19 +1015,19 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle) if (!vehicle->armed()) { // First switch to flight mode we can arm from if (!_setFlightModeAndValidate(vehicle, "Guided")) { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle failed to change to Guided mode.")); + qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to change to Guided mode.")); return; } if (!_armVehicleAndValidate(vehicle)) { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle failed to arm.")); + qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to arm.")); return; } } if (vehicle->fixedWing()) { if (!_setFlightModeAndValidate(vehicle, "Auto")) { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode.")); + qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode.")); return; } } else { @@ -1097,7 +1097,7 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti static bool sentOnce = false; if (!sentOnce) { sentOnce = true; - qgcApp()->showMessage(tr("Follow failed: Home position not set.")); + qgcApp()->showAppMessage(tr("Follow failed: Home position not set.")); } return; } @@ -1107,7 +1107,7 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti if (!sentOnce) { sentOnce = true; qWarning() << "APMFirmwarePlugin::_sendGCSMotionReport estimateCapabilities" << estimationCapabilities; - qgcApp()->showMessage(tr("Follow failed: Ground station cannot provide required position information.")); + qgcApp()->showAppMessage(tr("Follow failed: Ground station cannot provide required position information.")); } return; } diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index 0dbef83d0970fff7235478c87968cafb9c85679c..9c8a67a2b734418fd97ff756b8ad2e704b7c89c1 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -76,7 +76,7 @@ void ArduRoverFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double Q_UNUSED(vehicle); Q_UNUSED(altitudeChange); - qgcApp()->showMessage(QStringLiteral("Change altitude not supported.")); + qgcApp()->showAppMessage(QStringLiteral("Change altitude not supported.")); } bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/) diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 29857ce590e5b6590b87c79fbe96ed90cbfd7eed..5751b54f887c65b029c182c2197bd52da47f5399 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -224,14 +224,14 @@ void FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode) { Q_UNUSED(vehicle); Q_UNUSED(guidedMode); - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void FirmwarePlugin::pauseVehicle(Vehicle* vehicle) { // Not supported by generic vehicle Q_UNUSED(vehicle); - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL) @@ -239,14 +239,14 @@ void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL) // Not supported by generic vehicle Q_UNUSED(vehicle); Q_UNUSED(smartRTL); - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void FirmwarePlugin::guidedModeLand(Vehicle* vehicle) { // Not supported by generic vehicle Q_UNUSED(vehicle); - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel) @@ -254,7 +254,7 @@ void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel) // Not supported by generic vehicle Q_UNUSED(vehicle); Q_UNUSED(takeoffAltRel); - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) @@ -262,19 +262,19 @@ void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordina // Not supported by generic vehicle Q_UNUSED(vehicle); Q_UNUSED(gotoCoord); - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double) { // Not supported by generic vehicle - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void FirmwarePlugin::startMission(Vehicle*) { // Not supported by generic vehicle - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } const FirmwarePlugin::remapParamNameMajorVersionMap_t& FirmwarePlugin::paramNameRemapMajorVersionMap(void) const @@ -862,7 +862,7 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString& QString currentVersionNumber = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion()) .arg(vehicle->firmwareMinorVersion()) .arg(vehicle->firmwarePatchVersion()); - qgcApp()->showMessage(tr("Vehicle is not running latest stable firmware! Running %1, latest stable is %2.").arg(currentVersionNumber, version)); + qgcApp()->showAppMessage(tr("Vehicle is not running latest stable firmware! Running %1, latest stable is %2.").arg(currentVersionNumber, version)); } } diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 0d967c4cc6398b609b327e02e1e3fb62866cb2f8..cdb2baf2ca5870d2cf1b4fb718e758ae954889ac 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -401,7 +401,7 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel { double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble(); if (qIsNaN(vehicleAltitudeAMSL)) { - qgcApp()->showMessage(tr("Unable to takeoff, vehicle position not known.")); + qgcApp()->showAppMessage(tr("Unable to takeoff, vehicle position not known.")); return; } @@ -424,7 +424,7 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) { if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) { - qgcApp()->showMessage(tr("Unable to go to location, vehicle position not known.")); + qgcApp()->showAppMessage(tr("Unable to go to location, vehicle position not known.")); return; } @@ -457,11 +457,11 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) { if (!vehicle->homePosition().isValid()) { - qgcApp()->showMessage(tr("Unable to change altitude, home position unknown.")); + qgcApp()->showAppMessage(tr("Unable to change altitude, home position unknown.")); return; } if (qIsNaN(vehicle->homePosition().altitude())) { - qgcApp()->showMessage(tr("Unable to change altitude, home position altitude unknown.")); + qgcApp()->showAppMessage(tr("Unable to change altitude, home position altitude unknown.")); return; } @@ -484,11 +484,11 @@ void PX4FirmwarePlugin::startMission(Vehicle* vehicle) { if (_setFlightModeAndValidate(vehicle, missionFlightMode())) { if (!_armVehicleAndValidate(vehicle)) { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle rejected arming.")); + qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle rejected arming.")); return; } } else { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle not changing to %1 flight mode.").arg(missionFlightMode())); + qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle not changing to %1 flight mode.").arg(missionFlightMode())); } } @@ -560,7 +560,7 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag if (notifyUser) { instanceData->versionNotified = true; - qgcApp()->showMessage(tr("QGroundControl supports PX4 Pro firmware Version %1.%2.%3 and above. You are using a version prior to that which will lead to unpredictable results. Please upgrade your firmware.").arg(supportedMajorVersion).arg(supportedMinorVersion).arg(supportedPatchVersion)); + qgcApp()->showAppMessage(tr("QGroundControl supports PX4 Pro firmware Version %1.%2.%3 and above. You are using a version prior to that which will lead to unpredictable results. Please upgrade your firmware.").arg(supportedMajorVersion).arg(supportedMinorVersion).arg(supportedPatchVersion)); } } } diff --git a/src/MissionManager/ComplexMissionItem.cc b/src/MissionManager/ComplexMissionItem.cc index 5fec0c0d77c34bb52a4d676022da2d171c13c429..9500b4bf7be28823f4606db4928afb8f7d1ddb8b 100644 --- a/src/MissionManager/ComplexMissionItem.cc +++ b/src/MissionManager/ComplexMissionItem.cc @@ -48,19 +48,19 @@ QStringList ComplexMissionItem::presetNames(void) void ComplexMissionItem::loadPreset(const QString& name) { Q_UNUSED(name); - qgcApp()->showMessage(tr("This Pattern does not support Presets.")); + qgcApp()->showAppMessage(tr("This Pattern does not support Presets.")); } void ComplexMissionItem::savePreset(const QString& name) { Q_UNUSED(name); - qgcApp()->showMessage(tr("This Pattern does not support Presets.")); + qgcApp()->showAppMessage(tr("This Pattern does not support Presets.")); } void ComplexMissionItem::deletePreset(const QString& name) { if (qgcApp()->toolbox()->corePlugin()->options()->surveyBuiltInPresetNames().contains(name)) { - qgcApp()->showMessage(tr("'%1' is a built-in preset which cannot be deleted.").arg(name)); + qgcApp()->showAppMessage(tr("'%1' is a built-in preset which cannot be deleted.").arg(name)); return; } diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc index 0d410d8dd57076d7a580168df89d83a0199ec85b..3033b7d77b6c6c11af9258415ec95f4df49de6d9 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.cc +++ b/src/MissionManager/FixedWingLandingComplexItem.cc @@ -216,7 +216,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq bool loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool(); bool landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool(); if (loiterAltitudeRelative != landingAltitudeRelative) { - qgcApp()->showMessage(tr("Fixed Wing Landing Pattern: " + qgcApp()->showAppMessage(tr("Fixed Wing Landing Pattern: " "Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. " "Both have been set to altitude relative. Be sure to adjust/check your plan prior to flight.")); _altitudesAreRelative = true; diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index 62fc0222c659f16eb67cf0bacea372eb82e91627..08d1d54a393fef61047e8567b854a585ae0fc6c6 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -88,7 +88,7 @@ void MissionManager::generateResumeMission(int resumeIndex) for (int i=0; i<_missionItems.count(); i++) { MissionItem* item = _missionItems[i]; if (item->command() == MAV_CMD_DO_JUMP) { - qgcApp()->showMessage(tr("Unable to generate resume mission due to MAV_CMD_DO_JUMP command.")); + qgcApp()->showAppMessage(tr("Unable to generate resume mission due to MAV_CMD_DO_JUMP command.")); return; } } diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc index 0bebc7424dea49bac90bcfcd52860615f4f5f576..09b3e9c3cc2c401a7689c27ecc25e8aa7a1cab4d 100644 --- a/src/MissionManager/PlanMasterController.cc +++ b/src/MissionManager/PlanMasterController.cc @@ -206,7 +206,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) void PlanMasterController::loadFromVehicle(void) { if (_managerVehicle->highLatencyLink()) { - qgcApp()->showMessage(tr("Download not supported on high latency links.")); + qgcApp()->showAppMessage(tr("Download not supported on high latency links.")); return; } @@ -313,7 +313,7 @@ void PlanMasterController::_startFlightPlanning(void) { void PlanMasterController::sendToVehicle(void) { if (_managerVehicle->highLatencyLink()) { - qgcApp()->showMessage(tr("Upload not supported on high latency links.")); + qgcApp()->showAppMessage(tr("Upload not supported on high latency links.")); return; } @@ -343,7 +343,7 @@ void PlanMasterController::loadFromFile(const QString& filename) if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { errorString = file.errorString() + QStringLiteral(" ") + filename; - qgcApp()->showMessage(errorMessage.arg(errorString)); + qgcApp()->showAppMessage(errorMessage.arg(errorString)); return; } @@ -353,7 +353,7 @@ void PlanMasterController::loadFromFile(const QString& filename) QByteArray bytes = file.readAll(); if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorString)) { - qgcApp()->showMessage(errorMessage.arg(errorString)); + qgcApp()->showAppMessage(errorMessage.arg(errorString)); return; } @@ -363,7 +363,7 @@ void PlanMasterController::loadFromFile(const QString& filename) int version; if (!JsonHelper::validateQGCJsonFile(json, kPlanFileType, kPlanFileVersion, kPlanFileVersion, version, errorString)) { - qgcApp()->showMessage(errorMessage.arg(errorString)); + qgcApp()->showAppMessage(errorMessage.arg(errorString)); return; } @@ -373,14 +373,14 @@ void PlanMasterController::loadFromFile(const QString& filename) { kJsonRallyPointsObjectKey, QJsonValue::Object, true }, }; if (!JsonHelper::validateKeys(json, rgKeyInfo, errorString)) { - qgcApp()->showMessage(errorMessage.arg(errorString)); + qgcApp()->showAppMessage(errorMessage.arg(errorString)); return; } if (!_missionController.load(json[kJsonMissionObjectKey].toObject(), errorString) || !_geoFenceController.load(json[kJsonGeoFenceObjectKey].toObject(), errorString) || !_rallyPointController.load(json[kJsonRallyPointsObjectKey].toObject(), errorString)) { - qgcApp()->showMessage(errorMessage.arg(errorString)); + qgcApp()->showAppMessage(errorMessage.arg(errorString)); } else { //-- Allow plugins to post process the load qgcApp()->toolbox()->corePlugin()->postLoadFromJson(this, json); @@ -388,13 +388,13 @@ void PlanMasterController::loadFromFile(const QString& filename) } } else if (fileInfo.suffix() == AppSettings::missionFileExtension) { if (!_missionController.loadJsonFile(file, errorString)) { - qgcApp()->showMessage(errorMessage.arg(errorString)); + qgcApp()->showAppMessage(errorMessage.arg(errorString)); } else { success = true; } } else if (fileInfo.suffix() == AppSettings::waypointsFileExtension || fileInfo.suffix() == QStringLiteral("txt")) { if (!_missionController.loadTextFile(file, errorString)) { - qgcApp()->showMessage(errorMessage.arg(errorString)); + qgcApp()->showAppMessage(errorMessage.arg(errorString)); } else { success = true; } @@ -458,7 +458,7 @@ void PlanMasterController::saveToFile(const QString& filename) QFile file(planFilename); if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { - qgcApp()->showMessage(tr("Plan save error %1 : %2").arg(filename).arg(file.errorString())); + qgcApp()->showAppMessage(tr("Plan save error %1 : %2").arg(filename).arg(file.errorString())); _currentPlanFile.clear(); emit currentPlanFileChanged(); } else { @@ -490,7 +490,7 @@ void PlanMasterController::saveToKml(const QString& filename) QFile file(kmlFilename); if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { - qgcApp()->showMessage(tr("KML save error %1 : %2").arg(filename).arg(file.errorString())); + qgcApp()->showAppMessage(tr("KML save error %1 : %2").arg(filename).arg(file.errorString())); } else { KMLPlanDomDocument planKML; _missionController.addMissionToKML(planKML); diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index aa78ffebe0a6d6c32638694be0de1dca3dc05420..e3b6854a886bc504d65aeeaee115647042c05c33 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -467,7 +467,7 @@ bool QGCMapPolygon::loadKMLOrSHPFile(const QString& file) QString errorString; QList rgCoords; if (!ShapeFileHelper::loadPolygonFromFile(file, rgCoords, errorString)) { - qgcApp()->showMessage(errorString); + qgcApp()->showAppMessage(errorString); return false; } diff --git a/src/MissionManager/QGCMapPolyline.cc b/src/MissionManager/QGCMapPolyline.cc index f063a0125495868208ec12ef0ba85b5128207f49..5dcb0f4beb75bdf1c323703efb6ea6e2c93c3f16 100644 --- a/src/MissionManager/QGCMapPolyline.cc +++ b/src/MissionManager/QGCMapPolyline.cc @@ -353,7 +353,7 @@ bool QGCMapPolyline::loadKMLFile(const QString& kmlFile) QString errorString; QList rgCoords; if (!KMLHelper::loadPolylineFromFile(kmlFile, rgCoords, errorString)) { - qgcApp()->showMessage(errorString); + qgcApp()->showAppMessage(errorString); return false; } diff --git a/src/MissionManager/SurveyComplexItem.cc b/src/MissionManager/SurveyComplexItem.cc index 050f92dd08a8b9a43b6cef977da16025a9382736..f31e16774ec08e462a5d269032886e1ca2f1062f 100644 --- a/src/MissionManager/SurveyComplexItem.cc +++ b/src/MissionManager/SurveyComplexItem.cc @@ -151,7 +151,7 @@ void SurveyComplexItem::loadPreset(const QString& name) QJsonObject presetObject = _loadPresetJson(name); if (!_loadV4V5(presetObject, 0, errorString, 5, true /* forPresets */)) { - qgcApp()->showMessage(QStringLiteral("Internal Error: Preset load failed. Name: %1 Error: %2").arg(name).arg(errorString)); + qgcApp()->showAppMessage(QStringLiteral("Internal Error: Preset load failed. Name: %1 Error: %2").arg(name).arg(errorString)); } _rebuildTransects(); } diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index 20e6c52d87af7bdc8b8a6a9349fc1fc58ddf2761..948a196bd91a9b899186e54332fe62accb6da2cd 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -520,7 +520,7 @@ void TransectStyleComplexItem::_adjustTransectsForTerrain(void) if (_followTerrain) { if (readyForSaveState() != ReadyForSave) { qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready"; - qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect.")); + qgcApp()->showAppMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect.")); return; } diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 822fd38cddd9adbfc0892f86c08899dfe068049b..bf765a8b8e1e42812d0cbc8172487d46b3e7467b 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -603,7 +603,7 @@ bool QGCApplication::_initForNormalAppBoot() toolbox()->joystickManager()->init(); if (_settingsUpgraded) { - showMessage(QString(tr("The format for %1 saved settings has been modified. " + showAppMessage(QString(tr("The format for %1 saved settings has been modified. " "Your saved settings have been reset to defaults.")).arg(applicationName())); } @@ -611,10 +611,13 @@ bool QGCApplication::_initForNormalAppBoot() toolbox()->linkManager()->startAutoConnectedLinks(); if (getQGCMapEngine()->wasCacheReset()) { - showMessage(tr("The Offline Map Cache database has been upgraded. " + showAppMessage(tr("The Offline Map Cache database has been upgraded. " "Your old map cache sets have been reset.")); } + showAppMessage("Foo"); + showAppMessage("Bar"); + settings.sync(); return true; } @@ -644,17 +647,17 @@ QGCApplication* qgcApp(void) void QGCApplication::informationMessageBoxOnMainThread(const QString& /*title*/, const QString& msg) { - showMessage(msg); + showAppMessage(msg); } void QGCApplication::warningMessageBoxOnMainThread(const QString& /*title*/, const QString& msg) { - showMessage(msg); + showAppMessage(msg); } void QGCApplication::criticalMessageBoxOnMainThread(const QString& /*title*/, const QString& msg) { - showMessage(msg); + showAppMessage(msg); } void QGCApplication::saveTelemetryLogOnMainThread(QString tempLogfile) @@ -680,7 +683,7 @@ void QGCApplication::saveTelemetryLogOnMainThread(QString tempLogfile) QFile tempFile(tempLogfile); if (!tempFile.copy(saveFilePath)) { QString error = tr("Unable to save telemetry log. Error copying telemetry to '%1': '%2'.").arg(saveFilePath).arg(tempFile.errorString()); - showMessage(error); + showAppMessage(error); } } QFile::remove(tempLogfile); @@ -697,14 +700,14 @@ bool QGCApplication::_checkTelemetrySavePath(bool /*useMessageBox*/) QString saveDirPath = _toolbox->settingsManager()->appSettings()->telemetrySavePath(); if (saveDirPath.isEmpty()) { QString error = tr("Unable to save telemetry log. Application save directory is not set."); - showMessage(error); + showAppMessage(error); return false; } QDir saveDir(saveDirPath); if (!saveDir.exists()) { QString error = tr("Unable to save telemetry log. Telemetry save directory \"%1\" does not exist.").arg(saveDirPath); - showMessage(error); + showAppMessage(error); return false; } @@ -737,7 +740,7 @@ void QGCApplication::_missingParamsDisplay(void) } _missingParams.clear(); - showMessage(tr("Parameters are missing from firmware. You may be running a version of firmware QGC does not work correctly with or your firmware has a bug in it. Missing params: %1").arg(params)); + showAppMessage(tr("Parameters are missing from firmware. You may be running a version of firmware QGC does not work correctly with or your firmware has a bug in it. Missing params: %1").arg(params)); } } @@ -748,8 +751,7 @@ QObject* QGCApplication::_rootQmlObject() return nullptr; } - -void QGCApplication::showMessage(const QString& message) +void QGCApplication::showVehicleMessage(const QString& message) { // PreArm messages are handled by Vehicle and shown in Map if (message.startsWith(QStringLiteral("PreArm")) || message.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive)) { @@ -759,10 +761,27 @@ void QGCApplication::showMessage(const QString& message) if (rootQmlObject) { QVariant varReturn; QVariant varMessage = QVariant::fromValue(message); - QMetaObject::invokeMethod(_rootQmlObject(), "showMessage", Q_RETURN_ARG(QVariant, varReturn), Q_ARG(QVariant, varMessage)); + QMetaObject::invokeMethod(_rootQmlObject(), "showVehicleMessage", Q_RETURN_ARG(QVariant, varReturn), Q_ARG(QVariant, varMessage)); + } else if (runningUnitTests()) { + // Unit tests can run without UI + qDebug() << "QGCApplication::showVehicleMessage unittest" << message; + } else { + qWarning() << "Internal error"; + } +} + +void QGCApplication::showAppMessage(const QString& message, const QString& title) +{ + QString dialogTitle = title.isEmpty() ? applicationName() : title; + + QObject* rootQmlObject = _rootQmlObject(); + if (rootQmlObject) { + QVariant varReturn; + QVariant varMessage = QVariant::fromValue(message); + QMetaObject::invokeMethod(_rootQmlObject(), "showMessageDialog", Q_RETURN_ARG(QVariant, varReturn), Q_ARG(QVariant, dialogTitle) /* No title */, Q_ARG(QVariant, varMessage)); } else if (runningUnitTests()) { // Unit tests can run without UI - qDebug() << "QGCApplication::showMessage unittest" << message; + qDebug() << "QGCApplication::showAppMessage unittest" << message << dialogTitle; } else { qWarning() << "Internal error"; } diff --git a/src/QGCApplication.h b/src/QGCApplication.h index 08a11daad15cb9c747a2f8b99559ae0b89cb59d2..155571df2ec7e164728ac3870071f7ab4187324e 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -70,8 +70,11 @@ public: /// multiple times. void reportMissingParameter(int componentId, const QString& name); - /// Show a non-modal message to the user - Q_SLOT void showMessage(const QString& message); + /// Show non-modal vehicle message to the user + Q_SLOT void showVehicleMessage(const QString& message); + + /// Show modal application message to the user + Q_SLOT void showAppMessage(const QString& message, const QString& title = QString()); /// @return true: Fake ui into showing mobile interface bool fakeMobile(void) const { return _fakeMobile; } diff --git a/src/QmlControls/AppMessages.cc b/src/QmlControls/AppMessages.cc index 7cd9a3ffa46bd81e973b02c46c7d7e93a72b907c..853c73f58cd3303fb1fa84381e223cde3b73ab8b 100644 --- a/src/QmlControls/AppMessages.cc +++ b/src/QmlControls/AppMessages.cc @@ -105,7 +105,7 @@ void AppLogModel::threadsafeLog(const QString message) _logFile.setFileName(saveFilePath); if (!_logFile.open(QIODevice::WriteOnly | QIODevice::Text)) { - qgcApp()->showMessage(tr("Open console log output file failed %1 : %2").arg(_logFile.fileName()).arg(_logFile.errorString())); + qgcApp()->showAppMessage(tr("Open console log output file failed %1 : %2").arg(_logFile.fileName()).arg(_logFile.errorString())); } } } diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index 8d4a4b84c47b500da17cb49811d2600af05f3a7d..e28afe8e0a7360b9c78c497363160d0b72a9c4b3 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -97,7 +97,7 @@ void ParameterEditorController::saveToFile(const QString& filename) QFile file(parameterFilename); if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { - qgcApp()->showMessage(tr("Unable to create file: %1").arg(parameterFilename)); + qgcApp()->showAppMessage(tr("Unable to create file: %1").arg(parameterFilename)); return; } @@ -115,7 +115,7 @@ void ParameterEditorController::loadFromFile(const QString& filename) QFile file(filename); if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { - qgcApp()->showMessage(tr("Unable to open file: %1").arg(filename)); + qgcApp()->showAppMessage(tr("Unable to open file: %1").arg(filename)); return; } diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index 654cf59254e3070563cdf8a767b8524885bed8c9..924e5339f58f6ae15da7c348d568cab60265299d 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -122,7 +122,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle << vehicleType; if (vehicleId == _mavlinkProtocol->getSystemId()) { - _app->showMessage(tr("Warning: A vehicle is using the same system id as %1: %2").arg(qgcApp()->applicationName()).arg(vehicleId)); + _app->showAppMessage(tr("Warning: A vehicle is using the same system id as %1: %2").arg(qgcApp()->applicationName()).arg(vehicleId)); } Vehicle* vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _joystickManager); @@ -140,7 +140,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle emit vehicleAdded(vehicle); if (_vehicles.count() > 1) { - qgcApp()->showMessage(tr("Connected to Vehicle %1").arg(vehicleId)); + qgcApp()->showAppMessage(tr("Connected to Vehicle %1").arg(vehicleId)); } else { setActiveVehicle(vehicle); } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 97b724c6494b604508cdd4b4987224670374f7c2..3f416391df9750d3a0db2d4a793749d0bd42ff25 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -731,7 +731,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes _capabilitiesRetryElapsed.start(); } else if (_capabilitiesRetryElapsed.elapsed() > 10000){ qCDebug(VehicleLog) << "Giving up on getting AUTOPILOT_VERSION after 10 seconds"; - qgcApp()->showMessage(QStringLiteral("Vehicle failed to send AUTOPILOT_VERSION after waiting/retrying for 10 seconds")); + qgcApp()->showAppMessage(QStringLiteral("Vehicle failed to send AUTOPILOT_VERSION after waiting/retrying for 10 seconds")); _handleUnsupportedRequestAutopilotCapabilities(); } else { // Vehicle never sent us AUTOPILOT_VERSION response. Try again. @@ -2174,7 +2174,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand) if (_priorityLink.data() != newPriorityLink) { if (_priorityLink) { - qgcApp()->showMessage((tr("switch to %2 as priority link")).arg(newPriorityLink->getName())); + qgcApp()->showAppMessage((tr("switch to %2 as priority link")).arg(newPriorityLink->getName())); } _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink); @@ -2629,19 +2629,19 @@ void Vehicle::sendMessageMultiple(mavlink_message_t message) void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg) { Q_UNUSED(errorCode); - qgcApp()->showMessage(tr("Mission transfer failed. Error: %1").arg(errorMsg)); + qgcApp()->showAppMessage(tr("Mission transfer failed. Error: %1").arg(errorMsg)); } void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg) { Q_UNUSED(errorCode); - qgcApp()->showMessage(tr("GeoFence transfer failed. Error: %1").arg(errorMsg)); + qgcApp()->showAppMessage(tr("GeoFence transfer failed. Error: %1").arg(errorMsg)); } void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg) { Q_UNUSED(errorCode); - qgcApp()->showMessage(tr("Rally Point transfer failed. Error: %1").arg(errorMsg)); + qgcApp()->showAppMessage(tr("Rally Point transfer failed. Error: %1").arg(errorMsg)); } void Vehicle::_clearCameraTriggerPoints() @@ -2897,7 +2897,7 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID } } } else { - qgcApp()->showMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost")); + qgcApp()->showAppMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost")); _updatePriorityLink(false /* updateActive */, true /* sendCommand */); } @@ -2906,17 +2906,17 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID if (communicationRegained) { commSpeech = tr("Communication regained"); if (_links.count() > 1) { - qgcApp()->showMessage(tr("Communication regained to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName())); + qgcApp()->showAppMessage(tr("Communication regained to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName())); } else if (multiVehicle) { - qgcApp()->showMessage(tr("Communication regained to vehicle %1").arg(_id)); + qgcApp()->showAppMessage(tr("Communication regained to vehicle %1").arg(_id)); } } if (communicationLost) { commSpeech = tr("Communication lost"); if (_links.count() > 1) { - qgcApp()->showMessage(tr("Communication lost to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName())); + qgcApp()->showAppMessage(tr("Communication lost to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName())); } else if (multiVehicle) { - qgcApp()->showMessage(tr("Communication lost to vehicle %1").arg(_id)); + qgcApp()->showAppMessage(tr("Communication lost to vehicle %1").arg(_id)); } } if (multiVehicle && (communicationLost || communicationRegained)) { @@ -3096,7 +3096,7 @@ QString Vehicle::gotoFlightMode() const void Vehicle::guidedModeRTL(bool smartRTL) { if (!guidedModeSupported()) { - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); return; } _firmwarePlugin->guidedModeRTL(this, smartRTL); @@ -3105,7 +3105,7 @@ void Vehicle::guidedModeRTL(bool smartRTL) void Vehicle::guidedModeLand() { if (!guidedModeSupported()) { - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); return; } _firmwarePlugin->guidedModeLand(this); @@ -3114,7 +3114,7 @@ void Vehicle::guidedModeLand() void Vehicle::guidedModeTakeoff(double altitudeRelative) { if (!guidedModeSupported()) { - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); return; } _firmwarePlugin->guidedModeTakeoff(this, altitudeRelative); @@ -3133,7 +3133,7 @@ void Vehicle::startMission() void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord) { if (!guidedModeSupported()) { - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); return; } if (!coordinate().isValid()) { @@ -3141,7 +3141,7 @@ void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord) } double maxDistance = _settingsManager->flyViewSettings()->maxGoToLocationDistance()->rawValue().toDouble(); if (coordinate().distanceTo(gotoCoord) > maxDistance) { - qgcApp()->showMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString())); + qgcApp()->showAppMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString())); return; } _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord); @@ -3150,7 +3150,7 @@ void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord) void Vehicle::guidedModeChangeAltitude(double altitudeChange) { if (!guidedModeSupported()) { - qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); + qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); return; } _firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange); @@ -3159,7 +3159,7 @@ void Vehicle::guidedModeChangeAltitude(double altitudeChange) void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude) { if (!orbitModeSupported()) { - qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle.")); + qgcApp()->showAppMessage(QStringLiteral("Orbit mode not supported by Vehicle.")); return; } if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) { @@ -3191,7 +3191,7 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord) { if (!roiModeSupported()) { - qgcApp()->showMessage(QStringLiteral("ROI mode not supported by Vehicle.")); + qgcApp()->showAppMessage(QStringLiteral("ROI mode not supported by Vehicle.")); return; } if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) { @@ -3225,7 +3225,7 @@ void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord) void Vehicle::stopGuidedModeROI() { if (!roiModeSupported()) { - qgcApp()->showMessage(QStringLiteral("ROI mode not supported by Vehicle.")); + qgcApp()->showAppMessage(QStringLiteral("ROI mode not supported by Vehicle.")); return; } if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) { @@ -3259,7 +3259,7 @@ void Vehicle::stopGuidedModeROI() void Vehicle::pauseVehicle() { if (!pauseVehicleSupported()) { - qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle.")); + qgcApp()->showAppMessage(QStringLiteral("Pause not supported by vehicle.")); return; } _firmwarePlugin->pauseVehicle(this); @@ -3383,7 +3383,7 @@ void Vehicle::_sendMavCommandAgain() emit mavCommandResult(_id, queuedCommand.component, queuedCommand.command, MAV_RESULT_FAILED, true /* noResponsefromVehicle */); if (queuedCommand.showError) { - qgcApp()->showMessage(tr("Vehicle did not respond to command: %1").arg(_toolbox->missionCommandTree()->friendlyName(queuedCommand.command))); + qgcApp()->showAppMessage(tr("Vehicle did not respond to command: %1").arg(_toolbox->missionCommandTree()->friendlyName(queuedCommand.command))); } _mavCommandQueue.removeFirst(); _sendNextQueuedMavCommand(); @@ -3535,7 +3535,7 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) #if !defined(NO_ARDUPILOT_DIALECT) if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) { - qgcApp()->showMessage(tr("Bootloader flash succeeded")); + qgcApp()->showAppMessage(tr("Bootloader flash succeeded")); } #endif @@ -3552,16 +3552,16 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) QString commandName = _toolbox->missionCommandTree()->friendlyName(static_cast(ack.command)); switch (ack.result) { case MAV_RESULT_TEMPORARILY_REJECTED: - qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName)); + qgcApp()->showAppMessage(tr("%1 command temporarily rejected").arg(commandName)); break; case MAV_RESULT_DENIED: - qgcApp()->showMessage(tr("%1 command denied").arg(commandName)); + qgcApp()->showAppMessage(tr("%1 command denied").arg(commandName)); break; case MAV_RESULT_UNSUPPORTED: - qgcApp()->showMessage(tr("%1 command not supported").arg(commandName)); + qgcApp()->showAppMessage(tr("%1 command not supported").arg(commandName)); break; case MAV_RESULT_FAILED: - qgcApp()->showMessage(tr("%1 command failed").arg(commandName)); + qgcApp()->showAppMessage(tr("%1 command failed").arg(commandName)); break; default: // Do nothing diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc index 19d88524a0243b1db166f8974829810f496cfa5d..e8fcf11c586f23573f1def95a524cdfbf16354b7 100644 --- a/src/VehicleSetup/JoystickConfigController.cc +++ b/src/VehicleSetup/JoystickConfigController.cc @@ -253,7 +253,7 @@ void JoystickConfigController::nextButtonClicked() if (_currentStep == -1) { // Need to have enough channels if (_axisCount < _axisMinimum) { - qgcApp()->showMessage(tr("Detected %1 joystick axes. To operate PX4, you need at least %2 axes.").arg(_axisCount).arg(_axisMinimum)); + qgcApp()->showAppMessage(tr("Detected %1 joystick axes. To operate PX4, you need at least %2 axes.").arg(_axisCount).arg(_axisMinimum)); return; } _startCalibration(); diff --git a/src/VideoManager/VideoManager.cc b/src/VideoManager/VideoManager.cc index 468a98c610e89ca6392c3d96a42831b62743d261..d30be677c035253a44de4a230b88d53b1d722dc3 100644 --- a/src/VideoManager/VideoManager.cc +++ b/src/VideoManager/VideoManager.cc @@ -220,14 +220,14 @@ VideoManager::startRecording(const QString& videoFile) } #if defined(QGC_GST_STREAMING) if (!_videoReceiver) { - qgcApp()->showMessage(tr("Video receiver is not ready.")); + qgcApp()->showAppMessage(tr("Video receiver is not ready.")); return; } const VideoReceiver::FILE_FORMAT fileFormat = static_cast(_videoSettings->recordingFormat()->rawValue().toInt()); if(fileFormat < VideoReceiver::FILE_FORMAT_MIN || fileFormat >= VideoReceiver::FILE_FORMAT_MAX) { - qgcApp()->showMessage(tr("Invalid video format defined.")); + qgcApp()->showAppMessage(tr("Invalid video format defined.")); return; } @@ -237,7 +237,7 @@ VideoManager::startRecording(const QString& videoFile) QString savePath = qgcApp()->toolbox()->settingsManager()->appSettings()->videoSavePath(); if(savePath.isEmpty()) { - qgcApp()->showMessage(tr("Unabled to record video. Video save path must be specified in Settings.")); + qgcApp()->showAppMessage(tr("Unabled to record video. Video save path must be specified in Settings.")); return; } diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 8a1b1caef860014ed7f0fc24d08215b21ca36f33..41eff10cff6b0a7488eb05b301bd30213275a8b1 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -295,7 +295,7 @@ SharedLinkInterfacePointer LinkManager::sharedLinkInterfacePointerForLink(LinkIn bool LinkManager::_connectionsSuspendedMsg(void) { if (_connectionsSuspended) { - qgcApp()->showMessage(tr("Connect not allowed: %1").arg(_connectionsSuspendedReason)); + qgcApp()->showAppMessage(tr("Connect not allowed: %1").arg(_connectionsSuspendedReason)); return true; } else { return false; @@ -932,7 +932,7 @@ void LinkManager::_activeLinkCheck(void) foundNSHPrompt = true; } } - qgcApp()->showMessage( + qgcApp()->showAppMessage( foundNSHPrompt ? tr("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") : tr("Your Vehicle is not responding. If this continues, shutdown %1, restart the Vehicle letting it boot completely, then start %1.").arg(qgcApp()->applicationName())); diff --git a/src/uas/UASMessageHandler.cc b/src/uas/UASMessageHandler.cc index 97163c048cbfb4c8cf51423faad8c67216eccf86..ddd9adcb891b9065990e7af1eb8f6e44447ab585 100644 --- a/src/uas/UASMessageHandler.cc +++ b/src/uas/UASMessageHandler.cc @@ -202,7 +202,7 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString emit textMessageCountChanged(count); if (_showErrorsInToolbar && message->severityIsError()) { - _app->showMessage(message->getText()); + _app->showVehicleMessage(message->getText()); } } diff --git a/src/ui/MainRootWindow.qml b/src/ui/MainRootWindow.qml index 96c78f323aa3ebb44622d60ac787fb6a9522767b..12dd6d896d28c678db7e55eb52d2f36bfa857287 100644 --- a/src/ui/MainRootWindow.qml +++ b/src/ui/MainRootWindow.qml @@ -151,12 +151,18 @@ ApplicationWindow { //-- Global simple message dialog function showMessageDialog(title, text) { - if(simpleMessageDialog.visible) { - simpleMessageDialog.close() + var dialog = simpleMessageDialog.createObject(mainWindow, { title: title, text: text }) + dialog.open() + } + + Component { + id: simpleMessageDialog + + MessageDialog { + standardButtons: StandardButton.Ok + modality: Qt.ApplicationModal + visible: false } - simpleMessageDialog.title = title - simpleMessageDialog.text = text - simpleMessageDialog.open() } /// Saves main window position and size @@ -164,13 +170,6 @@ ApplicationWindow { window: mainWindow } - MessageDialog { - id: simpleMessageDialog - standardButtons: StandardButton.Ok - modality: Qt.ApplicationModal - visible: false - } - //------------------------------------------------------------------------- //-- Global complex dialog @@ -524,7 +523,7 @@ ApplicationWindow { property var _messageQueue: [] property string _systemMessage: "" - function showMessage(message) { + function showVehicleMessage(message) { vehicleMessageArea.close() if(systemMessageArea.visible || QGroundControl.videoManager.fullScreen) { _messageQueue.push(message)