Unverified Commit d00b30af authored by Don Gagne's avatar Don Gagne Committed by GitHub
Browse files

Merge pull request #8666 from DonLakeFlyer/AppVehicleMessaging

Use different UI for App/Vehicle messaging
parents 9e8a5dcb 284a2c08
...@@ -66,7 +66,7 @@ void ADSBVehicleManager::adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehi ...@@ -66,7 +66,7 @@ void ADSBVehicleManager::adsbVehicleUpdate(const ADSBVehicle::VehicleInfo_t vehi
void ADSBVehicleManager::_tcpError(const QString errorMsg) void ADSBVehicleManager::_tcpError(const QString errorMsg)
{ {
qgcApp()->showMessage(tr("ADSB Server Error: %1").arg(errorMsg)); qgcApp()->showAppMessage(tr("ADSB Server Error: %1").arg(errorMsg));
} }
......
...@@ -89,7 +89,7 @@ void ...@@ -89,7 +89,7 @@ void
AirMapManager::_error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails) AirMapManager::_error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails)
{ {
qCDebug(AirMapManagerLog) << "Error: "<<what<<", msg: "<<airmapdMessage<<", details: "<<airmapdDetails; qCDebug(AirMapManagerLog) << "Error: "<<what<<", msg: "<<airmapdMessage<<", details: "<<airmapdDetails;
qgcApp()->showMessage(QString("Error: %1. %2").arg(what).arg(airmapdMessage)); qgcApp()->showAppMessage(QString("Error: %1. %2").arg(what).arg(airmapdMessage));
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -254,7 +254,7 @@ void APMAirframeComponentController::_githubJsonDownloadFinished(QString remoteF ...@@ -254,7 +254,7 @@ void APMAirframeComponentController::_githubJsonDownloadFinished(QString remoteF
void APMAirframeComponentController::_githubJsonDownloadError(QString errorMsg) 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(); qgcApp()->restoreOverrideCursor();
} }
...@@ -267,7 +267,7 @@ void APMAirframeComponentController::_paramFileDownloadFinished(QString remoteFi ...@@ -267,7 +267,7 @@ void APMAirframeComponentController::_paramFileDownloadFinished(QString remoteFi
void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg) 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(); qgcApp()->restoreOverrideCursor();
} }
......
...@@ -218,7 +218,7 @@ void APMAutoPilotPlugin::_checkForBadCubeBlack(void) ...@@ -218,7 +218,7 @@ void APMAutoPilotPlugin::_checkForBadCubeBlack(void)
if (paramMgr->parameterExists(-1, paramAcc3) && paramMgr->getParameter(-1, paramAcc3)->rawValue().toInt() == 0 && 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, paramGyr3) && paramMgr->getParameter(-1, paramGyr3)->rawValue().toInt() == 0 &&
paramMgr->parameterExists(-1, paramEnableMask) && paramMgr->getParameter(-1, paramEnableMask)->rawValue().toInt() >= 7) { 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"));
} }
} }
......
...@@ -196,7 +196,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll ...@@ -196,7 +196,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll
default: default:
// Assume failed // Assume failed
_hideAllCalAreas(); _hideAllCalAreas();
qgcApp()->showMessage(tr("Calibration failed. Calibration log will be displayed.")); qgcApp()->showAppMessage(tr("Calibration failed. Calibration log will be displayed."));
break; break;
} }
......
...@@ -71,7 +71,7 @@ void AutoPilotPlugin::parametersReadyPreChecks(void) ...@@ -71,7 +71,7 @@ void AutoPilotPlugin::parametersReadyPreChecks(void)
} }
if (!_setupComplete) { 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 // Take the user to Vehicle Summary
qgcApp()->showSetupView(); qgcApp()->showSetupView();
......
...@@ -288,7 +288,7 @@ void RadioComponentController::nextButtonClicked(void) ...@@ -288,7 +288,7 @@ void RadioComponentController::nextButtonClicked(void)
if (_unitTestMode) { if (_unitTestMode) {
emit nextButtonMessageBoxDisplayed(); emit nextButtonMessageBoxDisplayed();
} else { } 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; return;
} }
......
...@@ -85,7 +85,7 @@ AirframeComponentController::~AirframeComponentController() ...@@ -85,7 +85,7 @@ AirframeComponentController::~AirframeComponentController()
void AirframeComponentController::changeAutostart(void) void AirframeComponentController::changeAutostart(void)
{ {
if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) { 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; return;
} }
......
...@@ -132,7 +132,7 @@ void PX4AutoPilotPlugin::parametersReadyPreChecks(void) ...@@ -132,7 +132,7 @@ void PX4AutoPilotPlugin::parametersReadyPreChecks(void)
QString hitlParam("SYS_HITL"); QString hitlParam("SYS_HITL");
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, hitlParam) && if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, hitlParam) &&
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, hitlParam)->rawValue().toBool()) { _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."));
} }
} }
......
...@@ -179,7 +179,7 @@ void SensorsComponentController::_stopCalibration(SensorsComponentController::St ...@@ -179,7 +179,7 @@ void SensorsComponentController::_stopCalibration(SensorsComponentController::St
default: default:
// Assume failed // Assume failed
_hideAllCalAreas(); _hideAllCalAreas();
qgcApp()->showMessage(tr("Calibration failed. Calibration log will be displayed.")); qgcApp()->showAppMessage(tr("Calibration failed. Calibration log will be displayed."));
break; break;
} }
......
...@@ -742,9 +742,9 @@ void Fact::_checkForRebootMessaging(void) ...@@ -742,9 +742,9 @@ void Fact::_checkForRebootMessaging(void)
if(qgcApp()) { if(qgcApp()) {
if (!qgcApp()->runningUnitTests()) { if (!qgcApp()->runningUnitTests()) {
if (vehicleRebootRequired()) { 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()) { } 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()));
} }
} }
} }
......
...@@ -120,7 +120,7 @@ void FactPanelController::_showInternalError(const QString& errorMsg) ...@@ -120,7 +120,7 @@ void FactPanelController::_showInternalError(const QString& errorMsg)
{ {
_notifyPanelErrorMsg(tr("Internal Error: %1").arg(errorMsg)); _notifyPanelErrorMsg(tr("Internal Error: %1").arg(errorMsg));
qCWarning(FactPanelControllerLog) << "Internal Error" << errorMsg; qCWarning(FactPanelControllerLog) << "Internal Error" << errorMsg;
qgcApp()->showMessage(errorMsg); qgcApp()->showAppMessage(errorMsg);
} }
void FactPanelController::getMissingParameters(QStringList rgNames) void FactPanelController::getMissingParameters(QStringList rgNames)
......
...@@ -782,7 +782,7 @@ void ParameterManager::_waitingParamTimeout(void) ...@@ -782,7 +782,7 @@ void ParameterManager::_waitingParamTimeout(void)
_waitingWriteParamNameMap[componentId].remove(paramName); _waitingWriteParamNameMap[componentId].remove(paramName);
QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName); QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
qCDebug(ParameterManagerLog) << errorMsg; qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg); qgcApp()->showAppMessage(errorMsg);
} }
} }
} }
...@@ -804,7 +804,7 @@ void ParameterManager::_waitingParamTimeout(void) ...@@ -804,7 +804,7 @@ void ParameterManager::_waitingParamTimeout(void)
_waitingReadParamNameMap[componentId].remove(paramName); _waitingReadParamNameMap[componentId].remove(paramName);
QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName); QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
qCDebug(ParameterManagerLog) << errorMsg; qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg); qgcApp()->showAppMessage(errorMsg);
} }
} }
} }
...@@ -1029,7 +1029,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian ...@@ -1029,7 +1029,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
for (const QString& name: cacheMap.keys()) { for (const QString& name: cacheMap.keys()) {
_debugCacheParamSeen[componentId][name] = false; _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) ...@@ -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 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()); "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; qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg); qgcApp()->showAppMessage(errorMsg);
if (!qgcApp()->runningUnitTests()) { if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList; 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) ...@@ -1320,7 +1320,7 @@ void ParameterManager::_initialRequestTimeout(void)
QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. " 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()); "This will cause %2 to be unable to display its full user interface.").arg(_vehicle->id()).arg(qgcApp()->applicationName());
qCDebug(ParameterManagerLog) << errorMsg; qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg); qgcApp()->showAppMessage(errorMsg);
} }
} }
} }
......
...@@ -397,7 +397,7 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess ...@@ -397,7 +397,7 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess
if (supportedMajorNumber != -1) { if (supportedMajorNumber != -1) {
if (firmwareVersion.majorNumber() < supportedMajorNumber || if (firmwareVersion.majorNumber() < supportedMajorNumber ||
(firmwareVersion.majorNumber() == supportedMajorNumber && firmwareVersion.minorNumber() < supportedMinorNumber)) { (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 ...@@ -798,7 +798,7 @@ void APMFirmwarePlugin::_soloVideoHandshake(Vehicle* vehicle, bool originalSoloF
void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketError) 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) QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
...@@ -888,7 +888,7 @@ void APMFirmwarePlugin::pauseVehicle(Vehicle* vehicle) ...@@ -888,7 +888,7 @@ void APMFirmwarePlugin::pauseVehicle(Vehicle* vehicle)
void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{ {
if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) { 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; return;
} }
...@@ -908,7 +908,7 @@ void APMFirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL) ...@@ -908,7 +908,7 @@ void APMFirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
{ {
if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) { 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; return;
} }
...@@ -968,13 +968,13 @@ double APMFirmwarePlugin::minimumTakeoffAltitude(Vehicle* vehicle) ...@@ -968,13 +968,13 @@ double APMFirmwarePlugin::minimumTakeoffAltitude(Vehicle* vehicle)
bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel) bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
{ {
if (!vehicle->multiRotor() && !vehicle->vtol()) { 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; return false;
} }
double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble(); double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble();
if (qIsNaN(vehicleAltitudeAMSL)) { 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; return false;
} }
...@@ -984,12 +984,12 @@ bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel) ...@@ -984,12 +984,12 @@ bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
} }
if (!_setFlightModeAndValidate(vehicle, "Guided")) { 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; return false;
} }
if (!_armVehicleAndValidate(vehicle)) { 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; return false;
} }
...@@ -1007,7 +1007,7 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle) ...@@ -1007,7 +1007,7 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle)
if (vehicle->flying()) { if (vehicle->flying()) {
// Vehicle already in the air, we just need to switch to auto // Vehicle already in the air, we just need to switch to auto
if (!_setFlightModeAndValidate(vehicle, "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; return;
} }
...@@ -1015,19 +1015,19 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle) ...@@ -1015,19 +1015,19 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle)
if (!vehicle->armed()) { if (!vehicle->armed()) {
// First switch to flight mode we can arm from // First switch to flight mode we can arm from
if (!_setFlightModeAndValidate(vehicle, "Guided")) { 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; return;
} }
if (!_armVehicleAndValidate(vehicle)) { 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; return;
} }
} }
if (vehicle->fixedWing()) { if (vehicle->fixedWing()) {
if (!_setFlightModeAndValidate(vehicle, "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; return;
} }
} else { } else {
...@@ -1097,7 +1097,7 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti ...@@ -1097,7 +1097,7 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti
static bool sentOnce = false; static bool sentOnce = false;
if (!sentOnce) { if (!sentOnce) {
sentOnce = true; sentOnce = true;
qgcApp()->showMessage(tr("Follow failed: Home position not set.")); qgcApp()->showAppMessage(tr("Follow failed: Home position not set."));
} }
return; return;
} }
...@@ -1107,7 +1107,7 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti ...@@ -1107,7 +1107,7 @@ void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMoti
if (!sentOnce) { if (!sentOnce) {
sentOnce = true; sentOnce = true;
qWarning() << "APMFirmwarePlugin::_sendGCSMotionReport estimateCapabilities" << estimationCapabilities; 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; return;
} }
......
...@@ -76,7 +76,7 @@ void ArduRoverFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double ...@@ -76,7 +76,7 @@ void ArduRoverFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
Q_UNUSED(altitudeChange); Q_UNUSED(altitudeChange);
qgcApp()->showMessage(QStringLiteral("Change altitude not supported.")); qgcApp()->showAppMessage(QStringLiteral("Change altitude not supported."));
} }
bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/) bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/)
......
...@@ -224,14 +224,14 @@ void FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode) ...@@ -224,14 +224,14 @@ void FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
{ {
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
Q_UNUSED(guidedMode); Q_UNUSED(guidedMode);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
} }
void FirmwarePlugin::pauseVehicle(Vehicle* vehicle) void FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{ {
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(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) void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
...@@ -239,14 +239,14 @@ void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL) ...@@ -239,14 +239,14 @@ void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
Q_UNUSED(smartRTL); Q_UNUSED(smartRTL);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
} }
void FirmwarePlugin::guidedModeLand(Vehicle* vehicle) void FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{ {
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(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) void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel)
...@@ -254,7 +254,7 @@ void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel) ...@@ -254,7 +254,7 @@ void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel)
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
Q_UNUSED(takeoffAltRel); 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) void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
...@@ -262,19 +262,19 @@ void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordina ...@@ -262,19 +262,19 @@ void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordina
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
Q_UNUSED(gotoCoord); Q_UNUSED(gotoCoord);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
} }
void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double) void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double)
{ {
// Not supported by generic vehicle // 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*) void FirmwarePlugin::startMission(Vehicle*)
{ {
// Not supported by generic 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 const FirmwarePlugin::remapParamNameMajorVersionMap_t& FirmwarePlugin::paramNameRemapMajorVersionMap(void) const
...@@ -862,7 +862,7 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString& ...@@ -862,7 +862,7 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString&
QString currentVersionNumber = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion()) QString currentVersionNumber = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion())
.arg(vehicle->firmwareMinorVersion()) .arg(vehicle->firmwareMinorVersion())
.arg(vehicle->firmwarePatchVersion()); .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));
} }
} }
......
...@@ -401,7 +401,7 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel ...@@ -401,7 +401,7 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel
{ {
double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble(); double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble();
if (qIsNaN(vehicleAltitudeAMSL)) { if (qIsNaN(vehicleAltitudeAMSL)) {
qgcApp()->showMessage(tr("Unable to takeoff, vehicle position not known.")); qgcApp()->showAppMessage(tr("Unable to takeoff, vehicle position not known."));
return; return;
} }
...@@ -424,7 +424,7 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel ...@@ -424,7 +424,7 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel
void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{ {
if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) { 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; return;
} }
...@@ -457,11 +457,11 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord ...@@ -457,11 +457,11 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
{ {
if (!vehicle->homePosition().isValid()) { 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; return;
} }
if (qIsNaN(vehicle->homePosition().altitude())) { 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; return;
} }
...@@ -484,11 +484,11 @@ void PX4FirmwarePlugin::startMission(Vehicle* vehicle) ...@@ -484,11 +484,11 @@ void PX4FirmwarePlugin::startMission(Vehicle* vehicle)
{ {
if (_setFlightModeAndValidate(vehicle, missionFlightMode())) { if (_setFlightModeAndValidate(vehicle, missionFlightMode())) {
if (!_armVehicleAndValidate(vehicle)) { if (!_armVehicleAndValidate(vehicle)) {
qgcApp()->showMessage(tr("Unable to start mission: Vehicle rejected arming.")); qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle rejected arming."));
return; return;
} }
} else { } 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 ...@@ -560,7 +560,7 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
if (notifyUser) { if (notifyUser) {
instanceData->versionNotified = true; 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));
} }
} }
} }
......
...@@ -48,19 +48,19 @@ QStringList ComplexMissionItem::presetNames(void) ...@@ -48,19 +48,19 @@ QStringList ComplexMissionItem::presetNames(void)
void ComplexMissionItem::loadPreset(const QString& name) void ComplexMissionItem::loadPreset(const QString& name)
{ {
Q_UNUSED(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) void ComplexMissionItem::savePreset(const QString& name)
{ {
Q_UNUSED(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) void ComplexMissionItem::deletePreset(const QString& name)
{ {
if (qgcApp()->toolbox()->corePlugin()->options()->surveyBuiltInPresetNames().contains(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; return;
} }
......
...@@ -216,7 +216,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq ...@@ -216,7 +216,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
bool loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool(); bool loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool();
bool landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool(); bool landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool();
if (loiterAltitudeRelative != landingAltitudeRelative) { 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. " "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.")); "Both have been set to altitude relative. Be sure to adjust/check your plan prior to flight."));
_altitudesAreRelative = true; _altitudesAreRelative = true;
......
...@@ -88,7 +88,7 @@ void MissionManager::generateResumeMission(int resumeIndex) ...@@ -88,7 +88,7 @@ void MissionManager::generateResumeMission(int resumeIndex)
for (int i=0; i<_missionItems.count(); i++) { for (int i=0; i<_missionItems.count(); i++) {
MissionItem* item = _missionItems[i]; MissionItem* item = _missionItems[i];
if (item->command() == MAV_CMD_DO_JUMP) { 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; return;
} }
} }
......
Supports Markdown
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