Commit 8498d36e authored by DonLakeFlyer's avatar DonLakeFlyer

Support survey polygon drag

parent 950ee021
......@@ -384,7 +384,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/FactSystem/ParameterManagerTest.h \
src/MissionManager/ComplexMissionItemTest.h \
src/MissionManager/SurveyMissionItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionControllerTest.h \
......@@ -412,7 +412,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/FactSystem/ParameterManagerTest.cc \
src/MissionManager/ComplexMissionItemTest.cc \
src/MissionManager/SurveyMissionItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionControllerTest.cc \
......
......@@ -85,6 +85,7 @@
<file alias="QGroundControl/Controls/QGCLabel.qml">src/QmlControls/QGCLabel.qml</file>
<file alias="QGroundControl/Controls/QGCListView.qml">src/QmlControls/QGCListView.qml</file>
<file alias="QGroundControl/Controls/QGCMapLabel.qml">src/QmlControls/QGCMapLabel.qml</file>
<file alias="QGroundControl/Controls/QGCMapPolygonVisuals.qml">src/MissionManager/QGCMapPolygonVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMouseArea.qml">src/QmlControls/QGCMouseArea.qml</file>
<file alias="QGroundControl/Controls/QGCMovableItem.qml">src/QmlControls/QGCMovableItem.qml</file>
<file alias="QGroundControl/Controls/QGCPipable.qml">src/QmlControls/QGCPipable.qml</file>
......
......@@ -16,15 +16,17 @@
#include <QDebug>
#include <QJsonArray>
const char* QGCMapPolygon::_jsonPolygonKey = "polygon";
const char* QGCMapPolygon::jsonPolygonKey = "polygon";
QGCMapPolygon::QGCMapPolygon(QObject* newCoordParent, QObject* parent)
: QObject(parent)
, _newCoordParent(newCoordParent)
, _dirty(false)
, _ignoreCenterUpdates(false)
{
connect(&_polygonModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolygon::_polygonModelDirtyChanged);
connect(&_polygonModel, &QmlObjectListModel::countChanged, this, &QGCMapPolygon::_polygonModelCountChanged);
connect(&_polygonModel, &QmlObjectListModel::countChanged, this, &QGCMapPolygon::_updateCenter);
}
void QGCMapPolygon::clear(void)
......@@ -43,6 +45,8 @@ void QGCMapPolygon::clear(void)
_polygonModel.clearAndDeleteContents();
emit cleared();
setDirty(true);
}
......@@ -53,6 +57,10 @@ void QGCMapPolygon::adjustVertex(int vertexIndex, const QGeoCoordinate coordinat
_polygonModel.value<QGCQGeoCoordinate*>(vertexIndex)->setCoordinate(coordinate);
if (!_ignoreCenterUpdates) {
_updateCenter();
}
setDirty(true);
}
......@@ -111,16 +119,6 @@ bool QGCMapPolygon::containsCoordinate(const QGeoCoordinate& coordinate) const
}
}
QGeoCoordinate QGCMapPolygon::center(void) const
{
if (_polygonPath.count() > 2) {
QPointF centerPoint = _toPolygonF().boundingRect().center();
return _coordFromPointF(centerPoint);
} else {
return QGeoCoordinate();
}
}
void QGCMapPolygon::setPath(const QList<QGeoCoordinate>& path)
{
_polygonPath.clear();
......@@ -152,7 +150,7 @@ void QGCMapPolygon::saveToJson(QJsonObject& json)
QJsonValue jsonValue;
JsonHelper::saveGeoCoordinateArray(_polygonPath, false /* writeAltitude*/, jsonValue);
json.insert(_jsonPolygonKey, jsonValue);
json.insert(jsonPolygonKey, jsonValue);
setDirty(false);
}
......@@ -162,14 +160,14 @@ bool QGCMapPolygon::loadFromJson(const QJsonObject& json, bool required, QString
clear();
if (required) {
if (!JsonHelper::validateRequiredKeys(json, QStringList(_jsonPolygonKey), errorString)) {
if (!JsonHelper::validateRequiredKeys(json, QStringList(jsonPolygonKey), errorString)) {
return false;
}
} else if (!json.contains(_jsonPolygonKey)) {
} else if (!json.contains(jsonPolygonKey)) {
return true;
}
if (!JsonHelper::loadGeoCoordinateArray(json[_jsonPolygonKey], false /* altitudeRequired */, _polygonPath, errorString)) {
if (!JsonHelper::loadGeoCoordinateArray(json[jsonPolygonKey], false /* altitudeRequired */, _polygonPath, errorString)) {
return false;
}
setDirty(false);
......@@ -249,3 +247,38 @@ void QGCMapPolygon::_polygonModelCountChanged(int count)
{
emit countChanged(count);
}
void QGCMapPolygon::_updateCenter(void)
{
if (!_ignoreCenterUpdates) {
QGeoCoordinate center;
if (_polygonPath.count() > 2) {
QPointF centerPoint = _toPolygonF().boundingRect().center();
center = _coordFromPointF(centerPoint);
}
_center = center;
emit centerChanged(center);
}
}
void QGCMapPolygon::setCenter(QGeoCoordinate newCenter)
{
if (newCenter != _center) {
_ignoreCenterUpdates = true;
// Adjust polygon vertices to new center
double distance = _center.distanceTo(newCenter);
double azimuth = _center.azimuthTo(newCenter);
for (int i=0; i<count(); i++) {
QGeoCoordinate oldVertex = _polygonPath[i].value<QGeoCoordinate>();
QGeoCoordinate newVertex = oldVertex.atDistanceAndAzimuth(distance, azimuth);
adjustVertex(i, newVertex);
}
_ignoreCenterUpdates = false;
_updateCenter();
}
}
......@@ -26,10 +26,11 @@ class QGCMapPolygon : public QObject
public:
QGCMapPolygon(QObject* newCoordParent, QObject* parent = NULL);
Q_PROPERTY(int count READ count NOTIFY countChanged)
Q_PROPERTY(QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(int count READ count NOTIFY countChanged)
Q_PROPERTY(QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_INVOKABLE void clear(void);
Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
......@@ -43,9 +44,6 @@ public:
/// Splits the segment comprised of vertextIndex -> vertexIndex + 1
Q_INVOKABLE void splitPolygonSegment(int vertexIndex);
/// Returns the center point coordinate for the polygon
Q_INVOKABLE QGeoCoordinate center(void) const;
/// Returns true if the specified coordinate is within the polygon
Q_INVOKABLE bool containsCoordinate(const QGeoCoordinate& coordinate) const;
......@@ -65,9 +63,11 @@ public:
// Property methods
int count (void) const { return _polygonPath.count(); }
bool dirty (void) const { return _dirty; }
void setDirty(bool dirty);
int count (void) const { return _polygonPath.count(); }
bool dirty (void) const { return _dirty; }
void setDirty(bool dirty);
QGeoCoordinate center (void) const { return _center; }
QVariantList path (void) const { return _polygonPath; }
QmlObjectListModel* qmlPathModel(void) { return &_polygonModel; }
......@@ -75,15 +75,21 @@ public:
void setPath(const QList<QGeoCoordinate>& path);
void setPath(const QVariantList& path);
void setCenter(QGeoCoordinate newCenter);
static const char* jsonPolygonKey;
signals:
void countChanged(int count);
void pathChanged(void);
void dirtyChanged(bool dirty);
void countChanged (int count);
void pathChanged (void);
void dirtyChanged (bool dirty);
void cleared (void);
void centerChanged (QGeoCoordinate center);
private slots:
void _polygonModelCountChanged(int count);
void _polygonModelDirtyChanged(bool dirty);
void _updateCenter(void);
private:
QPolygonF _toPolygonF(void) const;
......@@ -94,8 +100,8 @@ private:
QVariantList _polygonPath;
QmlObjectListModel _polygonModel;
bool _dirty;
static const char* _jsonPolygonKey;
QGeoCoordinate _center;
bool _ignoreCenterUpdates;
};
#endif
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// QGCMapPolygon map visuals
Item {
id: _root
property var mapControl ///< Map control to place item in
property var mapPolygon ///< QGCMapPolygon object
property var _polygonComponent
property var _dragHandlesComponent
property var _splitHandlesComponent
property var _centerDragHandleComponent
function addVisuals() {
_polygonComponent = polygonComponent.createObject(mapControl)
mapControl.addMapItem(_polygonComponent)
}
function removeVisuals() {
_polygonComponent.destroy()
}
function addHandles() {
_dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
_splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
_centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
}
function removeHandles() {
if (_dragHandlesComponent) {
_dragHandlesComponent.destroy()
_dragHandlesComponent = undefined
}
if (_splitHandlesComponent) {
_splitHandlesComponent.destroy()
_splitHandlesComponent = undefined
}
if (_centerDragHandleComponent) {
_centerDragHandleComponent.destroy()
_centerDragHandleComponent = undefined
}
}
Component.onDestruction: {
removeVisuals()
removeHandles()
}
Component {
id: polygonComponent
MapPolygon {
color: "green"
opacity: 0.5
path: mapPolygon.path
}
}
Component {
id: splitHandleComponent
MapQuickItem {
id: mapQuickItem
anchorPoint.x: dragHandle.width / 2
anchorPoint.y: dragHandle.height / 2
z: QGroundControl.zOrderMapItems + 1
property int vertexIndex
sourceItem: Rectangle {
id: dragHandle
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
radius: width / 2
color: "white"
opacity: .50
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
text: "+"
}
QGCMouseArea {
fillItem: parent
onClicked: mapPolygon.splitPolygonSegment(mapQuickItem.vertexIndex)
}
}
}
}
Component {
id: splitHandlesComponent
Repeater {
model: mapPolygon.path
delegate: Item {
property var _splitHandle
property var _vertices: mapPolygon.path
function _setHandlePosition() {
var nextIndex = index + 1
if (nextIndex > _vertices.length - 1) {
nextIndex = 0
}
var distance = _vertices[index].distanceTo(_vertices[nextIndex])
var azimuth = _vertices[index].azimuthTo(_vertices[nextIndex])
_splitHandle.coordinate = _vertices[index].atDistanceAndAzimuth(distance / 2, azimuth)
}
Component.onCompleted: {
_splitHandle = splitHandleComponent.createObject(mapControl)
_splitHandle.vertexIndex = index
_setHandlePosition()
mapControl.addMapItem(_splitHandle)
}
Component.onDestruction: {
if (_splitHandle) {
_splitHandle.destroy()
}
}
}
}
}
// Control which is used to drag polygon vertices
Component {
id: dragAreaComponent
MissionItemIndicatorDrag {
id: dragArea
property int polygonVertex
property bool _creationComplete: false
Component.onCompleted: _creationComplete = true
onItemCoordinateChanged: {
if (_creationComplete) {
// During component creation some bad coordinate values got through which screws up polygon draw
mapPolygon.adjustVertex(polygonVertex, itemCoordinate)
}
}
onClicked: mapPolygon.removeVertex(polygonVertex)
}
}
Component {
id: dragHandleComponent
MapQuickItem {
id: mapQuickItem
anchorPoint.x: dragHandle.width / 2
anchorPoint.y: dragHandle.height / 2
z: QGroundControl.zOrderMapItems + 2
sourceItem: Rectangle {
id: dragHandle
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
radius: width / 2
color: "white"
opacity: .90
}
}
}
// Add all polygon vertex drag handles to the map
Component {
id: dragHandlesComponent
Repeater {
model: mapPolygon.pathModel
delegate: Item {
property var _visuals: [ ]
Component.onCompleted: {
var dragHandle = dragHandleComponent.createObject(mapControl)
dragHandle.coordinate = Qt.binding(function() { return object.coordinate })
mapControl.addMapItem(dragHandle)
var dragArea = dragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": object.coordinate })
dragArea.polygonVertex = Qt.binding(function() { return index })
_visuals.push(dragHandle)
_visuals.push(dragArea)
}
Component.onDestruction: {
for (var i=0; i<_visuals.length; i++) {
_visuals[i].destroy()
}
_visuals = [ ]
}
}
}
}
Component {
id: centerDragAreaComponent
MissionItemIndicatorDrag {
onItemCoordinateChanged: mapPolygon.center = itemCoordinate
}
}
Component {
id: centerDragHandleComponent
Item {
property var dragHandle
property var dragArea
Component.onCompleted: {
dragHandle = dragHandleComponent.createObject(mapControl)
dragHandle.coordinate = Qt.binding(function() { return mapPolygon.center })
mapControl.addMapItem(dragHandle)
dragArea = centerDragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": mapPolygon.center })
}
Component.onDestruction: {
dragHandle.destroy()
dragArea.destroy()
}
}
}
}
This diff is collapsed.
......@@ -15,6 +15,7 @@
#include "MissionItem.h"
#include "SettingsFact.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
Q_DECLARE_LOGGING_CATEGORY(SurveyMissionItemLog)
......@@ -52,25 +53,18 @@ public:
Q_PROPERTY(bool refly90Degrees READ refly90Degrees WRITE setRefly90Degrees NOTIFY refly90DegreesChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
#if 0
// The polygon vertices are also exposed as a list mode since MapItemView will only work with a QAbstractItemModel as
// opposed to polygonPath which is a QVariantList.
Q_PROPERTY(QmlObjectListModel* polygonModel READ polygonModel CONSTANT)
Q_INVOKABLE void clearPolygon(void);
Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate);
Q_INVOKABLE void adjustPolygonCoordinate(int vertexIndex, const QGeoCoordinate coordinate);
Q_INVOKABLE void removePolygonVertex(int vertexIndex);
// Splits the segment between vertextIndex and the next vertex in half
Q_INVOKABLE void splitPolygonSegment(int vertexIndex);
QVariantList polygonPath (void) { return _polygonPath; }
QmlObjectListModel* polygonModel(void) { return &_polygonModel; }
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
#endif
QVariantList gridPoints (void) { return _simpleGridPoints; }
......@@ -96,11 +90,12 @@ public:
Fact* fixedValueIsAltitude (void) { return &_fixedValueIsAltitudeFact; }
Fact* camera (void) { return &_cameraFact; }
int cameraShots (void) const;
double coveredArea (void) const { return _coveredArea; }
double timeBetweenShots (void) const;
bool hoverAndCaptureAllowed (void) const;
bool refly90Degrees (void) const { return _refly90Degrees; }
int cameraShots (void) const;
double coveredArea (void) const { return _coveredArea; }
double timeBetweenShots (void) const;
bool hoverAndCaptureAllowed (void) const;
bool refly90Degrees (void) const { return _refly90Degrees; }
QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
void setRefly90Degrees(bool refly90Degrees);
......@@ -179,6 +174,8 @@ signals:
private slots:
void _setDirty(void);
void _polygonDirtyChanged(bool dirty);
void _clearInternal(void);
private:
enum CameraTriggerCode {
......@@ -188,9 +185,7 @@ private:
CameraTriggerHoverAndCapture
};
void _clear(void);
void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _clearGrid(void);
void _generateGrid(void);
void _updateCoordinateAltitude(void);
int _gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& simpleGridPoints, QList<QList<QPointF>>& transectSegments, bool refly);
......@@ -216,8 +211,7 @@ private:
int _sequenceNumber;
bool _dirty;
QVariantList _polygonPath;
QmlObjectListModel _polygonModel;
QGCMapPolygon _mapPolygon;
QVariantList _simpleGridPoints; ///< Grid points for drawing simple grid visuals
QList<QList<QGeoCoordinate>> _transectSegments; ///< Internal transect segments including grid exit, turnaround and internal camera points
QList<QList<QGeoCoordinate>> _reflyTransectSegments; ///< Refly segments
......@@ -257,7 +251,6 @@ private:
SettingsFact _fixedValueIsAltitudeFact;
SettingsFact _cameraFact;
static const char* _jsonPolygonObjectKey;
static const char* _jsonGridObjectKey;
static const char* _jsonGridAltitudeKey;
static const char* _jsonGridAltitudeRelativeKey;
......
......@@ -8,15 +8,15 @@
****************************************************************************/
#include "ComplexMissionItemTest.h"
#include "SurveyMissionItemTest.h"
ComplexMissionItemTest::ComplexMissionItemTest(void)
SurveyMissionItemTest::SurveyMissionItemTest(void)
{
_polyPoints << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) <<
QGeoCoordinate(47.633619320000001, -122.08811074) << QGeoCoordinate(47.633189139999999, -122.08900124);
}
void ComplexMissionItemTest::init(void)
void SurveyMissionItemTest::init(void)
{
_rgComplexMissionItemSignals[polygonPathChangedIndex] = SIGNAL(polygonPathChanged());
_rgComplexMissionItemSignals[lastSequenceNumberChangedIndex] = SIGNAL(lastSequenceNumberChanged(int));
......@@ -45,7 +45,8 @@ void ComplexMissionItemTest::init(void)
_rgComplexMissionItemSignals[exitCoordinateHasRelativeAltitudeChangedIndex] = SIGNAL(exitCoordinateHasRelativeAltitudeChanged(bool));
_rgComplexMissionItemSignals[exitCoordinateSameAsEntryChangedIndex] = SIGNAL(exitCoordinateSameAsEntryChanged(bool));
_complexItem = new SurveyMissionItem(NULL /* Vehicle */, this);
_surveyItem = new SurveyMissionItem(NULL /* Vehicle */, this);
_mapPolygon = _surveyItem->mapPolygon();
// It's important to check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
......@@ -53,66 +54,66 @@ void ComplexMissionItemTest::init(void)
_multiSpy = new MultiSignalSpy();
Q_CHECK_PTR(_multiSpy);
QCOMPARE(_multiSpy->init(_complexItem, _rgComplexMissionItemSignals, _cComplexMissionItemSignals), true);
QCOMPARE(_multiSpy->init(_surveyItem, _rgComplexMissionItemSignals, _cComplexMissionItemSignals), true);
}
void ComplexMissionItemTest::cleanup(void)
void SurveyMissionItemTest::cleanup(void)
{
delete _complexItem;
delete _surveyItem;
delete _multiSpy;
}
void ComplexMissionItemTest::_testDirty(void)
void SurveyMissionItemTest::_testDirty(void)
{
QVERIFY(!_complexItem->dirty());
_complexItem->setDirty(false);
QVERIFY(!_complexItem->dirty());
QVERIFY(!_surveyItem->dirty());
_surveyItem->setDirty(false);
QVERIFY(!_surveyItem->dirty());
QVERIFY(_multiSpy->checkNoSignals());
_complexItem->setDirty(true);
QVERIFY(_complexItem->dirty());
_surveyItem->setDirty(true);
QVERIFY(_surveyItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_multiSpy->clearAllSignals();
_complexItem->setDirty(false);
QVERIFY(!_complexItem->dirty());
_surveyItem->setDirty(false);
QVERIFY(!_surveyItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(!_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
}
void ComplexMissionItemTest::_testAddPolygonCoordinate(void)
void SurveyMissionItemTest::_testAddPolygonCoordinate(void)
{
QCOMPARE(_complexItem->polygonPath().count(), 0);
QCOMPARE(_mapPolygon->count(), 0);
// First call to addPolygonCoordinate should trigger:
// polygonPathChanged
// dirtyChanged
_complexItem->addPolygonCoordinate(_polyPoints[0]);
_mapPolygon->appendVertex(_polyPoints[0]);
QVERIFY(_multiSpy->checkOnlySignalByMask(polygonPathChangedMask | dirtyChangedMask));
// Validate object data
QVariantList polyList = _complexItem->polygonPath();
QVariantList polyList = _mapPolygon->path();
QCOMPARE(polyList.count(), 1);
QCOMPARE(polyList[0].value<QGeoCoordinate>(), _polyPoints[0]);
// Reset
_complexItem->setDirty(false);
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
// Second call to addPolygonCoordinate should only trigger:
// polygonPathChanged
// dirtyChanged
_complexItem->addPolygonCoordinate(_polyPoints[1]);
_mapPolygon->appendVertex(_polyPoints[1]);
QVERIFY(_multiSpy->checkOnlySignalByMask(polygonPathChangedMask | dirtyChangedMask));
polyList = _complexItem->polygonPath();
polyList = _mapPolygon->path();
QCOMPARE(polyList.count(), 2);
for (int i=0; i<polyList.count(); i++) {
QCOMPARE(polyList[i].value<QGeoCoordinate>(), _polyPoints[i]);
}
_complexItem->setDirty(false);
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
// Third call to addPolygonCoordinate should trigger:
......@@ -126,33 +127,33 @@ void ComplexMissionItemTest::_testAddPolygonCoordinate(void)
// lastSequenceNumberChanged - number of internal mission items changes
// gridPointsChanged - grid points show up for the first time
_complexItem->addPolygonCoordinate(_polyPoints[2]);
_mapPolygon->appendVertex(_polyPoints[2]);
QVERIFY(_multiSpy->checkOnlySignalByMask(polygonPathChangedMask | lastSequenceNumberChangedMask | gridPointsChangedMask | coordinateChangedMask |
exitCoordinateChangedMask | specifiesCoordinateChangedMask | dirtyChangedMask));
int seqNum = _multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex);
QVERIFY(seqNum > 0);
polyList = _complexItem->polygonPath();
polyList = _mapPolygon->path();
QCOMPARE(polyList.count(), 3);
for (int i=0; i<polyList.count(); i++) {
QCOMPARE(polyList[i].value<QGeoCoordinate>(), _polyPoints[i]);
}
// Test that number of waypoints is doubled when using turnaround waypoints
_complexItem->setTurnaroundDist(60.0);
QVariantList gridPoints = _complexItem->gridPoints();
_complexItem->setTurnaroundDist(0.0);
QVariantList gridPointsNoT = _complexItem->gridPoints();
_surveyItem->setTurnaroundDist(60.0);
QVariantList gridPoints = _surveyItem->gridPoints();
_surveyItem->setTurnaroundDist(0.0);
QVariantList gridPointsNoT = _surveyItem->gridPoints();
QCOMPARE(gridPoints.count(), 2 * gridPointsNoT.count());
}
void ComplexMissionItemTest::_testClearPolygon(void)
void SurveyMissionItemTest::_testClearPolygon(void)
{
for (int i=0; i<3; i++) {
_complexItem->addPolygonCoordinate(_polyPoints[i]);
_mapPolygon->appendVertex(_polyPoints[i]);
}