Commit 982e4d06 authored by Don Gagne's avatar Don Gagne

Merge pull request #2104 from DonLakeFlyer/MissionDrag

Mission drag visuals
parents a5597700 d8fb65d6
......@@ -62,6 +62,7 @@
<file alias="ZoomMinus.svg">src/FlightMap/Images/ZoomMinus.svg</file>
<!-- Map Buttons -->
<file alias="ArrowHead.svg">src/FlightMap/Images/ArrowHead.svg</file>
<file alias="Help.svg">src/FlightMap/Images/Help.svg</file>
<file alias="HelpBlack.svg">src/FlightMap/Images/HelpBlack.svg</file>
<file alias="MapAddMission.svg">src/FlightMap/Images/MapAddMission.svg</file>
......
......@@ -75,7 +75,7 @@ QGCView {
id: controller
Component.onCompleted: start(true /* editMode */)
/*
/*
FIXME: autoSync is temporarily disconnected since it's still buggy
autoSync: QGroundControl.flightMapSettings.loadMapSetting(editorMap.mapName, _autoSyncKey, true)
......@@ -83,7 +83,7 @@ QGCView {
onAutoSyncChanged: QGroundControl.flightMapSettings.saveMapSetting(editorMap.mapName, _autoSyncKey, autoSync)
*/
onMissionItemsChanged: itemEditor.clearItem()
onMissionItemsChanged: itemDragger.clearItem()
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......@@ -160,58 +160,178 @@ QGCView {
}
// We use this item to support dragging since dragging a MapQuickItem just doesn't seem to work
Item {
id: itemEditor
x: missionItemIndicator ? (missionItemIndicator.x + missionItemIndicator.anchorPoint.x - (itemEditor.width / 2)) : 100
y: missionItemIndicator ? (missionItemIndicator.y + missionItemIndicator.anchorPoint.y - (itemEditor.height / 2)) : 100
width: ScreenTools.defaultFontPixelHeight * 7
height: ScreenTools.defaultFontPixelHeight * 7
visible: false
z: QGroundControl.zOrderMapItems + 1 // Above item icons
Rectangle {
id: itemDragger
x: missionItemIndicator ? (missionItemIndicator.x + missionItemIndicator.anchorPoint.x - (itemDragger.width / 2)) : 100
y: missionItemIndicator ? (missionItemIndicator.y + missionItemIndicator.anchorPoint.y - (itemDragger.height / 2)) : 100
width: _radius * 2
height: _radius * 2
radius: _radius
border.width: 2
border.color: "white"
color: "transparent"
visible: false
z: QGroundControl.zOrderMapItems + 1 // Above item icons
property var missionItem
property var missionItemIndicator
property real heading: missionItem ? missionItem.heading : 0
readonly property real _radius: ScreenTools.defaultFontPixelHeight * 4
readonly property real _arrowHeight: ScreenTools.defaultFontPixelHeight
function clearItem() {
itemEditor.visible = false
itemEditor.missionItem = undefined
itemEditor.missionItemIndicator = undefined
itemDragger.visible = false
itemDragger.missionItem = undefined
itemDragger.missionItemIndicator = undefined
}
Image {
anchors.horizontalCenter: parent.horizontalCenter
anchors.top: parent.top
height: parent._arrowHeight
fillMode: Image.PreserveAspectFit
mipmap: true
smooth: true
source: "/qmlimages/ArrowHead.svg"
}
Image {
id: arrowUp
anchors.verticalCenter: parent.verticalCenter
anchors.right: parent.right
height: parent._arrowHeight
fillMode: Image.PreserveAspectFit
mipmap: true
smooth: true
source: "/qmlimages/ArrowHead.svg"
transform: Rotation { origin.x: arrowUp.width / 2; origin.y: arrowUp.height / 2; angle: 90}
}
Image {
id: arrowDown
anchors.horizontalCenter: parent.horizontalCenter
anchors.bottom: parent.bottom
height: parent._arrowHeight
fillMode: Image.PreserveAspectFit
mipmap: true
smooth: true
source: "/qmlimages/ArrowHead.svg"
transform: Rotation { origin.x: arrowDown.width / 2; origin.y: arrowDown.height / 2; angle: 180}
}
Image {
id: arrowLeft
anchors.verticalCenter: parent.verticalCenter
anchors.left: parent.left
height: parent._arrowHeight
fillMode: Image.PreserveAspectFit
mipmap: true
smooth: true
source: "/qmlimages/ArrowHead.svg"
transform: Rotation { origin.x: arrowLeft.width / 2; origin.y: arrowLeft.height / 2; angle: -90}
}
Rectangle {
width: _radius * 2
height: _radius * 2
radius: _radius
anchors.verticalCenter: parent.verticalCenter
anchors.horizontalCenter: parent.horizontalCenter
border.width: 1
border.color: "white"
readonly property real _radius: ScreenTools.defaultFontPixelWidth / 4
}
Drag.active: itemDrag.drag.active
Drag.hotSpot.x: width / 2
Drag.hotSpot.y: height / 2
MissionItemIndexLabel {
x: (itemEditor.width / 2) - (width / 2)
y: (itemEditor.height / 2) - (height / 2)
label: itemEditor.missionItemIndicator ? itemEditor.missionItemIndicator.label : ""
isCurrentItem: true
}
MouseArea {
id: itemDrag
anchors.fill: parent
drag.target: parent
drag.minimumX: 0
drag.minimumY: 0
drag.maximumX: itemDragger.parent.width - parent.width
drag.maximumY: itemDragger.parent.height - parent.height
property bool dragActive: drag.active
onDragActiveChanged: {
if (!drag.active) {
var point = Qt.point(itemEditor.x + (itemEditor.width / 2), itemEditor.y + (itemEditor.height / 2))
var point = Qt.point(itemDragger.x + (itemDragger.width / 2), itemDragger.y + (itemDragger.height / 2))
var coordinate = editorMap.toCoordinate(point)
coordinate.altitude = itemEditor.missionItem.coordinate.altitude
itemEditor.missionItem.coordinate = coordinate
coordinate.altitude = itemDragger.missionItem.coordinate.altitude
itemDragger.missionItem.coordinate = coordinate
editorMap.latitude = itemDragger.missionItem.coordinate.latitude
editorMap.longitude = itemDragger.missionItem.coordinate.longitude
}
}
}
}
// Add the mission items to the map
MissionItemView {
MapItemView {
model: controller.missionItems
itemDragger: itemEditor
delegate: delegateComponent
}
Component {
id: delegateComponent
MissionItemIndicator {
id: itemIndicator
label: object.homePosition ? "H" : object.sequenceNumber
isCurrentItem: object.isCurrentItem
coordinate: object.coordinate
visible: object.specifiesCoordinate && (!object.homePosition || object.homePositionValid)
z: QGroundControl.zOrderMapItems
onClicked: setCurrentItem(object.sequenceNumber)
Connections {
target: object
onIsCurrentItemChanged: {
if (object.isCurrentItem && object.specifiesCoordinate) {
// Setup our drag item
if (object.sequenceNumber != 0) {
itemDragger.visible = true
itemDragger.missionItem = Qt.binding(function() { return object })
itemDragger.missionItemIndicator = Qt.binding(function() { return itemIndicator })
} else {
itemDragger.clearItem()
}
// Move to the new position
editorMap.latitude = object.coordinate.latitude
editorMap.longitude = object.coordinate.longitude
} else {
itemDragger.clearItem()
}
}
}
// These are the non-coordinate child mission items attached to this item
Row {
anchors.top: parent.top
anchors.left: parent.right
Repeater {
model: object.childItems
delegate: MissionItemIndexLabel {
label: object.sequenceNumber
isCurrentItem: object.isCurrentItem
z: 2
onClicked: setCurrentItem(object.sequenceNumber)
}
}
}
}
}
// Add lines between waypoints
......@@ -782,7 +902,7 @@ QGCView {
z: QGroundControl.zOrderWidgets
onClicked: {
itemEditor.clearItem()
itemDragger.clearItem()
controller.deleteCurrentMissionItem()
checked = false
}
......
......@@ -29,6 +29,8 @@ This file is part of the QGROUNDCONTROL project
#include "QGCMessageBox.h"
#include "FirmwarePlugin.h"
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")
const char* MissionController::_settingsGroup = "MissionController";
MissionController::MissionController(QObject *parent)
......@@ -39,7 +41,7 @@ MissionController::MissionController(QObject *parent)
, _activeVehicle(NULL)
, _liveHomePositionAvailable(false)
, _autoSync(false)
, _firstMissionItemSync(false)
, _firstItemsFromVehicle(false)
, _missionItemsRequested(false)
, _queuedSend(false)
{
......@@ -48,50 +50,75 @@ MissionController::MissionController(QObject *parent)
MissionController::~MissionController()
{
// Start with empty list
_canEdit = true;
_missionItems = new QmlObjectListModel(this);
_initAllMissionItems();
}
void MissionController::start(bool editMode)
{
qCDebug(MissionControllerLog) << "start editMode" << editMode;
_editMode = editMode;
MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance();
connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
Vehicle* activeVehicle = multiVehicleMgr->activeVehicle();
if (activeVehicle) {
_activeVehicleChanged(activeVehicle);
} else {
_missionItemsRequested = true;
_newMissionItemsAvailable();
}
_setupMissionItems(true /* fromVehicle */, true /* force */);
}
void MissionController::_newMissionItemsAvailable(void)
void MissionController::_newMissionItemsAvailableFromVehicle(void)
{
if (_editMode) {
if (_firstMissionItemSync) {
// This is the first time the vehicle is seeing items. We have to be careful of transitioning from offline
// to online.
_firstMissionItemSync = false;
if (_missionItems && _missionItems->count() > 1) {
QGCMessageBox::StandardButton button = QGCMessageBox::warning("Mission Editing",
"The vehicle has sent a new set of Mission Items. "
"Do you want to discard your current set of unsaved items and use the ones from the vehicle instead?",
QGCMessageBox::Yes | QGCMessageBox::No,
QGCMessageBox::No);
if (button == QGCMessageBox::No) {
return;
qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";
_setupMissionItems(true /* fromVehicle */, false /* force */);
}
/// @param fromVehicle true: load items from vehicle
/// @param force true: disregard any flags which may prevent load
void MissionController::_setupMissionItems(bool fromVehicle, bool force)
{
qCDebug(MissionControllerLog) << "_setupMissionItems fromVehicle:force:_editMode:_firstItemsFromVehicle" << fromVehicle << force << _editMode << _firstItemsFromVehicle;
MissionManager* missionManager = NULL;
if (_activeVehicle) {
missionManager = _activeVehicle->missionManager();
} else {
qCDebug(MissionControllerLog) << "running offline";
}
if (!force) {
if (_editMode && fromVehicle) {
if (_firstItemsFromVehicle) {
if (missionManager) {
if (missionManager->inProgress()) {
// Still in progress of retrieving items from vehicle, leave current set alone and wait for
// mission manager to finish
qCDebug(MissionControllerLog) << "disregarding due to MissionManager in progress";
return;
} else {
// We have the first set of items from the vehicle. If we haven't already started creating a
// new mission, switch to the items from the vehicle
_firstItemsFromVehicle = false;
if (_missionItems->count() != 1) {
qCDebug(MissionControllerLog) << "disregarding due to existing items";
return;
}
}
}
} else if (!_missionItemsRequested) {
// We didn't specifically ask for new mission items. Disregard the new set since it is
// the most likely the set we just sent to the vehicle.
qCDebug(MissionControllerLog) << "disregarding due to unrequested notification";
return;
}
} else if (!_missionItemsRequested) {
// We didn't specifically ask for new mission items. Disregard the new set since it is
// the most likely the set we just sent to the vehicle.
return;
}
}
qCDebug(MissionControllerLog) << "fell through to main setup";
_missionItemsRequested = false;
if (_missionItems) {
......@@ -99,17 +126,14 @@ void MissionController::_newMissionItemsAvailable(void)
_missionItems->deleteLater();
}
MissionManager* missionManager = NULL;
if (_activeVehicle) {
missionManager = _activeVehicle->missionManager();
}
if (!missionManager || missionManager->inProgress()) {
if (!missionManager || !fromVehicle || missionManager->inProgress()) {
_canEdit = true;
_missionItems = new QmlObjectListModel(this);
qCDebug(MissionControllerLog) << "creating empty set";
} else {
_canEdit = missionManager->canEdit();
_missionItems = missionManager->copyMissionItems();
qCDebug(MissionControllerLog) << "loading from vehicle count"<< _missionItems->count();
}
_initAllMissionItems();
......@@ -121,8 +145,6 @@ void MissionController::getMissionItems(void)
if (activeVehicle) {
_missionItemsRequested = true;
MissionManager* missionManager = activeVehicle->missionManager();
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailable);
activeVehicle->missionManager()->requestMissionItems();
}
}
......@@ -406,15 +428,19 @@ void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD com
void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
{
qCDebug(MissionControllerLog) << "_activeVehicleChanged activeVehicle" << activeVehicle;
if (_activeVehicle) {
MissionManager* missionManager = _activeVehicle->missionManager();
disconnect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailable);
disconnect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
disconnect(missionManager, &MissionManager::inProgressChanged, this, &MissionController::_inProgressChanged);
disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged);
disconnect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
_activeVehicle = NULL;
_newMissionItemsAvailable();
// When the active vehicle goes away we toss the editor items
_setupMissionItems(false /* fromVehicle */, true /* force */);
_activeVehicleHomePositionAvailableChanged(false);
}
......@@ -423,21 +449,13 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
if (_activeVehicle) {
MissionManager* missionManager = activeVehicle->missionManager();
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailable);
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
connect(missionManager, &MissionManager::inProgressChanged, this, &MissionController::_inProgressChanged);
connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged);
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged);
if (missionManager->inProgress()) {
// Vehicle is still in process of requesting mission items
_firstMissionItemSync = true;
} else {
// Vehicle already has mission items
_firstMissionItemSync = false;
}
_missionItemsRequested = true;
_newMissionItemsAvailable();
_firstItemsFromVehicle = true;
_setupMissionItems(true /* fromVehicle */, false /* force */);
_activeVehicleHomePositionChanged(_activeVehicle->homePosition());
_activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
......
......@@ -28,6 +28,9 @@ This file is part of the QGROUNDCONTROL project
#include "QmlObjectListModel.h"
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
class MissionController : public QObject
{
......@@ -72,7 +75,7 @@ signals:
void autoSyncChanged(bool autoSync);
private slots:
void _newMissionItemsAvailable();
void _newMissionItemsAvailableFromVehicle();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void _activeVehicleChanged(Vehicle* activeVehicle);
......@@ -91,6 +94,7 @@ private:
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
void _autoSyncSend(void);
void _setupMissionItems(bool fromVehicle, bool force);
private:
bool _editMode;
......@@ -101,7 +105,7 @@ private:
bool _liveHomePositionAvailable;
QGeoCoordinate _liveHomePosition;
bool _autoSync;
bool _firstMissionItemSync;
bool _firstItemsFromVehicle;
bool _missionItemsRequested;
bool _queuedSend;
......
......@@ -47,8 +47,6 @@ void MissionControllerManagerTest::cleanup(void)
void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
{
UnitTest::init();
LinkManager* linkMgr = LinkManager::instance();
Q_CHECK_PTR(linkMgr);
......
......@@ -36,12 +36,15 @@ MissionControllerTest::MissionControllerTest(void)
void MissionControllerTest::cleanup(void)
{
delete _missionController;
_missionController = NULL;
MissionControllerManagerTest::cleanup();
}
void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
{
bool startController = false;
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
_rgSignals[missionItemsChangedSignalIndex] = SIGNAL(missionItemsChanged());
......@@ -49,17 +52,22 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
_rgSignals[liveHomePositionAvailableChangedSignalIndex] = SIGNAL(liveHomePositionAvailableChanged(bool));
_rgSignals[liveHomePositionChangedSignalIndex] = SIGNAL(liveHomePositionChanged(const QGeoCoordinate&));
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
if (!_missionController) {
startController = true;
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
}
_multiSpy = new MultiSignalSpy();
Q_CHECK_PTR(_multiSpy);
QCOMPARE(_multiSpy->init(_missionController, _rgSignals, _cSignals), true);
_missionController->start(false /* editMode */);
if (startController) {
_missionController->start(false /* editMode */);
}
// All signals should some through on start
QCOMPARE(_multiSpy->checkOnlySignalByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask | liveHomePositionAvailableChangedSignalMask | liveHomePositionChangedSignalMask), true);
QCOMPARE(_multiSpy->checkOnlySignalsByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask | liveHomePositionAvailableChangedSignalMask | liveHomePositionChangedSignalMask), true);
_multiSpy->clearAllSignals();
QmlObjectListModel* missionItems = _missionController->missionItems();
......@@ -183,3 +191,28 @@ void MissionControllerTest::_testAddWayppointPX4(void)
{
_testAddWaypointWorker(MAV_AUTOPILOT_PX4);
}
void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType)
{
// Start offline and add item
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */);
_missionController->addMissionItem(QGeoCoordinate(37.803784, -122.462276));
// Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
// Make sure our offline mission items are still there
QCOMPARE(_missionController->missionItems()->count(), 2);
}
void MissionControllerTest::_testOfflineToOnlineAPM(void)
{
_testOfflineToOnlineWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}
void MissionControllerTest::_testOfflineToOnlinePX4(void)
{
_testOfflineToOnlineWorker(MAV_AUTOPILOT_PX4);
}
......@@ -43,15 +43,19 @@ public:
private slots:
void cleanup(void);
void _testEmptyVehicleAPM(void);
void _testEmptyVehiclePX4(void);
void _testAddWayppointAPM(void);
void _testAddWayppointPX4(void);
void _testOfflineToOnlineAPM(void);
void _testOfflineToOnlinePX4(void);
private:
void _initForFirmwareType(MAV_AUTOPILOT firmwareType);
void _testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType);
void _testAddWaypointWorker(MAV_AUTOPILOT firmwareType);
void _testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType);
void _testEmptyVehicleAPM(void);
void _testEmptyVehiclePX4(void);
void _testAddWayppointAPM(void);
void _testAddWayppointPX4(void);
enum {
missionItemsChangedSignalIndex = 0,
......
......@@ -91,8 +91,8 @@ Item {
onPositionChanged: {
tabletPosition = positionSource.position.coordinate
_root.latitude = tabletPosition.latitude
_root.longitude = tabletPosition.longitude
flightView.latitude = tabletPosition.latitude
flightView.longitude = tabletPosition.longitude
positionSource.active = false
}
}
......
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