Unverified Commit 84a6c9d9 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6962 from mavlink/feature/concave_poly

Feature: Concave Polygon Support by Splitting into Sub-Polygons
parents da8e98a1 a2a82f30
......@@ -13,6 +13,7 @@ Note: This file only contains high level features or important fixes.
* Make Heading to Home available for display from instrument panel.
* Edit Position dialog available on polygon vertices.
* Fixed Wing Landing Pattern: Add stop photo/video support. Defaults to on such that doing an RTL will stop camera.
* Survey Planning: add mode that supports concave polygons
## 3.4
......
......@@ -14,5 +14,11 @@
"shortDescription": "Fly every other transect in each pass.",
"type": "bool",
"defaultValue": false
},
{
"name": "SplitConcavePolygons",
"shortDescription": "Split mission concave polygons into separate regular, convex polygons.",
"type": "bool",
"defaultValue": true
}
]
......@@ -28,6 +28,7 @@ const char* SurveyComplexItem::settingsGroup = "Survey";
const char* SurveyComplexItem::gridAngleName = "GridAngle";
const char* SurveyComplexItem::gridEntryLocationName = "GridEntryLocation";
const char* SurveyComplexItem::flyAlternateTransectsName = "FlyAlternateTransects";
const char* SurveyComplexItem::splitConcavePolygonsName = "SplitConcavePolygons";
const char* SurveyComplexItem::_jsonGridAngleKey = "angle";
const char* SurveyComplexItem::_jsonEntryPointKey = "entryLocation";
......@@ -58,12 +59,14 @@ const char* SurveyComplexItem::_jsonV3CameraOrientationLandscapeKey = "orienta
const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey = "fixedValueIsAltitude";
const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90Degrees";
const char* SurveyComplexItem::_jsonFlyAlternateTransectsKey = "flyAlternateTransects";
const char* SurveyComplexItem::_jsonSplitConcavePolygonsKey = "splitConcavePolygons";
SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlFile, QObject* parent)
: TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
, _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName])
, _flyAlternateTransectsFact(settingsGroup, _metaDataMap[flyAlternateTransectsName])
, _splitConcavePolygonsFact (settingsGroup, _metaDataMap[splitConcavePolygonsName])
, _entryPoint (EntryLocationTopLeft)
{
_editorQml = "qrc:/qml/SurveyItemEditor.qml";
......@@ -82,10 +85,12 @@ SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, const QStri
connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyComplexItem::_setDirty);
connect(&_flyAlternateTransectsFact,&Fact::valueChanged, this, &SurveyComplexItem::_setDirty);
connect(&_splitConcavePolygonsFact, &Fact::valueChanged, this, &SurveyComplexItem::_setDirty);
connect(this, &SurveyComplexItem::refly90DegreesChanged, this, &SurveyComplexItem::_setDirty);
connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyComplexItem::_rebuildTransects);
connect(&_flyAlternateTransectsFact,&Fact::valueChanged, this, &SurveyComplexItem::_rebuildTransects);
connect(&_splitConcavePolygonsFact, &Fact::valueChanged, this, &SurveyComplexItem::_rebuildTransects);
connect(this, &SurveyComplexItem::refly90DegreesChanged, this, &SurveyComplexItem::_rebuildTransects);
// FIXME: Shouldn't these be in TransectStyleComplexItem? They are also in CorridorScanComplexItem constructur
......@@ -105,11 +110,12 @@ void SurveyComplexItem::save(QJsonArray& planItems)
_save(saveObject);
saveObject[JsonHelper::jsonVersionKey] = 4;
saveObject[JsonHelper::jsonVersionKey] = 5;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
saveObject[_jsonGridAngleKey] = _gridAngleFact.rawValue().toDouble();
saveObject[_jsonFlyAlternateTransectsKey] = _flyAlternateTransectsFact.rawValue().toBool();
saveObject[_jsonSplitConcavePolygonsKey] = _splitConcavePolygonsFact.rawValue().toBool();
saveObject[_jsonEntryPointKey] = _entryPoint;
// Polygon shape
......@@ -129,13 +135,13 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe
}
int version = complexObject[JsonHelper::jsonVersionKey].toInt();
if (version < 2 || version > 4) {
if (version < 2 || version > 5) {
errorString = tr("Survey items do not support version %1").arg(version);
return false;
}
if (version == 4) {
if (!_loadV4(complexObject, sequenceNumber, errorString)) {
if (version == 4 || version == 5) {
if (!_loadV4V5(complexObject, sequenceNumber, errorString, version)) {
return false;
}
} else {
......@@ -158,7 +164,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe
return true;
}
bool SurveyComplexItem::_loadV4(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version)
{
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
......@@ -167,6 +173,12 @@ bool SurveyComplexItem::_loadV4(const QJsonObject& complexObject, int sequenceNu
{ _jsonGridAngleKey, QJsonValue::Double, true },
{ _jsonFlyAlternateTransectsKey, QJsonValue::Bool, false },
};
if(version == 5) {
JsonHelper::KeyValidateInfo jSplitPolygon = { _jsonSplitConcavePolygonsKey, QJsonValue::Bool, true };
keyInfoList.append(jSplitPolygon);
}
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
}
......@@ -195,6 +207,10 @@ bool SurveyComplexItem::_loadV4(const QJsonObject& complexObject, int sequenceNu
_gridAngleFact.setRawValue (complexObject[_jsonGridAngleKey].toDouble());
_flyAlternateTransectsFact.setRawValue (complexObject[_jsonFlyAlternateTransectsKey].toBool(false));
if(version == 5) {
_splitConcavePolygonsFact.setRawValue (complexObject[_jsonSplitConcavePolygonsKey].toBool(true));
}
_entryPoint = complexObject[_jsonEntryPointKey].toInt();
_ignoreRecalc = false;
......@@ -1060,13 +1076,22 @@ bool SurveyComplexItem::_hoverAndCaptureEnabled(void) const
void SurveyComplexItem::_rebuildTransectsPhase1(void)
{
_rebuildTransectsPhase1Worker(false /* refly */);
bool split = splitConcavePolygons()->rawValue().toBool();
if (split) {
_rebuildTransectsPhase1WorkerSplitPolygons(false /* refly */);
} else {
_rebuildTransectsPhase1WorkerSinglePolygon(false /* refly */);
}
if (_refly90DegreesFact.rawValue().toBool()) {
_rebuildTransectsPhase1Worker(true /* refly */);
if (split) {
_rebuildTransectsPhase1WorkerSplitPolygons(true /* refly */);
} else {
_rebuildTransectsPhase1WorkerSinglePolygon(true /* refly */);
}
}
}
void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
void SurveyComplexItem::_rebuildTransectsPhase1WorkerSinglePolygon(bool refly)
{
if (_ignoreRecalc) {
return;
......@@ -1076,7 +1101,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = NULL;
_loadedMissionItemsParent = nullptr;
}
// First pass will clear old transect data, refly will append to existing data
......@@ -1182,9 +1207,418 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
// Convert from NED to Geo
QList<QList<QGeoCoordinate>> transects;
for (const QLineF& line: resultLines) {
for (const QLineF& line : resultLines) {
QGeoCoordinate coord;
QList<QGeoCoordinate> transect;
convertNedToGeo(line.p1().y(), line.p1().x(), 0, tangentOrigin, &coord);
transect.append(coord);
convertNedToGeo(line.p2().y(), line.p2().x(), 0, tangentOrigin, &coord);
transect.append(coord);
transects.append(transect);
}
_adjustTransectsToEntryPointLocation(transects);
if (refly) {
_optimizeTransectsForShortestDistance(_transects.last().last().coord, transects);
}
if (_flyAlternateTransectsFact.rawValue().toBool()) {
QList<QList<QGeoCoordinate>> alternatingTransects;
for (int i=0; i<transects.count(); i++) {
if (!(i & 1)) {
alternatingTransects.append(transects[i]);
}
}
for (int i=transects.count()-1; i>0; i--) {
if (i & 1) {
alternatingTransects.append(transects[i]);
}
}
transects = alternatingTransects;
}
// Adjust to lawnmower pattern
bool reverseVertices = false;
for (int i=0; i<transects.count(); i++) {
// We must reverse the vertices for every other transect in order to make a lawnmower pattern
QList<QGeoCoordinate> transectVertices = transects[i];
if (reverseVertices) {
reverseVertices = false;
QList<QGeoCoordinate> reversedVertices;
for (int j=transectVertices.count()-1; j>=0; j--) {
reversedVertices.append(transectVertices[j]);
}
transectVertices = reversedVertices;
} else {
reverseVertices = true;
}
transects[i] = transectVertices;
}
// Convert to CoordInfo transects and append to _transects
for (const QList<QGeoCoordinate>& transect : transects) {
QGeoCoordinate coord;
QList<TransectStyleComplexItem::CoordInfo_t> coordInfoTransect;
TransectStyleComplexItem::CoordInfo_t coordInfo;
coordInfo = { transect[0], CoordTypeSurveyEdge };
coordInfoTransect.append(coordInfo);
coordInfo = { transect[1], CoordTypeSurveyEdge };
coordInfoTransect.append(coordInfo);
// For hover and capture we need points for each camera location within the transect
if (triggerCamera() && hoverAndCaptureEnabled()) {
double transectLength = transect[0].distanceTo(transect[1]);
double transectAzimuth = transect[0].azimuthTo(transect[1]);
if (triggerDistance() < transectLength) {
int cInnerHoverPoints = static_cast<int>(floor(transectLength / triggerDistance()));
qCDebug(SurveyComplexItemLog) << "cInnerHoverPoints" << cInnerHoverPoints;
for (int i=0; i<cInnerHoverPoints; i++) {
QGeoCoordinate hoverCoord = transect[0].atDistanceAndAzimuth(triggerDistance() * (i + 1), transectAzimuth);
TransectStyleComplexItem::CoordInfo_t coordInfo = { hoverCoord, CoordTypeInteriorHoverTrigger };
coordInfoTransect.insert(1 + i, coordInfo);
}
}
}
// Extend the transect ends for turnaround
if (_hasTurnaround()) {
QGeoCoordinate turnaroundCoord;
double turnAroundDistance = _turnAroundDistanceFact.rawValue().toDouble();
double azimuth = transect[0].azimuthTo(transect[1]);
turnaroundCoord = transect[0].atDistanceAndAzimuth(-turnAroundDistance, azimuth);
turnaroundCoord.setAltitude(qQNaN());
TransectStyleComplexItem::CoordInfo_t coordInfo = { turnaroundCoord, CoordTypeTurnaround };
coordInfoTransect.prepend(coordInfo);
azimuth = transect.last().azimuthTo(transect[transect.count() - 2]);
turnaroundCoord = transect.last().atDistanceAndAzimuth(-turnAroundDistance, azimuth);
turnaroundCoord.setAltitude(qQNaN());
coordInfo = { turnaroundCoord, CoordTypeTurnaround };
coordInfoTransect.append(coordInfo);
}
_transects.append(coordInfoTransect);
}
}
void SurveyComplexItem::_rebuildTransectsPhase1WorkerSplitPolygons(bool refly)
{
if (_ignoreRecalc) {
return;
}
// If the transects are getting rebuilt then any previously loaded mission items are now invalid
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = nullptr;
}
// First pass will clear old transect data, refly will append to existing data
if (!refly) {
_transects.clear();
_transectsPathHeightInfo.clear();
}
if (_surveyAreaPolygon.count() < 3) {
return;
}
// Convert polygon to NED
QList<QPointF> polygonPoints;
QGeoCoordinate tangentOrigin = _surveyAreaPolygon.pathModel().value<QGCQGeoCoordinate*>(0)->coordinate();
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Convert polygon to NED - _surveyAreaPolygon.count():tangentOrigin" << _surveyAreaPolygon.count() << tangentOrigin;
for (int i=0; i<_surveyAreaPolygon.count(); i++) {
double y, x, down;
QGeoCoordinate vertex = _surveyAreaPolygon.pathModel().value<QGCQGeoCoordinate*>(i)->coordinate();
if (i == 0) {
// This avoids a nan calculation that comes out of convertGeoToNed
x = y = 0;
} else {
convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
}
polygonPoints += QPointF(x, y);
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 vertex:x:y" << vertex << polygonPoints.last().x() << polygonPoints.last().y();
}
// convert into QPolygonF
QPolygonF polygon;
for (int i=0; i<polygonPoints.count(); i++) {
qCDebug(SurveyComplexItemLog) << "Vertex" << polygonPoints[i];
polygon << polygonPoints[i];
}
// Create list of separate polygons
QList<QPolygonF> polygons{};
_PolygonDecomposeConvex(polygon, polygons);
// iterate over polygons
for (auto p = polygons.begin(); p != polygons.end(); ++p) {
QPointF* vMatch = nullptr;
// find matching vertex in previous polygon
if (p != polygons.begin()) {
auto pLast = p - 1;
for (auto& i : *p) {
for (auto& j : *pLast) {
if (i == j) {
vMatch = &i;
break;
}
if (vMatch) break;
}
}
}
// close polygon
*p << p->front();
// build transects for this polygon
// TODO figure out tangent origin
// TODO improve selection of entry points
// qCDebug(SurveyComplexItemLog) << "Transects from polynom p " << p;
_rebuildTranscetsFromPolygon(refly, *p, tangentOrigin, vMatch);
}
}
void SurveyComplexItem::_PolygonDecomposeConvex(const QPolygonF& polygon, QList<QPolygonF>& decomposedPolygons)
{
// this follows "Mark Keil's Algorithm" https://mpen.ca/406/keil
int decompSize = std::numeric_limits<int>::max();
if (polygon.size() < 3) return;
if (polygon.size() == 3) {
decomposedPolygons << polygon;
return;
}
QList<QPolygonF> decomposedPolygonsMin{};
for (auto vertex = polygon.begin(); vertex != polygon.end(); ++vertex)
{
// is vertex reflex?
bool vertexIsReflex = _VertexIsReflex(polygon, vertex);
if (!vertexIsReflex) continue;
for (auto vertexOther = polygon.begin(); vertexOther != polygon.end(); ++vertexOther)
{
auto vertexBefore = vertex == polygon.begin() ? polygon.end() - 1 : vertex - 1;
auto vertexAfter = vertex == polygon.end() - 1 ? polygon.begin() : vertex + 1;
if (vertexOther == vertex) continue;
if (vertexAfter == vertexOther) continue;
if (vertexBefore == vertexOther) continue;
bool canSee = _VertexCanSeeOther(polygon, vertex, vertexOther);
if (!canSee) continue;
QPolygonF polyLeft;
auto v = vertex;
auto polyLeftContainsReflex = false;
while ( v != vertexOther) {
if (v != vertex && _VertexIsReflex(polygon, v)) {
polyLeftContainsReflex = true;
}
polyLeft << *v;
++v;
if (v == polygon.end()) v = polygon.begin();
}
polyLeft << *vertexOther;
auto polyLeftValid = !(polyLeftContainsReflex && polyLeft.size() == 3);
QPolygonF polyRight;
v = vertexOther;
auto polyRightContainsReflex = false;
while ( v != vertex) {
if (v != vertex && _VertexIsReflex(polygon, v)) {
polyRightContainsReflex = true;
}
polyRight << *v;
++v;
if (v == polygon.end()) v = polygon.begin();
}
polyRight << *vertex;
auto polyRightValid = !(polyRightContainsReflex && polyRight.size() == 3);
if (!polyLeftValid || ! polyRightValid) {
// decompSize = std::numeric_limits<int>::max();
continue;
}
// recursion
QList<QPolygonF> polyLeftDecomposed{};
_PolygonDecomposeConvex(polyLeft, polyLeftDecomposed);
QList<QPolygonF> polyRightDecomposed{};
_PolygonDecomposeConvex(polyRight, polyRightDecomposed);
// compositon
auto subSize = polyLeftDecomposed.size() + polyRightDecomposed.size();
if ((polyLeftContainsReflex && polyLeftDecomposed.size() == 1)
|| (polyRightContainsReflex && polyRightDecomposed.size() == 1))
{
// don't accept polygons that contian reflex vertices and were not split
subSize = std::numeric_limits<int>::max();
}
if (subSize < decompSize) {
decompSize = subSize;
decomposedPolygonsMin = polyLeftDecomposed + polyRightDecomposed;
}
}
}
// assemble output
if (decomposedPolygonsMin.size() > 0) {
decomposedPolygons << decomposedPolygonsMin;
} else {
decomposedPolygons << polygon;
}
return;
}
bool SurveyComplexItem::_VertexCanSeeOther(const QPolygonF& polygon, const QPointF* vertexA, const QPointF* vertexB) {
if (vertexA == vertexB) return false;
auto vertexAAfter = vertexA + 1 == polygon.end() ? polygon.begin() : vertexA + 1;
auto vertexABefore = vertexA == polygon.begin() ? polygon.end() - 1 : vertexA - 1;
if (vertexAAfter == vertexB) return false;
if (vertexABefore == vertexB) return false;
// qCDebug(SurveyComplexItemLog) << "_VertexCanSeeOther false after first checks ";
bool visible = true;
// auto diff = *vertexA - *vertexB;
QLineF lineAB{*vertexA, *vertexB};
auto distanceAB = lineAB.length();//sqrtf(diff.x() * diff.x() + diff.y()*diff.y());
// qCDebug(SurveyComplexItemLog) << "_VertexCanSeeOther distanceAB " << distanceAB;
for (auto vertexC = polygon.begin(); vertexC != polygon.end(); ++vertexC)
{
if (vertexC == vertexA) continue;
if (vertexC == vertexB) continue;
auto vertexD = vertexC + 1 == polygon.end() ? polygon.begin() : vertexC + 1;
if (vertexD == vertexA) continue;
if (vertexD == vertexB) continue;
QLineF lineCD(*vertexC, *vertexD);
QPointF intersection{};
auto intersects = lineAB.intersect(lineCD, &intersection);
if (intersects == QLineF::IntersectType::BoundedIntersection) {
// auto diffIntersection = *vertexA - intersection;
// auto distanceIntersection = sqrtf(diffIntersection.x() * diffIntersection.x() + diffIntersection.y()*diffIntersection.y());
// qCDebug(SurveyComplexItemLog) << "*vertexA " << *vertexA << "*vertexB " << *vertexB << " intersection " << intersection;
QLineF lineIntersection{*vertexA, intersection};
auto distanceIntersection = lineIntersection.length();//sqrtf(diff.x() * diff.x() + diff.y()*diff.y());
qCDebug(SurveyComplexItemLog) << "_VertexCanSeeOther distanceIntersection " << distanceIntersection;
if (distanceIntersection < distanceAB) {
visible = false;
break;
}
}
}
return visible;
}
bool SurveyComplexItem::_VertexIsReflex(const QPolygonF& polygon, const QPointF* vertex) {
auto vertexBefore = vertex == polygon.begin() ? polygon.end() - 1 : vertex - 1;
auto vertexAfter = vertex == polygon.end() - 1 ? polygon.begin() : vertex + 1;
auto area = (((vertex->x() - vertexBefore->x())*(vertexAfter->y() - vertexBefore->y()))-((vertexAfter->x() - vertexBefore->x())*(vertex->y() - vertexBefore->y())));
return area > 0;
}
void SurveyComplexItem::_rebuildTranscetsFromPolygon(bool refly, const QPolygonF& polygon, const QGeoCoordinate& tangentOrigin, const QPointF* const transitionPoint)
{
// Generate transects
double gridAngle = _gridAngleFact.rawValue().toDouble();
double gridSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
gridAngle = _clampGridAngle90(gridAngle);
gridAngle += refly ? 90 : 0;
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Clamped grid angle" << gridAngle;
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 gridSpacing:gridAngle:refly" << gridSpacing << gridAngle << refly;
// Convert polygon to bounding rect
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Polygon";
QRectF boundingRect = polygon.boundingRect();
QPointF boundingCenter = boundingRect.center();
qCDebug(SurveyComplexItemLog) << "Bounding rect" << boundingRect.topLeft().x() << boundingRect.topLeft().y() << boundingRect.bottomRight().x() << boundingRect.bottomRight().y();
// Create set of rotated parallel lines within the expanded bounding rect. Make the lines larger than the
// bounding box to guarantee intersection.
QList<QLineF> lineList;
// Transects are generated to be as long as the largest width/height of the bounding rect plus some fudge factor.
// This way they will always be guaranteed to intersect with a polygon edge no matter what angle they are rotated to.
// They are initially generated with the transects flowing from west to east and then points within the transect north to south.
double maxWidth = qMax(boundingRect.width(), boundingRect.height()) + 2000.0;
double halfWidth = maxWidth / 2.0;
double transectX = boundingCenter.x() - halfWidth;
double transectXMax = transectX + maxWidth;
while (transectX < transectXMax) {
double transectYTop = boundingCenter.y() - halfWidth;
double transectYBottom = boundingCenter.y() + halfWidth;
lineList += QLineF(_rotatePoint(QPointF(transectX, transectYTop), boundingCenter, gridAngle), _rotatePoint(QPointF(transectX, transectYBottom), boundingCenter, gridAngle));
transectX += gridSpacing;
}
// Now intersect the lines with the polygon
QList<QLineF> intersectLines;
#if 1
_intersectLinesWithPolygon(lineList, polygon, intersectLines);
#else
// This is handy for debugging grid problems, not for release
intersectLines = lineList;
#endif
// Less than two transects intersected with the polygon:
// Create a single transect which goes through the center of the polygon
// Intersect it with the polygon
if (intersectLines.count() < 2) {
_surveyAreaPolygon.center();
QLineF firstLine = lineList.first();
QPointF lineCenter = firstLine.pointAt(0.5);
QPointF centerOffset = boundingCenter - lineCenter;
firstLine.translate(centerOffset);
lineList.clear();
lineList.append(firstLine);
intersectLines = lineList;
_intersectLinesWithPolygon(lineList, polygon, intersectLines);
}
// Make sure all lines are going the same direction. Polygon intersection leads to lines which
// can be in varied directions depending on the order of the intesecting sides.
QList<QLineF> resultLines;
_adjustLineDirection(intersectLines, resultLines);
// Convert from NED to Geo
QList<QList<QGeoCoordinate>> transects;
if (transitionPoint != nullptr) {
QList<QGeoCoordinate> transect;
QGeoCoordinate coord;
convertNedToGeo(transitionPoint->y(), transitionPoint->x(), 0, tangentOrigin, &coord);
transect.append(coord);
transect.append(coord); //TODO
transects.append(transect);
}
for (const QLineF& line: resultLines) {
QList<QGeoCoordinate> transect;
QGeoCoordinate coord;
convertNedToGeo(line.p1().y(), line.p1().x(), 0, tangentOrigin, &coord);
transect.append(coord);
......@@ -1249,7 +1683,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
double transectLength = transect[0].distanceTo(transect[1]);
double transectAzimuth = transect[0].azimuthTo(transect[1]);
if (triggerDistance() < transectLength) {
int cInnerHoverPoints = floor(transectLength / triggerDistance());
int cInnerHoverPoints = static_cast<int>(floor(transectLength / triggerDistance()));
qCDebug(SurveyComplexItemLog) << "cInnerHoverPoints" << cInnerHoverPoints;
for (int i=0; i<cInnerHoverPoints; i++) {
QGeoCoordinate hoverCoord = transect[0].atDistanceAndAzimuth(triggerDistance() * (i + 1), transectAzimuth);
......@@ -1279,6 +1713,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
_transects.append(coordInfoTransect);
}
qCDebug(SurveyComplexItemLog) << "_transects.size() " << _transects.size();
}
void SurveyComplexItem::_rebuildTransectsPhase2(void)
......
......@@ -28,9 +28,11 @@ public:
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* flyAlternateTransects READ flyAlternateTransects CONSTANT)
Q_PROPERTY(Fact* splitConcavePolygons READ splitConcavePolygons CONSTANT)
Fact* gridAngle (void) { return &_gridAngleFact; }
Fact* flyAlternateTransects (void) { return &_flyAlternateTransectsFact; }
Fact* splitConcavePolygons (void) { return &_splitConcavePolygonsFact; }
Q_INVOKABLE void rotateEntryPoint(void);
......@@ -66,6 +68,7 @@ public:
static const char* gridAngleName;
static const char* gridEntryLocationName;
static const char* flyAlternateTransectsName;
static const char* splitConcavePolygonsName;
static const char* jsonV3ComplexItemTypeValue;
......@@ -109,18 +112,29 @@ private:
double _turnaroundDistance(void) const;
bool _hoverAndCaptureEnabled(void) const;
bool _loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString);
bool _loadV4(const QJsonObject& complexObject, int sequenceNumber, QString& errorString);
bool _loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version);
void _rebuildTransectsPhase1Worker(bool refly);
void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly);
void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly);
/// Adds to the _transects array from one polygon
void _rebuildTranscetsFromPolygon(bool refly, const QPolygonF& polygon, const QGeoCoordinate& tangentOrigin, const QPointF* const transitionPoint);
// Decompose polygon into list of convex sub polygons
void _PolygonDecomposeConvex(const QPolygonF& polygon, QList<QPolygonF>& decomposedPolygons);
// return true if vertex a can see vertex b
bool _VertexCanSeeOther(const QPolygonF& polygon, const QPointF* vertexA, const QPointF* vertexB);
bool _VertexIsReflex(const QPolygonF& polygon, const QPointF* vertex);
QMap<QString, FactMetaData*> _metaDataMap;
SettingsFact _gridAngleFact;
SettingsFact _flyAlternateTransectsFact;
SettingsFact _splitConcavePolygonsFact;
int _entryPoint;
static const char* _jsonGridAngleKey;
static const char* _jsonEntryPointKey;
static const char* _jsonFlyAlternateTransectsKey;
static const char* _jsonSplitConcavePolygonsKey;
static const char* _jsonV3GridObjectKey;
static const char* _jsonV3GridAltitudeKey;
......
......@@ -9,6 +9,7 @@ import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
......@@ -119,6 +120,13 @@ Rectangle {
onClicked: missionItem.rotateEntryPoint();
}
FactCheckBox {
text: qsTr("Split concave polygons")
fact: _splitConcave
visible: _splitConcave.visible
property Fact _splitConcave: missionItem.splitConcavePolygons
}
FactCheckBox {
text: qsTr("Hover and capture image")
fact: missionItem.hoverAndCapture
......
......@@ -61,29 +61,29 @@ const char* AppSettings::crashDirectory = "CrashLogs";
AppSettings::AppSettings(QObject* parent)
: SettingsGroup (name, settingsGroup, parent)
, _offlineEditingFirmwareTypeFact (NULL)
, _offlineEditingVehicleTypeFact (NULL)
, _offlineEditingCruiseSpeedFact (NULL)
, _offlineEditingHoverSpeedFact (NULL)
, _offlineEditingAscentSpeedFact (NULL)
, _offlineEditingDescentSpeedFact (NULL)
, _batteryPercentRemainingAnnounceFact (NULL)
, _defaultMissionItemAltitudeFact (NULL)
, _telemetrySaveFact (NULL)
, _telemetrySaveNotArmedFact (NULL)
, _audioMutedFact (NULL)
, _virtualJoystickFact (NULL)
, _appFontPointSizeFact (NULL)
, _indoorPaletteFact (NULL)
, _showLargeCompassFact (NULL)
, _savePathFact (NULL)
, _autoLoadMissionsFact (NULL)
, _useChecklistFact (NULL)
, _mapboxTokenFact (NULL)
, _esriTokenFact (NULL)
, _defaultFirmwareTypeFact (NULL)
, _gstDebugFact (NULL)
, _followTargetFact (NULL)
, _offlineEditingFirmwareTypeFact (nullptr)
, _offlineEditingVehicleTypeFact (nullptr)
, _offlineEditingCruiseSpeedFact (nullptr)
, _offlineEditingHoverSpeedFact (nullptr)
, _offlineEditingAscentSpeedFact (nullptr)
, _offlineEditingDescentSpeedFact (nullptr)
, _batteryPercentRemainingAnnounceFact (nullptr)
, _defaultMissionItemAltitudeFact (nullptr)
, _telemetrySaveFact (nullptr)
, _telemetrySaveNotArmedFact (nullptr)
, _audioMutedFact (nullptr)
, _virtualJoystickFact (nullptr)
, _appFontPointSizeFact (nullptr)
, _indoorPaletteFact (nullptr)
, _showLargeCompassFact (nullptr)
, _savePathFact (nullptr)
, _autoLoadMissionsFact (nullptr)
, _useChecklistFact (nullptr)
, _mapboxTokenFact (nullptr)
, _esriTokenFact (nullptr)
, _defaultFirmwareTypeFact (nullptr)
, _gstDebugFact (nullptr)
, _followTargetFact (nullptr)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<AppSettings>("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only");
......@@ -427,4 +427,3 @@ Fact* AppSettings::followTarget(void)
return _followTargetFact;
}
......@@ -18,7 +18,7 @@ class AppSettings : public SettingsGroup
Q_OBJECT
public:
AppSettings(QObject* parent = NULL);
AppSettings(QObject* parent = nullptr);
Q_PROPERTY(Fact* offlineEditingFirmwareType READ offlineEditingFirmwareType CONSTANT)
Q_PROPERTY(Fact* offlineEditingVehicleType READ offlineEditingVehicleType CONSTANT)
......@@ -87,8 +87,8 @@ public:
QString parameterSavePath (void);
QString telemetrySavePath (void);
QString logSavePath (void);
QString videoSavePath (void);
QString crashSavePath (void);
QString videoSavePath (void);
QString crashSavePath (void);
static MAV_AUTOPILOT offlineEditingFirmwareTypeFromFirmwareType(MAV_AUTOPILOT firmwareType);
static MAV_TYPE offlineEditingVehicleTypeFromVehicleType(MAV_TYPE vehicleType);
......
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