Commit f1d00721 authored by DonLakeFlyer's avatar DonLakeFlyer

Major rework of polygon editing

parent 59c8eaa3
...@@ -461,6 +461,7 @@ HEADERS += \ ...@@ -461,6 +461,7 @@ HEADERS += \
src/QGCMapPalette.h \ src/QGCMapPalette.h \
src/QGCMobileFileDialogController.h \ src/QGCMobileFileDialogController.h \
src/QGCPalette.h \ src/QGCPalette.h \
src/QGCQGeoCoordinate.h \
src/QGCQmlWidgetHolder.h \ src/QGCQmlWidgetHolder.h \
src/QGCQuickWidget.h \ src/QGCQuickWidget.h \
src/QGCTemporaryFile.h \ src/QGCTemporaryFile.h \
...@@ -629,6 +630,7 @@ SOURCES += \ ...@@ -629,6 +630,7 @@ SOURCES += \
src/QGCMapPalette.cc \ src/QGCMapPalette.cc \
src/QGCMobileFileDialogController.cc \ src/QGCMobileFileDialogController.cc \
src/QGCPalette.cc \ src/QGCPalette.cc \
src/QGCQGeoCoordinate.cc \
src/QGCQmlWidgetHolder.cpp \ src/QGCQmlWidgetHolder.cpp \
src/QGCQuickWidget.cc \ src/QGCQuickWidget.cc \
src/QGCTemporaryFile.cc \ src/QGCTemporaryFile.cc \
......
...@@ -14,7 +14,7 @@ import QGroundControl 1.0 ...@@ -14,7 +14,7 @@ import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
/// Use the drag a MissionItemIndicator /// Use to drag a MissionItemIndicator
Rectangle { Rectangle {
id: itemDragger id: itemDragger
x: itemIndicator.x - _touchMarginHorizontal x: itemIndicator.x - _touchMarginHorizontal
...@@ -28,9 +28,11 @@ Rectangle { ...@@ -28,9 +28,11 @@ Rectangle {
property var itemIndicator ///< The mission item indicator to drag around property var itemIndicator ///< The mission item indicator to drag around
property var itemCoordinate ///< Coordinate we are updating during drag property var itemCoordinate ///< Coordinate we are updating during drag
signal clicked
property bool _preventCoordinateBindingLoop: false property bool _preventCoordinateBindingLoop: false
property bool _mobile: true//ScreenTools.isMobile property bool _mobile: ScreenTools.isMobile
property real _touchWidth: Math.max(itemIndicator.width, ScreenTools.minTouchPixels) property real _touchWidth: Math.max(itemIndicator.width, ScreenTools.minTouchPixels)
property real _touchHeight: Math.max(itemIndicator.height, ScreenTools.minTouchPixels) property real _touchHeight: Math.max(itemIndicator.height, ScreenTools.minTouchPixels)
property real _touchMarginHorizontal: _mobile ? (_touchWidth - itemIndicator.width) / 2 : 0 property real _touchMarginHorizontal: _mobile ? (_touchWidth - itemIndicator.width) / 2 : 0
...@@ -40,7 +42,7 @@ Rectangle { ...@@ -40,7 +42,7 @@ Rectangle {
onYChanged: liveDrag() onYChanged: liveDrag()
function liveDrag() { function liveDrag() {
if (!itemDragger._preventCoordinateBindingLoop && Drag.active) { if (!itemDragger._preventCoordinateBindingLoop && itemDrag.drag.active) {
var point = Qt.point(itemDragger.x + _touchMarginHorizontal + itemIndicator.anchorPoint.x, itemDragger.y + _touchMarginVertical + itemIndicator.anchorPoint.y) var point = Qt.point(itemDragger.x + _touchMarginHorizontal + itemIndicator.anchorPoint.x, itemDragger.y + _touchMarginVertical + itemIndicator.anchorPoint.y)
var coordinate = map.toCoordinate(point) var coordinate = map.toCoordinate(point)
itemDragger._preventCoordinateBindingLoop = true itemDragger._preventCoordinateBindingLoop = true
...@@ -61,5 +63,15 @@ Rectangle { ...@@ -61,5 +63,15 @@ Rectangle {
drag.maximumX: itemDragger.parent.width - parent.width drag.maximumX: itemDragger.parent.width - parent.width
drag.maximumY: itemDragger.parent.height - parent.height drag.maximumY: itemDragger.parent.height - parent.height
preventStealing: true preventStealing: true
onClicked: itemDragger.clicked()
}
Item {
id: fakeItemIndicator
Item {
id: anchorPoint
}
} }
} }
...@@ -92,15 +92,11 @@ QGCView { ...@@ -92,15 +92,11 @@ QGCView {
MapFitFunctions { MapFitFunctions {
id: mapFitFunctions id: mapFitFunctions
map: editorMap map: editorMap
mapFitViewport: Qt.rect(leftToolWidth, toolbarHeight, editorMap.width - leftToolWidth - rightPanelWidth, editorMap.height - toolbarHeight) mapFitViewport: editorMap.centerViewport
usePlannedHomePosition: true usePlannedHomePosition: true
mapGeoFenceController: geoFenceController mapGeoFenceController: geoFenceController
mapMissionController: missionController mapMissionController: missionController
mapRallyPointController: rallyPointController mapRallyPointController: rallyPointController
property real toolbarHeight: qgcView.height - ScreenTools.availableHeight
property real rightPanelWidth: _rightPanelWidth
property real leftToolWidth: toolStrip.x + toolStrip.width
} }
MissionController { MissionController {
...@@ -343,6 +339,13 @@ QGCView { ...@@ -343,6 +339,13 @@ QGCView {
anchors.right: parent.right anchors.right: parent.right
mapName: "MissionEditor" mapName: "MissionEditor"
// This is the center rectangle of the map which is not obscured by tools
property rect centerViewport: Qt.rect(_leftToolWidth, _toolbarHeight, editorMap.width - _leftToolWidth - _rightPanelWidth, editorMap.height - _statusHeight - _toolbarHeight)
property real _toolbarHeight: qgcView.height - ScreenTools.availableHeight
property real _leftToolWidth: toolStrip.x + toolStrip.width
property real _statusHeight: waypointValuesDisplay.visible ? editorMap.height - waypointValuesDisplay.y : 0
readonly property real animationDuration: 500 readonly property real animationDuration: 500
// Initial map position duplicates Fly view position // Initial map position duplicates Fly view position
......
...@@ -124,16 +124,6 @@ Rectangle { ...@@ -124,16 +124,6 @@ Rectangle {
property bool _noCameraValueRecalc: false ///< Prevents uneeded recalcs property bool _noCameraValueRecalc: false ///< Prevents uneeded recalcs
Connections {
target: missionItem
onIsCurrentItemChanged: {
if (!missionItem.isCurrentItem) {
polygonEditor.cancelPolygonEdit()
}
}
}
Connections { Connections {
target: missionItem.camera target: missionItem.camera
...@@ -459,44 +449,6 @@ Rectangle { ...@@ -459,44 +449,6 @@ Rectangle {
Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen } Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
SectionHeader { text: qsTr("Polygon") }
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCButton {
width: _root.width * 0.45
text: polygonEditor.drawingPolygon ? qsTr("Finish Draw") : qsTr("Draw")
visible: !polygonEditor .adjustingPolygon
enabled: ((polygonEditor.drawingPolygon && polygonEditor.polygonReady) || !polygonEditor.drawingPolygon)
onClicked: {
if (polygonEditor.drawingPolygon) {
polygonEditor.finishCapturePolygon()
} else {
polygonEditor.startCapturePolygon()
}
}
}
QGCButton {
width: _root.width * 0.4
text: polygonEditor.adjustingPolygon ? qsTr("Finish Adjust") : qsTr("Adjust")
visible: missionItem.polygonPath.length > 0 && !polygonEditor.drawingPolygon
onClicked: {
if (polygonEditor.adjustingPolygon) {
polygonEditor.finishAdjustPolygon()
} else {
polygonEditor.startAdjustPolygon(missionItem.polygonPath)
}
}
}
}
Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
SectionHeader { text: qsTr("Statistics") } SectionHeader { text: qsTr("Statistics") }
Grid { Grid {
...@@ -521,10 +473,4 @@ Rectangle { ...@@ -521,10 +473,4 @@ Rectangle {
} }
} }
} }
PolygonEditor {
id: polygonEditor
map: editorMap
callbackObject: parent
}
} }
...@@ -16,18 +16,21 @@ import QGroundControl 1.0 ...@@ -16,18 +16,21 @@ import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// Survey Complex Mission Item visuals /// Survey Complex Mission Item visuals
Item { Item {
property var map ///< Map control to place item in property var map ///< Map control to place item in
property var _missionItem: object property var _missionItem: object
property var _polygon property var _polygon
property var _grid property var _grid
property var _entryCoordinate property var _entryCoordinate
property var _exitCoordinate property var _exitCoordinate
property var _dragHandles
property var _splitHandles
Component.onCompleted: { function _addVisualElements() {
_polygon = polygonComponent.createObject(map) _polygon = polygonComponent.createObject(map)
_grid = gridComponent.createObject(map) _grid = gridComponent.createObject(map)
_entryCoordinate = entryPointComponent.createObject(map) _entryCoordinate = entryPointComponent.createObject(map)
...@@ -38,13 +41,78 @@ Item { ...@@ -38,13 +41,78 @@ Item {
map.addMapItem(_exitCoordinate) map.addMapItem(_exitCoordinate)
} }
Component.onDestruction: { function _destroyVisualElements() {
_polygon.destroy() _polygon.destroy()
_grid.destroy() _grid.destroy()
_entryCoordinate.destroy() _entryCoordinate.destroy()
_exitCoordinate.destroy() _exitCoordinate.destroy()
} }
function _addDragHandles() {
if (!_dragHandles) {
_dragHandles = dragHandlesComponent.createObject(map)
}
if (!_splitHandles) {
_splitHandles = splitHandlesComponent.createObject(map)
}
}
function _destroyDragHandles() {
if (_dragHandles) {
_dragHandles.destroy()
_dragHandles = undefined
}
if (_splitHandles) {
_splitHandles.destroy()
_splitHandles = undefined
}
}
/// Add an initial 4 sided polygon if there is none
function _addInitialPolygon() {
if (_missionItem.polygonPath.length < 3) {
// Initial polygon is inset to take 2/3rds space
var rect = map.centerViewport
rect.x += (rect.width * 0.25) / 2
rect.y += (rect.height * 0.25) / 2
rect.width *= 0.75
rect.height *= 0.75
var topLeft = Qt.point(rect.x, rect.y)
var topRight = Qt.point(rect.x + rect.width, rect.y)
var bottomLeft = Qt.point(rect.x, rect.y + rect.height)
var bottomRight = Qt.point(rect.x + rect.width, rect.y + rect.height)
_missionItem.addPolygonCoordinate(map.toCoordinate(topLeft))
_missionItem.addPolygonCoordinate(map.toCoordinate(topRight))
_missionItem.addPolygonCoordinate(map.toCoordinate(bottomRight))
_missionItem.addPolygonCoordinate(map.toCoordinate(bottomLeft))
}
}
Component.onCompleted: {
_addInitialPolygon()
_addVisualElements()
if (_missionItem.isCurrentItem) {
_addDragHandles()
}
}
Component.onDestruction: {
_destroyVisualElements()
_destroyDragHandles()
}
Connections {
target: _missionItem
onIsCurrentItemChanged: {
if (_missionItem.isCurrentItem) {
_addDragHandles()
} else {
_destroyDragHandles()
}
}
}
// Survey area polygon // Survey area polygon
Component { Component {
id: polygonComponent id: polygonComponent
...@@ -108,4 +176,147 @@ Item { ...@@ -108,4 +176,147 @@ Item {
} }
} }
} }
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: .80
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
text: "+"
}
QGCMouseArea {
fillItem: parent
onClicked: _missionItem.splitPolygonSegment(mapQuickItem.vertexIndex)
}
}
}
}
Component {
id: splitHandlesComponent
Repeater {
model: _missionItem.polygonPath
delegate: Item {
property var _splitHandle
property var _vertices: _missionItem.polygonPath
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(map)
_splitHandle.vertexIndex = index
_setHandlePosition()
map.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
_missionItem.adjustPolygonCoordinate(polygonVertex, itemCoordinate)
}
}
onClicked: _missionItem.removePolygonVertex(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: .80
}
}
}
// Add all polygon vertex drag handles to the map
Component {
id: dragHandlesComponent
Repeater {
model: _missionItem.polygonModel
delegate: Item {
property var _visuals: [ ]
Component.onCompleted: {
var dragHandle = dragHandleComponent.createObject(map)
dragHandle.coordinate = Qt.binding(function() { return object.coordinate })
map.addMapItem(dragHandle)
var dragArea = dragAreaComponent.createObject(map, { "itemIndicator": dragHandle, "itemCoordinate": object.coordinate, "polygonVertex": index })
_visuals.push(dragHandle)
_visuals.push(dragArea)
}
Component.onDestruction: {
for (var i=0; i<_visuals.length; i++) {
_visuals[i].destroy()
}
_visuals = [ ]
}
}
}
}
} }
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include "MissionController.h" #include "MissionController.h"
#include "QGCGeo.h" #include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h" #include "QGroundControlQmlGlobal.h"
#include "QGCQGeoCoordinate.h"
#include <QPolygonF> #include <QPolygonF>
...@@ -167,6 +168,8 @@ void SurveyMissionItem::clearPolygon(void) ...@@ -167,6 +168,8 @@ void SurveyMissionItem::clearPolygon(void)
// will cause the polygon to go away. // will cause the polygon to go away.
_polygonPath.clear(); _polygonPath.clear();
_polygonModel.clearAndDeleteContents();
_clearGrid(); _clearGrid();
setDirty(true); setDirty(true);
...@@ -176,6 +179,8 @@ void SurveyMissionItem::clearPolygon(void) ...@@ -176,6 +179,8 @@ void SurveyMissionItem::clearPolygon(void)
void SurveyMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate) void SurveyMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate)
{ {
_polygonModel.append(new QGCQGeoCoordinate(coordinate, this));
_polygonPath << QVariant::fromValue(coordinate); _polygonPath << QVariant::fromValue(coordinate);
emit polygonPathChanged(); emit polygonPathChanged();
...@@ -191,12 +196,72 @@ void SurveyMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate) ...@@ -191,12 +196,72 @@ void SurveyMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate)
void SurveyMissionItem::adjustPolygonCoordinate(int vertexIndex, const QGeoCoordinate coordinate) void SurveyMissionItem::adjustPolygonCoordinate(int vertexIndex, const QGeoCoordinate coordinate)
{ {
if (vertexIndex < 0 && vertexIndex > _polygonPath.length() - 1) {
qWarning() << "Call to adjustPolygonCoordinate with bad vertexIndex:count" << vertexIndex << _polygonPath.length();
return;
}
_polygonModel.value<QGCQGeoCoordinate*>(vertexIndex)->setCoordinate(coordinate);
_polygonPath[vertexIndex] = QVariant::fromValue(coordinate); _polygonPath[vertexIndex] = QVariant::fromValue(coordinate);
emit polygonPathChanged(); emit polygonPathChanged();
_generateGrid(); _generateGrid();
setDirty(true); setDirty(true);
} }
void SurveyMissionItem::splitPolygonSegment(int vertexIndex)
{
int nextIndex = vertexIndex + 1;
if (nextIndex > _polygonPath.length() - 1) {
nextIndex = 0;
}
QGeoCoordinate firstVertex = _polygonPath[vertexIndex].value<QGeoCoordinate>();
QGeoCoordinate nextVertex = _polygonPath[nextIndex].value<QGeoCoordinate>();
double distance = firstVertex.distanceTo(nextVertex);
double azimuth = firstVertex.azimuthTo(nextVertex);
QGeoCoordinate newVertex = firstVertex.atDistanceAndAzimuth(distance / 2, azimuth);
if (nextIndex == 0) {
addPolygonCoordinate(newVertex);
} else {
_polygonModel.insert(nextIndex, new QGCQGeoCoordinate(newVertex, this));
_polygonPath.insert(nextIndex, QVariant::fromValue(newVertex));
emit polygonPathChanged();
int pointCount = _polygonPath.count();
if (pointCount >= 3) {
if (pointCount == 3) {
emit specifiesCoordinateChanged();
}
_generateGrid();
}
setDirty(true);
}
}
void SurveyMissionItem::removePolygonVertex(int vertexIndex)
{
if (vertexIndex < 0 && vertexIndex > _polygonPath.length() - 1) {
qWarning() << "Call to removePolygonCoordinate with bad vertexIndex:count" << vertexIndex << _polygonPath.length();
return;
}
if (_polygonPath.length() <= 3) {
// Don't allow the user to trash the polygon
return;
}
QObject* coordObj = _polygonModel.removeAt(vertexIndex);
coordObj->deleteLater();
_polygonPath.removeAt(vertexIndex);
emit polygonPathChanged();
_generateGrid();
setDirty(true);
}
int SurveyMissionItem::lastSequenceNumber(void) const int SurveyMissionItem::lastSequenceNumber(void) const
{ {
int lastSeq = _sequenceNumber; int lastSeq = _sequenceNumber;
...@@ -433,6 +498,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe ...@@ -433,6 +498,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe
return false; return false;
} }
_polygonPath << QVariant::fromValue(pointCoord); _polygonPath << QVariant::fromValue(pointCoord);
_polygonModel.append(new QGCQGeoCoordinate(pointCoord, this));
} }
_generateGrid(); _generateGrid();
......
...@@ -53,11 +53,21 @@ public: ...@@ -53,11 +53,21 @@ public:
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged) Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged) Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
// 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 clearPolygon(void);
Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate); Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate);
Q_INVOKABLE void adjustPolygonCoordinate(int vertexIndex, 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; }
QVariantList polygonPath(void) { return _polygonPath; }
QVariantList gridPoints (void) { return _gridPoints; } QVariantList gridPoints (void) { return _gridPoints; }
Fact* manualGrid (void) { return &_manualGridFact; } Fact* manualGrid (void) { return &_manualGridFact; }
...@@ -171,13 +181,14 @@ private: ...@@ -171,13 +181,14 @@ private:
void _setCoveredArea(double coveredArea); void _setCoveredArea(double coveredArea);
void _cameraValueChanged(void); void _cameraValueChanged(void);
int _sequenceNumber; int _sequenceNumber;
bool _dirty; bool _dirty;
QVariantList _polygonPath; QVariantList _polygonPath;
QVariantList _gridPoints; QmlObjectListModel _polygonModel;
QGeoCoordinate _coordinate; QVariantList _gridPoints;
QGeoCoordinate _exitCoordinate; QGeoCoordinate _coordinate;
bool _cameraOrientationFixed; QGeoCoordinate _exitCoordinate;
bool _cameraOrientationFixed;
double _surveyDistance; double _surveyDistance;
int _cameraShots; int _cameraShots;
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "QGCQGeoCoordinate.h"
QGCQGeoCoordinate::QGCQGeoCoordinate(const QGeoCoordinate& coord, QObject* parent)
: QObject(parent)
, _coordinate(coord)
{
}
void QGCQGeoCoordinate::setCoordinate(const QGeoCoordinate& coordinate)
{
if (_coordinate != coordinate) {
_coordinate = coordinate;
emit coordinateChanged(coordinate);
}
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QGeoCoordinate>
/// This is a QGeoCoordinate within a QObject such that it can be used on a QmlObjectListModel
class QGCQGeoCoordinate : public QObject
{
Q_OBJECT
public:
QGCQGeoCoordinate(const QGeoCoordinate& coord, QObject* parent = NULL);
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
QGeoCoordinate coordinate(void) const { return _coordinate; }
void setCoordinate(const QGeoCoordinate& coordinate);
signals:
void coordinateChanged(QGeoCoordinate coordinate);
private:
QGeoCoordinate _coordinate;
};
...@@ -51,7 +51,7 @@ public: ...@@ -51,7 +51,7 @@ public:
/// Calls deleteLater on all items and this itself. /// Calls deleteLater on all items and this itself.
void deleteListAndContents(void); void deleteListAndContents(void);
/// Clears the list and calls delete on each entry /// Clears the list and calls deleteLater on each entry
void clearAndDeleteContents(void); void clearAndDeleteContents(void);
signals: signals:
......
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