Commit dfaafee2 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #3606 from DonLakeFlyer/MissionLoad

Plan: Mission loads from vehicle automatically
parents d23621eb 90cfe9db
...@@ -28,8 +28,6 @@ import QGroundControl.Controllers 1.0 ...@@ -28,8 +28,6 @@ import QGroundControl.Controllers 1.0
QGCView { QGCView {
id: _root id: _root
property bool syncNeeded: controller.visualItems.dirty // Unsaved changes, visible to parent container
viewPanel: panel viewPanel: panel
// zOrder comes from the Loader in MainWindow.qml // zOrder comes from the Loader in MainWindow.qml
...@@ -46,6 +44,7 @@ QGCView { ...@@ -46,6 +44,7 @@ QGCView {
readonly property int _addMissionItemsButtonAutoOffTimeout: 10000 readonly property int _addMissionItemsButtonAutoOffTimeout: 10000
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276) readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
property bool _syncNeeded: controller.visualItems.dirty // Unsaved changes, visible to parent container
property var _visualItems: controller.visualItems property var _visualItems: controller.visualItems
property var _currentMissionItem property var _currentMissionItem
property int _currentMissionIndex: 0 property int _currentMissionIndex: 0
...@@ -561,7 +560,7 @@ QGCView { ...@@ -561,7 +560,7 @@ QGCView {
DropButton { DropButton {
id: syncButton id: syncButton
dropDirection: dropRight dropDirection: dropRight
buttonImage: syncNeeded ? "/qmlimages/MapSyncChanged.svg" : "/qmlimages/MapSync.svg" buttonImage: _syncNeeded ? "/qmlimages/MapSyncChanged.svg" : "/qmlimages/MapSync.svg"
viewportMargins: ScreenTools.defaultFontPixelWidth / 2 viewportMargins: ScreenTools.defaultFontPixelWidth / 2
exclusiveGroup: _dropButtonsExclusiveGroup exclusiveGroup: _dropButtonsExclusiveGroup
dropDownComponent: syncDropDownComponent dropDownComponent: syncDropDownComponent
...@@ -745,7 +744,7 @@ QGCView { ...@@ -745,7 +744,7 @@ QGCView {
QGCLabel { QGCLabel {
width: sendSaveGrid.width width: sendSaveGrid.width
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
text: syncNeeded && !controller.autoSync ? text: _syncNeeded && !controller.autoSync ?
qsTr("You have unsaved changed to you mission. You should send to your vehicle, or save to a file:") : qsTr("You have unsaved changed to you mission. You should send to your vehicle, or save to a file:") :
qsTr("Sync:") qsTr("Sync:")
} }
...@@ -771,7 +770,7 @@ QGCView { ...@@ -771,7 +770,7 @@ QGCView {
enabled: _activeVehicle && !controller.syncInProgress enabled: _activeVehicle && !controller.syncInProgress
onClicked: { onClicked: {
syncButton.hideDropDown() syncButton.hideDropDown()
if (syncNeeded) { if (_syncNeeded) {
_root.showDialog(syncLoadFromVehicleOverwrite, qsTr("Mission overwrite"), _root.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel) _root.showDialog(syncLoadFromVehicleOverwrite, qsTr("Mission overwrite"), _root.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel)
} else { } else {
loadFromVehicle() loadFromVehicle()
...@@ -793,7 +792,7 @@ QGCView { ...@@ -793,7 +792,7 @@ QGCView {
enabled: !controller.syncInProgress enabled: !controller.syncInProgress
onClicked: { onClicked: {
syncButton.hideDropDown() syncButton.hideDropDown()
if (syncNeeded) { if (_syncNeeded) {
_root.showDialog(syncLoadFromFileOverwrite, qsTr("Mission overwrite"), _root.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel) _root.showDialog(syncLoadFromFileOverwrite, qsTr("Mission overwrite"), _root.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel)
} else { } else {
loadFromFile() loadFromFile()
......
...@@ -76,10 +76,10 @@ void MissionController::_newMissionItemsAvailableFromVehicle(void) ...@@ -76,10 +76,10 @@ void MissionController::_newMissionItemsAvailableFromVehicle(void)
if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) { if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) {
// Fly Mode: // Fly Mode:
// - Always accepts new items fromthe vehicle so Fly view is kept up to date // - Always accepts new items from the vehicle so Fly view is kept up to date
// Edit Mode: // Edit Mode:
// - Either a load from vehicle was manually requested or // - Either a load from vehicle was manually requested or
// - The initial automatic load from a vehicle completed and the current editor it empty // - The initial automatic load from a vehicle completed and the current editor is empty
QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this); QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems(); const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
...@@ -948,6 +948,10 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -948,6 +948,10 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
_activeVehicle = NULL; _activeVehicle = NULL;
} }
// We always remove all items on vehicle change. This leaves a user model hole:
// If the user has unsaved changes in the Plan view they will lose them
removeAllMissionItems();
_activeVehicle = activeVehicle; _activeVehicle = activeVehicle;
if (_activeVehicle) { if (_activeVehicle) {
...@@ -959,8 +963,9 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -959,8 +963,9 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged);
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
if (!_editMode) { if (!syncInProgress()) {
removeAllMissionItems(); // We have to manually ask for the items from the Vehicle
getMissionItems();
} }
_activeVehicleHomePositionChanged(_activeVehicle->homePosition()); _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
......
...@@ -175,8 +175,13 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp ...@@ -175,8 +175,13 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
// Go online to empty vehicle // Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType); MissionControllerManagerTest::_initForFirmwareType(firmwareType);
// Make sure our offline mission items are still there #if 1
// Due to current limitations, offline items will go away
QCOMPARE(_missionController->visualItems()->count(), 1);
#else
//Make sure our offline mission items are still there
QCOMPARE(_missionController->visualItems()->count(), 2); QCOMPARE(_missionController->visualItems()->count(), 2);
#endif
} }
void MissionControllerTest::_testOfflineToOnlineAPM(void) void MissionControllerTest::_testOfflineToOnlineAPM(void)
......
...@@ -44,6 +44,11 @@ MissionManager::~MissionManager() ...@@ -44,6 +44,11 @@ MissionManager::~MissionManager()
void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems) void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
{ {
if (inProgress()) {
qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
return;
}
bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle(); bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
_missionItems.clear(); _missionItems.clear();
...@@ -68,11 +73,6 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems) ...@@ -68,11 +73,6 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count(); qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
if (inProgress()) {
qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
return;
}
// Prime write list // Prime write list
for (int i=0; i<_missionItems.count(); i++) { for (int i=0; i<_missionItems.count(); i++) {
_itemIndicesToWrite << i; _itemIndicesToWrite << i;
...@@ -132,6 +132,11 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC ...@@ -132,6 +132,11 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC
void MissionManager::requestMissionItems(void) void MissionManager::requestMissionItems(void)
{ {
qCDebug(MissionManagerLog) << "requestMissionItems read sequence"; qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
if (inProgress()) {
qCDebug(MissionManagerLog) << "requestMissionItems called while transaction in progress";
return;
}
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_request_list_t request; mavlink_mission_request_list_t request;
......
Markdown is supported
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