Commit 47641f63 authored by Valentin Platzgummer's avatar Valentin Platzgummer

wima planer edited

parent 1ac83998
......@@ -64,6 +64,7 @@ Rectangle {
GridLayout {
id: generalGrid
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
......@@ -75,7 +76,48 @@ Rectangle {
FactTextField {
fact: missionItem.cameraCalc.distanceToSurface
Layout.fillWidth: true
//onUpdated: rSlider.value = missionItem.deltaR.value
}
QGCCheckBox {
id: relAlt
text: qsTr("Relative altitude")
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain)
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
Layout.fillWidth: true
Layout.columnSpan: 2
Connections {
target: missionItem.cameraCalc
onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
}
}
QGCLabel {
text: qsTr("Type")
Layout.columnSpan: 2
}
property var typeFact: missionItem.type
property int type: typeFact.value
property var names: ["Circular", "Linear"]
ExclusiveGroup{id: typeGroup}
Repeater{
model: missionItem.typeCount
QGCRadioButton {
checked: index === generalGrid.type
text: qsTr(generalGrid.names[index])
onCheckedChanged: {
if (checked){
missionItem.type.value = index
}
checked = Qt.binding(function(){ return index === generalGrid.type})
}
}
}
}
......@@ -92,11 +134,10 @@ Rectangle {
columns: 2
visible: transectsHeader.checked
QGCLabel { text: qsTr("Delta R") }
QGCLabel { text: qsTr("Distance") }
FactTextField {
fact: missionItem.deltaR
fact: missionItem.transectDistance
Layout.fillWidth: true
//onUpdated: rSlider.value = missionItem.deltaR.value
}
/*QGCSlider {
......@@ -113,18 +154,16 @@ Rectangle {
updateValueWhileDragging: true
}*/
QGCLabel { text: qsTr("Delta Alpha") }
QGCLabel { text: qsTr("Alpha") }
FactTextField {
fact: missionItem.deltaAlpha
fact: missionItem.alpha
Layout.fillWidth: true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
}
QGCLabel { text: qsTr("Min. Length") }
FactTextField {
fact: missionItem.transectMinLength
fact: missionItem.minLength
Layout.fillWidth: true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
}
}
......@@ -148,21 +187,6 @@ Rectangle {
Layout.fillWidth: true
}
QGCCheckBox {
id: relAlt
text: qsTr("Relative altitude")
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain)
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
Layout.fillWidth: true
Layout.columnSpan: 2
Connections {
target: missionItem.cameraCalc
onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
}
}
}
......
......@@ -73,7 +73,7 @@ void RoutingWorker::run() {
auto &transectsInfo = pRouteData->transectsInfo;
auto &route = pRouteData->route;
const auto routingStart = std::chrono::high_resolution_clock::now();
const auto maxRoutingTime = std::chrono::minutes(1);
const auto maxRoutingTime = std::chrono::minutes(10);
const auto routingEnd = routingStart + maxRoutingTime;
const auto &restart = this->_restart;
auto stopLambda = [&restart, routingEnd] {
......
#include "CircularSurveyComplexItem.h"
#include "JsonHelper.h"
#include "QGCApplication.h"
#include <chrono>
const char* CircularSurveyComplexItem::settingsGroup = "CircularSurvey";
const char* CircularSurveyComplexItem::deltaRName = "DeltaR";
const char* CircularSurveyComplexItem::deltaAlphaName = "DeltaAlpha";
const char* CircularSurveyComplexItem::transectMinLengthName = "TransectMinLength";
const char* CircularSurveyComplexItem::fixedDirectionName = "FixedDirection";
const char* CircularSurveyComplexItem::reverseName = "Reverse";
const char* CircularSurveyComplexItem::maxWaypointsName = "MaxWaypoints";
const char* CircularSurveyComplexItem::jsonComplexItemTypeValue = "circularSurvey";
const char* CircularSurveyComplexItem::jsonDeltaRKey = "deltaR";
const char* CircularSurveyComplexItem::jsonDeltaAlphaKey = "deltaAlpha";
const char* CircularSurveyComplexItem::jsonTransectMinLengthKey = "transectMinLength";
const char* CircularSurveyComplexItem::jsonfixedDirectionKey = "fixedDirection";
const char* CircularSurveyComplexItem::jsonReverseKey = "reverse";
const char* CircularSurveyComplexItem::jsonReferencePointLatKey = "referencePointLat";
const char* CircularSurveyComplexItem::jsonReferencePointLongKey = "referencePointLong";
const char* CircularSurveyComplexItem::jsonReferencePointAltKey = "referencePointAlt";
CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyView, const QString &kmlOrShpFile, QObject *parent)
: TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
, _referencePoint (QGeoCoordinate(0, 0,0))
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CircularSurvey.SettingsGroup.json"), this))
, _deltaR (settingsGroup, _metaDataMap[deltaRName])
, _deltaAlpha (settingsGroup, _metaDataMap[deltaAlphaName])
, _transectMinLength (settingsGroup, _metaDataMap[transectMinLengthName])
, _fixedDirection (settingsGroup, _metaDataMap[fixedDirectionName])
, _reverse (settingsGroup, _metaDataMap[reverseName])
, _maxWaypoints (settingsGroup, _metaDataMap[maxWaypointsName])
, _isInitialized (false)
, _reverseOnly (false)
{
Q_UNUSED(kmlOrShpFile)
_editorQml = "qrc:/qml/CircularSurveyItemEditor.qml";
connect(&_deltaR, &Fact::valueChanged, this, &CircularSurveyComplexItem::_triggerSlowRecalc);
connect(&_deltaAlpha, &Fact::valueChanged, this, &CircularSurveyComplexItem::_triggerSlowRecalc);
connect(&_transectMinLength, &Fact::valueChanged, this, &CircularSurveyComplexItem::_triggerSlowRecalc);
connect(&_fixedDirection, &Fact::valueChanged, this, &CircularSurveyComplexItem::_triggerSlowRecalc);
connect(&_maxWaypoints, &Fact::valueChanged, this, &CircularSurveyComplexItem::_triggerSlowRecalc);
connect(&_reverse, &Fact::valueChanged, this, &CircularSurveyComplexItem::_reverseTransects);
connect(this, &CircularSurveyComplexItem::refPointChanged, this, &CircularSurveyComplexItem::_triggerSlowRecalc);
//connect(&_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this->)
}
void CircularSurveyComplexItem::resetReference()
{
setRefPoint(_surveyAreaPolygon.center());
}
void CircularSurveyComplexItem::comprehensiveUpdate()
{
_triggerSlowRecalc();
}
void CircularSurveyComplexItem::setRefPoint(const QGeoCoordinate &refPt)
{
if (refPt != _referencePoint){
_referencePoint = refPt;
emit refPointChanged();
}
}
void CircularSurveyComplexItem::setIsInitialized(bool isInitialized)
{
if (isInitialized != _isInitialized) {
_isInitialized = isInitialized;
emit isInitializedChanged();
}
}
QGeoCoordinate CircularSurveyComplexItem::refPoint() const
{
return _referencePoint;
}
Fact *CircularSurveyComplexItem::deltaR()
{
return &_deltaR;
}
Fact *CircularSurveyComplexItem::deltaAlpha()
{
return &_deltaAlpha;
}
bool CircularSurveyComplexItem::isInitialized()
{
return _isInitialized;
}
bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString)
{
// We need to pull version first to determine what validation/conversion needs to be performed
QList<JsonHelper::KeyValidateInfo> versionKeyInfoList = {
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(complexObject, versionKeyInfoList, errorString)) {
return false;
}
int version = complexObject[JsonHelper::jsonVersionKey].toInt();
if (version != 1) {
errorString = tr("Survey items do not support version %1").arg(version);
return false;
}
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
{ ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
{ jsonDeltaRKey, QJsonValue::Double, true },
{ jsonDeltaAlphaKey, QJsonValue::Double, true },
{ jsonTransectMinLengthKey, QJsonValue::Double, true },
{ jsonfixedDirectionKey, QJsonValue::Bool, true },
{ jsonReverseKey, QJsonValue::Bool, true },
{ jsonReferencePointLatKey, QJsonValue::Double, true },
{ jsonReferencePointLongKey, QJsonValue::Double, true },
{ jsonReferencePointAltKey, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
}
QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
return false;
}
_ignoreRecalc = true;
setSequenceNumber(sequenceNumber);
if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
_surveyAreaPolygon.clear();
return false;
}
if (!_load(complexObject, errorString)) {
_ignoreRecalc = false;
return false;
}
_deltaR.setRawValue (complexObject[jsonDeltaRKey].toDouble());
_deltaAlpha.setRawValue (complexObject[jsonDeltaAlphaKey].toDouble());
_transectMinLength.setRawValue (complexObject[jsonTransectMinLengthKey].toDouble());
_referencePoint.setLongitude (complexObject[jsonReferencePointLongKey].toDouble());
_referencePoint.setLatitude (complexObject[jsonReferencePointLatKey].toDouble());
_referencePoint.setAltitude (complexObject[jsonReferencePointAltKey].toDouble());
_fixedDirection.setRawValue (complexObject[jsonfixedDirectionKey].toBool());
_reverse.setRawValue (complexObject[jsonReverseKey].toBool());
setIsInitialized(true);
_ignoreRecalc = false;
_recalcComplexDistance();
if (_cameraShots == 0) {
// Shot count was possibly not available from plan file
_recalcCameraShots();
}
return true;
}
void CircularSurveyComplexItem::save(QJsonArray &planItems)
{
QJsonObject saveObject;
_save(saveObject);
saveObject[JsonHelper::jsonVersionKey] = 1;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
saveObject[jsonDeltaRKey] = _deltaR.rawValue().toDouble();
saveObject[jsonDeltaAlphaKey] = _deltaAlpha.rawValue().toDouble();
saveObject[jsonTransectMinLengthKey] = _transectMinLength.rawValue().toDouble();
saveObject[jsonfixedDirectionKey] = _fixedDirection.rawValue().toBool();
saveObject[jsonReverseKey] = _reverse.rawValue().toBool();
saveObject[jsonReferencePointLongKey] = _referencePoint.longitude();
saveObject[jsonReferencePointLatKey] = _referencePoint.latitude();
saveObject[jsonReferencePointAltKey] = _referencePoint.altitude();
// Polygon shape
_surveyAreaPolygon.saveToJson(saveObject);
planItems.append(saveObject);
}
void CircularSurveyComplexItem::appendMissionItems(QList<MissionItem *> &items, QObject *missionItemParent)
{
if (_transectsDirty)
return;
if (_loadedMissionItems.count()) {
// We have mission items from the loaded plan, use those
_appendLoadedMissionItems(items, missionItemParent);
} else {
// Build the mission items on the fly
_buildAndAppendMissionItems(items, missionItemParent);
}
}
void CircularSurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
//qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems";
if (_transectsDirty)
return;
int seqNum = _sequenceNumber;
for (const MissionItem* loadedMissionItem: _loadedMissionItems) {
MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
item->setSequenceNumber(seqNum++);
items.append(item);
}
}
void CircularSurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
// original code: SurveyComplexItem::_buildAndAppendMissionItems()
//qCDebug(SurveyComplexItemLog) << "_buildAndAppendMissionItems";
// Now build the mission items from the transect points
if (_transectsDirty)
return;
MissionItem* item;
int seqNum = _sequenceNumber;
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative()
? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect : _transects) {
//bool transectEntry = true;
for (const CoordInfo_t& transectCoordInfo: transect) {
item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT,
mavFrame,
0, // Hold time (delay for hover and capture to settle vehicle before image is taken)
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
transectCoordInfo.coord.latitude(),
transectCoordInfo.coord.longitude(),
transectCoordInfo.coord.altitude(),
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
}
}
void CircularSurveyComplexItem::applyNewAltitude(double newAltitude)
{
_cameraCalc.valueSetIsDistance()->setRawValue(true);
_cameraCalc.distanceToSurface()->setRawValue(newAltitude);
_cameraCalc.setDistanceToSurfaceRelative(true);
}
double CircularSurveyComplexItem::timeBetweenShots()
{
return 1;
}
bool CircularSurveyComplexItem::readyForSave() const
{
return TransectStyleComplexItem::readyForSave();
}
double CircularSurveyComplexItem::additionalTimeDelay() const
{
return 0;
}
void CircularSurveyComplexItem::_rebuildTransectsPhase1(void){
if (_doFastRecalc){
_rebuildTransectsFast();
} else {
_rebuildTransectsSlow();
_doFastRecalc = true;
}
}
void CircularSurveyComplexItem::_rebuildTransectsFast()
{
using namespace GeoUtilities;
using namespace PolygonCalculus;
using namespace PlanimetryCalculus;
_transects.clear();
QPolygonF surveyPolygon;
toCartesianList(_surveyAreaPolygon.coordinateList(), _referencePoint, surveyPolygon);
if (!_rebuildTransectsInputCheck(surveyPolygon))
return;
// If the transects are getting rebuilt then any previously loaded mission items are now invalid
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = nullptr;
}
QVector<QVector<QPointF>> transectPath;
if(!_generateTransectPath(transectPath, surveyPolygon))
return;
/// optimize path to snake or zig-zag pattern
bool fixedDirectionBool = _fixedDirection.rawValue().toBool();
QVector<QPointF> currentSection = transectPath.takeFirst();
if ( currentSection.isEmpty() )
return;
QVector<QPointF> optiPath; // optimized path
while( !transectPath.empty() ) {
optiPath.append(currentSection);
QPointF endVertex = currentSection.last();
double minDist = std::numeric_limits<double>::infinity();
int index = 0;
bool reversePath = false;
// iterate over all paths in fullPath and assign the one with the shortest distance to endVertex to currentSection
for (int i = 0; i < transectPath.size(); i++) {
auto iteratorPath = transectPath[i];
double dist = PlanimetryCalculus::distance(endVertex, iteratorPath.first());
if ( dist < minDist ) {
minDist = dist;
index = i;
reversePath = false;
}
dist = PlanimetryCalculus::distance(endVertex, iteratorPath.last());
if (dist < minDist) {
minDist = dist;
index = i;
reversePath = true;
}
}
currentSection = transectPath.takeAt(index);
if (reversePath && !fixedDirectionBool) {
PolygonCalculus::reversePath(currentSection);
}
}
optiPath.append(currentSection); // append last section
if (optiPath.size() > _maxWaypoints.rawValue().toInt())
return;
_rebuildTransectsToGeo(optiPath, _referencePoint);
_transectsDirty = true;
}
void CircularSurveyComplexItem::_rebuildTransectsSlow()
{
using namespace GeoUtilities;
using namespace PolygonCalculus;
using namespace PlanimetryCalculus;
if (_reverseOnly) { // reverse transects and return
_reverseOnly = false;
QList<QList<CoordInfo_t>> transectsReverse;
transectsReverse.reserve(_transects.size());
for (auto list : _transects) {
QList<CoordInfo_t> listReverse;
for (auto coordinate : list)
listReverse.prepend(coordinate);
transectsReverse.prepend(listReverse);
}
_transects = transectsReverse;
return;
}
_transects.clear();
QPolygonF surveyPolygon;
toCartesianList(_surveyAreaPolygon.coordinateList(), _referencePoint, surveyPolygon);
if (!_rebuildTransectsInputCheck(surveyPolygon))
return;
// If the transects are getting rebuilt then any previously loaded mission items are now invalid.
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = nullptr;
}
QVector<QVector<QPointF>> transectPath;
if(!_generateTransectPath(transectPath, surveyPolygon))
return;
// optimize path to snake or zig-zag pattern
const bool fixedDirectionBool = _fixedDirection.rawValue().toBool();
QVector<QPointF> currentSection = transectPath.takeFirst(); if ( currentSection.isEmpty() ) return;
QVector<QPointF> optimizedPath(currentSection);
bool reversePath = true; // controlls if currentSection gets reversed, has nothing todo with _reverseOnly
while( !transectPath.empty() ) {
QPointF endVertex = currentSection.last();
double minDist = std::numeric_limits<double>::infinity();
int index = 0;
// iterate over all paths in fullPath and assign the one with the shortest distance to endVertex to currentSection
QVector<QPointF> connectorPath;
for (int i = 0; i < transectPath.size(); i++) {
QVector<QPointF> iteratorPath = transectPath[i];
QVector<QPointF> tempConnectorPath;
bool retVal;
if (reversePath && !fixedDirectionBool) {
retVal = PolygonCalculus::shortestPath(surveyPolygon, endVertex, iteratorPath.last(), tempConnectorPath);
} else {
retVal = PolygonCalculus::shortestPath(surveyPolygon, endVertex, iteratorPath.first(), tempConnectorPath);
}
if (!retVal)
qWarning("CircularSurveyComplexItem::_rebuildTransectsPhase1: internal error; false shortestPath");
double dist = 0;
for (int i = 0; i < tempConnectorPath.size()-1; ++i)
dist += PlanimetryCalculus::distance(tempConnectorPath[i], tempConnectorPath[i+1]);
if (dist < minDist) {
minDist = dist;
index = i;
connectorPath = tempConnectorPath;
}
}
currentSection = transectPath.takeAt(index);
if (reversePath && !fixedDirectionBool) {
PolygonCalculus::reversePath(currentSection);
}
reversePath ^= true; // toggle
connectorPath.pop_front();
connectorPath.pop_back();
if (connectorPath.size() > 0)
optimizedPath.append(connectorPath);
optimizedPath.append(currentSection);
}
if (optimizedPath.size() > _maxWaypoints.rawValue().toInt())
return;
_rebuildTransectsToGeo(optimizedPath, _referencePoint);
_transectsDirty = false;
//_triggerSlowRecalcTimer.stop(); // stop any pending slow recalculations
return;
}
void CircularSurveyComplexItem::_triggerSlowRecalc()
{
_doFastRecalc = false;
_rebuildTransects();
}
void CircularSurveyComplexItem::_recalcComplexDistance()
{
_complexDistance = 0;
if (_transectsDirty)
return;
for (int i=0; i<_visualTransectPoints.count() - 1; i++) {
_complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
}
emit complexDistanceChanged();
}
// no cameraShots in Circular Survey, add if desired
void CircularSurveyComplexItem::_recalcCameraShots()
{
_cameraShots = 0;
}
void CircularSurveyComplexItem::_reverseTransects()
{
_reverseOnly = true;
_triggerSlowRecalc();
}
bool CircularSurveyComplexItem::_shortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QVector<QGeoCoordinate> &shortestPath)
{
using namespace GeoUtilities;
using namespace PolygonCalculus;
QPolygonF polygon2D;
toCartesianList(this->surveyAreaPolygon()->coordinateList(), /*origin*/ start, polygon2D);
QPointF start2D(0,0);
QPointF end2D;
toCartesian(destination, start, end2D);
QVector<QPointF> path2D;
bool retVal = PolygonCalculus::shortestPath(polygon2D, start2D, end2D, path2D);
if (retVal)
toGeoList(path2D, /*origin*/ start, shortestPath);
return retVal;
}
bool CircularSurveyComplexItem::_generateTransectPath(QVector<QVector<QPointF> > &transectPath, const QPolygonF &surveyPolygon)
{
using namespace PlanimetryCalculus;
QVector<double> distances;
for (const QPointF &p : surveyPolygon) distances.append(norm(p));
// fetch input data
double dalpha = _deltaAlpha.rawValue().toDouble()/180.0*M_PI; // angle discretisation of circles
double dr = _deltaR.rawValue().toDouble(); // distance between circles
double lmin = _transectMinLength.rawValue().toDouble(); // minimal transect length
double r_min = dr; // minimal circle radius
double r_max = (*std::max_element(distances.begin(), distances.end())); // maximal circle radius
unsigned int maxWaypoints = _maxWaypoints.rawValue().toUInt();
QPointF origin(0, 0);
IntersectType type;
bool originInside = true;
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_min;
while ( r < r_max) {
Circle circle(r, origin);
if (intersects(circle, surveyPolygon)) {
r_min = r;
break;
}
r += dr;
}
originInside = false;
}
double r = r_min;
unsigned int waypointCounter = 0;
while (r < r_max) {
Circle circle(r, origin);
QVector<QPointFVector> intersectPoints;
QVector<IntersectType> typeList;
QVector<QPair<int, int>> neighbourList;
if (intersects(circle, surveyPolygon, intersectPoints, neighbourList, typeList)) {
// intersection Points between circle and polygon, entering polygon
// when walking in counterclockwise direction along circle
QVector<QPointF> entryPoints;
// intersection Points between circle and polygon, leaving polygon
// when walking in counterclockwise direction along circle
QVector<QPointF> exitPoints;
// determine entryPoints and exit Points
for (int j = 0; j < intersectPoints.size(); j++) {
QVector<QPointF> intersects = intersectPoints[j]; // one pt = tangent, two pt = sekant
QPointF p1 = surveyPolygon[neighbourList[j].first];
QPointF p2 = surveyPolygon[neighbourList[j].second];
QLineF intersetLine(p1, p2);
double lineAngle = angle(intersetLine);
for (QPointF ipt : intersects) {
double circleTangentAngle = angle(ipt)+M_PI_2;
if ( !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle))
&& !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI) ))
{
if (truncateAngle(circleTangentAngle - lineAngle) > M_PI) {
entryPoints.append(ipt);
} else {
exitPoints.append(ipt);
}
}
}
}
// sort
std::sort(entryPoints.begin(), entryPoints.end(), [](QPointF p1, QPointF p2) {
return angle(p1) < angle(p2);
});
std::sort(exitPoints.begin(), exitPoints.end(), [](QPointF p1, QPointF p2) {
return angle(p1) < angle(p2);
});