Commit 6ac2e382 authored by Valentin Platzgummer's avatar Valentin Platzgummer

circular survey edited

parent 89e1c7a3
error when loading wima file
...@@ -220,6 +220,7 @@ ...@@ -220,6 +220,7 @@
<file alias="QGroundControl/Controls/WimaMeasurementAreaMapVisual.qml">src/WimaView/WimaMeasurementAreaMapVisual.qml</file> <file alias="QGroundControl/Controls/WimaMeasurementAreaMapVisual.qml">src/WimaView/WimaMeasurementAreaMapVisual.qml</file>
<file alias="QGroundControl/Controls/WimaCorridorMapVisual.qml">src/WimaView/WimaCorridorMapVisual.qml</file> <file alias="QGroundControl/Controls/WimaCorridorMapVisual.qml">src/WimaView/WimaCorridorMapVisual.qml</file>
<file alias="QGroundControl/Controls/WimaMeasurementAreaEditor.qml">src/WimaView/WimaMeasurementAreaEditor.qml</file> <file alias="QGroundControl/Controls/WimaMeasurementAreaEditor.qml">src/WimaView/WimaMeasurementAreaEditor.qml</file>
<file alias="QGroundControl/Controls/SpericalSurveyMapVisual.qml">src/WimaView/SphericalSurveyMapVisual.qml</file>
</qresource> </qresource>
<qresource prefix="/json"> <qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file> <file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
......
...@@ -31,6 +31,8 @@ ...@@ -31,6 +31,8 @@
#include "KML.h" #include "KML.h"
#include "QGCCorePlugin.h" #include "QGCCorePlugin.h"
#include "src/Wima/CircularSurveyComplexItem.h"
#ifndef __mobile__ #ifndef __mobile__
#include "MainWindow.h" #include "MainWindow.h"
#include "QGCQFileDialog.h" #include "QGCQFileDialog.h"
...@@ -61,19 +63,20 @@ const QString MissionController::patternStructureScanName (QT_TRANSLATE_NOOP("M ...@@ -61,19 +63,20 @@ const QString MissionController::patternStructureScanName (QT_TRANSLATE_NOOP("M
const QString MissionController::patternCorridorScanName (QT_TRANSLATE_NOOP("MissionController", "Corridor Scan")); const QString MissionController::patternCorridorScanName (QT_TRANSLATE_NOOP("MissionController", "Corridor Scan"));
MissionController::MissionController(PlanMasterController* masterController, QObject *parent) MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
: PlanElementController (masterController, parent) : PlanElementController (masterController, parent)
, _missionManager (_managerVehicle->missionManager()) , _missionManager (_managerVehicle->missionManager())
, _missionItemCount (0) , _missionItemCount (0)
, _visualItems (nullptr) , _visualItems (nullptr)
, _settingsItem (nullptr) , _settingsItem (nullptr)
, _firstItemsFromVehicle (false) , _firstItemsFromVehicle (false)
, _itemsRequested (false) , _itemsRequested (false)
, _inRecalcSequence (false) , _inRecalcSequence (false)
, _surveyMissionItemName (tr("Survey")) , _surveyMissionItemName (tr("Survey"))
, _appSettings (qgcApp()->toolbox()->settingsManager()->appSettings()) , _circularSurveyMissionItemName(tr("Circular Survey"))
, _progressPct (0) , _appSettings (qgcApp()->toolbox()->settingsManager()->appSettings())
, _currentPlanViewIndex (-1) , _progressPct (0)
, _currentPlanViewItem (nullptr) , _currentPlanViewIndex (-1)
, _currentPlanViewItem (nullptr)
{ {
_resetMissionFlightStatus(); _resetMissionFlightStatus();
managerVehicleChanged(_managerVehicle); managerVehicleChanged(_managerVehicle);
...@@ -254,7 +257,7 @@ void MissionController::sendToVehicle(void) ...@@ -254,7 +257,7 @@ void MissionController::sendToVehicle(void)
} }
/// Converts from visual items to MissionItems /// Converts from visual items to MissionItems
/// @param missionItemParent QObject parent for newly allocated MissionItems /// @param missionItemParent QObject parent for newly allocated MissionItems, _surveyMissionItemName (tr("Survey"))
/// @return true: Mission end action was added to end of list /// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent) bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{ {
...@@ -422,6 +425,8 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate ...@@ -422,6 +425,8 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */); newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
} else if (itemName == patternCorridorScanName) { } else if (itemName == patternCorridorScanName) {
newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */); newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
} else if (itemName == _circularSurveyMissionItemName) {
newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
} else { } else {
qWarning() << "Internal error: Unknown complex item:" << itemName; qWarning() << "Internal error: Unknown complex item:" << itemName;
return sequenceNumber; return sequenceNumber;
...@@ -436,6 +441,8 @@ int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QS ...@@ -436,6 +441,8 @@ int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QS
if (itemName == _surveyMissionItemName) { if (itemName == _surveyMissionItemName) {
newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems); newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
} else if (itemName == _circularSurveyMissionItemName) {
newItem = new CircularSurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
} else if (itemName == patternStructureScanName) { } else if (itemName == patternStructureScanName) {
newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems); newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
} else if (itemName == patternCorridorScanName) { } else if (itemName == patternCorridorScanName) {
...@@ -1952,6 +1959,7 @@ QStringList MissionController::complexMissionItemNames(void) const ...@@ -1952,6 +1959,7 @@ QStringList MissionController::complexMissionItemNames(void) const
{ {
QStringList complexItems; QStringList complexItems;
complexItems.append(_circularSurveyMissionItemName);
complexItems.append(_surveyMissionItemName); complexItems.append(_surveyMissionItemName);
complexItems.append(patternCorridorScanName); complexItems.append(patternCorridorScanName);
if (_controllerVehicle->fixedWing()) { if (_controllerVehicle->fixedWing()) {
......
...@@ -20,6 +20,8 @@ ...@@ -20,6 +20,8 @@
#include <QHash> #include <QHash>
class CoordinateVector; class CoordinateVector;
class VisualMissionItem; class VisualMissionItem;
class MissionItem; class MissionItem;
...@@ -168,16 +170,17 @@ public: ...@@ -168,16 +170,17 @@ public:
// Property accessors // Property accessors
QmlObjectListModel* visualItems (void) { return _visualItems; } QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; } QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
QVariantList waypointPath (void) { return _waypointPath; } QVariantList waypointPath (void) { return _waypointPath; }
QStringList complexMissionItemNames (void) const; QStringList complexMissionItemNames (void) const;
QGeoCoordinate plannedHomePosition (void) const; QGeoCoordinate plannedHomePosition (void) const;
VisualMissionItem* currentPlanViewItem (void) const; VisualMissionItem* currentPlanViewItem (void) const;
double progressPct (void) const { return _progressPct; } double progressPct (void) const { return _progressPct; }
QString surveyComplexItemName (void) const { return _surveyMissionItemName; } QString surveyComplexItemName (void) const { return _surveyMissionItemName; }
QString corridorScanComplexItemName (void) const { return patternCorridorScanName; } QString circularSurveyComplexItemName (void) const { return _circularSurveyMissionItemName; }
QString structureScanComplexItemName(void) const { return patternStructureScanName; } QString corridorScanComplexItemName (void) const { return patternCorridorScanName; }
QString structureScanComplexItemName (void) const { return patternStructureScanName; }
int missionItemCount (void) const { return _missionItemCount; } int missionItemCount (void) const { return _missionItemCount; }
int currentMissionIndex (void) const; int currentMissionIndex (void) const;
...@@ -292,6 +295,7 @@ private: ...@@ -292,6 +295,7 @@ private:
bool _inRecalcSequence; bool _inRecalcSequence;
MissionFlightStatus_t _missionFlightStatus; MissionFlightStatus_t _missionFlightStatus;
QString _surveyMissionItemName; QString _surveyMissionItemName;
QString _circularSurveyMissionItemName;
AppSettings* _appSettings; AppSettings* _appSettings;
double _progressPct; double _progressPct;
int _currentPlanViewIndex; int _currentPlanViewIndex;
......
...@@ -1245,7 +1245,6 @@ void SurveyComplexItem::_rebuildTransectsFromPolygon(bool refly, const QPolygonF ...@@ -1245,7 +1245,6 @@ void SurveyComplexItem::_rebuildTransectsFromPolygon(bool refly, const QPolygonF
while (transectX < transectXMax) { while (transectX < transectXMax) {
double transectYTop = boundingCenter.y() - halfWidth; double transectYTop = boundingCenter.y() - halfWidth;
double transectYBottom = boundingCenter.y() + halfWidth; double transectYBottom = boundingCenter.y() + halfWidth;
lineList += QLineF(_rotatePoint(QPointF(transectX, transectYTop), boundingCenter, gridAngle), _rotatePoint(QPointF(transectX, transectYBottom), boundingCenter, gridAngle)); lineList += QLineF(_rotatePoint(QPointF(transectX, transectYTop), boundingCenter, gridAngle), _rotatePoint(QPointF(transectX, transectYBottom), boundingCenter, gridAngle));
transectX += gridSpacing; transectX += gridSpacing;
} }
......
...@@ -95,4 +95,6 @@ WimaCorridorMapVisual 1.0 WimaCorridorMapVisual.qml ...@@ -95,4 +95,6 @@ WimaCorridorMapVisual 1.0 WimaCorridorMapVisual.qml
WimaItemEditor 1.0 WimaItemEditor.qml WimaItemEditor 1.0 WimaItemEditor.qml
WimaMapPolygonVisuals 1.0 WimaMapPolygonVisuals.qml WimaMapPolygonVisuals 1.0 WimaMapPolygonVisuals.qml
WimaMapPolylineVisuals 1.0 WimaMapPolylineVisuals.qml WimaMapPolylineVisuals 1.0 WimaMapPolylineVisuals.qml
SphericalSurveyMapVisual 1.0 SphericalSurveyMapVisual.qml
...@@ -97,7 +97,7 @@ QList<QPointF> Circle::approximate(int numberOfCorners) const ...@@ -97,7 +97,7 @@ QList<QPointF> Circle::approximate(int numberOfCorners) const
{ {
if ( numberOfCorners < 3) if ( numberOfCorners < 3)
return QList<QPointF>(); return QList<QPointF>();
return approximateSektor(numberOfCorners, 0, 2*M_PI); return approximateSektor(numberOfCorners+1, 0, 2*M_PI);
} }
QList<QPointF> Circle::approximate(double angleDiscretisation) const QList<QPointF> Circle::approximate(double angleDiscretisation) const
...@@ -107,37 +107,39 @@ QList<QPointF> Circle::approximate(double angleDiscretisation) const ...@@ -107,37 +107,39 @@ QList<QPointF> Circle::approximate(double angleDiscretisation) const
QList<QPointF> Circle::approximateSektor(int numberOfCorners, double alpha1, double alpha2) const QList<QPointF> Circle::approximateSektor(int numberOfCorners, double alpha1, double alpha2) const
{ {
if ( numberOfCorners < 3)
return QList<QPointF>();
return approximateSektor((alpha2-alpha1)/double(numberOfCorners-1), alpha1, alpha2); return approximateSektor((alpha2-alpha1)/double(numberOfCorners-1), alpha1, alpha2);
} }
QList<QPointF> Circle::approximateSektor(double angleDiscretisation, double alpha1, double alpha2) const QList<QPointF> Circle::approximateSektor(double angleDiscretisation, double alpha1, double alpha2) const
{ {
using namespace PlanimetryCalculus;
// truncate alpha1 to [0, 2*pi], fmod() does not work in this case // truncate alpha1 to [0, 2*pi], fmod() does not work in this case
alpha1 = PlanimetryCalculus::truncateAngle(alpha1); alpha1 = truncateAngle(alpha1);
alpha2 = PlanimetryCalculus::truncateAngle(alpha2); alpha2 = truncateAngle(alpha2);
double deltaAlpha = PlanimetryCalculus::truncateAngle(alpha2 - alpha1); double deltaAlpha = truncateAngle(alpha2 - alpha1);
angleDiscretisation = PlanimetryCalculus::truncateAngle(angleDiscretisation); angleDiscretisation = truncateAngle(angleDiscretisation)*signum(angleDiscretisation);
if (angleDiscretisation > deltaAlpha || qFuzzyIsNull(angleDiscretisation)) if (fabs(angleDiscretisation) > deltaAlpha || qFuzzyIsNull(angleDiscretisation))
return QList<QPointF>(); return QList<QPointF>();
QList<QPointF> sector; QList<QPointF> sector;
QPointF vertex(-_circleRadius,0); // initial vertex QPointF vertex0(_circleRadius,0); // initial vertex
double currentAngle = alpha1; double currentAngle = alpha1;
// rotate the vertex numberOfCorners-1 times add the origin and append to the polygon. // rotate the vertex numberOfCorners-1 times add the origin and append to the polygon.
while(currentAngle < alpha2) { do {
PlanimetryCalculus::rotateReference(vertex, currentAngle); QPointF currentVertex = rotateReturn(vertex0, currentAngle);
sector.append(vertex + _circleOrigin); sector.append(currentVertex + _circleOrigin);
currentAngle = PlanimetryCalculus::truncateAngle(currentAngle + angleDiscretisation); currentAngle = PlanimetryCalculus::truncateAngle(currentAngle + angleDiscretisation);
} }while(currentAngle < alpha2);
// append last point if necessarry // append last point if necessarry
PlanimetryCalculus::rotateReference(vertex, alpha2); QPointF currentVertex = rotateReturn(vertex0, alpha2) + _circleOrigin;
vertex = vertex + _circleOrigin; if ( !qFuzzyIsNull(PlanimetryCalculus::distance(sector.first(), currentVertex))
if ( !qFuzzyIsNull(PlanimetryCalculus::distance(sector.first(), vertex)) && !qFuzzyIsNull(PlanimetryCalculus::distance(sector.last(), currentVertex )) ){
&& !qFuzzyIsNull(PlanimetryCalculus::distance(sector.last(), vertex )) ){ sector.append(currentVertex);
sector.append(vertex);
} }
return sector; return sector;
......
...@@ -4,9 +4,25 @@ ...@@ -4,9 +4,25 @@
const char* CircularSurveyComplexItem::settingsGroup = "Survey"; const char* CircularSurveyComplexItem::settingsGroup = "Survey";
CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyView, const QString &kmlOrShpFile, QObject *parent) CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyView, const QString &kmlOrShpFile, QObject *parent)
: TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent) : TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
, _referencePoint(QGeoCoordinate(47.770859, 16.531076,0))
{
}
void CircularSurveyComplexItem::setRefPoint(const QGeoCoordinate &refPt)
{ {
if (refPt != _referencePoint){
_referencePoint = refPt;
emit refPointChanged();
}
}
QGeoCoordinate CircularSurveyComplexItem::refPoint() const
{
return _referencePoint;
} }
bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString)
...@@ -50,78 +66,120 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1() ...@@ -50,78 +66,120 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
using namespace PolygonCalculus; using namespace PolygonCalculus;
using namespace PlanimetryCalculus; using namespace PlanimetryCalculus;
if ( _surveyAreaPolygon.count() < 3)
return;
_transects.clear(); _transects.clear();
QPolygonF surveyPolygon = toQPolygonF(toCartesian2D(_surveyAreaPolygon.coordinateList(), _referencePoint)); QPolygonF surveyPolygon = toQPolygonF(toCartesian2D(_surveyAreaPolygon.coordinateList(), _referencePoint));
QPolygonF boundingPolygon = surveyPolygon.boundingRect();
QVector<double> distances; QVector<double> distances;
for (const QPointF &p : boundingPolygon) distances.append(norm(p)); for (const QPointF &p : surveyPolygon) distances.append(norm(p));
QVector<double> angles;
for (const QPointF &p : boundingPolygon) angles.append(truncateAngle(angle(p)));
double alpha1 = 0.95*(*std::min_element(angles.begin(), angles.end()));; // radiants
double alpha2 = 1.05*(*std::max_element(angles.begin(), angles.end())); // radiants; // radiants
double dalpha = 0.5/180*M_PI; // radiants double dalpha = 0.5/180*M_PI; // radiants
double r0 = 0.9*(*std::min_element(distances.begin(), distances.end())); // meter double dr = 30; // meter
double r1 = 1.1*(*std::max_element(distances.begin(), distances.end())); // meter double r_min = dr; // meter
double dr = 1; // meter double r_max = (*std::max_element(distances.begin(), distances.end())); // meter
QPointF origin(0, 0);
IntersectType type;
if (!contains(surveyPolygon, origin, type)) {
QVector<double> angles;
for (const QPointF &p : surveyPolygon) angles.append(truncateAngle(angle(p)));
// determine r_min by successive approximation
double r = r_max;
while ( r > r_min) {
Circle circle(r, origin);
if (!intersects(circle, surveyPolygon)) {
r_min = r;
break;
}
r -= dr;
}
}
qWarning("r_min, r_max:");
qWarning() << r_min;
qWarning() << r_max;
QList<QPolygonF> convexPolygons; QList<QPolygonF> convexPolygons;
decomposeToConvex(surveyPolygon, convexPolygons); decomposeToConvex(surveyPolygon, convexPolygons);
QPointF origin(0, 0); QList<QList<QPointF>> fullPath;
QList<QPointF> fullPath;
for (int i = 0; i < convexPolygons.size(); i++){ for (int i = 0; i < convexPolygons.size(); i++){
const QPolygonF &polygon = convexPolygons[i]; const QPolygonF &polygon = convexPolygons[i];
double r = r0; double r = r_min;
QList<QPointF> currPolyPath; QList<QList<QPointF>> currPolyPath;
bool currentPolyPathUpdated = false;
int direction = 1; int direction = 1;
while (r < r1) { while (r < r_max) {
Circle circle(r, origin); Circle circle(r, origin);
QList<QPointF> sector = circle.approximateSektor(dalpha, alpha1, alpha2); QList<QPointFList> intersectPoints;
QList<QPointF> sectorPath; QList<IntersectType> typeList;
for ( const QPointF &p : sector) { if (intersects(circle, polygon, intersectPoints, typeList)) {
if (polygon.containsPoint(p, Qt::FillRule::OddEvenFill)) if (intersectPoints.size() >= 1) {
sectorPath.append(p); // continue here
QPointF p1 = intersectPoints.first()[0];
QPointF p2 = intersectPoints.first()[1];
double beta1 = angle(p1);
double beta2 = angle(p2);
double alpha1 = fmin(beta1, beta2);
double alpha2 = fmax(beta1, beta2);
QList<QPointF> sector = circle.approximateSektor(direction*dalpha, alpha1, alpha2);
QList<QPointF> sectorPath;
for ( const QPointF &p : sector) {
if (polygon.containsPoint(p, Qt::FillRule::OddEvenFill))
sectorPath.append(p);
}
if (sectorPath.size() > 0 ) {
if (direction == -1){
direction = 1;
} else
direction = -1;
// use shortestPath() here if necessary, could be a problem if dr >>
currPolyPath.append(sectorPath);
currentPolyPathUpdated = true;
}
}
} }
if (direction == -1){
reversePath(sectorPath);
direction = 1;
} else
direction = -1;;
// use shortestPath() here if necessary, could be a problem if dr >>
currPolyPath.append(sectorPath);
r += dr; r += dr;
} }
if (i > 0) { if (currentPolyPathUpdated) {
QPointF start = fullPath.last(); if (fullPath.size() > 1) {
QPointF end = currPolyPath.first(); QPointF start = fullPath.last().last();
QList<QPointF> path; QPointF end = currPolyPath.last().first();
if(!shortestPath(surveyPolygon, start, end, path)) QList<QPointF> path;
return; if(!shortestPath(surveyPolygon, start, end, path))
path.removeFirst(); return;
path.removeLast(); path.removeFirst();
fullPath.append(path); path.removeLast();
fullPath.append(fullPath); currPolyPath.last().append(path);
}
fullPath.append(currPolyPath);
} }
}
QList<QGeoCoordinate> geoPath = toGeo(fullPath, _referencePoint);
for ( const QGeoCoordinate &coordinate : geoPath) {
CoordInfo_t coordinfo = {coordinate, CoordTypeInterior};
_transects.append(coordinfo);
} }
for ( const QList<QPointF> &transect : fullPath) {
QList<QGeoCoordinate> geoPath = toGeo(transect, _referencePoint);
QList<CoordInfo_t> transectList;
for ( const QGeoCoordinate &coordinate : geoPath) {
CoordInfo_t coordinfo = {coordinate, CoordTypeInterior};
transectList.append(coordinfo);
}
_transects.append(transectList);
}
} }
......
...@@ -17,6 +17,14 @@ public: ...@@ -17,6 +17,14 @@ public:
/// @param kmlOrShpFile Polygon comes from this file, empty for default polygon /// @param kmlOrShpFile Polygon comes from this file, empty for default polygon
CircularSurveyComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrShpFile, QObject* parent); CircularSurveyComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrShpFile, QObject* parent);
Q_PROPERTY(QGeoCoordinate refPoint READ refPoint WRITE setRefPoint NOTIFY refPointChanged)
// Property setters
void setRefPoint(const QGeoCoordinate &refPt);
// Property getters
QGeoCoordinate refPoint() const;
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("SpericalSurveyMapVisual.qml"); } QString mapVisualQML (void) const final { return QStringLiteral("SpericalSurveyMapVisual.qml"); }
...@@ -29,20 +37,24 @@ public: ...@@ -29,20 +37,24 @@ public:
double timeBetweenShots (void) final; double timeBetweenShots (void) final;
// Overrides from VisualMissionionItem // Overrides from VisualMissionionItem
QString commandDescription (void) const final { return tr("Spherical Survey"); } QString commandDescription (void) const final { return tr("Circular Survey"); }
QString commandName (void) const final { return tr("SphericalSurvey"); } QString commandName (void) const final { return tr("Circular Survey"); }
QString abbreviation (void) const final { return tr("Sph.S"); } QString abbreviation (void) const final { return tr("C.S."); }
bool readyForSave (void) const final; bool readyForSave (void) const final;
double additionalTimeDelay (void) const final; double additionalTimeDelay (void) const final;
static const char* settingsGroup; static const char* settingsGroup;
signals:
void refPointChanged();
private slots: private slots:
// Overrides from TransectStyleComplexItem // Overrides from TransectStyleComplexItem
void _rebuildTransectsPhase1 (void) final; void _rebuildTransectsPhase1 (void) final;
void _recalcComplexDistance (void) final; void _recalcComplexDistance (void) final;
void _recalcCameraShots (void) final; void _recalcCameraShots (void) final;
private:
QGeoCoordinate _referencePoint; // center of the circular lanes, e.g. base station QGeoCoordinate _referencePoint; // center of the circular lanes, e.g. base station
}; };
......
add refpt gui and edit constructor
...@@ -17,84 +17,6 @@ namespace OptimisationTools { ...@@ -17,84 +17,6 @@ namespace OptimisationTools {
* \sa QList * \sa QList
*/ */
template <class T> template <class T>
bool dijkstraAlgorithm(const QList<T> &elements, int startIndex, int endIndex, QList<T> &elementPath, std::function<double(const T &, const T &)> distance) // don't seperate parameters with new lines or documentation will break bool dijkstraAlgorithm(const QList<T> &elements, int startIndex, int endIndex, QList<T> &elementPath, std::function<double(const T &, const T &)> distance); // don't seperate parameters with new lines or documentation will break
{
if ( elements.isEmpty() || startIndex < 0
|| startIndex >= elements.size() || endIndex < 0
|| endIndex >= elements.size()) {
return false;
}
//qWarning("optitools");
// Each element of type T gets stuff into a Node
/// @param distance is the distance between the Node and it's predecessor
struct Node{
T element;
double distance = std::numeric_limits<qreal>::infinity();
Node* predecessorNode = nullptr;
};
// The list with all Nodes (elements)
QList<Node> nodeList;
// This list will be initalized with (pointer to) all elements of nodeList.
// Elements will be successively remove during the execution of the Dijkstra Algorithm.
QList<Node*> workingSet;
//append elements to node list
for (int i = 0; i < elements.size(); i++) {
Node node;
node.element = elements[i];
nodeList.append(node);
workingSet.append(&nodeList[i]);
}
nodeList[startIndex].distance = 0;
// Dijkstra Algorithm
// https://de.wikipedia.org/wiki/Dijkstra-Algorithmus
while (workingSet.size() > 0) {
// serach Node with minimal distance
double minDist = std::numeric_limits<qreal>::infinity();
int minDistIndex = 0;
for (int i = 0; i < workingSet.size(); i++) {
Node* node = workingSet.value(i);
double dist = node->distance;
if (dist < minDist) {
minDist = dist;
minDistIndex = i;
}
}
Node* u = workingSet.takeAt(minDistIndex);
//update distance
for (int i = 0; i < workingSet.size(); i++) {
Node* v = workingSet[i];
double dist = distance(u->element, v->element);
// is ther a alternative path which is shorter?
double alternative = u->distance + dist;
if (alternative < v->distance) {
v->distance = alternative;
v->predecessorNode = u;
}
}
}
// end Djikstra Algorithm
// reverse assemble path
Node* node = &nodeList[endIndex];
while (1) {
if (node == nullptr) {
if (elementPath[0] == elements[startIndex])// check if starting point was reached
break;
return false;
}
elementPath.prepend(node->element);
//Update Node
node = node->predecessorNode;
}
return true;
}
} // end OptimisationTools namespace } // end OptimisationTools namespace
...@@ -5,8 +5,97 @@ ...@@ -5,8 +5,97 @@
#include <QPointF> #include <QPointF>
namespace OptimisationTools { namespace OptimisationTools {
/*!
* \fn bool dijkstraAlgorithm(int startIndex, int endIndex, const QList<T> elements, QList<T> &elementPath, double(*distance)(const T &t1, const T &t2))
* Calculates the shortest path between the elements stored in \a elements.
* The \l {Dijkstra Algorithm} is used to find the shorest path.
* Stores the result inside \a elementPath when sucessfull.
* The function handle \a distance is used to calculate the distance between two elements. The distance must be positive.
* Returns \c true if successful, \c false else.
*
* \sa QList
*/
template <class T> template <class T>
bool dijkstraAlgorithm(const QList<T> &elements, int startIndex, int endIndex, QList<T> &elementPath, std::function<double(const T &, const T &)> distance); bool dijkstraAlgorithm(const QList<T> &elements, int startIndex, int endIndex, QList<T> &elementPath, std::function<double(const T &, const T &)> distance)
{
if ( elements.isEmpty() || startIndex < 0
|| startIndex >= elements.size() || endIndex < 0
|| endIndex >= elements.size()) {
return false;
}
//qWarning("optitools");
// Each element of type T gets stuff into a Node
/// @param distance is the distance between the Node and it's predecessor
struct Node{
T element;
double distance = std::numeric_limits<qreal>::infinity();
Node* predecessorNode = nullptr;
};
// The list with all Nodes (elements)
QList<Node> nodeList;
// This list will be initalized with (pointer to) all elements of nodeList.
// Elements will be successively remove during the execution of the Dijkstra Algorithm.
QList<Node*> workingSet;
//append elements to node list
for (int i = 0; i < elements.size(); i++) {
Node node;
node.element = elements[i];
nodeList.append(node);
workingSet.append(&nodeList[i]);
}
nodeList[startIndex].distance = 0;
// Dijkstra Algorithm
// https://de.wikipedia.org/wiki/Dijkstra-Algorithmus
while (workingSet.size() > 0) {
// serach Node with minimal distance
double minDist = std::numeric_limits<qreal>::infinity();
int minDistIndex = 0;
for (int i = 0; i < workingSet.size(); i++) {
Node* node = workingSet.value(i);
double dist = node->distance;
if (dist < minDist) {
minDist = dist;
minDistIndex = i;
}
}
Node* u = workingSet.takeAt(minDistIndex);
//update distance
for (int i = 0; i < workingSet.size(); i++) {
Node* v = workingSet[i];
double dist = distance(u->element, v->element);
// is ther a alternative path which is shorter?
double alternative = u->distance + dist;
if (alternative < v->distance) {
v->distance = alternative;
v->predecessorNode = u;
}
}
}
// end Djikstra Algorithm
// reverse assemble path
Node* node = &nodeList[endIndex];
while (1) {
if (node == nullptr) {
if (elementPath[0] == elements[startIndex])// check if starting point was reached
break;
return false;
}
elementPath.prepend(node->element);
//Update Node
node = node->predecessorNode;
}
return true;
}
} }
...@@ -480,16 +480,7 @@ angle ...@@ -480,16 +480,7 @@ angle
return line; return line;
} }
/*!
* \fntemplate <typename T> int signum(T val)
* Returns the signum of a value \a val.
*
* \sa QPair, QList
*/
template <typename T> int signum(T val)
{
return (T(0) < val) - (val < T(0));
}
bool intersects(const QLineF &line1, const QLineF &line2, QPointF &intersectionPt) bool intersects(const QLineF &line1, const QLineF &line2, QPointF &intersectionPt)
{ {
...@@ -632,6 +623,70 @@ angle ...@@ -632,6 +623,70 @@ angle
return qAtan2(p1.y(), p1.x()); return qAtan2(p1.y(), p1.x());
} }
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints, NeighbourList &neighbourList, IntersectList &typeList)
{
using namespace PolygonCalculus;
for (int i = 0; i < polygon.size(); i++) {
QPointF p1 = polygon[i];
int j = nextVertexIndex(polygon.size(), i);
QPointF p2 = polygon[j];
QLineF line(p1, p2);
QPointFList lineIntersecPts;
IntersectType type;
if (intersects(circle, line, lineIntersecPts, type)) {
QPair<int, int> neigbours;
neigbours.first = i;
neigbours.second = j;
neighbourList.append(neigbours);
typeList.append(type);
intersectionPoints.append(lineIntersecPts);
}
}
if (intersectionPoints.size() > 0)
return true;
else {
return false;
}
}
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints, NeighbourList &neighbourList)
{
QList<IntersectType> types;
return intersects(circle, polygon, intersectionPoints, neighbourList, types);
}
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints, IntersectList &typeList)
{
NeighbourList neighbourList;
return intersects(circle, polygon, intersectionPoints, neighbourList, typeList);
}
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints)
{
NeighbourList neighbourList;
return intersects(circle, polygon, intersectionPoints, neighbourList);
}
bool intersects(const Circle &circle, const QPolygonF &polygon)
{
QList<QPointFList> intersectionPoints;
return intersects(circle, polygon, intersectionPoints);
}
bool intersects(const QLineF &line1, const QLineF &line2)
{
QPointF intersectionPoint;
return intersects(line1, line2, intersectionPoint);
}
bool intersects(const Circle &circle, const QLineF &line, QPointFList &intersectionPoints, IntersectType &type)
{
return intersects(circle, line, intersectionPoints, type, true /* calculate intersection points*/);
}
......
...@@ -44,12 +44,19 @@ namespace PlanimetryCalculus { ...@@ -44,12 +44,19 @@ namespace PlanimetryCalculus {
bool intersects(const Circle &circle1, const Circle &circle2, IntersectType &type); bool intersects(const Circle &circle1, const Circle &circle2, IntersectType &type);
bool intersects(const Circle &circle1, const Circle &circle2, QPointFList &intersectionPoints); bool intersects(const Circle &circle1, const Circle &circle2, QPointFList &intersectionPoints);
bool intersects(const Circle &circle1, const Circle &circle2, QPointFList &intersectionPoints, IntersectType &type); bool intersects(const Circle &circle1, const Circle &circle2, QPointFList &intersectionPoints, IntersectType &type);
bool intersects(const Circle &circle, const QLineF &line); bool intersects(const Circle &circle, const QLineF &line);
bool intersects(const Circle &circle, const QLineF &line, IntersectType &type); bool intersects(const Circle &circle, const QLineF &line, IntersectType &type);
bool intersects(const Circle &circle, const QLineF &line, QPointFList &intersectionPoints); bool intersects(const Circle &circle, const QLineF &line, QPointFList &intersectionPoints);
bool intersects(const Circle &circle, const QLineF &line, QPointFList &intersectionPoints, IntersectType &type); bool intersects(const Circle &circle, const QLineF &line, QPointFList &intersectionPoints, IntersectType &type);
bool intersects(const Circle &circle, const QPolygonF &polygon);
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints);
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints, IntersectList &typeList);
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints, NeighbourList &neighbourList);
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints, NeighbourList &neighbourList, IntersectList &typeList);
bool intersects(const QLineF &line1, const QLineF &line2);
bool intersects(const QLineF &line1, const QLineF &line2, QPointF &intersectionPt); bool intersects(const QLineF &line1, const QLineF &line2, QPointF &intersectionPt);
bool intersects(const QLineF &line1, const QLineF &line2, QPointF &intersectionPt, IntersectType &type); bool intersects(const QLineF &line1, const QLineF &line2, QPointF &intersectionPt, IntersectType &type);
bool intersects(const QPolygonF &polygon, const QLineF &line, QPointFList &intersectionList); bool intersects(const QPolygonF &polygon, const QLineF &line, QPointFList &intersectionList);
...@@ -73,7 +80,16 @@ namespace PlanimetryCalculus { ...@@ -73,7 +80,16 @@ namespace PlanimetryCalculus {
double truncateAngle(double angle); double truncateAngle(double angle);
double truncateAngleDegree(double angle); double truncateAngleDegree(double angle);
template <typename T> int signum(T val); /*!
* \fntemplate <typename T> int signum(T val)
* Returns the signum of a value \a val.
*
* \sa QPair, QList
*/
template <typename T> int signum(T val)
{
return (T(0) < val) - (val < T(0));
}
} }
......
...@@ -147,31 +147,31 @@ bool WimaArea::join(const WimaArea &area1, const WimaArea &area2, WimaArea &join ...@@ -147,31 +147,31 @@ bool WimaArea::join(const WimaArea &area1, const WimaArea &area2, WimaArea &join
QList<QGeoCoordinate> GeoPolygon1 = area1.coordinateList(); QList<QGeoCoordinate> GeoPolygon1 = area1.coordinateList();
QList<QGeoCoordinate> GeoPolygon2 = area2.coordinateList(); QList<QGeoCoordinate> GeoPolygon2 = area2.coordinateList();
qWarning("befor joining"); // qWarning("befor joining");
qWarning() << GeoPolygon1; // qWarning() << GeoPolygon1;
qWarning() << GeoPolygon2; // qWarning() << GeoPolygon2;
QGeoCoordinate origin = GeoPolygon1[0]; QGeoCoordinate origin = GeoPolygon1[0];
QGeoCoordinate tset = GeoPolygon1[2]; // QGeoCoordinate tset = GeoPolygon1[2];
qWarning() << tset;qWarning() << toGeo(toCartesian2D(tset, origin), origin); // qWarning() << tset;qWarning() << toGeo(toCartesian2D(tset, origin), origin);
QPolygonF polygon1 = toQPolygonF(toCartesian2D(GeoPolygon1, origin)); QPolygonF polygon1 = toQPolygonF(toCartesian2D(GeoPolygon1, origin));
QPolygonF polygon2 = toQPolygonF(toCartesian2D(GeoPolygon2, origin)); QPolygonF polygon2 = toQPolygonF(toCartesian2D(GeoPolygon2, origin));
qWarning("after 1 transform"); // qWarning("after 1 transform");
qWarning() << polygon1; // qWarning() << polygon1;
qWarning() << polygon2; // qWarning() << polygon2;
QPolygonF joinedPolygon; QPolygonF joinedPolygon;
JoinPolygonError retValue = PolygonCalculus::join(polygon1, polygon2, joinedPolygon); JoinPolygonError retValue = PolygonCalculus::join(polygon1, polygon2, joinedPolygon);
qWarning("after joining"); // qWarning("after joining");
qWarning() << joinedPolygon; // qWarning() << joinedPolygon;
if (retValue == JoinPolygonError::Disjoint) { if (retValue == JoinPolygonError::Disjoint) {
qWarning("Polygons are disjoint."); qWarning("Polygons are disjoint.");
...@@ -181,8 +181,8 @@ bool WimaArea::join(const WimaArea &area1, const WimaArea &area2, WimaArea &join ...@@ -181,8 +181,8 @@ bool WimaArea::join(const WimaArea &area1, const WimaArea &area2, WimaArea &join
qWarning("Polygon vertex count is low."); qWarning("Polygon vertex count is low.");
} else { } else {
QList<QGeoCoordinate> path = toGeo(toQPointFList(joinedPolygon), origin); QList<QGeoCoordinate> path = toGeo(toQPointFList(joinedPolygon), origin);
qWarning("after transform"); // qWarning("after transform");
qWarning() << path; // qWarning() << path;
joinedArea.setPath(path); joinedArea.setPath(path);
return true; return true;
} }
......
...@@ -160,7 +160,7 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -160,7 +160,7 @@ void WimaController::containerDataValidChanged(bool valid)
qWarning() << areaData->type(); qWarning() << areaData->type();
if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area? if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
_serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData); _serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData);
qWarning("Service area, wuhuuu!"); // qWarning("Service area, wuhuuu!");
areaCounter++; areaCounter++;
_visualItems.append(&_serviceArea); _visualItems.append(&_serviceArea);
...@@ -169,7 +169,7 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -169,7 +169,7 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area? if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
_measurementArea = *qobject_cast<const WimaMeasurementAreaData*>(areaData); _measurementArea = *qobject_cast<const WimaMeasurementAreaData*>(areaData);
qWarning("Measurement area, wuhuuu!"); // qWarning("Measurement area, wuhuuu!");
areaCounter++; areaCounter++;
_visualItems.append(&_measurementArea); _visualItems.append(&_measurementArea);
...@@ -178,7 +178,7 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -178,7 +178,7 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor? if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
_corridor = *qobject_cast<const WimaCorridorData*>(areaData); _corridor = *qobject_cast<const WimaCorridorData*>(areaData);
qWarning("WimaCorridorData, wuhuuu!"); // qWarning("WimaCorridorData, wuhuuu!");
areaCounter++; areaCounter++;
//_visualItems.append(&_corridor); // not needed //_visualItems.append(&_corridor); // not needed
...@@ -187,7 +187,7 @@ void WimaController::containerDataValidChanged(bool valid) ...@@ -187,7 +187,7 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor? if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
_joinedArea = *qobject_cast<const WimaJoinedAreaData*>(areaData); _joinedArea = *qobject_cast<const WimaJoinedAreaData*>(areaData);
qWarning("WimaJoinedAreaData, wuhuuu!"); // qWarning("WimaJoinedAreaData, wuhuuu!");
areaCounter++; areaCounter++;
_visualItems.append(&_joinedArea); _visualItems.append(&_joinedArea);
......
...@@ -12,7 +12,16 @@ WimaDataContainer::WimaDataContainer(QObject *parent) ...@@ -12,7 +12,16 @@ WimaDataContainer::WimaDataContainer(QObject *parent)
* \fn bool WimaDataContainer::dataValid() const * \fn bool WimaDataContainer::dataValid() const
* Returns \c true if the data is valid, \c false else. * Returns \c true if the data is valid, \c false else.
*/ */
bool WimaDataContainer::dataValid() const bool WimaDataContainer::dataValid() const/*!
* \fn bool dijkstraAlgorithm(int startIndex, int endIndex, const QList<T> elements, QList<T> &elementPath, double(*distance)(const T &t1, const T &t2))
* Calculates the shortest path between the elements stored in \a elements.
* The \l {Dijkstra Algorithm} is used to find the shorest path.
* Stores the result inside \a elementPath when sucessfull.
* The function handle \a distance is used to calculate the distance between two elements. The distance must be positive.
* Returns \c true if successful, \c false else.
*
* \sa QList
*/
{ {
return _dataValid; return _dataValid;
} }
......
#include "WimaPlaner.h" #include "WimaPlaner.h"
#include "CircularSurveyComplexItem.h"
const char* WimaPlaner::wimaFileExtension = "wima"; const char* WimaPlaner::wimaFileExtension = "wima";
...@@ -244,18 +246,21 @@ bool WimaPlaner::updateMission() ...@@ -244,18 +246,21 @@ bool WimaPlaner::updateMission()
// create survey item, will be extened with more()-> mission types in the future // create survey item, will be extened with more()-> mission types in the future
_missionController->insertComplexMissionItem(_missionController->surveyComplexItemName(), _measurementArea.center(), missionItems->count()); _missionController->insertComplexMissionItem(_missionController->circularSurveyComplexItemName(), _measurementArea.center(), missionItems->count());
SurveyComplexItem* survey = qobject_cast<SurveyComplexItem*>(missionItems->get(missionItems->count()-1)); CircularSurveyComplexItem* survey = qobject_cast<CircularSurveyComplexItem*>(missionItems->get(missionItems->count()-1));
if (survey == nullptr){ if (survey == nullptr){
qWarning("WimaPlaner::updateMission(): survey == nullptr"); qWarning("WimaPlaner::updateMission(): survey == nullptr");
return false; return false;
} else { } else {
survey->surveyAreaPolygon()->clear(); survey->surveyAreaPolygon()->clear();
survey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList()); survey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList());
//survey->
} }
// calculate path from take off to opArea // calculate path from take off to opArea
if (survey->visualTransectPoints().size() == 0) {
qWarning("WimaPlaner::updateMission(): survey no points.");
return false;
}
QGeoCoordinate start = _serviceArea.center(); QGeoCoordinate start = _serviceArea.center();
QGeoCoordinate end = survey->visualTransectPoints().first().value<QGeoCoordinate>(); QGeoCoordinate end = survey->visualTransectPoints().first().value<QGeoCoordinate>();
QList<QGeoCoordinate> path; QList<QGeoCoordinate> path;
...@@ -440,7 +445,7 @@ bool WimaPlaner::loadFromFile(const QString &filename) ...@@ -440,7 +445,7 @@ bool WimaPlaner::loadFromFile(const QString &filename)
emit currentFileChanged(); emit currentFileChanged();
//recalcJoinedArea(); //recalcJoinedArea();
// MissionItems // MissionItems4
// extrac MissionItems part // extrac MissionItems part
QJsonDocument missionJsonDoc = QJsonDocument(json[missionItemsName].toObject()); QJsonDocument missionJsonDoc = QJsonDocument(json[missionItemsName].toObject());
// create temporary file with missionItems // create temporary file with missionItems
...@@ -529,7 +534,10 @@ bool WimaPlaner::recalcJoinedArea(QString &errorString) ...@@ -529,7 +534,10 @@ bool WimaPlaner::recalcJoinedArea(QString &errorString)
// remove if debugging finished // remove if debugging finished
WimaServiceArea *test = new WimaServiceArea(this); WimaServiceArea *test = new WimaServiceArea(this);
test->setPath(_joinedArea.path()); Circle circle(25, this);
using namespace GeoUtilities;
test->setPath(toGeo(circle.approximateSektor(10, -1, 1), _joinedArea.center()));
_visualItems.append(test); _visualItems.append(test);
return true; return true;
......
...@@ -29,7 +29,7 @@ ...@@ -29,7 +29,7 @@
#include "PlanimetryCalculus.h" #include "PlanimetryCalculus.h"
#include "GeoUtilities.h" #include "GeoUtilities.h"
#define TEST_FUN 1 #define TEST_FUN 0
#if TEST_FUN #if TEST_FUN
#include "TestPolygonCalculus.h" #include "TestPolygonCalculus.h"
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
// original file: SurveyMapVisual.qml
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
/// Survey Complex Mission Item visuals
Item {
id: _root
property var map ///< Map control to place item in
property var qgcView ///< QGCView to use for popping dialogs
property var _missionItem: object
property var _mapPolygon: object.surveyAreaPolygon
property var _visualTransectsComponent
property var _entryCoordinate
property var _exitCoordinate
signal clicked(int sequenceNumber)
function _addVisualElements() {
_visualTransectsComponent = visualTransectsComponent.createObject(map)
_entryCoordinate = entryPointComponent.createObject(map)
_exitCoordinate = exitPointComponent.createObject(map)
map.addMapItem(_visualTransectsComponent)
map.addMapItem(_entryCoordinate)
map.addMapItem(_exitCoordinate)
}
function _destroyVisualElements() {
_visualTransectsComponent.destroy()
_entryCoordinate.destroy()
_exitCoordinate.destroy()
}
/// Add an initial 4 sided polygon if there is none
function _addInitialPolygon() {
if (_mapPolygon.count < 3) {
// Initial polygon is inset to take 2/3rds space
var rect = Qt.rect(map.centerViewport.x, map.centerViewport.y, map.centerViewport.width, map.centerViewport.height)
rect.x += (rect.width * 0.25) / 2
rect.y += (rect.height * 0.25) / 2
rect.width *= 0.75
rect.height *= 0.75
var centerCoord = map.toCoordinate(Qt.point(rect.x + (rect.width / 2), rect.y + (rect.height / 2)), false /* clipToViewPort */)
var topLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */)
var topRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */)
var bottomLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y + rect.height), false /* clipToViewPort */)
var bottomRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y + rect.height), false /* clipToViewPort */)
// Initial polygon has max width and height of 3000 meters
var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2
var halfHeightMeters = Math.min(topLeftCoord.distanceTo(bottomLeftCoord), 3000) / 2
topLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 0)
topRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 0)
bottomLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 180)
bottomRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 180)
_mapPolygon.appendVertex(topLeftCoord)
_mapPolygon.appendVertex(topRightCoord)
_mapPolygon.appendVertex(bottomRightCoord)
_mapPolygon.appendVertex(bottomLeftCoord)
}
}
Component.onCompleted: {
_addInitialPolygon()
_addVisualElements()
}
Component.onDestruction: {
_destroyVisualElements()
}
QGCMapPolygonVisuals {
id: mapPolygonVisuals
qgcView: _root.qgcView
mapControl: map
mapPolygon: _mapPolygon
interactive: _missionItem.isCurrentItem
borderWidth: 1
borderColor: "black"
interiorColor: "green"
interiorOpacity: 0.5
}
// Transect lines
Component {
id: visualTransectsComponent
MapPolyline {
line.color: "white"
line.width: 2
path: _missionItem.visualTransectPoints
}
}
// Entry point
Component {
id: entryPointComponent
MapQuickItem {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.coordinate
visible: _missionItem.exitCoordinate.isValid
sourceItem: MissionItemIndexLabel {
index: _missionItem.sequenceNumber
label: "Entry"
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
// Exit point
Component {
id: exitPointComponent
MapQuickItem {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.exitCoordinate
visible: _missionItem.exitCoordinate.isValid
sourceItem: MissionItemIndexLabel {
index: _missionItem.lastSequenceNumber
label: "Exit"
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
}
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