diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 8c7813459c91f5619fe0968336cecfa1ef51d5a1..2025d4b6b69c38bf4801ae7de76cb58d904710c4 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -404,11 +404,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 9be3c6ad5aefcb7ef4f5845c46086f38cb84f0eb..e08b0f78976f598b9673dac77d739314d522dbbe 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1750,19 +1750,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)