diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 827bf856b479f6d933f77380341902b5276c6e6f..4cef7aaf859e195c89d837f9343f2cb3024bdb43 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -401,11 +401,11 @@ bool QGCApplication::_initForNormalAppBoot(void) // Start the user interface MainWindow* mainWindow = MainWindow::_create(); Q_CHECK_PTR(mainWindow); +#endif // Now that main window is up check for lost log files connect(this, &QGCApplication::checkForLostLogFiles, toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); -#endif // Load known link configurations toolbox()->linkManager()->loadLinkConfigurationList(); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 68309dcea73931771f063961376d03b5ef04233e..01030f8f859a00235d9a65fe235b1225282ff10c 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1836,19 +1836,19 @@ void Vehicle::sendMessageMultiple(mavlink_message_t message) void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg) { Q_UNUSED(errorCode); - qgcApp()->showMessage(QString("Error during Mission communication with Vehicle: %1").arg(errorMsg)); + qgcApp()->showMessage(QString("Mission transfer failed. Retry transfer. Error: %1").arg(errorMsg)); } void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg) { Q_UNUSED(errorCode); - qgcApp()->showMessage(QString("Error during GeoFence communication with Vehicle: %1").arg(errorMsg)); + qgcApp()->showMessage(QString("GeoFence transfer failed. Retry transfer. Error: %1").arg(errorMsg)); } void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg) { Q_UNUSED(errorCode); - qgcApp()->showMessage(QString("Error during Rally Point communication with Vehicle: %1").arg(errorMsg)); + qgcApp()->showMessage(QString("Rally Point transfer failed. Retry transfer. Error: %1").arg(errorMsg)); } void Vehicle::_addNewMapTrajectoryPoint(void)