diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index 253720c..6b44b3d 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project #include "UAS.h" #include "mavlink_types.h" #include "UASManager.h" +#include "MainWindow.h" #define PROTOCOL_TIMEOUT_MS 2000 ///< maximum time to wait for pending messages until timeout #define PROTOCOL_DELAY_MS 20 ///< minimum delay between sent messages @@ -371,6 +372,10 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi { if (wp) { + // Check if this is the first waypoint in an offline list + if (waypointsEditable.count() == 0 && uas == NULL) + MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect.")); + wp->setId(waypointsEditable.count()); if (enforceFirstActive && waypointsEditable.count() == 0) { @@ -390,10 +395,15 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi */ Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive) { + // Check if this is the first waypoint in an offline list + if (waypointsEditable.count() == 0 && uas == NULL) + MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect.")); + Waypoint* wp = new Waypoint(); wp->setId(waypointsEditable.count()); wp->setFrame((MAV_FRAME)getFrameRecommendation()); wp->setAltitude(getAltitudeRecommendation()); + wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation()); if (enforceFirstActive && waypointsEditable.count() == 0) { wp->setCurrent(true); diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index f4473a0..b453f34 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -206,18 +206,6 @@ void WaypointList::saveWaypoints() void WaypointList::loadWaypoints() { - //create a popup notifying the user about the limitations of offline editing - if (showOfflineWarning == true) - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Warning); - msgBox.setText("Offline editor!"); - msgBox.setInformativeText("You are using the offline mission editor. Please don't forget to save your mission plan before connecting the UAV, otherwise it will be lost."); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - showOfflineWarning = false; - } QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)")); WPM->loadWaypoints(fileName); } @@ -346,18 +334,6 @@ void WaypointList::addEditable(bool onCurrentPosition) UASManager::instance()->getHomeLongitude(), WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); - //create a popup notifying the user about the limitations of offline editing - if (showOfflineWarning == true) - { - QMessageBox msgBox; - msgBox.setIcon(QMessageBox::Warning); - msgBox.setText("Offline editor!"); - msgBox.setInformativeText("You are using the offline mission editor. Please don't forget to save your mission plan before connecting the UAV, otherwise it will be lost."); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - showOfflineWarning = false; - } } } }