Commit 6e896092 authored by Don Gagne's avatar Don Gagne

More work on load/save send/load semantics

parent 1a9e6289
......@@ -29,8 +29,8 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
, _fenceEnableFact(NULL)
, _fenceTypeFact(NULL)
{
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived);
connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &APMGeoFenceManager::_parametersReady);
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived);
connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &APMGeoFenceManager::_parametersReady);
if (_vehicle->getParameterManager()->parametersAreReady()) {
_parametersReady();
......@@ -42,7 +42,7 @@ APMGeoFenceManager::~APMGeoFenceManager()
}
void APMGeoFenceManager::sendToVehicle(void)
void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{
if (_vehicle->isOfflineEditingVehicle()) {
return;
......@@ -58,17 +58,20 @@ void APMGeoFenceManager::sendToVehicle(void)
}
// Validate
int validatedPolygonCount = polygon.count();
if (polygonSupported()) {
if (_polygon.count() < 3) {
_sendError(TooFewPoints, QStringLiteral("Geo-Fence polygon must contain at least 3 points."));
return;
if (polygon.count() < 3) {
validatedPolygonCount = 0;
}
if (_polygon.count() > std::numeric_limits<uint8_t>::max()) {
if (polygon.count() > std::numeric_limits<uint8_t>::max()) {
_sendError(TooManyPoints, QStringLiteral("Geo-Fence polygon has too many points: %1.").arg(_polygon.count()));
return;
validatedPolygonCount = 0;
}
}
_breachReturnPoint = breachReturn;
_polygon = polygon;
// First thing is to turn off geo fence while we are updating. This prevents the vehicle from going haywire it is in the air.
// Unfortunately the param to do this with differs between plane and copter.
const char* enableParam = _vehicle->fixedWing() ? _fenceActionParam : _fenceEnableParam;
......@@ -77,7 +80,7 @@ void APMGeoFenceManager::sendToVehicle(void)
fenceEnableFact->setRawValue(0);
// Total point count, +1 polygon close in last index, +1 for breach in index 0
_cWriteFencePoints = _polygon.count() + 1 + 1 ;
_cWriteFencePoints = (validatedPolygonCount ? (validatedPolygonCount + 1) : 0) + 1 ;
_vehicle->getParameterFact(FactSystem::defaultComponentId, _fenceTotalParam)->setRawValue(_cWriteFencePoints);
// FIXME: No validation of correct fence received
......@@ -86,11 +89,13 @@ void APMGeoFenceManager::sendToVehicle(void)
}
fenceEnableFact->setRawValue(savedEnableState);
emit loadComplete(_breachReturnPoint, _polygon);
}
void APMGeoFenceManager::loadFromVehicle(void)
{
if (_vehicle->isOfflineEditingVehicle()) {
if (_vehicle->isOfflineEditingVehicle() || _readTransactionInProgress) {
return;
}
......@@ -142,7 +147,7 @@ void APMGeoFenceManager::_mavlinkMessageReceived(const mavlink_message_t& messag
}
if (fencePoint.idx == 0) {
setBreachReturnPoint(QGeoCoordinate(fencePoint.lat, fencePoint.lng));
_breachReturnPoint = QGeoCoordinate(fencePoint.lat, fencePoint.lng);
qCDebug(GeoFenceManagerLog) << "From vehicle: breach return point" << _breachReturnPoint;
_requestFencePoint(++_currentFencePoint);
} else if (fencePoint.idx < _cReadFencePoints - 1) {
......@@ -155,7 +160,7 @@ void APMGeoFenceManager::_mavlinkMessageReceived(const mavlink_message_t& messag
} else {
// We've finished collecting fence points
_readTransactionInProgress = false;
emit polygonChanged(_polygon);
emit loadComplete(_breachReturnPoint, _polygon);
}
}
}
......
......@@ -25,7 +25,7 @@ public:
// Overrides from GeoFenceManager
bool inProgress (void) const final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void sendToVehicle (const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon) final;
bool fenceSupported (void) const final { return _fenceSupported; }
bool circleSupported (void) const final;
bool polygonSupported (void) const final;
......
......@@ -78,7 +78,5 @@ Column {
polygon: geoFenceController.polygon
sectionLabel: qsTr("Fence Polygon:")
visible: geoFenceController.polygonSupported
onPolygonEditCompleted: geoFenceController.sendToVehicle()
}
}
import QtQuick 2.2
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
......@@ -31,17 +32,6 @@ Column {
factPanel: qgcView.viewPanel
}
Connections {
target: fenceAction
onValueChanged: actionCombo.recalcSelection()
}
Connections {
target: fenceRetRally
onValueChanged: actionCombo.recalcSelection()
}
QGCLabel { text: qsTr("Fence Settings:") }
Rectangle {
......@@ -60,100 +50,91 @@ Column {
anchors.right: parent.right
model: ListModel {
id: actionModel
ListElement { text: qsTr("None"); actionValue: 0; retRallyValue: 0 }
ListElement { text: qsTr("Report only"); actionValue: 2; retRallyValue: 0 }
ListElement { text: qsTr("Fly to breach return point"); actionValue: 1; retRallyValue: 0 }
ListElement { text: qsTr("Fly to breach return point (throttle control)"); actionValue: 3; retRallyValue: 0 }
ListElement { text: qsTr("Fly to nearest rally point"); actionValue: 4; retRallyValue: 1 }
ListElement { text: qsTr("None"); actionValue: 0 }
ListElement { text: qsTr("Report only"); actionValue: 2 }
ListElement { text: qsTr("Fly to return point"); actionValue: 1 }
ListElement { text: qsTr("Fly to return point (throttle control)"); actionValue: 3 }
}
onActivated: {
fenceAction.value = actionModel.get(index).actionValue
fenceRetRally.value = actionModel.get(index).retRallyValue
onActivated: fenceAction.rawValue = actionModel.get(index).actionValue
Component.onCompleted: recalcSelection()
Connections {
target: fenceAction
onValueChanged: actionCombo.recalcSelection()
}
function recalcSelection() {
if (fenceAction.value != 0 && fenceRetRally.value == 1) {
actionCombo.currentIndex = 4
} else {
switch (fenceAction.value) {
case 0:
actionCombo.currentIndex = 0
break
case 1:
actionCombo.currentIndex = 2
break
case 2:
actionCombo.currentIndex = 1
break
case 3:
actionCombo.currentIndex = 3
break
case 4:
actionCombo.currentIndex = 4
break
case 0:
default:
actionCombo.currentIndex = 0
break
for (var i=0; i<actionModel.count; i++) {
if (actionModel.get(i).actionValue == fenceAction.rawValue) {
actionCombo.currentIndex = i
return
}
}
actionCombo.currentIndex = 0
}
}
Item { width: 1; height: 1 }
ExclusiveGroup { id: returnLocationRadioGroup }
QGCCheckBox {
id: minAltFenceCheckBox
text: qsTr("Minimum altitude fence")
checked: fenceMinAlt.value > 0
onClicked: fenceMinAlt.value = checked ? 10 : 0
property bool _returnPointUsed: fenceAction.rawValue == 1 || fenceAction.rawValue == 3
QGCRadioButton {
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
text: qsTr("Fly to breach return point")
checked: fenceRetRally.rawValue != 1
enabled: _returnPointUsed
exclusiveGroup: returnLocationRadioGroup
onClicked: fenceRetRally.rawValue = 0
}
Row {
anchors.margins: ScreenTools.defaultFontPixelWidth
QGCRadioButton {
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
spacing: _margin
text: qsTr("Fly to nearest rally point")
checked: fenceRetRally.rawValue == 1
enabled: _returnPointUsed
exclusiveGroup: returnLocationRadioGroup
onClicked: fenceRetRally.rawValue = 1
}
QGCLabel {
anchors.baseline: fenceAltMinField.baseline
text: qsTr("Min Altitude:")
Item { width: 1; height: 1 }
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: ScreenTools.defaultFontPixelWidth
columns: 2
QGCCheckBox {
id: minAltFenceCheckBox
text: qsTr("Min altitude:")
checked: fenceMinAlt.value > 0
onClicked: fenceMinAlt.value = checked ? 10 : 0
}
FactTextField {
id: fenceAltMinField
Layout.fillWidth: true
showUnits: true
fact: fenceMinAlt
enabled: minAltFenceCheckBox.checked
width: _editFieldWidth
}
}
Item { width: 1; height: 1 }
QGCCheckBox {
id: maxAltFenceCheckBox
text: qsTr("Maximum altitude fence")
checked: fenceMaxAlt.value > 0
onClicked: fenceMaxAlt.value = checked ? 100 : 0
}
Row {
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
spacing: _margin
QGCLabel {
anchors.baseline: fenceAltMaxField.baseline
text: qsTr("Max Altitude:")
QGCCheckBox {
id: maxAltFenceCheckBox
text: qsTr("Max altitude:")
checked: fenceMaxAlt.value > 0
onClicked: fenceMaxAlt.value = checked ? 100 : 0
}
FactTextField {
id: fenceAltMaxField
Layout.fillWidth: true
showUnits: true
fact: fenceMaxAlt
enabled: maxAltFenceCheckBox.checked
width: _editFieldWidth
}
}
......@@ -167,6 +148,7 @@ Column {
anchors.right: parent.right
wrapMode: Text.WordWrap
text: qsTr("Click in map to set breach return location.")
font.pointSize: ScreenTools.smallFontPointSize
}
Row {
......@@ -220,7 +202,5 @@ Column {
flightMap: editorMap
polygon: geoFenceController.polygon
sectionLabel: qsTr("Fence Polygon:")
onPolygonEditCompleted: geoFenceController.sendToVehicle()
}
}
......@@ -175,12 +175,6 @@ QGCView {
_editingLayer = _layerMission
}
}
onBreachReturnPointChanged: {
if (polygon.count() > 3) {
sendToVehicle()
}
}
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......@@ -321,7 +315,6 @@ QGCView {
}
break
case _layerGeoFence:
console.log("Updating breach return point", coordinate)
geoFenceController.breachReturnPoint = coordinate
break
}
......@@ -628,13 +621,6 @@ QGCView {
visible: geoFenceController.breachReturnSupported
sourceItem: MissionItemIndexLabel { label: "F" }
z: QGroundControl.zOrderMapItems
Connections {
target: geoFenceController
onBreachReturnPointChanged: console.log("breachreturn changed inside", geoFenceController.breachReturnPoint)
}
onCoordinateChanged: console.log("MqpQuickItem coodinateChanged", coordinate)
}
//-- Dismiss Drop Down (if any)
......
......@@ -27,7 +27,8 @@
QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog")
const char* GeoFenceController::_jsonFileTypeValue = "GeoFence";
const char* GeoFenceController::_jsonFileTypeValue = "GeoFence";
const char* GeoFenceController::_jsonBreachReturnKey = "breachReturn";
GeoFenceController::GeoFenceController(QObject* parent)
: PlanElementController(parent)
......@@ -53,7 +54,6 @@ void GeoFenceController::start(bool editMode)
void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint)
{
if (_breachReturnPoint != breachReturnPoint) {
qDebug() << "GeoFenceController::setBreachReturnPoint" << breachReturnPoint;
_breachReturnPoint = breachReturnPoint;
setDirty(true);
emit breachReturnPointChanged(breachReturnPoint);
......@@ -71,12 +71,11 @@ void GeoFenceController::_signalAll(void)
emit paramsChanged(params());
emit paramLabelsChanged(paramLabels());
emit editorQmlChanged(editorQml());
emit dirtyChanged(dirty());
}
void GeoFenceController::_activeVehicleBeingRemoved(void)
{
_clearGeoFence();
_signalAll();
_activeVehicle->geoFenceManager()->disconnect(this);
}
......@@ -90,13 +89,13 @@ void GeoFenceController::_activeVehicleSet(void)
connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged, this, &GeoFenceController::polygonSupportedChanged);
connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged, this, &GeoFenceController::breachReturnSupportedChanged);
connect(geoFenceManager, &GeoFenceManager::circleRadiusChanged, this, &GeoFenceController::circleRadiusChanged);
connect(geoFenceManager, &GeoFenceManager::polygonChanged, this, &GeoFenceController::_setPolygon);
connect(geoFenceManager, &GeoFenceManager::breachReturnPointChanged, this, &GeoFenceController::setBreachReturnPoint);
connect(geoFenceManager, &GeoFenceManager::paramsChanged, this, &GeoFenceController::paramsChanged);
connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged, this, &GeoFenceController::paramLabelsChanged);
connect(geoFenceManager, &GeoFenceManager::loadComplete, this, &GeoFenceController::_loadComplete);
_setPolygon(geoFenceManager->polygon());
setBreachReturnPoint(geoFenceManager->breachReturnPoint());
if (!geoFenceManager->inProgress()) {
_loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon());
}
_signalAll();
}
......@@ -133,9 +132,23 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr
return false;
}
if (!_polygon.loadFromJson(json, false /* reauired */, errorString)) {
return false;
if (breachReturnSupported()) {
if (json.contains(_jsonBreachReturnKey)
&& !JsonHelper::toQGeoCoordinate(json[_jsonBreachReturnKey], _breachReturnPoint, false /* altitudeRequired */, errorString)) {
return false;
}
} else {
_breachReturnPoint = QGeoCoordinate();
}
if (polygonSupported()) {
if (!_polygon.loadFromJson(json, false /* reauired */, errorString)) {
return false;
}
} else {
_polygon.clear();
}
_polygon.setDirty(false);
return true;
}
......@@ -222,7 +235,8 @@ void GeoFenceController::loadFromFile(const QString& filename)
qgcApp()->showMessage(errorString);
}
setDirty(false);
_signalAll();
setDirty(true);
}
void GeoFenceController::loadFromFilePicker(void)
......@@ -239,8 +253,6 @@ void GeoFenceController::loadFromFilePicker(void)
void GeoFenceController::saveToFile(const QString& filename)
{
qDebug() << filename;
if (filename.isEmpty()) {
return;
}
......@@ -273,7 +285,15 @@ void GeoFenceController::saveToFile(const QString& filename)
paramMgr->saveToJson(paramMgr->defaultComponentId(), paramNames, fenceFileObject);
}
_polygon.saveToJson(fenceFileObject);
if (breachReturnSupported()) {
QJsonValue jsonBreachReturn;
JsonHelper::writeQGeoCoordinate(jsonBreachReturn, _breachReturnPoint, false /* writeAltitude */);
fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
}
if (polygonSupported()) {
_polygon.saveToJson(fenceFileObject);
}
QJsonDocument saveDoc(fenceFileObject);
file.write(saveDoc.toJson());
......@@ -296,7 +316,8 @@ void GeoFenceController::saveToFilePicker(void)
void GeoFenceController::removeAll(void)
{
_clearGeoFence();
setBreachReturnPoint(QGeoCoordinate());
_polygon.clear();
}
void GeoFenceController::loadFromVehicle(void)
......@@ -311,22 +332,14 @@ void GeoFenceController::loadFromVehicle(void)
void GeoFenceController::sendToVehicle(void)
{
if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) {
_activeVehicle->geoFenceManager()->setPolygon(polygon());
_activeVehicle->geoFenceManager()->setBreachReturnPoint(breachReturnPoint());
setDirty(false);
_polygon.setDirty(false);
_activeVehicle->geoFenceManager()->sendToVehicle();
_activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _polygon.coordinateList());
} else {
qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterManager()->parametersAreReady() << syncInProgress();
}
}
void GeoFenceController::_clearGeoFence(void)
{
setBreachReturnPoint(QGeoCoordinate());
_polygon.clear();
}
bool GeoFenceController::syncInProgress(void) const
{
return _activeVehicle->geoFenceManager()->inProgress();
......@@ -381,11 +394,17 @@ void GeoFenceController::_setDirty(void)
setDirty(true);
}
void GeoFenceController::_setPolygon(const QList<QGeoCoordinate>& polygon)
void GeoFenceController::_setPolygonFromManager(const QList<QGeoCoordinate>& polygon)
{
_polygon.setPath(polygon);
// This is coming from a GeoFenceManager::loadFromVehicle call
setDirty(false);
_polygon.setDirty(false);
emit polygonPathChanged(_polygon.path());
}
void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnPoint)
{
_breachReturnPoint = breachReturnPoint;
emit breachReturnPointChanged(_breachReturnPoint);
}
float GeoFenceController::circleRadius(void) const
......@@ -407,3 +426,10 @@ QString GeoFenceController::editorQml(void) const
{
return _activeVehicle->geoFenceManager()->editorQml();
}
void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{
_setReturnPointFromManager(breachReturn);
_setPolygonFromManager(polygon);
setDirty(false);
}
......@@ -63,7 +63,6 @@ public:
QStringList paramLabels (void) const;
QString editorQml (void) const;
public slots:
void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint);
signals:
......@@ -81,10 +80,11 @@ signals:
private slots:
void _polygonDirtyChanged(bool dirty);
void _setDirty(void);
void _setPolygon(const QList<QGeoCoordinate>& polygon);
void _setPolygonFromManager(const QList<QGeoCoordinate>& polygon);
void _setReturnPointFromManager(QGeoCoordinate breachReturnPoint);
void _loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
private:
void _clearGeoFence(void);
void _signalAll(void);
bool _loadJsonFile(QJsonDocument& jsonDoc, QString& errorString);
......@@ -97,6 +97,7 @@ private:
QVariantList _params;
static const char* _jsonFileTypeValue;
static const char* _jsonBreachReturnKey;
};
#endif
......@@ -34,26 +34,13 @@ void GeoFenceManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
void GeoFenceManager::loadFromVehicle(void)
{
// No geofence support in unknown vehicle
loadComplete(QGeoCoordinate(), QList<QGeoCoordinate>());
}
void GeoFenceManager::sendToVehicle(void)
void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{
// No geofence support in unknown vehicle
}
Q_UNUSED(breachReturn);
Q_UNUSED(polygon);
void GeoFenceManager::setPolygon(QGCMapPolygon* polygon)
{
_polygon.clear();
for (int index=0; index<polygon->count(); index++) {
_polygon.append((*polygon)[index]);
}
emit polygonChanged(_polygon);
}
void GeoFenceManager::setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint)
{
if (breachReturnPoint != _breachReturnPoint) {
_breachReturnPoint = breachReturnPoint;
emit breachReturnPointChanged(breachReturnPoint);
}
// No geofence support in unknown vehicle
}
......@@ -14,7 +14,6 @@
#include <QGeoCoordinate>
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
class Vehicle;
......@@ -33,11 +32,11 @@ public:
/// Returns true if the manager is currently communicating with the vehicle
virtual bool inProgress(void) const { return false; }
/// Load the current settings from teh vehicle
/// Load the current settings from the vehicle
virtual void loadFromVehicle(void);
/// Send the current settings to the vehicle
virtual void sendToVehicle(void);
virtual void sendToVehicle(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
// Support flags
virtual bool fenceSupported (void) const { return false; }
......@@ -54,9 +53,6 @@ public:
virtual QString editorQml(void) const { return QStringLiteral("qrc:/FirmwarePlugin/GeoFenceEditor.qml"); }
void setPolygon(QGCMapPolygon* polygon);
void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint);
/// Error codes returned in error signal
typedef enum {
InternalError,
......@@ -66,13 +62,12 @@ public:
} ErrorCode_t;
signals:
void loadComplete (const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
void fenceSupportedChanged (bool fenceSupported);
void circleSupportedChanged (bool circleSupported);
void polygonSupportedChanged (bool polygonSupported);
void breachReturnSupportedChanged (bool fenceSupported);
void circleRadiusChanged (float circleRadius);
void polygonChanged (QList<QGeoCoordinate> polygon);
void breachReturnPointChanged (QGeoCoordinate breachReturnPoint);
void inProgressChanged (bool inProgress);
void error (int errorCode, const QString& errorMsg);
void paramsChanged (QVariantList params);
......
......@@ -52,13 +52,6 @@ void QGCMapPolygon::clear(void)
setDirty(true);
}
void QGCMapPolygon::addCoordinate(const QGeoCoordinate coordinate)
{
_polygonPath << QVariant::fromValue(coordinate);
emit pathChanged();
setDirty(true);
}
void QGCMapPolygon::adjustCoordinate(int vertexIndex, const QGeoCoordinate coordinate)
{
_polygonPath[vertexIndex] = QVariant::fromValue(coordinate);
......@@ -148,18 +141,30 @@ bool QGCMapPolygon::loadFromJson(const QJsonObject& json, bool required, QString
return false;
}
QJsonArray rgPoints = json[_jsonPolygonKey].toArray();
for (int i=0; i<rgPoints.count(); i++) {
QList<QGeoCoordinate> rgPoints;
QJsonArray jsonPoints = json[_jsonPolygonKey].toArray();
for (int i=0; i<jsonPoints.count(); i++) {
QGeoCoordinate coordinate;
if (!JsonHelper::toQGeoCoordinate(rgPoints[i], coordinate, false /* altitudeRequired */, errorString)) {
if (!JsonHelper::toQGeoCoordinate(jsonPoints[i], coordinate, false /* altitudeRequired */, errorString)) {
return false;
}
addCoordinate(coordinate);
rgPoints.append(coordinate);
}
setPath(rgPoints);
setDirty(false);
return true;
}
QList<QGeoCoordinate> QGCMapPolygon::coordinateList(void) const
{
QList<QGeoCoordinate> coords;
for (int i=0; i<count(); i++) {
coords.append((*this)[i]);
}
return coords;
}
......@@ -27,16 +27,17 @@ public:
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_INVOKABLE void clear(void);
Q_INVOKABLE void addCoordinate(const QGeoCoordinate coordinate);
Q_INVOKABLE void adjustCoordinate(int vertexIndex, const QGeoCoordinate coordinate);
Q_INVOKABLE QGeoCoordinate center(void) const;
Q_INVOKABLE int count(void) const { return _polygonPath.count(); }
const QVariantList path(void) const { return _polygonPath; }
QVariantList path(void) const { return _polygonPath; }
void setPath(const QList<QGeoCoordinate>& path);
void setPath(const QVariantList& path);
const QGeoCoordinate operator[](int index) { return _polygonPath[index].value<QGeoCoordinate>(); }
QList<QGeoCoordinate> coordinateList(void) const;
QGeoCoordinate operator[](int index) const { return _polygonPath[index].value<QGeoCoordinate>(); }
bool dirty(void) const { return _dirty; }
void setDirty(bool dirty);
......
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