diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 64a35ef4f7613ddcf059457a09bc2d5f21e0bb72..ba496589697f2ec2212d1228bbba7b1e1048ece9 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -416,7 +416,6 @@ INCLUDEPATH += \
src/QtLocationPlugin \
src/QtLocationPlugin/QMLControl \
src/Settings \
- src/Wima/Snake \
src/Wima \
src/Terrain \
src/Vehicle \
@@ -447,74 +446,58 @@ contains (DEFINES, QGC_ENABLE_PAIRING) {
HEADERS += \
src/QmlControls/QmlUnitsConversion.h \
src/Vehicle/VehicleEscStatusFactGroup.h \
- src/Wima/CircularSurvey.h \
- src/Wima/GenericSingelton.h \
- src/Wima/Geometry/GenericCircle.h \
- src/Wima/RoutingThread.h \
- src/Wima/Snake/CircularGenerator.h \
- src/Wima/Snake/GeneratorBase.h \
- src/Wima/Snake/LinearGenerator.h \
- src/Wima/Snake/clipper/clipper.hpp \
- src/Wima/Snake/mapbox/feature.hpp \
- src/Wima/Snake/mapbox/geometry.hpp \
- src/Wima/Snake/mapbox/geometry/box.hpp \
- src/Wima/Snake/mapbox/geometry/empty.hpp \
- src/Wima/Snake/mapbox/geometry/envelope.hpp \
- src/Wima/Snake/mapbox/geometry/for_each_point.hpp \
- src/Wima/Snake/mapbox/geometry/geometry.hpp \
- src/Wima/Snake/mapbox/geometry/line_string.hpp \
- src/Wima/Snake/mapbox/geometry/multi_line_string.hpp \
- src/Wima/Snake/mapbox/geometry/multi_point.hpp \
- src/Wima/Snake/mapbox/geometry/multi_polygon.hpp \
- src/Wima/Snake/mapbox/geometry/point.hpp \
- src/Wima/Snake/mapbox/geometry/point_arithmetic.hpp \
- src/Wima/Snake/mapbox/geometry/polygon.hpp \
- src/Wima/Snake/mapbox/geometry_io.hpp \
- src/Wima/Snake/mapbox/optional.hpp \
- src/Wima/Snake/mapbox/polylabel.hpp \
- src/Wima/Snake/mapbox/recursive_wrapper.hpp \
- src/Wima/Snake/mapbox/variant.hpp \
- src/Wima/Snake/mapbox/variant_io.hpp \
- src/Wima/Snake/snake.h \
- src/Wima/Geometry/GenericPolygon.h \
- src/Wima/Geometry/GenericPolygonArray.h \
- src/Wima/Geometry/GeoPoint3D.h \
- src/Wima/Snake/NemoInterface.h \
- src/Wima/Snake/QNemoHeartbeat.h \
- src/Wima/Snake/QNemoProgress.h \
- src/Wima/Snake/QNemoProgress.h \
- src/Wima/Snake/SnakeTile.h \
- src/Wima/Snake/SnakeTileLocal.h \
- src/Wima/Snake/SnakeTiles.h \
- src/Wima/Snake/SnakeTilesLocal.h \
- src/Wima/Utils.h \
- src/Wima/WimaBridge.h \
- src/Wima/WimaStateMachine.h \
- src/Wima/call_once.h \
+ src/RouteMissionItem/RouteComplexItem.h \
+ src/RouteMissionItem/GenericSingelton.h \
+ src/RouteMissionItem/geometry/GenericCircle.h \
+ src/RouteMissionItem/RoutingThread.h \
+ src/RouteMissionItem/CircularGenerator.h \
+ src/RouteMissionItem/GeneratorBase.h \
+ src/RouteMissionItem/LinearGenerator.h \
+ src/RouteMissionItem/geometry/clipper/clipper.hpp \
+ src/RouteMissionItem/geometry/mapbox/feature.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/box.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/empty.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/envelope.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/for_each_point.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/geometry.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/line_string.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/multi_line_string.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/multi_point.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/multi_polygon.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/point.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/point_arithmetic.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry/polygon.hpp \
+ src/RouteMissionItem/geometry/mapbox/geometry_io.hpp \
+ src/RouteMissionItem/geometry/mapbox/optional.hpp \
+ src/RouteMissionItem/geometry/mapbox/polylabel.hpp \
+ src/RouteMissionItem/geometry/mapbox/recursive_wrapper.hpp \
+ src/RouteMissionItem/geometry/mapbox/variant.hpp \
+ src/RouteMissionItem/geometry/mapbox/variant_io.hpp \
+ src/RouteMissionItem/geometry/snake.h \
+ src/RouteMissionItem/geometry/GenericPolygon.h \
+ src/RouteMissionItem/geometry/GenericPolygonArray.h \
+ src/RouteMissionItem/geometry/GeoPoint3D.h \
+ src/RouteMissionItem/NemoInterface.h \
+ src/RouteMissionItem/nemo_interface/QNemoHeartbeat.h \
+ src/RouteMissionItem/nemo_interface/QNemoProgress.h \
+ src/RouteMissionItem/nemo_interface/QNemoProgress.h \
+ src/RouteMissionItem/nemo_interface/SnakeTile.h \
+ src/RouteMissionItem/nemo_interface/SnakeTileLocal.h \
+ src/RouteMissionItem/nemo_interface/SnakeTiles.h \
+ src/RouteMissionItem/nemo_interface/SnakeTilesLocal.h \
+ src/RouteMissionItem/call_once.h \
src/api/QGCCorePlugin.h \
src/api/QGCOptions.h \
src/api/QGCSettings.h \
src/api/QmlComponentInfo.h \
src/GPS/Drivers/src/base_station.h \
- src/Wima/Geometry/WimaArea.h \
- src/Wima/Geometry/WimaServiceArea.h \
- src/Wima/Geometry/WimaTrackerPolyline.h \
- src/Wima/WimaPlaner.h \
- src/Wima/Geometry/WimaMeasurementArea.h \
- src/Wima/Geometry/WimaCorridor.h \
- src/Wima/Geometry/WimaAreaData.h \
- src/Wima/Geometry/WimaServiceAreaData.h \
- src/Wima/Geometry/WimaCorridorData.h \
- src/Wima/Geometry/WimaMeasurementAreaData.h \
- src/Wima/WimaPlanData.h \
- src/Wima/Geometry/WimaJoinedArea.h \
- src/Wima/Geometry/WimaJoinedAreaData.h \
- src/Wima/Geometry/PlanimetryCalculus.h \
- src/Wima/Geometry/PolygonCalculus.h \
- src/Wima/OptimisationTools.h \
- src/Wima/Geometry/GeoUtilities.h \
- src/Wima/Geometry/TestPolygonCalculus.h \
- src/Wima/Geometry/testplanimetrycalculus.h \
+ src/RouteMissionItem/geometry/WimaArea.h \
+ src/RouteMissionItem/geometry/WimaServiceArea.h \
+ src/RouteMissionItem/geometry/WimaMeasurementArea.h \
+ src/RouteMissionItem/geometry/PlanimetryCalculus.h \
+ src/RouteMissionItem/geometry/PolygonCalculus.h \
+ src/RouteMissionItem/OptimisationTools.h \
src/Settings/WimaSettings.h \
src/comm/ros_bridge/include/RosBridgeClient.h \
src/comm/ros_bridge/include/com_private.h \
@@ -540,25 +523,23 @@ contains (DEFINES, QGC_ENABLE_PAIRING) {
SOURCES += \
src/Vehicle/VehicleEscStatusFactGroup.cc \
- src/Wima/WimaStateMachine.cpp \
+ src/RouteMissionItem/AreaData.cc \
src/api/QGCCorePlugin.cc \
src/api/QGCOptions.cc \
src/api/QGCSettings.cc \
src/api/QmlComponentInfo.cc \
- src/Wima/CircularSurvey.cc \
- src/Wima/GenericSingelton.cpp \
- src/Wima/RoutingThread.cpp \
- src/Wima/Snake/CircularGenerator.cpp \
- src/Wima/Snake/GeneratorBase.cc \
- src/Wima/Snake/LinearGenerator.cpp \
- src/Wima/Snake/clipper/clipper.cpp \
- src/Wima/Snake/snake.cpp \
- src/Wima/Geometry/GeoPoint3D.cpp \
- src/Wima/Snake/NemoInterface.cpp \
- src/Wima/Snake/QNemoProgress.cc \
- src/Wima/Snake/SnakeTile.cpp \
- src/Wima/Utils.cpp \
- src/Wima/WimaBridge.cc \
+ src/RouteMissionItem/RouteComplexItem.cc \
+ src/RouteMissionItem/GenericSingelton.cpp \
+ src/RouteMissionItem/RoutingThread.cpp \
+ src/RouteMissionItem/CircularGenerator.cpp \
+ src/RouteMissionItem/GeneratorBase.cc \
+ src/RouteMissionItem/LinearGenerator.cpp \
+ src/RouteMissionItem/geometry/clipper/clipper.cpp \
+ src/RouteMissionItem/geometry/snake.cpp \
+ src/RouteMissionItem/geometry/GeoPoint3D.cpp \
+ src/RouteMissionItem/NemoInterface.cpp \
+ src/RouteMissionItem/nemo_interface/QNemoProgress.cc \
+ src/RouteMissionItem/nemo_interface/SnakeTile.cpp \
src/comm/ros_bridge/include/RosBridgeClient.cpp \
src/comm/ros_bridge/include/com_private.cpp \
src/comm/ros_bridge/include/messages/geographic_msgs/geopoint.cpp \
@@ -573,25 +554,12 @@ SOURCES += \
src/comm/ros_bridge/include/server.cpp \
src/comm/ros_bridge/include/topic_publisher.cpp \
src/comm/ros_bridge/include/topic_subscriber.cpp \
- src/Wima/Geometry/WimaArea.cc \
- src/Wima/Geometry/WimaServiceArea.cc \
- src/Wima/Geometry/WimaTrackerPolyline.cc \
- src/Wima/WimaPlaner.cc \
- src/Wima/Geometry/WimaMeasurementArea.cc \
- src/Wima/Geometry/WimaCorridor.cc \
- src/Wima/Geometry/WimaAreaData.cc \
- src/Wima/Geometry/WimaServiceAreaData.cc \
- src/Wima/Geometry/WimaCorridorData.cpp \
- src/Wima/WimaPlanData.cc \
- src/Wima/Geometry/WimaMeasurementAreaData.cc \
- src/Wima/Geometry/WimaJoinedArea.cc \
- src/Wima/Geometry/WimaJoinedAreaData.cc \
- src/Wima/Geometry/PlanimetryCalculus.cc \
- src/Wima/OptimisationTools.cc \
- src/Wima/Geometry/GeoUtilities.cc \
- src/Wima/Geometry/PolygonCalculus.cc \
- src/Wima/Geometry/TestPolygonCalculus.cpp \
- src/Wima/Geometry/testplanimetrycalculus.cpp \
+ src/RouteMissionItem/geometry/WimaArea.cc \
+ src/RouteMissionItem/geometry/WimaServiceArea.cc \
+ src/RouteMissionItem/geometry/WimaMeasurementArea.cc \
+ src/RouteMissionItem/geometry/PlanimetryCalculus.cc \
+ src/RouteMissionItem/OptimisationTools.cc \
+ src/RouteMissionItem/geometry/PolygonCalculus.cc \
src/Settings/WimaSettings.cc \
src/comm/ros_bridge/src/ros_bridge.cpp
@@ -1586,9 +1554,4 @@ contains (CONFIG, QGC_DISABLE_INSTALLER_SETUP) {
}
DISTFILES += \
- src/Wima/Routing/json/CircularGenerator.SettingsGroup.json \
- src/Wima/Snake/json/LinearGenerator.SettingsGroup.json \
- src/Wima/json/CircularSurvey.SettingsGroup.json \
- src/WimaView/WimaMeasurementAreaEditor.qml \
- src/Settings/Wima.SettingsGroup.json \
src/QmlControls/QGroundControl/Specific/qmldir
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 0ffb5bcccece4e31e9db2293fc18fd682484bf5b..9b4e3f387b2ab5c0ef272fc5f841f0350124bea9 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -289,7 +289,6 @@
src/WimaView/WimaServiceAreaEditor.qml
src/WimaView/WimaServiceAreaMapVisual.qml
src/WimaView/WimaToolBar.qml
- src/WimaView/WimaView.qml
src/VehicleSetup/SetupParameterEditor.qml
src/VehicleSetup/SetupView.qml
src/PlanView/SimpleItemEditor.qml
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index 3b78dcbd6b1488b7e674cfd8bc983b5d0716c5f7..b084c5bcdc4c16881dabf83c9b5741bedca7e2ae 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -112,8 +112,6 @@
#include "Wima/Snake/CircularGenerator.h"
#include "Wima/Snake/LinearGenerator.h"
#include "Wima/Snake/NemoInterface.h"
-#include "Wima/WimaController.h"
-#include "Wima/WimaPlaner.h"
#if defined(QGC_ENABLE_PAIRING)
#include "PairingManager.h"
@@ -596,8 +594,6 @@ void QGCApplication::_initCommon()
#endif
// Wima
- qmlRegisterType("Wima", 1, 0, "WimaController");
- qmlRegisterType("Wima", 1, 0, "WimaPlaner");
qmlRegisterType("Wima", 1, 0, "NemoInterface");
qmlRegisterInterface("GeneratorBase");
qmlRegisterType("Wima", 1, 0,
diff --git a/src/QmlControls/FlightPathSegment.h b/src/QmlControls/FlightPathSegment.h
index 1eb0797ff73bea9a6bc0b44b93d61d4e0e065353..638bdd4e1abcae67cb3ce1f3632e6f627e2160d8 100644
--- a/src/QmlControls/FlightPathSegment.h
+++ b/src/QmlControls/FlightPathSegment.h
@@ -35,7 +35,7 @@ public:
Q_PROPERTY(double distanceBetween MEMBER _distanceBetween NOTIFY distanceBetweenChanged)
Q_PROPERTY(double finalDistanceBetween MEMBER _finalDistanceBetween NOTIFY finalDistanceBetweenChanged)
Q_PROPERTY(double totalDistance MEMBER _totalDistance NOTIFY totalDistanceChanged)
- Q_PROPERTY(bool terrainCollision MEMBER _terrainCollision NOTIFY terrainCollisionChanged);
+ Q_PROPERTY(bool terrainCollision MEMBER _terrainCollision NOTIFY terrainCollisionChanged)
QGeoCoordinate coordinate1 (void) const { return _coord1; }
QGeoCoordinate coordinate2 (void) const { return _coord2; }
diff --git a/src/Wima/.directory b/src/Wima/.directory
deleted file mode 100644
index fb64c37e492746510948a33681efb302a4e63cac..0000000000000000000000000000000000000000
--- a/src/Wima/.directory
+++ /dev/null
@@ -1,4 +0,0 @@
-[Dolphin]
-Timestamp=2020,7,8,11,13,28
-Version=4
-ViewMode=1
diff --git a/src/Wima/CircularSurvey.cc b/src/Wima/CircularSurvey.cc
deleted file mode 100644
index c5c2ffc2cf17d91e182e7d6ba935af1699590684..0000000000000000000000000000000000000000
--- a/src/Wima/CircularSurvey.cc
+++ /dev/null
@@ -1,646 +0,0 @@
-#include "CircularSurvey.h"
-#include "RoutingThread.h"
-// QGC
-#include "JsonHelper.h"
-#include "QGCApplication.h"
-#include "QGCLoggingCategory.h"
-// Wima
-#include "snake.h"
-#define CLIPPER_SCALE 1000000
-#include "clipper/clipper.hpp"
-
-#include "Geometry/GenericCircle.h"
-#include "Snake/SnakeTile.h"
-
-// boost
-#include
-#include
-
-#include "CircularGenerator.h"
-#include "LinearGenerator.h"
-
-// ToDo: Check what happened to _transectsDirty
-
-QGC_LOGGING_CATEGORY(CircularSurveyLog, "CircularSurveyLog")
-
-template
-constexpr typename std::underlying_type::type integral(T value) {
- return static_cast::type>(value);
-}
-
-const char *CircularSurvey::settingsGroup = "CircularSurvey";
-const char *CircularSurvey::jsonComplexItemTypeValue = "CircularSurvey";
-const char *CircularSurvey::variantName = "Variant";
-const QString CircularSurvey::name(tr("Circular Survey"));
-
-CircularSurvey::CircularSurvey(PlanMasterController *masterController,
- bool flyView, const QString &kmlOrShpFile,
- QObject *parent)
- : TransectStyleComplexItem(masterController, flyView, settingsGroup,
- parent),
- _state(STATE::IDLE),
- _metaDataMap(FactMetaData::createMapFromJsonFile(
- QStringLiteral(":/json/CircularSurvey.SettingsGroup.json"), this)),
- _variant(settingsGroup, _metaDataMap[variantName]),
- _areaData(std::make_shared()),
- _pWorker(std::make_unique()) {
-
- Q_UNUSED(kmlOrShpFile)
- _editorQml = "qrc:/qml/CircularSurveyItemEditor.qml";
-
- // Connect facts.
- connect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
-
- // Connect worker.
- connect(this->_pWorker.get(), &RoutingThread::result, this,
- &CircularSurvey::_setTransects);
- connect(this->_pWorker.get(), &RoutingThread::calculatingChanged, this,
- &CircularSurvey::calculatingChanged);
-
- // Register Generators.
- auto lg = std::make_shared(this->_areaData);
- registerGenerator(lg->name(), lg);
- auto cg = std::make_shared(this->_areaData);
- registerGenerator(cg->name(), cg);
-}
-
-CircularSurvey::~CircularSurvey() {}
-
-void CircularSurvey::reverse() {
- this->_setState(STATE::REVERT_PATH);
- this->_rebuildTransects();
-}
-
-void CircularSurvey::setPlanData(const AreaData &d) {
- *this->_areaData = d;
-}
-
-const AreaData &CircularSurvey::planData() const {
- return *this->_areaData;
-}
-
-AreaData &CircularSurvey::planData() { return *this->_areaData; }
-
-QStringList CircularSurvey::variantNames() const { return _variantNames; }
-
-bool CircularSurvey::load(const QJsonObject &complexObject, int sequenceNumber,
- QString &errorString) {
- // We need to pull version first to determine what validation/conversion
- // needs to be performed
- QList 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 keyInfoList = {
- {VisualMissionItem::jsonTypeKey, QJsonValue::String, true},
- {ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true},
- {variantName, QJsonValue::Double, false},
- };
-
- 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, sequenceNumber, errorString)) {
- _ignoreRecalc = false;
- return false;
- }
-
- _variant.setRawValue(complexObject[variantName].toInt());
-
- _ignoreRecalc = false;
-
- if (_cameraShots == 0) {
- // Shot count was possibly not available from plan file
- _recalcCameraShots();
- }
-
- return true;
-}
-
-QString CircularSurvey::mapVisualQML() const {
- return QStringLiteral("CircularSurveyMapVisual.qml");
-}
-
-void CircularSurvey::save(QJsonArray &planItems) {
- QJsonObject saveObject;
-
- _save(saveObject);
-
- saveObject[JsonHelper::jsonVersionKey] = 1;
- saveObject[VisualMissionItem::jsonTypeKey] =
- VisualMissionItem::jsonTypeComplexItemValue;
- saveObject[ComplexMissionItem::jsonComplexItemTypeKey] =
- jsonComplexItemTypeValue;
-
- saveObject[variantName] = double(_variant.rawValue().toUInt());
-
- // Polygon shape
- _surveyAreaPolygon.saveToJson(saveObject);
-
- planItems.append(saveObject);
-}
-
-bool CircularSurvey::specifiesCoordinate() const {
- return _transects.count() > 0 ? _transects.first().count() > 0 : false;
-}
-
-bool CircularSurvey::_switchToGenerator(
- const CircularSurvey::PtrGenerator &newG) {
- if (this->_pGenerator != newG) {
- if (this->_pGenerator != nullptr) {
- disconnect(this->_pGenerator.get(),
- &routing::GeneratorBase::generatorChanged, this,
- &CircularSurvey::_rebuildTransects);
- }
-
- this->_pGenerator = newG;
- connect(this->_pGenerator.get(), &routing::GeneratorBase::generatorChanged,
- this, &CircularSurvey::_rebuildTransects);
- emit generatorChanged();
-
- this->_setState(STATE::IDLE);
- _rebuildTransects();
-
- return true;
- } else {
- return false;
- }
-}
-
-void CircularSurvey::_setState(CircularSurvey::STATE state) {
- if (this->_state != state) {
- auto oldState = this->_state;
- this->_state = state;
- if (_calculating(oldState) != _calculating(state)) {
- emit calculatingChanged();
- }
- }
-}
-
-bool CircularSurvey::_calculating(CircularSurvey::STATE state) const {
- return state == STATE::ROUTING;
-}
-
-void CircularSurvey::_changeVariant() {
- this->_setState(STATE::CHANGE_VARIANT);
- this->_rebuildTransects();
-}
-
-bool CircularSurvey::_updateWorker() {
- // Reset data.
- this->_transects.clear();
- this->_variantVector.clear();
- this->_variantNames.clear();
- emit variantNamesChanged();
-
- if (this->_areaData->isValid()) {
-
- // Prepare data.
- auto origin = this->_areaData->origin();
- origin.setAltitude(0);
- if (!origin.isValid()) {
- qCDebug(CircularSurveyLog)
- << "_updateWorker(): origin invalid." << origin;
- return false;
- }
-
- // Convert safe area.
- auto geoSafeArea = this->_areaData->joinedArea().coordinateList();
- if (!(geoSafeArea.size() >= 3)) {
- qCDebug(CircularSurveyLog)
- << "_updateWorker(): safe area invalid." << geoSafeArea;
- return false;
- }
- for (auto &v : geoSafeArea) {
- if (v.isValid()) {
- v.setAltitude(0);
- } else {
- qCDebug(CircularSurveyLog)
- << "_updateWorker(): safe area contains invalid coordinate."
- << geoSafeArea;
- return false;
- }
- }
-
- // Routing par.
- RoutingParameter par;
- par.numSolutions = 5;
- auto &safeAreaENU = par.safeArea;
- snake::areaToEnu(origin, geoSafeArea, safeAreaENU);
-
- // Create generator.
- if (this->_pGenerator) {
- routing::GeneratorBase::Generator g; // Transect generator.
- if (this->_pGenerator->get(g)) {
- // Start/Restart routing worker.
- this->_pWorker->route(par, g);
- return true;
- } else {
- qCDebug(CircularSurveyLog)
- << "_updateWorker(): generator creation failed.";
- return false;
- }
- } else {
- qCDebug(CircularSurveyLog)
- << "_updateWorker(): pGenerator == nullptr, number of registered "
- "generators: "
- << this->_generatorList.size();
- return false;
- }
- } else {
- qCDebug(CircularSurveyLog) << "_updateWorker(): plan data invalid.";
- return false;
- }
-}
-
-void CircularSurvey::_changeVariantWorker() {
- auto variant = this->_variant.rawValue().toUInt();
-
- // Find old variant and run. Old run corresponts with empty list.
- std::size_t old_variant = std::numeric_limits::max();
- for (std::size_t i = 0; i < std::size_t(this->_variantVector.size()); ++i) {
- const auto &variantCoordinates = this->_variantVector.at(i);
- if (variantCoordinates.isEmpty()) {
- old_variant = i;
- break;
- }
- }
-
- // Swap route.
- if (variant != old_variant) {
- // Swap in new variant.
- if (variant < std::size_t(this->_variantVector.size())) {
- if (old_variant != std::numeric_limits::max()) {
- // this->_transects containes a route, swap it back to
- // this->_solutionVector
- auto &oldVariantCoordinates = this->_variantVector[old_variant];
- oldVariantCoordinates.swap(this->_transects);
- }
- auto &newVariantCoordinates = this->_variantVector[variant];
- this->_transects.swap(newVariantCoordinates);
-
- } else { // error
- qCDebug(CircularSurveyLog)
- << "Variant out of bounds (variant =" << variant << ").";
- qCDebug(CircularSurveyLog) << "Resetting variant to zero.";
-
- disconnect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
- this->_variant.setCookedValue(QVariant(0));
- connect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
-
- if (this->_variantVector.size() > 0) {
- this->_changeVariantWorker();
- }
- }
- }
-}
-
-void CircularSurvey::_reverseWorker() {
- if (this->_transects.size() > 0) {
- auto &t = this->_transects.front();
- std::reverse(t.begin(), t.end());
- }
-}
-
-double CircularSurvey::timeBetweenShots() { return 0; }
-
-QString CircularSurvey::commandDescription() const {
- return tr("Circular Survey");
-}
-
-QString CircularSurvey::commandName() const { return tr("Circular Survey"); }
-
-QString CircularSurvey::abbreviation() const { return tr("C.S."); }
-
-TransectStyleComplexItem::ReadyForSaveState
-CircularSurvey::readyForSaveState() const {
- if (TransectStyleComplexItem::readyForSaveState() ==
- TransectStyleComplexItem::ReadyForSaveState::ReadyForSave) {
- if (this->_state == STATE::IDLE) {
- return ReadyForSaveState::ReadyForSave;
- } else {
- return ReadyForSaveState::NotReadyForSaveData;
- }
- } else {
- return TransectStyleComplexItem::readyForSaveState();
- }
-}
-
-double CircularSurvey::additionalTimeDelay() const { return 0; }
-
-QString CircularSurvey::patternName() const { return name; }
-
-bool CircularSurvey::registerGenerator(
- const QString &name, std::shared_ptr g) {
- if (name.isEmpty()) {
- qCDebug(CircularSurveyLog) << "registerGenerator(): empty name string.";
- return false;
- }
-
- if (!g) {
- qCDebug(CircularSurveyLog) << "registerGenerator(): empty generator.";
- return false;
- }
-
- if (this->_generatorNameList.contains(name)) {
- qCDebug(CircularSurveyLog) << "registerGenerator(): generator "
- "already registered.";
- return false;
- } else {
- this->_generatorNameList.push_back(name);
- this->_generatorList.push_back(g);
- if (this->_generatorList.size() == 1) {
- _switchToGenerator(g);
- }
-
- emit generatorNameListChanged();
- return true;
- }
-}
-
-bool CircularSurvey::unregisterGenerator(const QString &name) {
- auto index = this->_generatorNameList.indexOf(name);
- if (index >= 0) {
- // Is this the current generator?
- const auto &g = this->_generatorList.at(index);
- if (g == this->_pGenerator) {
- if (index > 0) {
- _switchToGenerator(this->_generatorList.at(index - 1));
- } else {
- _switchToGenerator(nullptr);
- qCDebug(CircularSurveyLog)
- << "unregisterGenerator(): last generator unregistered.";
- }
- }
-
- this->_generatorNameList.removeAt(index);
- this->_generatorList.removeAt(index);
-
- emit generatorNameListChanged();
- return true;
- } else {
- qCDebug(CircularSurveyLog)
- << "unregisterGenerator(): generator " << name << " not registered.";
- return false;
- }
-}
-
-bool CircularSurvey::unregisterGenerator(int index) {
- if (index > 0 && index < this->_generatorNameList.size()) {
- return unregisterGenerator(this->_generatorNameList.at(index));
- } else {
- qCDebug(CircularSurveyLog) << "unregisterGenerator(): index (" << index
- << ") out"
- "of bounds ( "
- << this->_generatorList.size() << " ).";
- return false;
- }
-}
-
-bool CircularSurvey::switchToGenerator(const QString &name) {
- auto index = this->_generatorNameList.indexOf(name);
- if (index >= 0) {
- _switchToGenerator(this->_generatorList.at(index));
- return true;
- } else {
- qCDebug(CircularSurveyLog)
- << "switchToGenerator(): generator " << name << " not registered.";
- return false;
- }
-}
-
-bool CircularSurvey::switchToGenerator(int index) {
- if (index >= 0) {
- _switchToGenerator(this->_generatorList.at(index));
- return true;
- } else {
- qCDebug(CircularSurveyLog) << "unregisterGenerator(): index (" << index
- << ") out"
- "of bounds ( "
- << this->_generatorNameList.size() << " ).";
- return false;
- }
-}
-
-QStringList CircularSurvey::generatorNameList() {
- return this->_generatorNameList;
-}
-
-routing::GeneratorBase *CircularSurvey::generator() {
- return _pGenerator.get();
-}
-
-int CircularSurvey::generatorIndex() {
- return this->_generatorList.indexOf(this->_pGenerator);
-}
-
-void CircularSurvey::_rebuildTransectsPhase1(void) {
- auto start = std::chrono::high_resolution_clock::now();
-
- switch (this->_state) {
- case STATE::SKIPP:
- qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: skipp.";
- this->_setState(STATE::IDLE);
- break;
- case STATE::CHANGE_VARIANT:
- qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: variant change.";
- this->_changeVariantWorker();
- this->_setState(STATE::IDLE);
- break;
- case STATE::REVERT_PATH:
- qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: reverse.";
- this->_reverseWorker();
- this->_setState(STATE::IDLE);
- break;
- case STATE::IDLE:
- case STATE::ROUTING:
- this->_setState(STATE::ROUTING);
- qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: update.";
- if (!this->_updateWorker()) {
- this->_setState(STATE::IDLE);
- }
- break;
- }
-
- qCDebug(CircularSurveyLog)
- << "rebuildTransectsPhase1(): "
- << std::chrono::duration_cast(
- std::chrono::high_resolution_clock::now() - start)
- .count()
- << " ms";
-}
-
-// no cameraShots in Circular Survey, add if desired
-void CircularSurvey::_recalcCameraShots() { _cameraShots = 0; }
-
-void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
- // Store solutions.
- auto ori = this->_areaData->origin();
- ori.setAltitude(0);
- const auto &transectsENU = pRoute->transects;
- QVector variantVector;
- const auto nSolutions = pRoute->solutionVector.size();
-
- for (std::size_t j = 0; j < nSolutions; ++j) {
- Variant var{QList()};
- const auto &solution = pRoute->solutionVector.at(j);
- if (solution.size() > 0) {
- const auto &route = solution.at(0);
- const auto &path = route.path;
- const auto &info = route.info;
- if (info.size() > 1) {
- // Find index of first waypoint.
- std::size_t idxFirst = 0;
- const auto &infoFirst = info.at(1);
- const auto &firstTransect = transectsENU[infoFirst.index];
- if (firstTransect.size() > 0) {
- const auto &firstWaypoint =
- infoFirst.reversed ? firstTransect.back() : firstTransect.front();
- double th = 0.01;
- for (std::size_t i = 0; i < path.size(); ++i) {
- auto dist = bg::distance(path[i], firstWaypoint);
- if (dist < th) {
- idxFirst = i;
- break;
- }
- }
-
- // Find index of last waypoint.
- std::size_t idxLast = path.size() - 1;
- const auto &infoLast = info.at(info.size() - 2);
- const auto &lastTransect = transectsENU[infoLast.index];
- if (lastTransect.size() > 0) {
- const auto &lastWaypoint =
- infoLast.reversed ? lastTransect.front() : lastTransect.back();
- for (long i = path.size() - 1; i >= 0; --i) {
- auto dist = bg::distance(path[i], lastWaypoint);
- if (dist < th) {
- idxLast = i;
- break;
- }
- }
-
- // Convert to geo coordinates.
- auto &list = var.front();
- for (std::size_t i = idxFirst; i <= idxLast; ++i) {
- auto &vertex = path[i];
- QGeoCoordinate c;
- snake::fromENU(ori, vertex, c);
- list.append(CoordInfo_t{c, CoordTypeInterior});
- }
-
- } else {
- qCDebug(CircularSurveyLog)
- << "_setTransects(): lastTransect.size() == 0";
- }
- } else {
- qCDebug(CircularSurveyLog)
- << "_setTransects(): firstTransect.size() == 0";
- }
- } else {
- qCDebug(CircularSurveyLog)
- << "_setTransects(): transectsInfo.size() <= 1";
- }
- } else {
- qCDebug(CircularSurveyLog) << "_setTransects(): solution.size() == 0";
- }
-
- if (var.size() > 0 && var.front().size() > 0) {
- variantVector.push_back(std::move(var));
- }
- }
-
- // Assign routes if no error occured.
- if (variantVector.size() > 0) {
- // Swap first route to _transects.
- this->_variantVector.swap(variantVector);
-
- // If the transects are getting rebuilt then any previously loaded
- // mission items are now invalid.
- if (_loadedMissionItemsParent) {
- _loadedMissionItems.clear();
- _loadedMissionItemsParent->deleteLater();
- _loadedMissionItemsParent = nullptr;
- }
-
- // Add route variant names.
- this->_variantNames.clear();
- for (std::size_t i = 1; i <= std::size_t(this->_variantVector.size());
- ++i) {
- this->_variantNames.append(QString::number(i));
- }
- emit variantNamesChanged();
-
- disconnect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
- this->_variant.setCookedValue(QVariant(0));
- connect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
- this->_changeVariantWorker();
-
- this->_setState(STATE::SKIPP);
- this->_rebuildTransects();
- } else {
- qCDebug(CircularSurveyLog)
- << "_setTransects(): failed, variantVector empty.";
- this->_setState(STATE::IDLE);
- }
-}
-
-Fact *CircularSurvey::variant() { return &_variant; }
-
-bool CircularSurvey::calculating() const {
- return this->_calculating(this->_state);
-}
-
-/*!
- \class CircularSurveyComplexItem
- \inmodule Wima
-
- \brief The \c CircularSurveyComplexItem class provides a survey mission
- item with circular transects around a point of interest.
-
- CircularSurveyComplexItem class provides a survey mission item with
- circular transects around a point of interest. Within the \c Wima module
- it's used to scan a defined area with constant angle (circular transects)
- to the base station (point of interest).
-
- \sa WimaArea
-*/
diff --git a/src/Wima/CircularSurvey.h b/src/Wima/CircularSurvey.h
deleted file mode 100644
index 50ab8edeef730fb11003f856951973c20d6f7728..0000000000000000000000000000000000000000
--- a/src/Wima/CircularSurvey.h
+++ /dev/null
@@ -1,131 +0,0 @@
-#pragma once
-
-#include
-#include
-#include
-
-#include "SettingsFact.h"
-#include "TransectStyleComplexItem.h"
-
-#include "Geometry/WimaJoinedAreaData.h"
-#include "Geometry/WimaMeasurementAreaData.h"
-#include "WimaPlanData.h"
-
-class RoutingThread;
-class RoutingData;
-
-namespace routing {
-class GeneratorBase;
-}
-
-class CircularSurvey : public TransectStyleComplexItem {
- Q_OBJECT
-
- using PtrGenerator = std::shared_ptr;
- using PtrRoutingData = std::shared_ptr;
- using PtrWorker = std::unique_ptr;
- using Transects = QList>;
- using Variant = Transects;
-
- enum class STATE { IDLE, ROUTING, SKIPP, REVERSE, VARIANT_CHANGE };
-
-public:
- CircularSurvey(PlanMasterController *masterController, bool flyView,
- const QString &kmlOrShpFile, QObject *parent);
- ~CircularSurvey();
-
- Q_PROPERTY(Fact *variant READ variant CONSTANT)
- Q_PROPERTY(
- QStringList variantNames READ variantNames NOTIFY variantNamesChanged)
- Q_PROPERTY(QStringList generatorNameList READ generatorNameList NOTIFY
- generatorNameListChanged)
- Q_PROPERTY(bool calculating READ calculating NOTIFY calculatingChanged)
- Q_PROPERTY(
- routing::GeneratorBase *generator READ generator NOTIFY generatorChanged)
- Q_PROPERTY(int generatorIndex READ generatorIndex NOTIFY generatorChanged)
-
- Q_INVOKABLE void reverse(void);
-
- // Property setters
- void setPlanData(const WimaPlanData &d);
-
- // Property getters
- const WimaPlanData &planData() const;
- WimaPlanData &planData();
- Fact *variant();
- QStringList variantNames() const;
- bool calculating() const;
-
- // Overrides
- virtual bool load(const QJsonObject &complexObject, int sequenceNumber,
- QString &errorString) override final;
- virtual QString mapVisualQML(void) const override final;
- virtual void save(QJsonArray &planItems) override final;
- virtual bool specifiesCoordinate(void) const override final;
- virtual double timeBetweenShots(void) override final;
- virtual QString commandDescription(void) const override final;
- virtual QString commandName(void) const override final;
- virtual QString abbreviation(void) const override final;
- virtual ReadyForSaveState readyForSaveState(void) const override final;
- virtual double additionalTimeDelay(void) const override final;
- virtual QString patternName(void) const override;
-
- // Generator
- bool registerGenerator(const QString &name,
- std::shared_ptr g);
- bool unregisterGenerator(const QString &name);
- bool unregisterGenerator(int index);
- Q_INVOKABLE bool switchToGenerator(const QString &name);
- Q_INVOKABLE bool switchToGenerator(int index);
- QStringList generatorNameList();
- routing::GeneratorBase *generator();
- int generatorIndex();
-
- static const char *settingsGroup;
- static const char *variantName;
- static const char *jsonComplexItemTypeValue;
- static const QString name;
-
-signals:
- void calculatingChanged();
- void variantNamesChanged();
- void generatorNameListChanged();
- void generatorChanged();
-
-private slots:
- // Overrides from TransectStyleComplexItem
- virtual void _rebuildTransectsPhase1(void) override final;
- virtual void _recalcCameraShots(void) override final;
-
- // Worker functions.
- void _setTransects(PtrRoutingData pRoute);
- void _changeVariant();
- bool _updateWorker();
- void _changeVariantWorker();
- void _reverseWorker();
-
-private:
- bool _switchToGenerator(const PtrGenerator &newG);
- void _setState(STATE state);
- bool _calculating(STATE state) const;
-
- // State.
- STATE _state;
-
- // center of the circular lanes, e.g. base station
- QMap _metaDataMap;
- SettingsFact _variant;
- QStringList _variantNames;
-
- // Area data
- std::shared_ptr _pAreaData;
-
- // Generators
- QList _generatorList;
- QStringList _generatorNameList;
- PtrGenerator _pGenerator;
-
- // Routing.
- QVector _variantVector;
- PtrWorker _pWorker;
-};
diff --git a/src/Wima/GenericSingelton.cpp b/src/Wima/GenericSingelton.cpp
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/src/Wima/GenericSingelton.h b/src/Wima/GenericSingelton.h
deleted file mode 100644
index 93e1ec0d5b684d8059b896f607a4851018b611ae..0000000000000000000000000000000000000000
--- a/src/Wima/GenericSingelton.h
+++ /dev/null
@@ -1,59 +0,0 @@
-#pragma once
-#include "call_once.h"
-#include
-#include
-
-template class GenericSingelton {
-private:
- typedef T *(*CreateInstanceFunction)();
-
-public:
- static T *instance(CreateInstanceFunction create);
-
-private:
- static void init();
-
- GenericSingelton();
- ~GenericSingelton();
- Q_DISABLE_COPY(GenericSingelton)
- static QBasicAtomicPointer create;
- static QBasicAtomicInt flag;
- static QBasicAtomicPointer tptr;
- bool inited;
-};
-
-template
-T *GenericSingelton::instance(CreateInstanceFunction create) {
- GenericSingelton::create.store(reinterpret_cast(create));
- qCallOnce(init, flag);
- return (T *)tptr.load();
-}
-
-template void GenericSingelton::init() {
- static GenericSingelton singleton;
- if (singleton.inited) {
- CreateInstanceFunction createFunction =
- (CreateInstanceFunction)GenericSingelton::create.load();
- tptr.store(createFunction());
- }
-}
-
-template GenericSingelton::GenericSingelton() { inited = true; }
-
-template GenericSingelton::~GenericSingelton() {
- T *createdTptr = (T *)tptr.fetchAndStoreOrdered(nullptr);
- if (createdTptr) {
- delete createdTptr;
- }
- create.store(nullptr);
-}
-
-template
-QBasicAtomicPointer
- GenericSingelton::create = Q_BASIC_ATOMIC_INITIALIZER(nullptr);
-template
-QBasicAtomicInt GenericSingelton::flag =
- Q_BASIC_ATOMIC_INITIALIZER(CallOnce::CO_Request);
-template
-QBasicAtomicPointer
- GenericSingelton::tptr = Q_BASIC_ATOMIC_INITIALIZER(nullptr);
diff --git a/src/Wima/Geometry/GenericCircle.h b/src/Wima/Geometry/GenericCircle.h
deleted file mode 100644
index 8d35c785ac0baf8615518e501e7d115bf1de70ff..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/GenericCircle.h
+++ /dev/null
@@ -1,154 +0,0 @@
-#pragma once
-
-#include
-#include
-
-#include
-
-#include "boost/units/systems/angle/degrees.hpp"
-#include "boost/units/systems/si.hpp"
-
-template auto get(const Point &p);
-
-namespace bu = boost::units;
-
-namespace qty {
-using Length = bu::quantity;
-using Angle = bu::quantity;
-using Degree = bu::quantity;
-using Radian = bu::quantity;
-} // namespace qty
-
-template class GenericCircle {
-public:
- GenericCircle();
- GenericCircle(NumberType rad, Point ori);
-
- // Property setters
- void setRadius(NumberType rad);
- void setOrigin(const Point &ori);
-
- // Property getters
- NumberType radius() const;
- const Point &origin() const;
- Point &origin();
-
-private:
- NumberType _r;
- Point _origin;
-};
-
-// Free functions.
-template
-void approximate(Circle &circ, long n, qty::Angle alpha1, qty::Angle alpha2,
- Container &c);
-template
-void approximate(Circle &circ, long n, Container &c);
-
-// Impl.
-template
-GenericCircle::GenericCircle() : _r(0), _origin(0, 0) {}
-
-template
-GenericCircle::GenericCircle(NumberType rad, Point ori)
- : _r(rad), _origin(ori) {}
-
-/*!
- * Returns a polygon with \a n corners which approximates the
- * circle.
- *
- * \sa Point
- */
-
-template
-void GenericCircle::setRadius(NumberType rad) {
- if (rad >= 0) {
- this->_r = rad;
- }
-}
-
-template
-void GenericCircle::setOrigin(const Point &ori) {
- this->_origin = ori;
-}
-
-template
-NumberType GenericCircle::radius() const {
- return this->_r;
-}
-
-template
-const Point &GenericCircle::origin() const {
- return this->_origin;
-}
-
-template
-Point &GenericCircle::origin() {
- return this->_origin;
-}
-
-template
-void approximate(Circle &circ, long n, qty::Angle alpha1, qty::Angle alpha2,
- Container &c) {
-
- auto clipp = [](double angle) {
- while (angle < 0) {
- angle += 2 * M_PI;
- }
- while (angle > 2 * M_PI) {
- angle -= 2 * M_PI;
- }
- return angle;
- };
-
- double a1 = clipp(alpha1.value());
- double a2 = clipp(alpha2.value());
- double angleDisc = 0;
- if (n > 0) {
- angleDisc = (a2 - a1) / (n - 1);
- } else {
- angleDisc = (a2 - a1) / (n + 1);
- n = n * (-1);
- }
-
- double a = a1;
- using Point =
- std::remove_cv_t>;
- auto x0 = get<0>(circ.origin());
- auto y0 = get<1>(circ.origin());
- auto r = circ.radius();
- using NumberType = std::remove_cv_t>;
- while (n--) {
- auto x = NumberType(x0 + r * std::cos(a));
- auto y = NumberType(y0 + r * std::sin(a));
- c.push_back(Point(x, y));
- a += angleDisc;
- }
-}
-
-template
-void approximate(Circle &circ, long n, Container &c) {
- using namespace bu;
-
- double angleDisc = 0;
- if (n > 0) {
- angleDisc = 2 * M_PI / (n - 1);
- } else {
- angleDisc = 2 * M_PI / (n + 1);
- n = n * (-1);
- }
-
- double a = 0;
- using Point =
- std::remove_cv_t>;
- auto x0 = get<0>(circ.origin());
- auto y0 = get<1>(circ.origin());
- auto r = circ.radius();
- using NumberType = std::remove_cv_t>;
- while (n--) {
- auto x = NumberType(x0 + r * std::cos(a));
- auto y = NumberType(y0 + r * std::sin(a));
- c.push_back(Point(x, y));
- a += angleDisc;
- }
-}
diff --git a/src/Wima/Geometry/GenericPolygon.h b/src/Wima/Geometry/GenericPolygon.h
deleted file mode 100644
index 974f49da6d504627f3f60b04bfe7f057643b6cee..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/GenericPolygon.h
+++ /dev/null
@@ -1,29 +0,0 @@
-#pragma once
-
-#include
-#include
-
-#include "ros_bridge/include/messages/geometry_msgs/polygon_stamped.h"
-
-template class ContainerType = QVector>
-class GenericPolygon{ //
- typedef ros_bridge::messages::geometry_msgs::polygon::GenericPolygon Polygon;
-public:
- GenericPolygon(){}
- GenericPolygon(const GenericPolygon &other) : _polygon(other._polygon){}
-
- GenericPolygon& operator=(const GenericPolygon& other) {
- this->_polygon = other._polygon;
- return *this;
- }
-
- const Polygon &polygon() const {return _polygon;}
- Polygon &polygon() {return _polygon;}
-
- const ContainerType &path() const {return _polygon.points();}
- ContainerType &path() {return _polygon.points();}
-
-private:
- Polygon _polygon;
-
-};
diff --git a/src/Wima/Geometry/GenericPolygonArray.h b/src/Wima/Geometry/GenericPolygonArray.h
deleted file mode 100644
index 68dfa14ae0afa5490df03e7fb57d348919347a12..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/GenericPolygonArray.h
+++ /dev/null
@@ -1,58 +0,0 @@
-#pragma once
-
-#include "QmlObjectListModel.h"
-
-#include
-#include
-
-template class ContainerType = QVector>
-class GenericPolygonArray
-{
-public:
- GenericPolygonArray() {}
- GenericPolygonArray(const GenericPolygonArray &other) :
- _polygons(other._polygons), _dirty(true)
- {}
- ~GenericPolygonArray(){
- _objs.clearAndDeleteContents();
- }
-
- class QmlObjectListModel *QmlObjectListModel(){
- if (_dirty)
- _updateObjects();
- _dirty = false;
- return &_objs;
- }
-
- const ContainerType &polygons() const {
- return _polygons;
- }
-
- ContainerType &polygons(){
- _dirty = true;
- return _polygons;
- }
-
- GenericPolygonArray &operator =(const GenericPolygonArray &other){
- this->_polygons = other._polygons;
- this->_dirty = true;
- return *this;
- }
-
-
-
-private:
- void _updateObjects(void){
- _objs.clearAndDeleteContents();
- for (long i=0; i<_polygons.size(); ++i){
- _objs.append(new PolygonType(_polygons[i]));
- }
- }
-
- ContainerType _polygons;
- class QmlObjectListModel _objs;
- bool _dirty;
-
-};
-
-
diff --git a/src/Wima/Geometry/GeoPoint3D.cpp b/src/Wima/Geometry/GeoPoint3D.cpp
deleted file mode 100644
index 2d5bd3d59366fa4e1c764f943e148dda65197651..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/GeoPoint3D.cpp
+++ /dev/null
@@ -1,37 +0,0 @@
-#include "GeoPoint3D.h"
-
-GeoPoint3D::GeoPoint3D(QObject *parent)
- : QObject(parent), ROSGeoPoint() {}
-
-GeoPoint3D::GeoPoint3D(double latitude, double longitude, double altitude, QObject *parent)
- : QObject(parent), ROSGeoPoint(latitude, longitude, altitude)
-{}
-
-GeoPoint3D::GeoPoint3D(const GeoPoint3D &p, QObject *parent)
- : QObject(parent), ROSGeoPoint(p.latitude(), p.longitude(), p.altitude())
-{}
-
-GeoPoint3D::GeoPoint3D(const ROSGeoPoint &p, QObject *parent)
- : QObject(parent), ROSGeoPoint(p.latitude(), p.longitude(), p.altitude())
-{}
-
-GeoPoint3D::GeoPoint3D(const QGeoCoordinate &p, QObject *parent)
- : QObject(parent), ROSGeoPoint(p.latitude(), p.longitude(), p.altitude())
-{}
-
-GeoPoint3D &GeoPoint3D::operator=(const GeoPoint3D &p)
-{
- this->setLatitude(p.latitude());
- this->setLongitude(p.longitude());
- this->setAltitude(p.altitude());
-
- return *this;
-}
-GeoPoint3D &GeoPoint3D::operator=(const QGeoCoordinate &p)
-{
- this->setLatitude(p.latitude());
- this->setLongitude(p.longitude());
- this->setAltitude(p.altitude());
-
- return *this;
-}
diff --git a/src/Wima/Geometry/GeoPoint3D.h b/src/Wima/Geometry/GeoPoint3D.h
deleted file mode 100644
index 63b221d117e52c061d27e3f48bcea27e3cc7f3f4..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/GeoPoint3D.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#pragma once
-
-#include
-#include
-
-#include "ros_bridge/include/messages/geographic_msgs/geopoint.h"
-
-
-typedef ros_bridge::messages::geographic_msgs::geo_point::GeoPoint ROSGeoPoint;
-class GeoPoint3D : public QObject, public ROSGeoPoint
-{
- Q_OBJECT
-public:
-
- GeoPoint3D(QObject *parent = nullptr);
- GeoPoint3D(double latitude,
- double longitude,
- double altitude,
- QObject *parent = nullptr);
- GeoPoint3D(const GeoPoint3D& p,
- QObject *parent = nullptr);
- GeoPoint3D(const ROSGeoPoint& p,
- QObject *parent = nullptr);
- GeoPoint3D(const QGeoCoordinate& p,
- QObject *parent = nullptr);
-
- GeoPoint3D &operator=(const GeoPoint3D&p);
- GeoPoint3D &operator=(const QGeoCoordinate&p);
-
-};
-
-
diff --git a/src/Wima/Geometry/PlanimetryCalculus.cc b/src/Wima/Geometry/PlanimetryCalculus.cc
deleted file mode 100644
index d8053d351c3d131cdfb41c5c7ca6de26cd0a5d8e..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/PlanimetryCalculus.cc
+++ /dev/null
@@ -1,774 +0,0 @@
-#include "PlanimetryCalculus.h"
-
-template qreal get(QPointF &p);
-template <> qreal get<0>(QPointF &p) { return p.x(); }
-template <> qreal get<1>(QPointF &p) { return p.y(); }
-
-namespace PlanimetryCalculus {
-namespace {
-/*!
- \fn IntersectType intersects(const Circle &circle, const QLineF &line,
- PointList &intersectionPoints, bool calcInstersect) Returns the Intersection
- type of \a circle and \a line. Stores the intersection points in \a
- intersectionPoints if \a calcIntersect is \c true. Returns \c Error if either
- line or circe \c {isNull() == true}.
-
- \sa QPointF, Circle
-*/
-bool intersects(const Circle &circle, const QLineF &line,
- QPointFVector &intersectionPoints, IntersectType &type,
- bool calcInstersect) {
- if (!line.isNull()) {
- QPointF translationVector = line.p1();
- double alpha = angle(line); // angle between wold and line coordinate system
-
- QPointF originCircleL = circle.origin() - translationVector;
- rotateReference(originCircleL,
- -alpha); // circle origin in line corrdinate system
-
- double y = originCircleL.y();
- double r = circle.radius();
- if (qAbs(y) > r) {
- type = NoIntersection;
- return false;
- } else if (qFuzzyCompare(qFabs(y), r)) { // tangent
- double x_ori = originCircleL.x();
-
- if (x_ori >= 0 && x_ori <= line.length()) {
- if (calcInstersect) {
- QPointF intersectionPt = QPointF(x_ori, 0);
- rotateReference(intersectionPt, alpha);
- intersectionPoints.append(intersectionPt + translationVector);
- }
-
- type = Tangent;
- return true;
- }
-
- type = NoIntersection;
- return false;
- } else { // secant
- double x_ori = originCircleL.x();
- double y_ori = originCircleL.y();
- double delta = qSqrt(qPow(r, 2) - qPow(y_ori, 2));
- double x1 =
- x_ori +
- delta; // x coordinate (line system) of fist intersection point
- double x2 =
- x_ori -
- delta; // x coordinate (line system) of second intersection point
- bool doesIntersect =
- false; // remember if actual intersection was on the line
-
- if (x1 >= 0 &&
- x1 <= line.length()) { // check if intersection point is on the line
- if (calcInstersect) {
- QPointF intersectionPt =
- QPointF(x1, 0); // first intersection point (line system)
- rotateReference(intersectionPt, alpha);
- intersectionPoints.append(
- intersectionPt +
- translationVector); // transform (to world system) and append
- // first intersection point
- }
- doesIntersect = true;
- }
- if (x2 >= 0 &&
- x2 <= line.length()) { // check if intersection point is on the line
- if (calcInstersect) {
- QPointF intersectionPt =
- QPointF(x2, 0); // second intersection point (line system)
- rotateReference(intersectionPt, alpha);
- intersectionPoints.append(
- intersectionPt +
- translationVector); // transform (to world system) and append
- // second intersection point
- }
- doesIntersect = true;
- }
- type = doesIntersect ? Secant : NoIntersection;
- return doesIntersect ? true : false;
- }
- }
-
- type = Error;
- return false;
-}
-
-/*!
- \fn bool intersects(const Circle &circle1, const Circle &circle2, PointList
- &intersectionPoints, IntersectType type) Calculates the intersection points
- of two circles if present and stores the result in \a intersectionPoints.
- Returns the intersection type of the two cirles \a circle1 and \a circle2.
-
- The function assumes that the list \a intersectionPoints is empty.
-
- \note Returns Error if circle.isNull() returns true;
-
- \sa Circle
-*/
-bool intersects(const Circle &circle1, const Circle &circle2,
- QPointFVector &intersectionPoints, IntersectType type,
- bool calcIntersection) {
- double r1 = circle1.radius();
- double r2 = circle2.radius();
- double d = distance(circle1.origin(), circle2.origin());
- double r = 0;
- double R = 0;
- if (r1 > r2) {
- R = r1; // large
- r = r2; // smallline1
- } else {
- // this branch is also choosen if r1 == r2
- R = r2;
- r = r1;
- }
-
- // determine intersection type
- if (r + d < R) {
- // this branch is also reached if d < rLarge && rSmall == 0
- type = InsideNoIntersection;
- return false;
- } else if (qFuzzyCompare(r + d, R)) {
- if (qFuzzyIsNull(d)) {
- type = CirclesEqual;
- return true;
- } else {
- type = InsideTouching;
- }
- } else if (d < R) {
- type = InsideIntersection;
- } else if (d - r < R) {
- type = OutsideIntersection;
- } else if (qFuzzyCompare(d - r, R)) {
- type = OutsideTouching;
- } else {
- type = OutsideNoIntersection;
- return false;
- }
-
- if (calcIntersection) {
- // calculate intersection
-
- // Coordinate system circle1: origin = circle1.origin(), x-axis towars
- // circle2.origin() y-axis such that the coordinate system is dextrorse
- // with z-axis outward faceing with respect to the drawing plane.
- double alpha =
- angle(circle1.origin(),
- circle2.origin()); // angle between world and circle1 system
- QPointF translationVector =
- circle1.origin(); // translation vector between world and circle1 system
-
- if (type == InsideTouching || type == OutsideTouching) {
- // Intersection point in coordinate system of circle 1.
- // Coordinate system circle1: origin = circle1.origin(), x-axis towars
- // circle2.origin() y-axis such that the coordinate system is dextrorse
- // with z-axis outward faceing with respect to the drawing plane.
- intersectionPoints.append(rotateReturn(QPointF(0, r1), alpha) +
- translationVector);
- } else { // triggered if ( type == InsideIntersection
- // || type == OutsideIntersection)
- // See fist branch for explanation
-
- // this equations are obtained by solving x^2+y^2=R^2 and (x -
- // d)^2+y^2=r^2
- double x = (qPow(d, 2) - qPow(r, 2) + qPow(R, 2)) / 2 / d;
- double y = 1 / 2 / d *
- qSqrt(4 * qPow(d * R, 2) -
- qPow(qPow(d, 2) - qPow(r, 2) + qPow(R, 2), 2));
-
- intersectionPoints.append(rotateReturn(QPointF(x, y), alpha) +
- translationVector);
- intersectionPoints.append(rotateReturn(QPointF(x, -y), alpha) +
- translationVector);
- }
- // Transform the coordinate to the world coordinate system. Alpha is the
- // angle between world and circle1 coordinate system.
-
- return true;
- }
- type = Error;
- return false;
-}
-} // end anonymous namespace
-
-/*!
- \fn void rotatePoint(QPointF &point, double alpha)
- Rotates the \a point counter clockwisely by the angle \a alpha (in
- radiants).
-*/
-void rotateReference(QPointF &point, double alpha) {
- if (!point.isNull()) {
- double x = point.x();
- double y = point.y();
-
- point.setX(x * qCos(alpha) - y * qSin(alpha));
- point.setY(x * qSin(alpha) + y * qCos(alpha));
- }
-}
-
-void rotateReference(QPointFVector &points, double alpha) {
- for (int i = 0; i < points.size(); i++) {
- rotateReference(points[i], alpha);
- }
-}
-
-/*!
- \fn void rotatePointDegree(QPointF &point, double alpha)
- Rotates the \a point counter clockwisely by the angle \a alpha (in degrees).
-*/
-void rotateReferenceDegree(QPointF &point, double alpha) {
- rotateReference(point, alpha / 180 * M_PI);
-}
-
-void rotateReferenceDegree(QPointFVector &points, double alpha) {
- for (int i = 0; i < points.size(); i++) {
- rotateReferenceDegree(points[i], alpha);
- }
-}
-
-/*!
- \fn IntersectType intersects(const Circle &circle, const QLineF &line)
- Returns the Intersection type of \a circle and \a line.
- Returns \c Error if either line or circe \c {isNull() == true}.
-
- \sa QPointF, Circle
-*/
-bool intersects(const Circle &circle, const QLineF &line) {
- QPointFVector dummyList;
- IntersectType type = NoIntersection;
- return intersects(circle, line, dummyList, type,
- false /* calculate intersection points*/);
-}
-
-bool intersects(const Circle &circle, const QLineF &line,
- QPointFVector &intersectionPoints) {
- IntersectType type = NoIntersection;
- return intersects(circle, line, intersectionPoints, type,
- true /* calculate intersection points*/);
-}
-
-/*!
- \fn double distance(const QPointF &p1, const QPointF p2)
- Calculates the distance (2-norm) between \a p1 and \a p2.
- \sa QPointF
-*/
-double distance(const QPointF &p1, const QPointF p2) {
- double dx = p2.x() - p1.x();
- double dy = p2.y() - p1.y();
-
- return norm(dx, dy);
-}
-
-/*!
- \fn double distance(const QPointF &p1, const QPointF p2)
- Calculates the angle (in radiants) between the line defined by \a p1 and \a
- p2 and the x-axis according to the following rule. Angle = qAtan2(dy, dx),
- where dx = p2.x()-p1.x() and dy = p2.y()-p1.y().
-
- \note The order of \a p1 and \a p2 matters. Swapping \a p1 and \a p2 will
- result in a angle of oposite sign. \sa QPointF
-*/
-double angle(const QPointF &p1, const QPointF p2) {
- double dx = p2.x() - p1.x();
- double dy = p2.y() - p1.y();
-
- return qAtan2(dy, dx);
-}
-
-/*!
- \fn double distance(const QPointF &p1, const QPointF p2)
- Calculates the angle (in degrees) between the line defined by \a p1 and \a
-p2 and the x-axis according to the following rule. Angle = qAtan2(dy,
-dx)*180/pi, where dx = p2.x()-p1.x() and dy = p2.y()-p1.y(). angle \note The
-order of \a p1 and \a p2 matters. Swapping \a p1 and \a p2 will result in a
-angle of oposite sign. \sa QPointF
-*/
-double angleDegree(const QPointF &p1, const QPointF p2) {
- return angle(p1, p2) * 180 / M_PI;
-}
-
-double truncateAngle(double angle) {
- while (angle < 0) {
- angle += 2 * M_PI;
- }
- while (angle > 2 * M_PI) {
- angle -= 2 * M_PI;
- }
-
- return angle;
-}
-
-double truncateAngleDegree(double angle) {
- return truncateAngle(angle / 180 * M_PI);
-}
-
-/*!
- * \fn IntersectType intersects(const QLineF &line1, const QLineF &line2,
- * QPointF &intersectionPt) Determines wheter \a line1 and \a line2 intersect
- * and of which type the intersection is. Stores the intersection point in \a
- * intersectionPt Returns the intersection type (\c IntersectType).
- *
- * Intersection Types:
- * \c NoIntersection
- * \c CornerCornerIntersection; A intersection is present such that two of the
- * lines cornes touch. \c EdgeCornerIntersection; A intersection is present such
- * that a corner and a edge touch. \c EdgeEdgeIntersection; A intersection is
- * present such two edges intersect. \c LinesParallel \c LinesEqual \c Error;
- * Returned if at least on line delivers isNULL() == true.
- *
- *
- * \sa QPointF
- */
-bool intersects(const QLineF &line1, const QLineF &line2,
- QPointF &intersectionPt, IntersectType &type) {
- if (line1.isNull() || line2.isNull()) {
- type = Error;
- return false;
- }
-
- // line 1 coordinate system: origin line1.p1(), x-axis towards line1.p2()
- QPointF translationVector =
- line1.p1(); // translation vector between world and line1 system
- double alpha = angle(line1);
- double l1 = line1.length();
-
- QLineF line2L1 = line2;
- line2L1.translate(-translationVector);
- rotateReference(line2L1, -alpha);
-
- double x1 = line2L1.x1();
- double x2 = line2L1.x2();
- double y1 = line2L1.y1();
- double y2 = line2L1.y2();
- if (x1 > x2) {
- x1 = x2;
- x2 = line2L1.x1();
- y1 = y2;
- y2 = line2L1.y1();
- }
-
- double dx = (x2 - x1);
- double dy = (y2 - y1);
- double xNull = 0; // (xNull, 0) intersection point in line1 system
-
- if (!qFuzzyIsNull(dx)) {
- double k = dy / dx;
-
- if (qFuzzyIsNull(k)) {
- if (qFuzzyIsNull(x1) && qFuzzyIsNull(y1) && qFuzzyCompare(x2, l1)) {
- type = LinesEqual;
- return true;
- } else {
- type = LinesParallel;
- return false;
- }
- }
-
- double d = (y1 * x2 - y2 * x1) / dx;
- xNull = -d / k;
- } else {
- // lines orthogonal
- if (signum(y1) != signum(y2)) {
- xNull = x1;
- } else {
- type = NoIntersection;
- return false;
- }
- }
-
- if (xNull >= x1 && xNull <= x2) {
- // determine intersection type#include "QVector3D"
-
- if (qFuzzyIsNull(xNull) || qFuzzyCompare(xNull, l1)) {
- if (qFuzzyIsNull(y1) || qFuzzyIsNull(y2))
- type = CornerCornerIntersection;
- else
- type = EdgeCornerIntersection;
- } else if (xNull > 0 && xNull < l1) {
- if (qFuzzyIsNull(y1) || qFuzzyIsNull(y2))
- type = EdgeCornerIntersection;
- else
- type = EdgeEdgeIntersection;
- } else {
- type = NoIntersection;
- return false;
- }
- } else {
- type = NoIntersection;
- return false;
- }
-
- intersectionPt = QPointF(xNull, 0); // intersection point in line1 system
- rotateReference(intersectionPt, alpha);
- intersectionPt += translationVector;
-
- return true;
-}
-
-/*!IntersectType type = NoIntersection;
- * \overload bool intersects(const QPolygonF &polygon, const QLineF &line,
- * PointList &intersectionList, NeighbourList &neighbourList, IntersectList
- * &typeList) Checks if \a polygon intersect with \a line. Stores the
- * intersection points in \a intersectionList.
- *
- * Stores the indices of the closest two \a area vetices for each of
- * coorespoinding intersection points in \a neighbourList. * For example if an
- * intersection point is found between the first and the second vertex of the \a
- * area the intersection point will be stored in \a intersectionList and the
- * indices 1 and 2 will be stored in \a neighbourList. \a neighbourList has
- * entries of type \c {QPair}, where \c{pair.first} would contain 1
- * and \c{pair.second} would contain 2, when relating to the above example.
- *
- * Returns the \c IntersectionType of each intersection point within a QVector.
- *
- * \sa QPair, QVector
- */
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList, NeighbourVector &neighbourList,
- IntersectVector &typeList) {
-
- if (polygon.size() >= 2) {
- IntersectVector intersectionTypeList;
- // Assemble a line form each tow consecutive polygon vertices and check
- // whether it intersects with line
- for (int i = 0; i < polygon.size(); i++) {
-
- QLineF interatorLine;
- QPointF currentVertex = polygon[i];
- QPointF nextVertex =
- polygon[PolygonCalculus::nextVertexIndex(polygon.size(), i)];
- interatorLine.setP1(currentVertex);
- interatorLine.setP2(nextVertex);
-
- QPointF intersectionPoint;
- IntersectType type;
- if (intersects(line, interatorLine, intersectionPoint, type)) {
- intersectionList.append(intersectionPoint);
-
- QPair neighbours;
- neighbours.first = i;
- neighbours.second = PolygonCalculus::nextVertexIndex(polygon.size(), i);
- neighbourList.append(neighbours);
-
- typeList.append(type);
- }
- }
-
- if (typeList.size() > 0) {
- return true;
- } else {
- return false;
- }
- } else {
- return false;
- }
-}
-
-/*!
- * \overload IntersectType intersects(const QPolygonF &polygon, const QLineF
- * &line) Returns \c true if any intersection between \a polygon and \a line
- * exists, \c false else.
- *
- * \sa QPair, QVector
- */
-bool intersects(const QPolygonF &polygon, const QLineF &line) {
- QPointFVector dummyGeo;
- QVector> dummyNeighbour;
- intersects(polygon, line, dummyGeo, dummyNeighbour);
-
- if (dummyGeo.size() > 0)
- return true;
-
- return false;
-}
-
-void rotateReference(QLineF &line, double alpha) {
- line.setP1(rotateReturn(line.p1(), alpha));
- line.setP2(rotateReturn(line.p2(), alpha));
-}
-
-QPointF rotateReturn(QPointF point, double alpha) {
- rotateReference(point, alpha);
- return point;
-}
-
-QPointFVector rotateReturn(QPointFVector points, double alpha) {
- rotateReference(points, alpha);
- return points;
-}
-
-QLineF rotateReturn(QLineF line, double alpha) {
- rotateReference(line, alpha);
- return line;
-}
-
-bool intersects(const QLineF &line1, const QLineF &line2,
- QPointF &intersectionPt) {
- IntersectType dummyType;
- return intersects(line1, line2, intersectionPt, dummyType);
-}
-
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList,
- NeighbourVector &neighbourList) {
- IntersectVector typeList;
- return intersects(polygon, line, intersectionList, neighbourList, typeList);
-}
-
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList, IntersectVector &typeList) {
- NeighbourVector neighbourList;
- return intersects(polygon, line, intersectionList, neighbourList, typeList);
-}
-
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList) {
- NeighbourVector neighbourList;
- IntersectVector typeList;
- return intersects(polygon, line, intersectionList, neighbourList, typeList);
-}
-
-/*!
- \fn IntersectType intersects(const Circle &circle1, const Circle &circle2)
- Returns the intersection type of the two cirles \a circle1 and \a circle2.
-
- \note Returns Error if circle.isNull() returns true;
-
- \sa Circle
-*/
-bool intersects(const Circle &circle1, const Circle &circle2) {
- IntersectType type = NoIntersection;
- QPointFVector intersectionPoints;
- return intersects(circle1, circle2, intersectionPoints, type,
- false /*calculate intersection points*/);
-}
-
-bool intersects(const Circle &circle1, const Circle &circle2,
- IntersectType &type) {
- QPointFVector intersectionPoints;
- return intersects(circle1, circle2, intersectionPoints, type,
- false /*calculate intersection points*/);
-}
-
-bool intersects(const Circle &circle1, const Circle &circle2,
- QPointFVector &intersectionPoints) {
- IntersectType type;
- return intersects(circle1, circle2, intersectionPoints, type);
-}
-
-bool intersects(const Circle &circle1, const Circle &circle2,
- QPointFVector &intersectionPoints, IntersectType &type) {
- return intersects(circle1, circle2, intersectionPoints, type,
- true /*calculate intersection points*/);
-}
-
-;
-
-double angle(const QLineF &line) { return angle(line.p1(), line.p2()); }
-
-bool contains(const QLineF &line, const QPointF &point, IntersectType &type) {
- QPointF translationVector = line.p1();
- double alpha = angle(line);
- double l = line.length();
-
- QPointF pointL1 = rotateReturn(point - translationVector, -alpha);
-
- double x = pointL1.x();
- double y = pointL1.y();
-
- if (x >= 0 && x <= l) {
- if (qFuzzyIsNull(x) || qFuzzyCompare(x, l)) {
- if (qFuzzyIsNull(y)) {
- type = CornerCornerIntersection;
- return true;
- }
- } else {
- if (qFuzzyIsNull(y)) {
- type = EdgeCornerIntersection;
- return true;
- }
- }
- }
- type = NoIntersection;
- return false;
-}
-
-bool contains(const QLineF &line, const QPointF &point) {
- IntersectType dummyType;
- return contains(line, point, dummyType);
-}
-
-bool contains(const QPolygonF &polygon, const QPointF &point,
- IntersectType &type) {
- using namespace PolygonCalculus;
- if (polygon.containsPoint(point, Qt::FillRule::OddEvenFill)) {
- type = Interior;
- return true;
- }
- int size = polygon.size();
- for (int i = 0; i < size; i++) {
- QLineF line(polygon[i], polygon[nextVertexIndex(size, i)]);
- if (contains(line, point, type)) {
- return true;
- }
- }
-
- return false;
-}
-
-bool contains(const QPolygonF &polygon, const QPointF &point) {
- IntersectType dummyType;
- return contains(polygon, point, dummyType);
-}
-
-double norm(double x, double y) { return qSqrt(x * x + y * y); }
-
-double norm(const QPointF &p) { return norm(p.x(), p.y()); }
-
-double angle(const QPointF &p1) {
- return truncateAngle(qAtan2(p1.y(), p1.x()));
-}
-
-bool intersects(const Circle &circle, const QPolygonF &polygon,
- QVector &intersectionPoints,
- NeighbourVector &neighbourList, IntersectVector &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);
-
- QPointFVector lineIntersecPts;
- IntersectType type;
- if (intersects(circle, line, lineIntersecPts, type)) {
- QPair 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,
- QVector &intersectionPoints,
- NeighbourVector &neighbourList) {
- QVector types;
- return intersects(circle, polygon, intersectionPoints, neighbourList, types);
-}
-
-bool intersects(const Circle &circle, const QPolygonF &polygon,
- QVector &intersectionPoints,
- IntersectVector &typeList) {
- NeighbourVector neighbourList;
- return intersects(circle, polygon, intersectionPoints, neighbourList,
- typeList);
-}
-
-bool intersects(const Circle &circle, const QPolygonF &polygon,
- QVector &intersectionPoints) {
- NeighbourVector neighbourList;
- return intersects(circle, polygon, intersectionPoints, neighbourList);
-}
-
-bool intersects(const Circle &circle, const QPolygonF &polygon) {
- QVector 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,
- QPointFVector &intersectionPoints, IntersectType &type) {
- return intersects(circle, line, intersectionPoints, type,
- true /* calculate intersection points*/);
-}
-
-bool intersectsFast(const QPolygonF &polygon, const QLineF &line) {
- for (int i = 0; i < polygon.size() - 1; ++i) {
- QLineF polygonSegment(polygon[i], polygon[i + 1]);
-
- if (QLineF::BoundedIntersection == line.intersect(polygonSegment, nullptr))
- return true;
- }
-
- return false;
-}
-
-// bool intersectsFast(const QLineF &line1, const QLineF &line2, QPointF
-// &intersectionPt)
-// {
-// if (line1.isNull() || line2.isNull()){
-// return false;
-// }
-
-// // determine line equations y = kx+d
-// double dx1 = line1.dx();
-// double dy1 = line1.dy();
-// double k1;
-// double d1 = 0;
-// if (qFuzzyIsNull(dx1)) {
-// k1 = std::numeric_limits::infinity();
-// } else {
-// k1 = dy1/dx1;
-// d1 = line1.y1()-k1*line1.x1();
-// }
-
-// double dx2 = line2.dx();
-// double dy2 = line2.dy();
-// double k2;
-// double d2 = 0;
-// if (qFuzzyIsNull(dx2)) {
-// k2 = std::numeric_limits::infinity();
-// } else {
-// k2 = dy2/dx2;
-// d2 = line2.y1()-k2*line2.x1();
-// }
-
-// if ( !qFuzzyCompare(k1, std::numeric_limits::infinity())
-// && !qFuzzyCompare(k1, std::numeric_limits::infinity()))
-// {
-// double dk = k2-k1;
-// double dd = d2-d1;
-// if (qFuzzyIsNull(dk)) { // lines parallel
-// if (qFuzzyIsNull(dd)) { // lines colinear
-// if ( ((line1.x1() >= line2.x1()) && ((line1.x1() <=
-// line2.x2())))
-// || ((line1.x2() >= line2.x1()) && ((line1.x2() <=
-// line2.x2()))) ) // intersect? return true;
-
-// return false;
-// }
-// return false;
-// }
-
-// double x_intersect = -dd/dk;
-
-// if (((x_intersect >= line2.x1()) && ((line1.x1() <= line2.x2())))
-
-// }
-
-// return true;
-// }
-
-} // end namespace PlanimetryCalculus
-
-/*!
- \class PlanimetryCalculus
- \inmodule Wima
-
- \brief The \c PlanimetryCalculus class provides routines handy for
- planimetrical (2D) calculations.
-*/
diff --git a/src/Wima/Geometry/PlanimetryCalculus.h b/src/Wima/Geometry/PlanimetryCalculus.h
deleted file mode 100644
index c54946dc5cc2fad09f3d6f205c534da80caa075c..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/PlanimetryCalculus.h
+++ /dev/null
@@ -1,124 +0,0 @@
-#pragma once
-
-#include
-#include
-#include
-#include
-
-#include "GenericCircle.h"
-#include "PolygonCalculus.h"
-
-using Circle = GenericCircle;
-
-namespace PlanimetryCalculus {
-
-enum IntersectType {
- InsideNoIntersection,
- InsideTouching,
- InsideIntersection,
- OutsideIntersection,
- OutsideTouching,
- OutsideNoIntersection,
- CirclesEqual, // Circle Circle intersection
-
- Tangent,
- Secant, // Circle Line Intersetion
-
- EdgeCornerIntersection,
- EdgeEdgeIntersection,
- CornerCornerIntersection,
- LinesParallel,
- LinesEqual, // Line Line intersection
-
- Interior, // Polygon contains
-
- NoIntersection,
- Error // general
-};
-
-typedef QVector> NeighbourVector;
-typedef QVector QPointFVector;
-typedef QVector IntersectVector;
-
-void rotateReference(QPointF &point, double alpha);
-void rotateReference(QPointFVector &points, double alpha);
-void rotateReference(QLineF &line, double alpha);
-// void rotateReference(QPolygonF &polygon, double alpha);
-
-QPointF rotateReturn(QPointF point, double alpha);
-QPointFVector rotateReturn(QPointFVector points, double alpha);
-QLineF rotateReturn(QLineF line, double alpha);
-// QPolygonF rotateReturn(QPolygonF &polygon, double alpha);
-
-bool intersects(const Circle &circle1, const Circle &circle2);
-bool intersects(const Circle &circle1, const Circle &circle2,
- IntersectType &type);
-bool intersects(const Circle &circle1, const Circle &circle2,
- QPointFVector &intersectionPoints);
-bool intersects(const Circle &circle1, const Circle &circle2,
- QPointFVector &intersectionPoints, IntersectType &type);
-
-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,
- QPointFVector &intersectionPoints);
-bool intersects(const Circle &circle, const QLineF &line,
- QPointFVector &intersectionPoints, IntersectType &type);
-
-bool intersects(const Circle &circle, const QPolygonF &polygon);
-bool intersects(const Circle &circle, const QPolygonF &polygon,
- QVector &intersectionPoints);
-bool intersects(const Circle &circle, const QPolygonF &polygon,
- QVector &intersectionPoints,
- IntersectVector &typeList);
-bool intersects(const Circle &circle, const QPolygonF &polygon,
- QVector &intersectionPoints,
- NeighbourVector &neighbourList);
-bool intersects(const Circle &circle, const QPolygonF &polygon,
- QVector &intersectionPoints,
- NeighbourVector &neighbourList, IntersectVector &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, IntersectType &type);
-// bool intersectsFast(const QLineF &line1, const QLineF &line2, QPointF
-// &intersectionPt, IntersectType &type);
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList);
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList, IntersectVector &typeList);
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList,
- NeighbourVector &neighbourList);
-bool intersects(const QPolygonF &polygon, const QLineF &line,
- QPointFVector &intersectionList, NeighbourVector &neighbourList,
- IntersectVector &typeList);
-
-bool intersectsFast(const QPolygonF &polygon, const QLineF &line);
-
-bool contains(const QLineF &line, const QPointF &point);
-bool contains(const QLineF &line, const QPointF &point, IntersectType &type);
-bool contains(const QPolygonF &polygon, const QPointF &point);
-bool contains(const QPolygonF &polygon, const QPointF &point,
- IntersectType &type);
-
-double distance(const QPointF &p1, const QPointF p2);
-double norm(double x, double y);
-double norm(const QPointF &p);
-double angle(const QPointF &p1, const QPointF p2);
-double angle(const QPointF &p1);
-double angle(const QLineF &line);
-double angleDegree(const QPointF &p1, const QPointF p2);
-double truncateAngle(double angle);
-double truncateAngleDegree(double angle);
-
-/*!
- * \fntemplate int signum(T val)
- * Returns the signum of a value \a val.
- *
- * \sa QPair, QVector
- */
-template int signum(T val) { return (T(0) < val) - (val < T(0)); }
-} // namespace PlanimetryCalculus
diff --git a/src/Wima/Geometry/PolygonCalculus.cc b/src/Wima/Geometry/PolygonCalculus.cc
deleted file mode 100644
index a296ed1e98b74e23bef029f011e279f5e05d30ed..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/PolygonCalculus.cc
+++ /dev/null
@@ -1,578 +0,0 @@
-#include "PolygonCalculus.h"
-#include "PlanimetryCalculus.h"
-#include "Wima/OptimisationTools.h"
-
-#include
-
-#include
-
-namespace PolygonCalculus {
- namespace {
- bool isReflexVertex(const QPolygonF& polygon, const QPointF *vertex) {
- // Original Code from SurveyComplexItem::_VertexIsReflex()
- 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;
- }
-
- } // end anonymous namespace
-
- /*!
- * \fn bool containsPath(QPolygonF polygon, const QPointF &c1, const QPointF &c2)
- * Returns true if the shortest path between the two coordinates is not fully inside the \a area.
- *
- * \sa QPointF, QPolygonF
- */
- bool containsPath(QPolygonF polygon, const QPointF &c1, const QPointF &c2)
- {
-
- if ( !polygon.isEmpty()) {
- if ( !polygon.containsPoint(c1, Qt::FillRule::OddEvenFill)
- || !polygon.containsPoint(c2, Qt::FillRule::OddEvenFill))
- return false;
-
- QLineF line(c1, c2);
- if (PlanimetryCalculus::intersectsFast(polygon, line))
- return false;
- return true;
- } else {
- return false;
- }
- }
-
- /*!
- * \fn int closestVertexIndex(const QPolygonF &polygon, const QPointF &coordinate)
- * Returns the vertex index of \a polygon which has the least distance to \a coordinate.
- *
- * \sa QPointF, QPolygonF
- */
- int closestVertexIndex(const QPolygonF &polygon, const QPointF &coordinate)
- {
- if (polygon.size() == 0) {
- qWarning("Path is empty!");
- return -1;
- }else if (polygon.size() == 1) {
- return 0;
- }else {
- int index = 0; // the index of the closest vertex
- double min_dist = PlanimetryCalculus::distance(coordinate, polygon[index]);
- for(int i = 1; i < polygon.size(); i++){
- double dist = PlanimetryCalculus::distance(coordinate, polygon[i]);
- if (dist < min_dist){
- min_dist = dist;
- index = i;
- }
- }
- return index;
- }
- }
-
- /*!auto distance
- * \fn QPointF closestVertex(const QPolygonF &polygon, const QPointF &coordinate);
- * Returns the vertex of \a polygon with the least distance to \a coordinate.
- *
- * \sa QPointF, QPolygonF
- */
- QPointF closestVertex(const QPolygonF &polygon, const QPointF &coordinate)
- {
- int index = closestVertexIndex(polygon, coordinate);
- if (index >=0 ) {
- return polygon[index];
- } else {
- return QPointF();
- }
- }
-
- /*!
- * \fn int nextPolygonIndex(int pathsize, int index)
- * Returns the index of the next vertex (of a polygon), which is \a index + 1 if \a index is smaller than \c {\a pathsize - 1},
- * or 0 if \a index equals \c {\a pathsize - 1}, or -1 if the \a index is out of bounds.
- * \note \a pathsize is usually obtained by invoking polygon.size()
- */
- int nextVertexIndex(int pathsize, int index)
- {
- if (index >= 0 && index < pathsize-1) {
- return index + 1;
- } else if (index == pathsize-1) {
- return 0;
- } else {
- qWarning("nextPolygonIndex(): Index out of bounds! index:count = %i:%i", index, pathsize);
- return -1;
- }
- }
-
- /*!
- * \fn int previousPolygonIndex(int pathsize, int index)
- * Returns the index of the previous vertex (of a polygon), which is \a index - 1 if \a index is larger 0,
- * or \c {\a pathsize - 1} if \a index equals 0, or -1 if the \a index is out of bounds.
- * \note pathsize is usually obtained by invoking polygon.size()
- */
- int previousVertexIndex(int pathsize, int index)
- {
- if (index > 0 && index = 3 && polygon2.size() >= 3) {
-
- if ( !isSimplePolygon(polygon1) || !isSimplePolygon(polygon2)) {
- return JoinPolygonError::NotSimplePolygon;
- }
-
- if (polygon1 == polygon2) {
- joinedPolygon = polygon1;
- return JoinPolygonError::PolygonJoined;
- }
- if ( !hasClockwiseWinding(polygon1)) {
- reversePath(polygon1);
- }
- if ( !hasClockwiseWinding(polygon2)) {
- reversePath(polygon2);
- }
-
- const QPolygonF *walkerPoly = &polygon1; // "walk" on this polygon towards higher indices
- const QPolygonF *crossPoly = &polygon2; // check for crossings with this polygon while "walking"
- // and swicht to this polygon on a intersection,
- // continue to walk towards higher indices
-
- // begin with the first index which is not inside crosspoly, if all Vertices are inside crosspoly return crosspoly
- int startIndex = 0;
- bool crossContainsWalker = true;
- for (int i = 0; i < walkerPoly->size(); i++) {
- if ( !contains(*crossPoly, walkerPoly->at(i)) ) {
- crossContainsWalker = false;
- startIndex = i;
- break;
- }
- }
-
- if ( crossContainsWalker == true) {
- joinedPolygon.append(*crossPoly);
- return JoinPolygonError::PolygonJoined;
- }
- QPointF currentVertex = walkerPoly->at(startIndex);
- QPointF startVertex = currentVertex;
- // possible nextVertex (if no intersection between currentVertex and protoVertex with crossPoly)
- int nextVertexNumber = nextVertexIndex(walkerPoly->size(), startIndex);
- QPointF protoNextVertex = walkerPoly->value(nextVertexNumber);
- long counter = 0;
- while (1) {
- //qDebug("nextVertexNumber: %i", nextVertexNumber);
- joinedPolygon.append(currentVertex);
-
- QLineF walkerPolySegment;
- walkerPolySegment.setP1(currentVertex);
- walkerPolySegment.setP2(protoNextVertex);
-
- QVector> neighbourList;
- QVector intersectionList;
- //qDebug("IntersectionList.size() on init: %i", intersectionList.size());
- PlanimetryCalculus::intersects(*crossPoly, walkerPolySegment, intersectionList, neighbourList);
-
- //qDebug("IntersectionList.size(): %i", intersectionList.size());
-
- if (intersectionList.size() > 0) {
- int minDistIndex = -1;
-
- double minDist = std::numeric_limits::infinity();
- for (int i = 0; i < intersectionList.size(); i++) {
- double currentDist = PlanimetryCalculus::distance(currentVertex, intersectionList[i]);
-
- if ( minDist > currentDist && !qFuzzyIsNull(distance(currentVertex, intersectionList[i])) ) {
- minDist = currentDist;
- minDistIndex = i;
- }
- }
-
- if (minDistIndex != -1){
- currentVertex = intersectionList.value(minDistIndex);
- QPair neighbours = neighbourList.value(minDistIndex);
- protoNextVertex = crossPoly->value(neighbours.second);
- nextVertexNumber = neighbours.second;
-
- // switch walker and cross poly
- const QPolygonF *temp = walkerPoly;
- walkerPoly = crossPoly;
- crossPoly = temp;
- } else {
- currentVertex = walkerPoly->value(nextVertexNumber);
- nextVertexNumber = nextVertexIndex(walkerPoly->size(), nextVertexNumber);
- protoNextVertex = walkerPoly->value(nextVertexNumber);
- }
-
- } else {
- currentVertex = walkerPoly->value(nextVertexNumber);
- nextVertexNumber = nextVertexIndex(walkerPoly->size(), nextVertexNumber);
- protoNextVertex = walkerPoly->value(nextVertexNumber);
- }
-
- if (currentVertex == startVertex) {
- if (polygon1.size() == joinedPolygon.size()) {
- for (int i = 0; i < polygon1.size(); i++) {
- if (polygon1[i] != joinedPolygon[i])
- return PolygonJoined;
- }
- return Disjoint;
- } else {
- return PolygonJoined;
- }
- }
-
- counter++;
- if (counter > 1e5) {
- qWarning("PolygonCalculus::join(): no successfull termination!");
- return Error;
- }
- }
-
- } else {
- return PathSizeLow;
- }
- }
-
- /*!
- * \fn bool isSimplePolygon(const QPolygonF &polygon);
- * Returns \c true if \a polygon is a \l {Simple Polygon}, \c false else.
- * \note A polygon is a Simple Polygon iff it is not self intersecting.
- */
- bool isSimplePolygon(const QPolygonF &polygon)
- {
- int i = 0;
- if (polygon.size() > 3) {
- // check if any edge of the area (formed by two adjacent vertices) intersects with any other edge of the area
- while(i < polygon.size()-1) {
- double cCIntersectCounter = 0; // corner corner intersection counter
- QPointF refBeginCoordinate = polygon[i];
- QPointF refEndCoordinate = polygon[nextVertexIndex(polygon.size(), i)];
- QLineF refLine;
- refLine.setP1(refBeginCoordinate);
- refLine.setP2(refEndCoordinate);
- int j = nextVertexIndex(polygon.size(), i);
- while(j < polygon.size()) {
-
- QPointF intersectionPt;
- QLineF iteratorLine;
- iteratorLine.setP1(polygon[j]);
- iteratorLine.setP2(polygon[nextVertexIndex(polygon.size(), j)]);
- PlanimetryCalculus::IntersectType intersectType;
- PlanimetryCalculus::intersects(refLine, iteratorLine, intersectionPt, intersectType);
- if ( intersectType == PlanimetryCalculus::CornerCornerIntersection) {
- cCIntersectCounter++;
- // max two corner corner intersections allowed, a specific coordinate can appear only once in a simple polygon
- }
- if ( cCIntersectCounter > 2
- || intersectType == PlanimetryCalculus::EdgeEdgeIntersection
- || intersectType == PlanimetryCalculus::EdgeCornerIntersection
- || intersectType == PlanimetryCalculus::LinesEqual
- || intersectType == PlanimetryCalculus::Error){
- return false;
- }
-
- j++;
- }
- i++;
- }
- }
- return true;
- }
-
- /*!
- * \fn bool hasClockwiseWinding(const QPolygonF &polygon)
- * Returns \c true if \a path has clockwiauto distancese winding, \c false else.
- */
- bool hasClockwiseWinding(const QPolygonF &polygon)
- {
- if (polygon.size() <= 2) {
- return false;
- }
-
- double sum = 0;
- for (int i=0; i 2) {
-
- // Walk the edges, offsetting by theauto distance specified distance
- QList rgOffsetEdges;
- for (int i = 0; i < polygon.size(); i++) {
- int nextIndex = nextVertexIndex(polygon.size(), i);
- QLineF offsetEdge;
- QLineF originalEdge(polygon[i], polygon[nextIndex]);
-
- QLineF workerLine = originalEdge;
- workerLine.setLength(offset);
- workerLine.setAngle(workerLine.angle() - 90.0);
- offsetEdge.setP1(workerLine.p2());
-
- workerLine.setPoints(originalEdge.p2(), originalEdge.p1()); bool containsPath (const QPointF &c1, const QPointF &c2, QPolygonF polygon);
- workerLine.setLength(offset);
- workerLine.setAngle(workerLine.angle() + 90.0);
- offsetEdge.setP2(workerLine.p2());
-
- rgOffsetEdges << offsetEdge;
- }
-
- // Intersect the offset edges to generate new vertices
- polygon.clear();
- QPointF newVertex;
- for (int i=0; i &convexPolygons)
- {
- // Original Code SurveyComplexItem::_PolygonDecomposeConvex()
- // this follows "Mark Keil's Algorithm" https://mpen.ca/406/keil
- int decompSize = std::numeric_limits::max();
- if (polygon.size() < 3) return;
- if (polygon.size() == 3) {
- convexPolygons << polygon;
- return;
- }
-
- QList decomposedPolygonsMin{};
-
- for (const QPointF *vertex = polygon.begin(); vertex != polygon.end(); ++vertex)
- {
- // is vertex reflex?
- bool vertexIsReflex = isReflexVertex(polygon, vertex);
-
- if (!vertexIsReflex) continue;
-
- for (const QPointF *vertexOther = polygon.begin(); vertexOther != polygon.end(); ++vertexOther)
- {
- const QPointF *vertexBefore = vertex == polygon.begin() ? polygon.end() - 1 : vertex - 1;
- const QPointF *vertexAfter = vertex == polygon.end() - 1 ? polygon.begin() : vertex + 1;
- if (vertexOther == vertex) continue;
- if (vertexAfter == vertexOther) continue;
- if (vertexBefore == vertexOther) continue;
- bool canSee = containsPath(polygon, *vertex, *vertexOther);
- if (!canSee) continue;
-
- QPolygonF polyLeft;
- const QPointF *v = vertex;
- bool polyLeftContainsReflex = false;
- while ( v != vertexOther) {
- if (v != vertex && isReflexVertex(polygon, v)) {
- polyLeftContainsReflex = true;
- }
- polyLeft << *v;
- ++v;
- if (v == polygon.end()) v = polygon.begin();
- }
- polyLeft << *vertexOther;
- bool polyLeftValid = !(polyLeftContainsReflex && polyLeft.size() == 3);
-
- QPolygonF polyRight;
- v = vertexOther;
- bool polyRightContainsReflex = false;
- while ( v != vertex) {
- if (v != vertex && isReflexVertex(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::max();
- continue;
- }
-
- // recursion
- QList polyLeftDecomposed{};
- decomposeToConvex(polyLeft, polyLeftDecomposed);
-
- QList polyRightDecomposed{};
- decomposeToConvex(polyRight, polyRightDecomposed);
-
- // compositon
- int 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::max();
- }
- if (subSize < decompSize) {
- decompSize = subSize;
- decomposedPolygonsMin = polyLeftDecomposed + polyRightDecomposed;
- }
- }
- }
-
- // assemble output
- if (decomposedPolygonsMin.size() > 0) {
- convexPolygons << decomposedPolygonsMin;
- } else {
- convexPolygons << polygon;
- }
-
- return;
- }
-
- bool shortestPath(const QPolygonF &polygon,const QPointF &startVertex, const QPointF &endVertex, QVector &shortestPath)
- {
- using namespace PlanimetryCalculus;
- QPolygonF bigPolygon(polygon);
- offsetPolygon(bigPolygon, 0.5); // solves numerical errors
- if ( bigPolygon.containsPoint(startVertex, Qt::FillRule::OddEvenFill)
- && bigPolygon.containsPoint(endVertex, Qt::FillRule::OddEvenFill)) {
-
- QVector elementList;
- elementList.append(startVertex);
- elementList.append(endVertex);
- for (auto vertex : polygon) elementList.append(vertex);
- const int listSize = elementList.size();
-
-
- std::function distanceDij = [bigPolygon, elementList](const int ind1, const int ind2) -> double {
- QPointF p1 = elementList[ind1];
- QPointF p2 = elementList[ind2];
- double dist = std::numeric_limits::infinity();
- if (containsPathFast(bigPolygon, p1, p2)){ // containsPathFast can be used since all points are inside bigPolygon
- double dx = p1.x()-p2.x();
- double dy = p1.y()-p2.y();
- dist = sqrt((dx*dx)+(dy*dy));
- }
-
- return dist;
- };
-
- QVector shortestPathIndex;
- bool retVal = OptimisationTools::dijkstraAlgorithm(listSize, 0, 1, shortestPathIndex, distanceDij);
- for (auto index : shortestPathIndex) shortestPath.append(elementList[index]);
- return retVal;
- } else {
- return false;
- }
- }
-
- QVector3DList toQVector3DList(const QPolygonF &polygon)
- {
- QVector3DList list;
- for ( auto vertex : polygon )
- list.append(QVector3D(vertex));
-
- return list;
- }
-
- QPolygonF toQPolygonF(const QPointFList &listF)
- {
- QPolygonF polygon;
- for ( auto vertex : listF )
- polygon.append(vertex);
-
- return polygon;
- }
-
- QPointFList toQPointFList(const QPolygonF &polygon)
- {
- QPointFList listF;
- for ( auto vertex : polygon )
- listF.append(vertex);
-
- return listF;
- }
-
- void reversePath(QPointFList &path)
- {
- QPointFList pathReversed;
- for ( auto element : path) {
- pathReversed.prepend(element);
- }
- path = pathReversed;
- }
-
- void reversePath(QPointFVector &path)
- {
- QPointFVector pathReversed;
- for ( auto element : path) {
- pathReversed.prepend(element);
- }
- path = pathReversed;
- }
-
-
-
- bool containsPathFast(QPolygonF polygon, const QPointF &c1, const QPointF &c2)
- {
-
- if ( !polygon.isEmpty()) {
- QLineF line(c1, c2);
- if (PlanimetryCalculus::intersectsFast(polygon, line))
- return false;
- return true;
- } else {
- return false;
- }
- }
-
-
-
-} // end PolygonCalculus namespace
-
diff --git a/src/Wima/Geometry/PolygonCalculus.h b/src/Wima/Geometry/PolygonCalculus.h
deleted file mode 100644
index 6914a1555c855f5e5aebe120d89bda1f68e784a6..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/PolygonCalculus.h
+++ /dev/null
@@ -1,45 +0,0 @@
-#pragma once
-
-
-#include
-#include
-#include
-
-
-
-namespace PolygonCalculus {
-
- enum JoinPolygonError { NotSimplePolygon, PolygonJoined, Disjoint, PathSizeLow, Error};
-
- typedef QList QVector3DList;
- typedef QList QPointFList;
- typedef QVector QPointFVector;
-
- int closestVertexIndex (const QPolygonF &polygon, const QPointF &coordinate);
- QPointF closestVertex (const QPolygonF &polygon, const QPointF &coordinate);
- int nextVertexIndex (int pathsize, int index);
- int previousVertexIndex (int pathsize, int index);
- JoinPolygonError join (QPolygonF polygon1, QPolygonF polygon2, QPolygonF &joinedPolygon);
- bool isSimplePolygon (const QPolygonF &polygon);
- bool hasClockwiseWinding (const QPolygonF &path);
- void reversePath (QPolygonF &path);
- void reversePath (QPointFList &path);
- void reversePath (QPointFVector &path);
- void offsetPolygon (QPolygonF &polygon, double offset);
- // returns true if the line c1-c2 is fully inside the polygon
- bool containsPath (QPolygonF polygon, const QPointF &c1, const QPointF &c2);
- // same as containsPath(), but works only if c1 and c2 are inside the polygon!
- bool containsPathFast (QPolygonF polygon, const QPointF &c1, const QPointF &c2);
- void decomposeToConvex (const QPolygonF &polygon, QList &convexPolygons);
- bool shortestPath (const QPolygonF &polygon, const QPointF &startVertex, const QPointF &endVertex, QVector &shortestPath);
-
- QPolygonF toQPolygonF(const QVector3DList &polygon);
- QPolygonF toQPolygonF(const QPointFList &polygon);
- QLineF toQLineF(const QVector3DList &line);
- QPointFList toQPointFList(const QVector3DList &list);
- QPointFList toQPointFList(const QPolygonF &list);
- QVector3DList toQVector3DList(const QPointFList &listF);
- QVector3DList toQVector3DList(const QPolygonF &listF);
-}
-
-
diff --git a/src/Wima/Geometry/TestPolygonCalculus.cpp b/src/Wima/Geometry/TestPolygonCalculus.cpp
deleted file mode 100644
index 474e43b25751730c4c7342f26a6a89b86f777792..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/TestPolygonCalculus.cpp
+++ /dev/null
@@ -1,33 +0,0 @@
-#include "TestPolygonCalculus.h"
-#include "PolygonCalculus.h"
-#include
-#include
-
-namespace TestPolygonCalculus {
- void test()
- {
- using namespace PolygonCalculus;
-
- QPolygonF polygon;
- polygon << QPointF(0, 0) << QPointF(1, 0) << QPointF(1, 1) << QPointF(0, 1);
-
- bool retVal = containsPath(polygon, QPointF(0.1, 0.1), QPointF(0.2, 0.1));
- qDebug("true %i", retVal);
- retVal = containsPath(polygon, QPointF(0.2, 0.1), QPointF(0.2, 0.1));
- qDebug("true %i", retVal);
- retVal = containsPath(polygon, QPointF(1, 0.1), QPointF(0.2, 0.1));
- qDebug("true %i", retVal);
- retVal = containsPath(polygon, QPointF(0.1, 0.1), QPointF(1, 0.1));
- qDebug("true %i", retVal);
- retVal = containsPath(polygon, QPointF(2, 0.1), QPointF(0.2, 0.1));
- qDebug("false %i", retVal);
- retVal = containsPath(polygon, QPointF(-2, 0.1), QPointF(0.2, 0.1));
- qDebug("false %i", retVal);
- polygon << QPointF(0.5, 0.6) << QPointF(0.5, 0.4);
- retVal = containsPath(polygon, QPointF(0.2, 0.1), QPointF(0.2, 0.9));
- qDebug("false %i", retVal);
- retVal = containsPath(polygon, QPointF(0.1, 0.05), QPointF(0.51, 0.6));
- qDebug("false %i", retVal);
- }
-
-}
diff --git a/src/Wima/Geometry/TestPolygonCalculus.h b/src/Wima/Geometry/TestPolygonCalculus.h
deleted file mode 100644
index 0212676bbfff46daafa97b2275ca0ac86d287905..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/TestPolygonCalculus.h
+++ /dev/null
@@ -1,9 +0,0 @@
-#ifndef TESTPOLYGONCALCULUS_H
-#define TESTPOLYGONCALCULUS_H
-
-
-
-namespace TestPolygonCalculus {
- void test();
-}
-#endif // TESTPOLYGONCALCULUS_H
diff --git a/src/Wima/Geometry/WimaArea.cc b/src/Wima/Geometry/WimaArea.cc
deleted file mode 100644
index d4681a10500fd455c2afbd609fc1bd0dda855bc7..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaArea.cc
+++ /dev/null
@@ -1,548 +0,0 @@
-#include "WimaArea.h"
-
-/*!
- * \variable WimaArea::epsilonMeter
- * \brief The accuracy used for distance calculations (unit: m).
- */
-const double WimaArea::epsilonMeter = 1e-5;
-/*!
- * \variable WimaArea::maxAltitudeName
- * \brief A string containing the name of the \c _maxAltitude member. Among
- * other used for storing.
- */
-const char *WimaArea::maxAltitudeName = "maxAltitude";
-/*!
- * \variable WimaArea::wimaAreaName
- * \brief A string containing the name of this \c WimaArea member. Among other
- * used for storing.
- */
-const char *WimaArea::wimaAreaName = "WimaArea";
-/*!
- * \variable WimaArea::areaTypeName
- * \brief A string containing \c {"AreaType"}. Among other used for stroing.
- */
-const char *WimaArea::areaTypeName = "AreaType";
-
-const char *WimaArea::borderPolygonOffsetName = "BorderPolygonOffset";
-const char *WimaArea::showBorderPolygonName = "ShowBorderPolygon";
-const char *WimaArea::settingsGroup = "MeasurementArea";
-
-// Constructors
-WimaArea::WimaArea(QObject *parent)
- : QGCMapPolygon(parent),
- _metaDataMap(FactMetaData::createMapFromJsonFile(
- QStringLiteral(":/json/WimaArea.SettingsGroup.json"),
- this /* QObject parent */)),
- _borderPolygonOffset(SettingsFact(settingsGroup,
- _metaDataMap[borderPolygonOffsetName],
- this /* QObject parent */)),
- _showBorderPolygon(SettingsFact(settingsGroup,
- _metaDataMap[showBorderPolygonName],
- this /* QObject parent */)),
- _borderPolygon(QGCMapPolygon(this)), _wimaAreaInteractive(false) {
- init();
- _maxAltitude = 30;
-}
-
-WimaArea::WimaArea(const WimaArea &other, QObject *parent)
- : QGCMapPolygon(parent),
- _metaDataMap(FactMetaData::createMapFromJsonFile(
- QStringLiteral(":/json/WimaArea.SettingsGroup.json"),
- this /* QObject parent */)),
- _borderPolygonOffset(SettingsFact(settingsGroup,
- _metaDataMap[borderPolygonOffsetName],
- this /* QObject parent */)),
- _showBorderPolygon(SettingsFact(settingsGroup,
- _metaDataMap[showBorderPolygonName],
- this /* QObject parent */)),
- _borderPolygon(QGCMapPolygon(this)), _wimaAreaInteractive(false) {
- init();
- *this = other;
-}
-
-/*!
- *\fn WimaArea &WimaArea::operator=(const WimaArea &other)
- *
- * Assigns \a other to this \c WimaArea and returns a reference to this \c
- *WimaArea.
- *
- * Copies only path and maximum altitude.
- */
-WimaArea &WimaArea::operator=(const WimaArea &other) {
- QGCMapPolygon::operator=(other);
- this->setMaxAltitude(other._maxAltitude);
- this->setPath(other.path());
-
- return *this;
-}
-
-void WimaArea::setWimaAreaInteractive(bool interactive) {
- if (WimaArea::_wimaAreaInteractive != interactive) {
- WimaArea::_wimaAreaInteractive = interactive;
-
- emit WimaArea::wimaAreaInteractiveChanged();
- }
-}
-
-/*!
- \fn void WimaArea::setMaxAltitude(double altitude)
-
- Sets the \c _maxAltitude member to \a altitude and emits the signal \c
- maxAltitudeChanged() if \c _maxAltitude is not equal to altitude.
- */
-void WimaArea::setMaxAltitude(double altitude) {
- if (altitude > 0 && qFuzzyCompare(altitude, _maxAltitude)) {
- _maxAltitude = altitude;
- emit maxAltitudeChanged();
- }
-}
-
-void WimaArea::setShowBorderPolygon(bool showBorderPolygon) {
- _showBorderPolygon.setRawValue(showBorderPolygon);
-}
-
-void WimaArea::setBorderPolygonOffset(double offset) {
- if (!qFuzzyCompare(_borderPolygonOffset.rawValue().toDouble(), offset)) {
- _borderPolygonOffset.setRawValue(offset);
-
- emit borderPolygonOffsetChanged();
- }
-}
-
-void WimaArea::recalcPolygons() {
- if (_showBorderPolygon.rawValue().toBool() == true) {
-
- if (_borderPolygon.count() >= 3) {
- //_borderPolygon.verifyClockwiseWinding(); // causes seg. fault
- this->setPath(_borderPolygon.coordinateList());
- this->offset(-_borderPolygonOffset.rawValue().toDouble());
- }
- } else {
-
- if (this->count() >= 3) {
- // this->verifyClockwiseWinding(); // causes seg. fault
- _borderPolygon.setPath(this->coordinateList());
- _borderPolygon.offset(_borderPolygonOffset.rawValue().toDouble());
- }
-
- emit borderPolygonChanged();
- }
-}
-
-void WimaArea::updatePolygonConnections(QVariant showBorderPolygon) {
- if (showBorderPolygon.toBool() == true) {
- connect(&_borderPolygon, &QGCMapPolygon::pathChanged, this,
- &WimaArea::recalcPolygons);
- disconnect(this, &QGCMapPolygon::pathChanged, this,
- &WimaArea::recalcPolygons);
- } else {
- disconnect(&_borderPolygon, &QGCMapPolygon::pathChanged, this,
- &WimaArea::recalcPolygons);
- connect(this, &QGCMapPolygon::pathChanged, this, &WimaArea::recalcPolygons);
- }
-}
-
-void WimaArea::recalcInteractivity() {
- if (_wimaAreaInteractive == false) {
- QGCMapPolygon::setInteractive(false);
- _borderPolygon.setInteractive(false);
- } else {
- if (_showBorderPolygon.rawValue().toBool() == true) {
- _borderPolygon.setInteractive(true);
- QGCMapPolygon::setInteractive(false);
- } else {
- _borderPolygon.setInteractive(false);
- QGCMapPolygon::setInteractive(true);
- }
- }
-}
-
-/*!
- * \fn int WimaArea::getClosestVertexIndex(const QGeoCoordinate &coordinate)
- * const Returns the index of the vertex (element of the polygon path) which has
- * the least distance to \a coordinate.
- *
- * \sa QGeoCoordinate
- */
-int WimaArea::getClosestVertexIndex(const QGeoCoordinate &coordinate) const {
- if (this->count() == 0) {
- qWarning("Polygon count == 0!");
- return -1;
- } else if (this->count() == 1) {
- return 0;
- } else {
- int index = 0;
- double min_dist = coordinate.distanceTo(this->vertexCoordinate(index));
- for (int i = 1; i < this->count(); i++) {
- double dist = coordinate.distanceTo(this->vertexCoordinate(i));
- if (dist < min_dist) {
- min_dist = dist;
- index = i;
- }
- }
-
- return index;
- }
-}
-
-/*!
- * \fn QGeoCoordinate WimaArea::getClosestVertex(const QGeoCoordinate&
- * coordinate) const Returns the vertex of the polygon path with the least
- * distance to \a coordinate.
- *
- * \sa QGeoCoordinate
- */
-QGeoCoordinate
-WimaArea::getClosestVertex(const QGeoCoordinate &coordinate) const {
- return this->vertexCoordinate(getClosestVertexIndex(coordinate));
-}
-
-/*!
- * \fn QGCMapPolygon WimaArea::toQGCPolygon(const WimaArea &area)
- * Converts the \c WimaArea \a area to \c QGCMapPolygon by copying the path
- * only.
- */
-QGCMapPolygon WimaArea::toQGCPolygon(const WimaArea &area) {
- QGCMapPolygon qgcPoly;
- qgcPoly.setPath(area.path());
-
- return QGCMapPolygon(qgcPoly);
-}
-
-/*!
- * \fn QGCMapPolygon WimaArea::toQGCPolygon() const
- * Converts the calling \c WimaArea to \c QGCMapPolygon by copying the path
- * only.
- */
-QGCMapPolygon WimaArea::toQGCPolygon() const { return toQGCPolygon(*this); }
-
-/*!
- * \fn bool WimaArea::join(WimaArea &area1, WimaArea &area2, WimaArea
- * &joinedArea, QString &errorString) Joins the areas \a area1 and \a area2 such
- * that a \l {Simple Polygon} is created. Stores the result inside \a
- * joinedArea. Stores error messages in \a errorString. Returns \c true if the
- * algorithm was able to join the areas; false else. The algorithm will be able
- * to join the areas, if either their edges intersect with each other, or one
- * area contains the other.
- */
-bool WimaArea::join(const WimaArea &area1, const WimaArea &area2,
- WimaArea &joinedArea, QString &errorString) {
- using namespace GeoUtilities;
- using namespace PolygonCalculus;
-
- Q_UNUSED(errorString);
-
- QList GeoPolygon1 = area1.coordinateList();
- QList GeoPolygon2 = area2.coordinateList();
-
- // qWarning("befor joining");
- // qWarning() << GeoPolygon1;
- // qWarning() << GeoPolygon2;
-
- QGeoCoordinate origin = GeoPolygon1[0];
-
- // QGeoCoordinate tset = GeoPolygon1[2];
-
- // qWarning() << tset;qWarning() << toGeo(toCartesian2D(tset, origin),
- // origin);
-
- QPolygonF polygon1;
- toCartesianList(GeoPolygon1, origin, polygon1);
- QPolygonF polygon2;
- toCartesianList(GeoPolygon2, origin, polygon2);
-
- // qWarning("after 1 transform");
- // qWarning() << polygon1;
- // qWarning() << polygon2;
-
- QPolygonF joinedPolygon;
- JoinPolygonError retValue =
- PolygonCalculus::join(polygon1, polygon2, joinedPolygon);
-
- // qWarning("after joining");
- // qWarning() << joinedPolygon;
-
- if (retValue == JoinPolygonError::Disjoint) {
- qWarning("Polygons are disjoint.");
- } else if (retValue == JoinPolygonError::NotSimplePolygon) {
- qWarning("Not a simple polygon.");
- } else if (retValue == JoinPolygonError::PathSizeLow) {
- qWarning("Polygon vertex count is low.");
- } else {
- QList path;
- toGeoList(joinedPolygon, origin, path);
- // qWarning("after transform");
- // qWarning() << path;
- joinedArea.setPath(path);
- return true;
- }
-
- return false;
-}
-
-/*!
- * \fn bool WimaArea::join(WimaArea &area1, WimaArea &area2, WimaArea
- * &joinedArea) Joins the areas \a area1 and \a area2 such that a \l {Simple
- * Polygon} is created. Stores the result inside \a joinedArea. Returns \c true
- * if the algorithm was able to join the areas; false else. The algorithm will
- * be able to join the areas, if either their edges intersect with each other,
- * or one area contains the other.
- */
-bool WimaArea::join(const WimaArea &area1, const WimaArea &area2,
- WimaArea &joinedArea) {
- QString dummy;
- return join(area1, area2, joinedArea, dummy);
-}
-
-/*!
- * \fn bool WimaArea::join(WimaArea &area)
- * Joins the calling \c WimaArea and the \a area such that a \l {Simple Polygon}
- * is created. Overwrites the calling \c WimaArea with the result, if the
- * algorithm was successful. Returns \c true if the algorithm was able to join
- * the areas; false else. The algorithm will be able to join the areas, if
- * either their edges intersect with each other, or one area contains the other.
- */
-bool WimaArea::join(WimaArea &area) {
- WimaArea joinedArea;
- if (join(*this, area, joinedArea)) {
- // qWarning("WimaArea::join(WimaArea &area)");
- // qWarning() << joinedArea.coordinateList();
- this->setPath(joinedArea.path());
- return true;
- } else {
- return false;
- }
-}
-
-/*!
- * \fn bool WimaArea::join(WimaArea &area, QString &errorString)
- * Joins the calling \c WimaArea and the \a area such that a \l {Simple Polygon}
- * is created. Overwrites the calling \c WimaArea with the result, if the
- * algorithm was successful.
- *
- * Returns \c true if the algorithm was able to join the areas; false else.
- * Stores error messages in \a errorString.
- *
- * The algorithm will be able to join the areas, if either their edges intersect
- * with each other, or one area contains the other.
- */
-bool WimaArea::join(WimaArea &area, QString &errorString) {
- WimaArea joinedArea;
- if (join(*this, area, joinedArea, errorString)) {
- this->setPath(joinedArea.path());
- return true;
- } else {
- return false;
- }
-}
-
-/*!
- * \fn int WimaArea::nextVertexIndex(int index) const
- * Returns the index of the next vertex (of the areas path), which is \a index +
- * 1 if \a index is smaller than \c {area.count() - 1}, or 0 if \a index equals
- * \c {area.count() - 1}, or -1 if the \a index is out of bounds. \note The
- * function \c {area.count()} (derived from \c QGCMapPolygon) returns the number
- * of vertices defining the area.
- */
-int WimaArea::nextVertexIndex(int index) const {
- if (index >= 0 && index < count() - 1) {
- return index + 1;
- } else if (index == count() - 1) {
- return 0;
- } else {
- qWarning(
- "WimaArea::nextVertexIndex(): Index out of bounds! index:count = %i:%i",
- index, count());
- return -1;
- }
-}
-
-/*!
- * \fn int WimaArea::previousVertexIndex(int index) const
- * Returns the index of the previous vertex (of the areas path), which is \a
- * index - 1 if \a index is larger 0, or \c {area.count() - 1} if \a index
- * equals 0, or -1 if the \a index is out of bounds. \note The function \c
- * {area.count()} (derived from \c QGCMapPolygon) returns the number of vertices
- * defining the area.
- */
-int WimaArea::previousVertexIndex(int index) const {
- if (index > 0 && index < count()) {
- return index - 1;
- } else if (index == 0) {
- return count() - 1;
- } else {
- qWarning("WimaArea::previousVertexIndex(): Index out of bounds! "
- "index:count = %i:%i",
- index, count());
- return -1;
- }
-}
-
-/*!
- * \fn bool WimaArea::isSelfIntersecting()
- * Returns \c true if the calling area is self intersecting, \c false else.
- * \note If the calling area is self intersecting, it's not a \l {Simple
- * Polygon}.
- */
-bool WimaArea::isSimplePolygon() const {
- using namespace PolygonCalculus;
- using namespace GeoUtilities;
-
- if (this->count() > 2) {
- QPolygonF polygon;
- toCartesianList(this->coordinateList(), this->vertexCoordinate(0), polygon);
- return PolygonCalculus::isSimplePolygon(polygon);
- } else
- return false;
-}
-
-bool WimaArea::containsCoordinate(const QGeoCoordinate &coordinate) const {
- using namespace PlanimetryCalculus;
- using namespace PolygonCalculus;
- using namespace GeoUtilities;
-
- if (this->count() > 2) {
- QPolygonF polygon;
- toCartesianList(this->coordinateList(), coordinate, polygon);
- return PlanimetryCalculus::contains(polygon, QPointF(0, 0));
- } else
- return false;
-}
-
-/*!
- * \fn void WimaArea::saveToJson(QJsonObject &json)
- * Saves the calling area to \c QJsonObject object and stores it inside \a json.
- *
- * \sa QJsonObject
- */
-void WimaArea::saveToJson(QJsonObject &json) {
- this->QGCMapPolygon::saveToJson(json);
-
- json[maxAltitudeName] = _maxAltitude;
- json[borderPolygonOffsetName] = _borderPolygonOffset.rawValue().toDouble();
- json[showBorderPolygonName] = _showBorderPolygon.rawValue().toDouble();
- json[areaTypeName] = wimaAreaName;
-}
-
-/*!
- * \fn bool WimaArea::loadFromJson(const QJsonObject &json, QString&
- * errorString) Loads data from \a json and stores it inside the calling area.
- * Returns \c true if loading was successful, \c false else.
- * Stores error messages inside \a errorString.
- *
- * \sa QJsonObject
- */
-bool WimaArea::loadFromJson(const QJsonObject &json, QString &errorString) {
- if (this->QGCMapPolygon::loadFromJson(json, false /*no poly required*/,
- errorString)) {
- if (json.contains(maxAltitudeName) && json[maxAltitudeName].isDouble()) {
- _maxAltitude = json[maxAltitudeName].toDouble();
- } else {
- errorString.append(tr("Could not load Maximum Altitude value!\n"));
- return false;
- }
-
- if (json.contains(borderPolygonOffsetName) &&
- json[borderPolygonOffsetName].isDouble()) {
- _borderPolygonOffset.setRawValue(
- json[borderPolygonOffsetName].toDouble());
- } else {
- errorString.append(tr("Could not load border polygon offset value!\n"));
- return false;
- }
-
- if (json.contains(showBorderPolygonName) &&
- json[showBorderPolygonName].isDouble()) {
- _showBorderPolygon.setRawValue(json[showBorderPolygonName].toBool());
- } else {
- errorString.append(tr("Could not load border polygon offset value!\n"));
- return false;
- }
- } else {
- qWarning() << errorString;
- return false;
- }
-
- return true;
-}
-
-/*!
- * \fn void WimaArea::init()
- * Funtion to be called during construction.
- */
-void WimaArea::init() {
- this->setObjectName(wimaAreaName);
-
- if (_showBorderPolygon.rawValue().toBool() == true) {
- connect(&_borderPolygon, &QGCMapPolygon::pathChanged, this,
- &WimaArea::recalcPolygons);
-
- } else {
- connect(this, &QGCMapPolygon::pathChanged, this, &WimaArea::recalcPolygons);
- }
-
- connect(&_borderPolygonOffset, &SettingsFact::rawValueChanged, this,
- &WimaArea::recalcPolygons);
- connect(&_showBorderPolygon, &SettingsFact::rawValueChanged, this,
- &WimaArea::updatePolygonConnections);
- connect(&_showBorderPolygon, &SettingsFact::rawValueChanged, this,
- &WimaArea::recalcInteractivity);
- connect(this, &WimaArea::wimaAreaInteractiveChanged, this,
- &WimaArea::recalcInteractivity);
-}
-
-// QDoc Documentation
-
-/*!
- \group WimaAreaGroup
- \title Group of WimaAreas
-
- Every \c WimaArea of the equally named group uses a \l {Simple Polygon}
- derived from \c {QGCMapPolygon} to define areas inside which certain taskts
- are performed.
-*/
-
-/*!
- \class WimaArea
- \inmodule Wima
- \ingroup WimaArea
-
- \brief The \c WimaArea class provides the a base class for
- all areas used within the Wima extension.
-
- \c WimaArea uses a \l {Simple Polygon} derived from \c {QGCMapPolygon}
- to define areas inside which certain taskts are performed. The polygon
- (often refered to as the path) can be displayed visually on a map.
-*/
-
-/*!
- \variable WimaArea::_maxAltitude
- \brief The maximum altitude vehicles are allowed to fly inside this area.
-*/
-
-/*!
- \property WimaArea::maxAltitude
- \brief The maximum altitude at which vehicles are allowed to fly.
-*/
-
-/*!
- \property WimaArea::mapVisualQML
- \brief A string containing the name of the QML file used to displays this area
- on a map.
-*/
-
-/*!
- \property WimaArea::editorQML
- \brief A string containing the name of the QML file allowing to edit the
- area's properties.
-*/
-
-/*!
- \externalpage https://en.wikipedia.org/wiki/Simple_polygon
- \title Simple Polygon
-*/
-
-/*!
- \externalpage https://en.wikipedia.org/wiki/Dijkstra%27s_algorithm
- \title Dijkstra Algorithm
-*/
diff --git a/src/Wima/Geometry/WimaArea.h b/src/Wima/Geometry/WimaArea.h
deleted file mode 100644
index 69fbeff5e1c5c712ad990a9aab63d0e456cb4b06..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaArea.h
+++ /dev/null
@@ -1,114 +0,0 @@
-#pragma once
-
-#include "QGCGeo.h"
-#include "QGCMapPolygon.h"
-#include "QGCMapPolyline.h"
-#include "Vehicle.h"
-#include "qobject.h"
-#include
-#include
-#include
-
-#include "GeoUtilities.h"
-#include "PlanimetryCalculus.h"
-#include "PolygonCalculus.h"
-
-class WimaArea : public QGCMapPolygon // abstract base class for all WimaAreas
-{
- Q_OBJECT
-public:
- WimaArea(QObject *parent = nullptr);
- WimaArea(const WimaArea &other, QObject *parent = nullptr);
- WimaArea &operator=(const WimaArea &other);
-
- Q_PROPERTY(double maxAltitude READ maxAltitude WRITE setMaxAltitude NOTIFY
- maxAltitudeChanged)
- Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT)
- Q_PROPERTY(QString editorQML READ editorQML CONSTANT)
- Q_PROPERTY(Fact *borderPolygonOffset READ borderPolygonOffsetFact CONSTANT)
- Q_PROPERTY(QGCMapPolygon *borderPolygon READ borderPolygon NOTIFY
- borderPolygonChanged)
- Q_PROPERTY(Fact *showBorderPolygon READ showBorderPolygon CONSTANT)
- Q_PROPERTY(bool wimaAreaInteractive READ wimaAreaInteractive WRITE
- setWimaAreaInteractive NOTIFY wimaAreaInteractiveChanged)
-
- // Property accessors
- double maxAltitude(void) const { return _maxAltitude; }
- Fact *borderPolygonOffsetFact(void) { return &_borderPolygonOffset; }
- Fact *showBorderPolygon(void) { return &_showBorderPolygon; }
- double borderPolygonOffset(void) const {
- return _borderPolygonOffset.rawValue().toDouble();
- }
- QGCMapPolygon *borderPolygon(void) { return &_borderPolygon; }
- bool wimaAreaInteractive(void) const { return _wimaAreaInteractive; }
-
- void setWimaAreaInteractive(bool interactive);
-
- // overrides from WimaArea
- virtual QString mapVisualQML(void) const { return ""; }
- virtual QString editorQML(void) const { return ""; }
-
- // Member Methodes
- int getClosestVertexIndex(const QGeoCoordinate &coordinate) const;
- QGeoCoordinate getClosestVertex(const QGeoCoordinate &coordinate) const;
- QGCMapPolygon toQGCPolygon() const;
- bool join(WimaArea &area);
- bool join(WimaArea &area, QString &errorString);
- int nextVertexIndex(int index) const;
- int previousVertexIndex(int index) const;
- bool isSimplePolygon() const;
- bool containsCoordinate(const QGeoCoordinate &coordinate) const;
-
- void saveToJson(QJsonObject &jsonObject);
- bool loadFromJson(const QJsonObject &jsonObject, QString &errorString);
-
- // static Methodes
- static QGCMapPolygon toQGCPolygon(const WimaArea &area);
- static bool join(const WimaArea &area1, const WimaArea &area2,
- WimaArea &joinedArea, QString &errorString);
- static bool join(const WimaArea &area1, const WimaArea &area2,
- WimaArea &joinedArea);
-
- // Friends
- friend void print(const WimaArea &area, QString &outputString);
- friend void print(const WimaArea &area);
-
- // static Members
- // Accurracy used to compute isDisjunct
- static const double epsilonMeter;
- static const char *maxAltitudeName;
- static const char *wimaAreaName;
- static const char *areaTypeName;
- static const char *borderPolygonOffsetName;
- static const char *showBorderPolygonName;
- static const char *settingsGroup;
-
-signals:
- void maxAltitudeChanged(void);
- void borderPolygonChanged(void);
- void borderPolygonOffsetChanged(void);
- void wimaAreaInteractiveChanged(void);
-
-public slots:
- void setMaxAltitude(double altitude);
- void setShowBorderPolygon(bool showBorderPolygon);
- void setBorderPolygonOffset(double offset);
-
-private slots:
- void recalcPolygons(void);
- void updatePolygonConnections(QVariant value);
- void recalcInteractivity(void);
-
-private:
- void init();
-
- double _maxAltitude;
-
- QMap _metaDataMap;
- SettingsFact _borderPolygonOffset;
- SettingsFact _showBorderPolygon;
-
- QGCMapPolygon _borderPolygon;
-
- bool _wimaAreaInteractive;
-};
diff --git a/src/Wima/Geometry/WimaAreaData.cc b/src/Wima/Geometry/WimaAreaData.cc
deleted file mode 100644
index ca977dc226454138182d6dd182a09cb5e4bce920..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaAreaData.cc
+++ /dev/null
@@ -1,138 +0,0 @@
-#include "WimaAreaData.h"
-
-WimaAreaData::WimaAreaData(QObject *parent) : QObject(parent) {}
-
-WimaAreaData::WimaAreaData(const WimaAreaData &other, QObject *parent)
- : QObject(parent), _path(other._path), _list(other._list),
- _center(other._center) {}
-
-WimaAreaData::WimaAreaData(const WimaArea &otherData, QObject *parent)
- : QObject(parent), _center(otherData.center()) {
- _setPathImpl(otherData.path());
-}
-
-bool WimaAreaData::operator==(const WimaAreaData &data) const {
- return this->_path == data._path && this->_center == data._center;
-}
-
-bool WimaAreaData::operator!=(const WimaAreaData &data) const {
- return !this->operator==(data);
-}
-
-QVariantList WimaAreaData::path() const { return _path; }
-
-QGeoCoordinate WimaAreaData::center() const { return _center; }
-
-const QList &WimaAreaData::coordinateList() const {
- return _list;
-}
-
-bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const {
- using namespace PlanimetryCalculus;
- using namespace PolygonCalculus;
- using namespace GeoUtilities;
-
- if (this->coordinateList().size() > 2) {
- QPolygonF polygon;
- toCartesianList(this->coordinateList(), coordinate, polygon);
- return PlanimetryCalculus::contains(polygon, QPointF(0, 0));
- } else
- return false;
-}
-
-void WimaAreaData::append(const QGeoCoordinate &c) {
- _list.append(c);
- _path.push_back(QVariant::fromValue(c));
- emit pathChanged();
-}
-
-void WimaAreaData::push_back(const QGeoCoordinate &c) { append(c); }
-
-void WimaAreaData::clear() {
- if (_list.size() > 0 || _path.size() > 0) {
- _list.clear();
- _path.clear();
- emit pathChanged();
- }
-}
-
-void WimaAreaData::setPath(const QVariantList &coordinateList) {
- if (_path != coordinateList) {
- _setPathImpl(coordinateList);
- emit pathChanged();
- }
-}
-
-void WimaAreaData::setCenter(const QGeoCoordinate ¢er) {
- if (_center != center) {
- _center = center;
- emit centerChanged();
- }
-}
-
-WimaAreaData &WimaAreaData::operator=(const WimaAreaData &otherData) {
- setPath(otherData._list);
- setCenter(otherData._center);
- return *this;
-}
-
-WimaAreaData &WimaAreaData::operator=(const WimaArea &otherData) {
- setPath(otherData.path());
- setCenter(otherData.center());
- return *this;
-}
-
-void WimaAreaData::_setPathImpl(const QList &coordinateList) {
- _list = coordinateList;
- _path.clear();
- // copy all coordinates to _path
- for (const auto &vertex : coordinateList) {
- _path.append(QVariant::fromValue(vertex));
- }
-}
-
-void WimaAreaData::_setPathImpl(const QVariantList &coordinateList) {
- _path = coordinateList;
- _list.clear();
- for (const auto &variant : coordinateList) {
- _list.push_back(variant.value());
- }
-}
-
-/*!
- * \fn void WimaAreaData::setPath(const QList &coordinateList)
- *
- * Sets the path member to \a coordinateList by copying all entries of \a
- * coordinateList. Emits the \c pathChanged() signal.
- */
-void WimaAreaData::setPath(const QList &coordinateList) {
- if (_list != coordinateList) {
- _setPathImpl(coordinateList);
- emit pathChanged();
- }
-}
-
-bool operator==(const WimaAreaData &m1, const WimaArea &m2) {
- return m1.path() == m2.path() && m1.center() == m2.center();
-}
-
-bool operator!=(const WimaAreaData &m1, const WimaArea &m2) {
- return !operator==(m1, m2);
-}
-
-bool operator==(const WimaArea &m1, const WimaAreaData &m2) { return m2 == m1; }
-
-bool operator!=(const WimaArea &m1, const WimaAreaData &m2) {
- return !operator==(m2, m1);
-}
-
-/*!
- * \class WimaArea::WimaAreaData
- * \brief Class to store and exchange data of a \c WimaArea Object.
- * Class to store and exchange data of a \c WimaArea Object. In contrast to \c
- * WimaArea this class does not uses the QGC Fact System. It is designed to
- * exchange data between the \c WimaPlaner and the \c WimaController class. And
- * it is the base class for any derived data objects
- *
- * \sa WimaArea
- */
diff --git a/src/Wima/Geometry/WimaAreaData.h b/src/Wima/Geometry/WimaAreaData.h
deleted file mode 100644
index b9348aa5fcfe9ad63271cc7aea27a023665f7101..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaAreaData.h
+++ /dev/null
@@ -1,62 +0,0 @@
-#pragma once
-
-#include
-
-#include "QGeoCoordinate"
-
-#include "WimaArea.h"
-
-class WimaAreaData
- : public QObject // Abstract class for all WimaAreaData derived objects
-{
- Q_OBJECT
-public:
- WimaAreaData(QObject *parent = nullptr);
-
- Q_PROPERTY(const QVariantList path READ path NOTIFY pathChanged)
- Q_PROPERTY(QString type READ type CONSTANT)
- Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT)
-
- bool operator==(const WimaAreaData &data) const;
- bool operator!=(const WimaAreaData &data) const;
-
- virtual QString mapVisualQML(void) const = 0;
-
- QVariantList path() const;
- QGeoCoordinate center() const;
- const QList &coordinateList() const;
- bool containsCoordinate(const QGeoCoordinate &coordinate) const;
- virtual QString type() const = 0;
-
- void append(const QGeoCoordinate &c);
- void push_back(const QGeoCoordinate &c);
- void clear();
-
-signals:
- void pathChanged();
- void centerChanged();
-
-public slots:
- void setPath(const QList &coordinateList);
- void setPath(const QVariantList &coordinateList);
- void setCenter(const QGeoCoordinate ¢er);
-
-protected:
- WimaAreaData(const WimaAreaData &otherData, QObject *parent);
- WimaAreaData(const WimaArea &otherData, QObject *parent);
- WimaAreaData &operator=(const WimaAreaData &otherData);
- WimaAreaData &operator=(const WimaArea &otherData);
-
-private:
- void _setPathImpl(const QList &coordinateList);
- void _setPathImpl(const QVariantList &coordinateList);
- // Member Variables
- mutable QVariantList _path;
- QList _list;
- QGeoCoordinate _center;
-};
-
-bool operator==(const WimaAreaData &m1, const WimaArea &m2);
-bool operator!=(const WimaAreaData &m1, const WimaArea &m2);
-bool operator==(const WimaArea &m1, const WimaAreaData &m2);
-bool operator!=(const WimaArea &m1, const WimaAreaData &m2);
diff --git a/src/Wima/Geometry/WimaCorridor.cc b/src/Wima/Geometry/WimaCorridor.cc
deleted file mode 100644
index 52c0659d2d27fc8e16fc05744a66ab46e1450c81..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaCorridor.cc
+++ /dev/null
@@ -1,58 +0,0 @@
-#include "WimaCorridor.h"
-
-const char* WimaCorridor::WimaCorridorName = "Corridor";
-
-
-
-WimaCorridor::WimaCorridor(QObject *parent)
- : WimaArea (parent)
-{
- init();
-}
-
-WimaCorridor::WimaCorridor(const WimaCorridor &other, QObject *parent)
- : WimaArea (other, parent)
-{
- init();
-}
-
-/*!
- * \overload operator=()
- *
- * Calls the inherited operator WimaArea::operator=().
- */
-WimaCorridor &WimaCorridor::operator=(const WimaCorridor &other)
-{
- WimaArea::operator=(other);
-
- return *this;
-}
-
-void WimaCorridor::saveToJson(QJsonObject &json)
-{
- this->WimaArea::saveToJson(json);
- json[areaTypeName] = WimaCorridorName;
-}
-
-bool WimaCorridor::loadFromJson(const QJsonObject &json, QString &errorString)
-{
- if ( this->WimaArea::loadFromJson(json, errorString)) {
- bool retVal = true;
- // code for loading here
- return retVal;
- } else {
- qWarning() << errorString;
- return false;
- }
-}
-
-void WimaCorridor::init()
-{
- this->setObjectName(WimaCorridorName);
-}
-
-
-/*!
- \class WimaCorridor
- \brief Corridor (derived from \c WimaArea) connecting the \c WimaMeasurementArea and the \c WimaServiceArea.
-*/
diff --git a/src/Wima/Geometry/WimaCorridor.h b/src/Wima/Geometry/WimaCorridor.h
deleted file mode 100644
index cef6494ed5ad566f847f742d7addc58a63d71df5..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaCorridor.h
+++ /dev/null
@@ -1,31 +0,0 @@
-#pragma once
-
-#include "WimaArea.h"
-#include
-
-class WimaCorridor : public WimaArea {
- Q_OBJECT
-public:
- WimaCorridor(QObject *parent = nullptr);
- WimaCorridor(const WimaCorridor &other, QObject *parent = nullptr);
-
- WimaCorridor &operator=(const WimaCorridor &other);
-
- // Overrides from WimaPolygon
- QString mapVisualQML(void) const { return "WimaCorridorMapVisual.qml"; }
- QString editorQML(void) const { return "WimaCorridorEditor.qml"; }
-
- // Methodes
- void saveToJson(QJsonObject &json);
- bool loadFromJson(const QJsonObject &json, QString &errorString);
-
- // static Members
- static const char *WimaCorridorName;
-
-signals:
-
-public slots:
-
-private:
- void init();
-};
diff --git a/src/Wima/Geometry/WimaMeasurementArea.cc b/src/Wima/Geometry/WimaMeasurementArea.cc
deleted file mode 100644
index eee40a95dd1984f2e32816f095cc1acf13e2ef7f..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaMeasurementArea.cc
+++ /dev/null
@@ -1,404 +0,0 @@
-#include "WimaMeasurementArea.h"
-#include "QtConcurrentRun"
-#include "SnakeTile.h"
-#include "snake.h"
-
-#include
-
-#include "QGCLoggingCategory.h"
-
-#ifndef SNAKE_MAX_TILES
-#define SNAKE_MAX_TILES 1000
-#endif
-
-QGC_LOGGING_CATEGORY(WimaMeasurementAreaLog, "WimaMeasurementAreaLog")
-
-TileData::TileData() : tiles(this) {}
-
-TileData::~TileData() { tiles.clearAndDeleteContents(); }
-
-TileData &TileData::operator=(const TileData &other) {
- this->tiles.clearAndDeleteContents();
- for (std::size_t i = 0; i < std::size_t(other.tiles.count()); ++i) {
- const auto *obj = other.tiles[i];
- const auto *tile = qobject_cast(obj);
- if (tile != nullptr) {
- this->tiles.append(new SnakeTile(*tile, this));
- } else {
- qCWarning(WimaMeasurementAreaLog) << "TileData::operator=: nullptr";
- }
- }
- this->tileCenterPoints = other.tileCenterPoints;
- return *this;
-}
-
-bool TileData::operator==(const TileData &other) const {
- if (this->tileCenterPoints == other.tileCenterPoints &&
- this->tiles.count() == other.tiles.count()) {
- for (int i = 0; i < other.tiles.count(); ++i) {
- if (this->tiles[i] != other.tiles[i]) {
- return false;
- }
- }
- return true;
- } else {
- return false;
- }
-}
-
-bool TileData::operator!=(const TileData &other) const {
- return !this->operator==(other);
-}
-
-void TileData::clear() {
- this->tiles.clearAndDeleteContents();
- this->tileCenterPoints.clear();
-}
-
-size_t TileData::size() const {
- if (tiles.count() == tileCenterPoints.size()) {
- return tiles.count();
- } else {
- return 0;
- }
-}
-
-const char *WimaMeasurementArea::settingsGroup = "MeasurementArea";
-const char *WimaMeasurementArea::tileHeightName = "TileHeight";
-const char *WimaMeasurementArea::tileWidthName = "TileWidth";
-const char *WimaMeasurementArea::minTileAreaName = "MinTileAreaPercent";
-const char *WimaMeasurementArea::showTilesName = "ShowTiles";
-const char *WimaMeasurementArea::WimaMeasurementAreaName = "Measurement Area";
-
-WimaMeasurementArea::WimaMeasurementArea(QObject *parent)
- : WimaArea(parent),
- _metaDataMap(FactMetaData::createMapFromJsonFile(
- QStringLiteral(":/json/WimaMeasurementArea.SettingsGroup.json"),
- this /* QObject parent */)),
- _tileHeight(SettingsFact(settingsGroup, _metaDataMap[tileHeightName],
- this /* QObject parent */)),
- _tileWidth(SettingsFact(settingsGroup, _metaDataMap[tileWidthName],
- this /* QObject parent */)),
- _minTileAreaPercent(SettingsFact(settingsGroup,
- _metaDataMap[minTileAreaName],
- this /* QObject parent */)),
- _showTiles(SettingsFact(settingsGroup, _metaDataMap[showTilesName],
- this /* QObject parent */)),
- _state(STATE::IDLE) {
- init();
-}
-
-WimaMeasurementArea::WimaMeasurementArea(const WimaMeasurementArea &other,
- QObject *parent)
- : WimaArea(other, parent),
- _metaDataMap(FactMetaData::createMapFromJsonFile(
- QStringLiteral(":/json/WimaMeasurementArea.SettingsGroup.json"),
- this /* QObject parent */)),
- _tileHeight(SettingsFact(settingsGroup, _metaDataMap[tileHeightName],
- this /* QObject parent */)),
- _tileWidth(SettingsFact(settingsGroup, _metaDataMap[tileWidthName],
- this /* QObject parent */)),
- _minTileAreaPercent(SettingsFact(settingsGroup,
- _metaDataMap[minTileAreaName],
- this /* QObject parent */)),
- _showTiles(SettingsFact(settingsGroup, _metaDataMap[showTilesName],
- this /* QObject parent */)),
- _state(STATE::IDLE) {
- init();
-}
-
-/*!
- * \overload operator=()
- *
- * Calls the inherited operator WimaArea::operator=().
- */
-WimaMeasurementArea &WimaMeasurementArea::
-operator=(const WimaMeasurementArea &other) {
- WimaArea::operator=(other);
- return *this;
-}
-
-WimaMeasurementArea::~WimaMeasurementArea() {}
-
-QString WimaMeasurementArea::mapVisualQML() const {
- return QStringLiteral("WimaMeasurementAreaMapVisual.qml");
-}
-
-QString WimaMeasurementArea::editorQML() const {
- return QStringLiteral("WimaMeasurementAreaEditor.qml");
-}
-
-Fact *WimaMeasurementArea::tileHeight() { return &_tileHeight; }
-
-Fact *WimaMeasurementArea::tileWidth() { return &_tileWidth; }
-
-Fact *WimaMeasurementArea::minTileArea() { return &_minTileAreaPercent; }
-
-Fact *WimaMeasurementArea::showTiles() { return &_showTiles; }
-
-QmlObjectListModel *WimaMeasurementArea::tiles() {
- return &this->_tileData.tiles;
-}
-
-const QVector &WimaMeasurementArea::progress() const {
- return this->_progress;
-}
-
-QVector WimaMeasurementArea::progressQml() const {
- return this->_progress;
-}
-
-const QmlObjectListModel *WimaMeasurementArea::tiles() const {
- return &this->_tileData.tiles;
-}
-
-const QVariantList &WimaMeasurementArea::tileCenterPoints() const {
- return this->_tileData.tileCenterPoints;
-}
-
-const TileData &WimaMeasurementArea::tileData() const {
- return this->_tileData;
-}
-
-int WimaMeasurementArea::maxTiles() const { return SNAKE_MAX_TILES; }
-
-bool WimaMeasurementArea::ready() const { return this->_state == STATE::IDLE; }
-
-void WimaMeasurementArea::saveToJson(QJsonObject &json) {
- if (ready()) {
- this->WimaArea::saveToJson(json);
- json[tileHeightName] = _tileHeight.rawValue().toDouble();
- json[tileWidthName] = _tileWidth.rawValue().toDouble();
- json[minTileAreaName] = _minTileAreaPercent.rawValue().toDouble();
- json[showTilesName] = _showTiles.rawValue().toBool();
- json[areaTypeName] = WimaMeasurementAreaName;
- } else {
- qCDebug(WimaMeasurementAreaLog) << "saveToJson(): not ready for saveing.";
- }
-}
-
-bool WimaMeasurementArea::loadFromJson(const QJsonObject &json,
- QString &errorString) {
- if (this->WimaArea::loadFromJson(json, errorString)) {
- disableUpdate();
- bool retVal = true;
-
- if (!json.contains(tileHeightName) || !json[tileHeightName].isDouble()) {
- errorString.append(tr("Could not load tile height!\n"));
- retVal = false;
- } else {
- _tileHeight.setRawValue(json[tileHeightName].toDouble());
- }
-
- if (!json.contains(tileWidthName) || !json[tileWidthName].isDouble()) {
- errorString.append(tr("Could not load tile width!\n"));
- retVal = false;
- } else {
- _tileWidth.setRawValue(json[tileWidthName].toDouble());
- }
-
- if (!json.contains(minTileAreaName) || !json[minTileAreaName].isDouble()) {
- errorString.append(tr("Could not load minimal tile area!\n"));
- retVal = false;
- } else {
- _minTileAreaPercent.setRawValue(json[minTileAreaName].toDouble());
- }
-
- if (!json.contains(showTilesName) || !json[showTilesName].isBool()) {
- errorString.append(tr("Could not load show tiles !\n"));
- retVal = false;
- } else {
- _showTiles.setRawValue(json[showTilesName].toBool());
- }
-
- enableUpdate();
- doUpdate();
-
- return retVal;
- } else {
- return false;
- }
-}
-
-bool WimaMeasurementArea::setProgress(const QVector &p) {
- if (ready()) {
- if (p.size() == this->tiles()->count() && this->_progress != p) {
- this->_progress = p;
- emit progressChanged();
- emit progressAccepted();
- return true;
- }
- }
- return false;
-}
-//!
-//! \brief WimaMeasurementArea::doUpdate
-//! \pre WimaMeasurementArea::deferUpdate must be called first, don't call
-//! this function directly!
-void WimaMeasurementArea::doUpdate() {
- using namespace snake;
- using namespace boost::units;
-
- auto start = std::chrono::high_resolution_clock::now();
-
- if (this->_state != STATE::UPDATEING && this->_state != STATE::STOP) {
- const auto height = this->_tileHeight.rawValue().toDouble() * si::meter;
- const auto width = this->_tileWidth.rawValue().toDouble() * si::meter;
- const auto tileArea = width * height;
- const auto totalArea = this->area() * si::meter * si::meter;
- const auto estNumTiles = totalArea / tileArea;
- // Check some conditions.
- if (long(std::ceil(estNumTiles.value())) <= SNAKE_MAX_TILES &&
- this->count() >= 3 && this->isSimplePolygon()) {
- setState(STATE::UPDATEING);
-
- auto polygon = this->coordinateList();
- for (auto &v : polygon) {
- v.setAltitude(0);
- }
- const auto minArea =
- this->_minTileAreaPercent.rawValue().toDouble() / 100 * tileArea;
- auto *th = this->thread();
- auto future = QtConcurrent::run([polygon, th, height, width, minArea] {
- auto start = std::chrono::high_resolution_clock::now();
-
- DataPtr pData(new TileData());
- // Convert to ENU system.
- QGeoCoordinate origin = polygon.first();
- FPolygon polygonENU;
- areaToEnu(origin, polygon, polygonENU);
- std::vector tilesENU;
- BoundingBox bbox;
- std::string errorString;
- // Generate tiles.
- if (snake::tiles(polygonENU, height, width, minArea, tilesENU, bbox,
- errorString)) {
- // Convert to geo system.
- for (const auto &t : tilesENU) {
- auto geoTile = new SnakeTile(pData.get());
- for (const auto &v : t.outer()) {
- QGeoCoordinate geoVertex;
- fromENU(origin, v, geoVertex);
- geoTile->push_back(geoVertex);
- }
- pData->tiles.append(geoTile);
- // Calculate center.
- snake::FPoint center;
- snake::polygonCenter(t, center);
- QGeoCoordinate geoCenter;
- fromENU(origin, center, geoCenter);
- pData->tileCenterPoints.append(QVariant::fromValue(geoCenter));
- }
- }
- pData->moveToThread(th);
-
- qCDebug(WimaMeasurementAreaLog)
- << "doUpdate(): update time: "
- << std::chrono::duration_cast(
- std::chrono::high_resolution_clock::now() - start)
- .count()
- << " ms";
-
- return pData;
- }); // QtConcurrent::run()
-
- this->_watcher.setFuture(future);
- }
- }
- qCDebug(WimaMeasurementAreaLog)
- << "doUpdate(): execution time: "
- << std::chrono::duration_cast(
- std::chrono::high_resolution_clock::now() - start)
- .count()
- << " ms";
-}
-
-void WimaMeasurementArea::deferUpdate() {
- if (this->_state == STATE::IDLE || this->_state == STATE::DEFERED) {
- qCDebug(WimaMeasurementAreaLog) << "defereUpdate(): defer update.";
- if (this->_state == STATE::IDLE) {
- this->_progress.clear();
- this->_tileData.clear();
- emit this->progressChanged();
- emit this->tilesChanged();
- }
- this->setState(STATE::DEFERED);
- this->_timer.start(100);
- } else if (this->_state == STATE::UPDATEING) {
- qCDebug(WimaMeasurementAreaLog) << "defereUpdate(): restart.";
- setState(STATE::RESTARTING);
- }
-}
-
-void WimaMeasurementArea::storeTiles() {
- auto start = std::chrono::high_resolution_clock::now();
-
- if (this->_state == STATE::UPDATEING) {
- qCDebug(WimaMeasurementAreaLog) << "storeTiles(): update.";
-
- this->_tileData = *this->_watcher.result();
- // This is expensive. Drawing tiles is expensive too.
- this->_progress = QVector(this->_tileData.tiles.count(), 0);
- this->progressChanged();
- emit this->tilesChanged();
- setState(STATE::IDLE);
- } else if (this->_state == STATE::RESTARTING) {
- qCDebug(WimaMeasurementAreaLog) << "storeTiles(): restart.";
- doUpdate();
- } else if (this->_state == STATE::STOP) {
- qCDebug(WimaMeasurementAreaLog) << "storeTiles(): stop.";
- }
- qCDebug(WimaMeasurementAreaLog)
- << "storeTiles() execution time: "
- << std::chrono::duration_cast(
- std::chrono::high_resolution_clock::now() - start)
- .count()
- << " ms";
-}
-
-void WimaMeasurementArea::disableUpdate() {
- setState(STATE::IDLE);
- this->_timer.stop();
-}
-
-void WimaMeasurementArea::enableUpdate() {
- if (this->_state == STATE::STOP) {
- setState(STATE::IDLE);
- }
-}
-
-void WimaMeasurementArea::init() {
- this->setObjectName(WimaMeasurementAreaName);
- connect(&this->_tileHeight, &Fact::rawValueChanged, this,
- &WimaMeasurementArea::deferUpdate);
- connect(&this->_tileWidth, &Fact::rawValueChanged, this,
- &WimaMeasurementArea::deferUpdate);
- connect(&this->_minTileAreaPercent, &Fact::rawValueChanged, this,
- &WimaMeasurementArea::deferUpdate);
- connect(this, &WimaArea::pathChanged, this,
- &WimaMeasurementArea::deferUpdate);
- this->_timer.setSingleShot(true);
- connect(&this->_timer, &QTimer::timeout, this,
- &WimaMeasurementArea::doUpdate);
- connect(&this->_watcher,
- &QFutureWatcher>::finished, this,
- &WimaMeasurementArea::storeTiles);
-}
-
-void WimaMeasurementArea::setState(WimaMeasurementArea::STATE s) {
- if (this->_state != s) {
- auto oldState = this->_state;
- this->_state = s;
- if (s == STATE::IDLE || oldState == STATE::IDLE) {
- emit readyChanged();
- }
- }
-}
-
-/*!
- * \class WimaMeasurementArea
- * \brief Class defining the area inside which the actual drone measurements
- * are performed.
- *
- * \sa WimaArea, WimaController, WimaPlaner
- */
diff --git a/src/Wima/Geometry/WimaMeasurementArea.h b/src/Wima/Geometry/WimaMeasurementArea.h
deleted file mode 100644
index 07266032584d19d5dfcdf81560e8bc77e4152fe2..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaMeasurementArea.h
+++ /dev/null
@@ -1,116 +0,0 @@
-#pragma once
-
-#include
-#include
-#include
-
-#include "WimaArea.h"
-
-#include "SettingsFact.h"
-
-class TileData : public QObject {
-public:
- QmlObjectListModel tiles;
- QVariantList tileCenterPoints;
-
- TileData();
- ~TileData();
-
- TileData &operator=(const TileData &other);
- bool operator==(const TileData &other) const;
- bool operator!=(const TileData &other) const;
-
- void clear();
- std::size_t size() const;
-};
-
-class WimaMeasurementArea : public WimaArea {
- Q_OBJECT
-
- enum class STATE { IDLE, DEFERED, UPDATEING, RESTARTING, STOP };
-
-public:
- WimaMeasurementArea(QObject *parent = nullptr);
- WimaMeasurementArea(const WimaMeasurementArea &other,
- QObject *parent = nullptr);
- WimaMeasurementArea &operator=(const WimaMeasurementArea &other);
- ~WimaMeasurementArea();
-
- Q_PROPERTY(Fact *tileHeight READ tileHeight CONSTANT)
- Q_PROPERTY(Fact *tileWidth READ tileWidth CONSTANT)
- Q_PROPERTY(Fact *minTileArea READ minTileArea CONSTANT)
- Q_PROPERTY(Fact *showTiles READ showTiles CONSTANT)
- Q_PROPERTY(QmlObjectListModel *tiles READ tiles NOTIFY tilesChanged)
- Q_PROPERTY(int maxTiles READ maxTiles NOTIFY maxTilesChanged)
- Q_PROPERTY(QVector progress READ progressQml NOTIFY progressChanged)
-
- // Overrides from WimaPolygon
- QString mapVisualQML(void) const;
- QString editorQML(void) const;
-
- // Property getters.
- Fact *tileHeight();
- Fact *tileWidth();
- Fact *minTileArea();
- Fact *showTiles();
- QmlObjectListModel *tiles();
- const QVector &progress() const;
- QVector progressQml() const;
- const QmlObjectListModel *tiles() const;
- const QVariantList &tileCenterPoints() const; // List of QGeoCoordinate
- const TileData &tileData() const;
- int maxTiles() const;
- bool ready() const;
-
- // Member Methodes
- void saveToJson(QJsonObject &json);
- bool loadFromJson(const QJsonObject &json, QString &errorString);
-
- // Static Variables
- static const char *settingsGroup;
- static const char *tileHeightName;
- static const char *tileWidthName;
- static const char *minTileAreaName;
- static const char *showTilesName;
- static const char *WimaMeasurementAreaName;
-
-signals:
- void tilesChanged();
- void maxTilesChanged();
- void progressChanged();
- void progressAccepted();
- void progressNotAccepted();
- void readyChanged();
-
-public slots:
- bool setProgress(const QVector &p);
-
-private slots:
- void doUpdate();
- void deferUpdate();
- void storeTiles();
- void disableUpdate();
- void enableUpdate();
-
-private:
- // Member Methodes
- void init();
- void setState(STATE s);
-
- // Members
- QMap _metaDataMap;
-
- SettingsFact _tileHeight;
- SettingsFact _tileWidth;
- SettingsFact _minTileAreaPercent; // 0..100
- SettingsFact _showTiles;
-
- QVector _progress;
- // Tile stuff.
- // Tile stuff.
- mutable QTimer _timer;
- using DataPtr = std::shared_ptr;
- mutable STATE _state;
- mutable TileData _tileData;
- mutable QFutureWatcher _watcher;
-};
diff --git a/src/Wima/Geometry/WimaMeasurementAreaData.cc b/src/Wima/Geometry/WimaMeasurementAreaData.cc
deleted file mode 100644
index 5d0b68fcc3b16aaf18b248600ab6404002e08378..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaMeasurementAreaData.cc
+++ /dev/null
@@ -1,137 +0,0 @@
-#include "WimaMeasurementAreaData.h"
-#include "SnakeTile.h"
-
-const char *WimaMeasurementAreaData::typeString = "WimaMeasurementAreaData";
-
-WimaMeasurementAreaData::WimaMeasurementAreaData(QObject *parent)
- : WimaAreaData(parent) {}
-
-WimaMeasurementAreaData::WimaMeasurementAreaData(
- const WimaMeasurementAreaData &other, QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
-
-WimaMeasurementAreaData::WimaMeasurementAreaData(
- const WimaMeasurementArea &other, QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
-
-bool WimaMeasurementAreaData::
-operator==(const WimaMeasurementAreaData &other) const {
- return this->WimaAreaData::operator==(other) &&
- this->_tileData == other.tileData() &&
- this->_progress == other.progress() &&
- this->center() == other.center();
-}
-
-bool WimaMeasurementAreaData::
-operator!=(const WimaMeasurementAreaData &other) const {
- return !(*this == other);
-}
-
-void WimaMeasurementAreaData::setTileData(const TileData &d) {
- if (this->_tileData != d) {
- this->_tileData = d;
- this->_progress.fill(0, d.size());
- emit progressChanged();
- emit tileDataChanged();
- }
-}
-
-void WimaMeasurementAreaData::setProgress(const QVector &d) {
- if (this->_progress != d && d.size() == this->_tileData.tiles.count()) {
- this->_progress = d;
- emit progressChanged();
- }
-}
-
-/*!
- * \overload operator=();
- *
- * Assigns \a other to the invoking object.
- */
-WimaMeasurementAreaData &WimaMeasurementAreaData::
-operator=(const WimaMeasurementAreaData &other) {
- WimaAreaData::operator=(other);
- setTileData(other._tileData);
- setProgress(other._progress);
-
- return *this;
-}
-
-/*!
- * \overload operator=();
- *
- * Assigns \a other to the invoking object.
- */
-WimaMeasurementAreaData &WimaMeasurementAreaData::
-operator=(const WimaMeasurementArea &other) {
- WimaAreaData::operator=(other);
- if (other.ready()) {
- setTileData(other.tileData());
- setProgress(other.progress());
- } else {
- qWarning() << "WimaMeasurementAreaData::operator=(): WimaMeasurementArea "
- "not ready.";
- }
-
- return *this;
-}
-
-QString WimaMeasurementAreaData::mapVisualQML() const {
- return QStringLiteral("WimaMeasurementAreaDataVisual.qml");
-}
-
-QString WimaMeasurementAreaData::type() const { return this->typeString; }
-
-QmlObjectListModel *WimaMeasurementAreaData::tiles() {
- return &this->_tileData.tiles;
-}
-
-const QmlObjectListModel *WimaMeasurementAreaData::tiles() const {
- return &this->_tileData.tiles;
-}
-
-const QVariantList &WimaMeasurementAreaData::tileCenterPoints() const {
- return this->_tileData.tileCenterPoints;
-}
-
-QVariantList &WimaMeasurementAreaData::tileCenterPoints() {
- return this->_tileData.tileCenterPoints;
-}
-
-const TileData &WimaMeasurementAreaData::tileData() const {
- return this->_tileData;
-}
-
-TileData &WimaMeasurementAreaData::tileData() { return this->_tileData; }
-
-const QVector &WimaMeasurementAreaData::progress() const {
- return this->_progress;
-}
-
-QVector &WimaMeasurementAreaData::progress() { return this->_progress; }
-
-bool operator==(const WimaMeasurementAreaData &m1,
- const WimaMeasurementArea &m2) {
- return operator==(*static_cast(&m1),
- *static_cast(&m2)) &&
- m1.tileData() == m2.tileData() && m1.progress() == m2.progress();
-}
-
-bool operator!=(const WimaMeasurementAreaData &m1,
- const WimaMeasurementArea &m2) {
- return !(m1 == m2);
-}
-
-bool operator==(const WimaMeasurementArea &m1,
- const WimaMeasurementAreaData &m2) {
- return m2 == m1;
-}
-
-bool operator!=(const WimaMeasurementArea &m1,
- const WimaMeasurementAreaData &m2) {
- return m2 != m1;
-}
diff --git a/src/Wima/Geometry/WimaMeasurementAreaData.h b/src/Wima/Geometry/WimaMeasurementAreaData.h
deleted file mode 100644
index dde208291fdd5c69080d651e9f828dcdd3852bf7..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaMeasurementAreaData.h
+++ /dev/null
@@ -1,65 +0,0 @@
-#pragma once
-
-#include
-#include
-
-#include "WimaAreaData.h"
-#include "WimaMeasurementArea.h"
-
-class WimaMeasurementAreaData : public WimaAreaData {
- Q_OBJECT
-
-public:
- WimaMeasurementAreaData(QObject *parent = nullptr);
- WimaMeasurementAreaData(const WimaMeasurementAreaData &other,
- QObject *parent = nullptr);
- WimaMeasurementAreaData(const WimaMeasurementArea &other,
- QObject *parent = nullptr);
- WimaMeasurementAreaData &operator=(const WimaMeasurementAreaData &other);
- WimaMeasurementAreaData &operator=(const WimaMeasurementArea &other);
-
- Q_PROPERTY(QmlObjectListModel *tiles READ tiles NOTIFY tileDataChanged)
- Q_PROPERTY(QVector progress READ progress NOTIFY progressChanged)
-
- virtual QString mapVisualQML() const override;
-
- bool operator==(const WimaMeasurementAreaData &other) const;
- bool operator!=(const WimaMeasurementAreaData &other) const;
-
- // Property setters.
- void setTileData(const TileData &d);
- void setProgress(const QVector &d);
-
- // Property getters.
- QString type() const;
- WimaMeasurementAreaData *Clone() const {
- return new WimaMeasurementAreaData(*this);
- }
- QmlObjectListModel *tiles();
- const QmlObjectListModel *tiles() const;
- const QVariantList &tileCenterPoints() const;
- QVariantList &tileCenterPoints();
- const TileData &tileData() const;
- TileData &tileData();
- const QVector &progress() const;
- QVector &progress();
-
- static const char *typeString;
-
-signals:
- void tileDataChanged();
- void progressChanged();
-
-private:
- TileData _tileData;
- QVector _progress;
-};
-
-bool operator==(const WimaMeasurementAreaData &m1,
- const WimaMeasurementArea &m2);
-bool operator!=(const WimaMeasurementAreaData &m1,
- const WimaMeasurementArea &m2);
-bool operator==(const WimaMeasurementArea &m1,
- const WimaMeasurementAreaData &m2);
-bool operator!=(const WimaMeasurementArea &m1,
- const WimaMeasurementAreaData &m2);
diff --git a/src/Wima/Geometry/WimaServiceArea.cc b/src/Wima/Geometry/WimaServiceArea.cc
deleted file mode 100644
index 84b6c6afd10848675321f2039f506eb6d1b5deb3..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaServiceArea.cc
+++ /dev/null
@@ -1,119 +0,0 @@
-#include "WimaServiceArea.h"
-
-#include "QGCLoggingCategory.h"
-#include "QGCQGeoCoordinate.h"
-
-QGC_LOGGING_CATEGORY(WimaServiceAreaLog, "WimaServiceAreaLog")
-
-const char *WimaServiceArea::wimaServiceAreaName = "Service Area";
-const char *WimaServiceArea::depotLatitudeName = "DepotLatitude";
-const char *WimaServiceArea::depotLongitudeName = "DepotLongitude";
-const char *WimaServiceArea::depotAltitudeName = "DepotAltitude";
-
-WimaServiceArea::WimaServiceArea(QObject *parent) : WimaArea(parent) { init(); }
-
-WimaServiceArea::WimaServiceArea(const WimaServiceArea &other, QObject *parent)
- : WimaArea(other, parent), _depot(other.depot()) {
- init();
-}
-
-/*!
- * \overload operator=()
- *
- * Calls the inherited operator WimaArea::operator=().
- */
-WimaServiceArea &WimaServiceArea::operator=(const WimaServiceArea &other) {
- WimaArea::operator=(other);
- this->setDepot(other.depot());
- return *this;
-}
-
-const QGeoCoordinate &WimaServiceArea::depot() const { return _depot; }
-
-QGeoCoordinate WimaServiceArea::depotQml() const { return _depot; }
-
-bool WimaServiceArea::setDepot(const QGeoCoordinate &coordinate) {
- if (_depot.latitude() != coordinate.latitude() ||
- _depot.longitude() != coordinate.longitude()) {
- if (this->containsCoordinate(coordinate)) {
- _depot = coordinate;
- _depot.setAltitude(0);
- emit depotChanged();
- return true;
- }
- }
- return false;
-}
-
-void WimaServiceArea::saveToJson(QJsonObject &json) {
- this->WimaArea::saveToJson(json);
- json[areaTypeName] = wimaServiceAreaName;
- json[depotLatitudeName] = _depot.latitude();
- json[depotLongitudeName] = _depot.longitude();
- json[depotAltitudeName] = _depot.altitude();
-}
-
-bool WimaServiceArea::loadFromJson(const QJsonObject &json,
- QString &errorString) {
- bool retVal = false;
- if (this->WimaArea::loadFromJson(json, errorString)) {
- double lat = 0;
- if (json.contains(depotLatitudeName) &&
- json[depotLatitudeName].isDouble()) {
- lat = json[depotLatitudeName].toDouble();
- double lon = 0;
- if (json.contains(depotLongitudeName) &&
- json[depotLongitudeName].isDouble()) {
- lon = json[depotLongitudeName].toDouble();
- double alt = 0;
- if (json.contains(depotAltitudeName) &&
- json[depotAltitudeName].isDouble()) {
- alt = json[depotAltitudeName].toDouble();
- this->setDepot(QGeoCoordinate(lat, lon, alt));
- retVal = true;
- } else {
- errorString = "Not able to load depot altitude.";
- }
- } else {
- errorString = "Not able to load depot longitude.";
- }
- } else {
- errorString = "Not able to load depot latitude.";
- }
- retVal = true;
- }
- return retVal;
-}
-
-void WimaServiceArea::init() {
- this->setObjectName(wimaServiceAreaName);
- connect(this, &WimaArea::pathChanged, [this] {
- if (!this->_depot.isValid() || !this->containsCoordinate(this->_depot)) {
- if (this->containsCoordinate(this->center())) {
- // Use center.
- this->setDepot(this->center());
- } else if (this->_depot.isValid()) {
- // Use nearest coordinate.
- auto minDist = std::numeric_limits::infinity();
- int minIndex = 0;
- for (int idx = 0; idx < this->pathModel().count(); ++idx) {
- const QObject *obj = this->pathModel()[idx];
- const auto *vertex = qobject_cast(obj);
- if (vertex != nullptr) {
- auto d = vertex->coordinate().distanceTo(this->_depot);
- if (d < minDist) {
- minDist = d;
- minIndex = idx;
- }
- } else {
- qCCritical(WimaServiceAreaLog) << "init(): nullptr catched!";
- }
- }
- this->setDepot(this->pathModel().value(minIndex)->coordinate());
- } else if (this->pathModel().count() > 0) {
- // Use first coordinate.
- this->setDepot(this->pathModel().value(0)->coordinate());
- }
- }
- });
-}
diff --git a/src/Wima/Geometry/WimaServiceArea.h b/src/Wima/Geometry/WimaServiceArea.h
deleted file mode 100644
index 08ff94c34ccec0a73ebc2f8b09228892b5e9b6d9..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaServiceArea.h
+++ /dev/null
@@ -1,46 +0,0 @@
-#pragma once
-
-#include "WimaArea.h"
-#include "WimaTrackerPolyline.h"
-#include
-
-class WimaServiceArea : public WimaArea {
- Q_OBJECT
-public:
- WimaServiceArea(QObject *parent = nullptr);
- WimaServiceArea(const WimaServiceArea &other, QObject *parent);
- WimaServiceArea &operator=(const WimaServiceArea &other);
-
- Q_PROPERTY(
- QGeoCoordinate depot READ depotQml WRITE setDepot NOTIFY depotChanged)
-
- // Overrides from WimaPolygon
- QString mapVisualQML(void) const { return "WimaServiceAreaMapVisual.qml"; }
- QString editorQML(void) const { return "WimaServiceAreaEditor.qml"; }
-
- // Property acessors
- const QGeoCoordinate &depot(void) const;
- QGeoCoordinate depotQml(void) const;
-
- // Member Methodes
- void saveToJson(QJsonObject &json);
- bool loadFromJson(const QJsonObject &json, QString &errorString);
-
- // static Members
- static const char *wimaServiceAreaName;
- static const char *depotLatitudeName;
- static const char *depotLongitudeName;
- static const char *depotAltitudeName;
-signals:
- void depotChanged(void);
-
-public slots:
- bool setDepot(const QGeoCoordinate &coordinate);
-
-private:
- // Member Methodes
- void init();
-
- // Members
- QGeoCoordinate _depot;
-};
diff --git a/src/Wima/Geometry/WimaServiceAreaData.cc b/src/Wima/Geometry/WimaServiceAreaData.cc
deleted file mode 100644
index ef52635dfe56dab66a887408c2f5315a99cc268f..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaServiceAreaData.cc
+++ /dev/null
@@ -1,66 +0,0 @@
-#include "WimaServiceAreaData.h"
-
-const char *WimaServiceAreaData::typeString = "WimaServiceAreaData";
-
-WimaServiceAreaData::WimaServiceAreaData(QObject *parent)
- : WimaAreaData(parent) {}
-
-WimaServiceAreaData::WimaServiceAreaData(const WimaServiceAreaData &other,
- QObject *parent)
- : WimaAreaData(other, parent), _depot(other._depot) {}
-
-WimaServiceAreaData::WimaServiceAreaData(const WimaServiceArea &other,
- QObject *parent)
- : WimaAreaData(other, parent), _depot(other.depot()) {}
-
-WimaServiceAreaData &WimaServiceAreaData::
-operator=(const WimaServiceAreaData &otherData) {
- WimaAreaData::operator=(otherData);
- this->setDepot(otherData.depot());
- return *this;
-}
-
-WimaServiceAreaData &WimaServiceAreaData::
-operator=(const WimaServiceArea &otherArea) {
- WimaAreaData::operator=(otherArea);
- this->setDepot(otherArea.depot());
- return *this;
-}
-
-QString WimaServiceAreaData::mapVisualQML() const {
- return QStringLiteral("WimaServiceAreaDataVisual.qml");
-}
-
-/*!
- * \fn const QGeoCoordinate &WimaServiceAreaData::takeOffPosition() const
- * Returns a constant reference to the takeOffPosition.
- *
- */
-const QGeoCoordinate &WimaServiceAreaData::depot() const { return _depot; }
-
-QString WimaServiceAreaData::type() const { return this->typeString; }
-/*!
- * \fn void WimaServiceAreaData::setTakeOffPosition(const QGeoCoordinate
- * &newCoordinate) Sets the takeoff position to the \a newCoordinate and emits
- * the takeOffPositionChanged() signal, if newCoordinate differs from the member
- * value.
- *
- */
-void WimaServiceAreaData::setDepot(const QGeoCoordinate &newCoordinate) {
- if (_depot != newCoordinate) {
- _depot = newCoordinate;
- emit depotChanged(_depot);
- }
-}
-
-/*!
- * \class WimaAreaData::WimaServiceAreaData
- * \brief Class to store and exchange data of a \c WimaServiceArea Object.
- * Class to store and exchange data of a \c WimaServiceArea Object. In contrast
- * to \c WimaServiceArea this class does not provied any interface to a grafical
- * user interface, neiter it uses the QGC Fact System. It is designed to
- * exchange data between the \c WimaPlaner and the \c WimaController class. And
- * it is the derived from WimaAreaData.
- *
- * \sa WimaServiceArea, WimaAreaData
- */
diff --git a/src/Wima/Geometry/WimaServiceAreaData.h b/src/Wima/Geometry/WimaServiceAreaData.h
deleted file mode 100644
index 2b93a20964008977061f992314174feee299d408..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/WimaServiceAreaData.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#pragma once
-
-#include "QGeoCoordinate"
-#include
-
-#include "WimaAreaData.h"
-#include "WimaServiceArea.h"
-
-class WimaServiceAreaData : public WimaAreaData {
- Q_OBJECT
-
-public:
- WimaServiceAreaData(QObject *parent = nullptr);
- WimaServiceAreaData(const WimaServiceAreaData &other,
- QObject *parent = nullptr);
- WimaServiceAreaData(const WimaServiceArea &other, QObject *parent = nullptr);
- WimaServiceAreaData &operator=(const WimaServiceAreaData &otherData);
- WimaServiceAreaData &operator=(const WimaServiceArea &otherArea);
-
- virtual QString mapVisualQML() const override;
-
- const QGeoCoordinate &depot() const;
-
- QString type() const;
- WimaServiceAreaData *Clone() const { return new WimaServiceAreaData(); }
- static const char *typeString;
-
-signals:
- void depotChanged(const QGeoCoordinate &other);
-
-public slots:
- void setDepot(const QGeoCoordinate &newCoordinate);
-
-private:
- // see WimaServieArea.h for explanation
- QGeoCoordinate _depot;
-};
diff --git a/src/Wima/Geometry/json/WimaArea.SettingsGroup.json b/src/Wima/Geometry/json/WimaArea.SettingsGroup.json
deleted file mode 100644
index 321fa4747e2e973f30e8d0831bbd879620119e7a..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/json/WimaArea.SettingsGroup.json
+++ /dev/null
@@ -1,17 +0,0 @@
-[
-{
- "name": "BorderPolygonOffset",
- "shortDescription": "The distance between the measurement area and it's surrounding polygon",
- "type": "double",
- "units": "m",
- "min": 0,
- "decimalPlaces": 1,
- "defaultValue": 5
-},
-{
- "name": "ShowBorderPolygon",
- "shortDescription": "Border polygon will be displayed if checked.",
- "type": "bool",
- "defaultValue": true
-}
-]
diff --git a/src/Wima/Geometry/json/WimaMeasurementArea.SettingsGroup.json b/src/Wima/Geometry/json/WimaMeasurementArea.SettingsGroup.json
deleted file mode 100644
index c4fda54e2296fc8eaf992feaac5054d0aa969c90..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/json/WimaMeasurementArea.SettingsGroup.json
+++ /dev/null
@@ -1,45 +0,0 @@
-[
-{
- "name": "TileHeight",
- "shortDescription": "The height of a tile",
- "type": "double",
- "units": "m",
- "min": 0.3,
- "decimalPlaces": 2,
- "defaultValue": 5
-},
-{
- "name": "TileWidth",
- "shortDescription": "The height of a tile",
- "type": "double",
- "units": "m",
- "min": 0.3,
- "decimalPlaces": 2,
- "defaultValue": 5
-},
-{
- "name": "MinTileAreaPercent",
- "shortDescription": "The minimal allowed area in percent (of width*height).",
- "type": "double",
- "units": "%",
- "min": 0,
- "max": 100,
- "decimalPlaces": 2,
- "defaultValue": 20
-},
-{
- "name": "ShowTiles",
- "shortDescription": "Show tiles",
- "type": "bool",
- "defaultValue": true
-},
-{
- "name": "BorderPolygonOffset",
- "shortDescription": "The distance between the measurement area and it's enclosing polygon",
- "type": "double",
- "units": "m",
- "min": 0,
- "decimalPlaces": 1,
- "defaultValue": 5
-}
-]
diff --git a/src/Wima/Geometry/testplanimetrycalculus.h b/src/Wima/Geometry/testplanimetrycalculus.h
deleted file mode 100644
index 5977e3803431ece2de612d0c958497500ee298a2..0000000000000000000000000000000000000000
--- a/src/Wima/Geometry/testplanimetrycalculus.h
+++ /dev/null
@@ -1,12 +0,0 @@
-#pragma once
-
-#include "PlanimetryCalculus.h"
-
-#include
-#include
-
-namespace TestPlanimetryCalculus {
-
- void test();
-
-}
diff --git a/src/Wima/OptimisationTools.cc b/src/Wima/OptimisationTools.cc
deleted file mode 100644
index 0d03739df441d601eb955d9c7ff7bd85e3f762c0..0000000000000000000000000000000000000000
--- a/src/Wima/OptimisationTools.cc
+++ /dev/null
@@ -1,105 +0,0 @@
-#include "OptimisationTools.h"
-
-namespace OptimisationTools {
- namespace {
-
- } // end anonymous namespace
-
- bool dijkstraAlgorithm(const int numElements, int startIndex, int endIndex, QVector &elementPath, std::function distanceDij)
- {
- if ( numElements < 0
- || startIndex < 0
- || endIndex < 0
- || startIndex >= numElements
- || endIndex >= numElements
- || endIndex == startIndex) {
- return false;
- }
- // Node struct
- // predecessorIndex is the index of the predecessor node (nodeList[predecessorIndex])
- // distance is the distance between the node and the start node
- // node number is stored by the position in nodeList
- struct Node{
- int predecessorIndex = -1;
- double distance = std::numeric_limits::infinity();
- };
-
- // The list with all Nodes (elements)
- QVector nodeList(numElements);
- // This list will be initalized with indices referring to the elements of nodeList.
- // Elements will be successively remove during the execution of the Dijkstra Algorithm.
- QVector workingSet(numElements);
-
- //append elements to node list
- for (int i = 0; i < numElements; ++i) workingSet[i] = i;
-
-
- nodeList[startIndex].distance = 0;
-
-// qDebug() << "nodeList" ;
-// for (auto node : nodeList) {
-// qDebug() << "predecessor: " << node.predecessorIndex;
-// qDebug() << "distance: " << node.distance;
-// }
-// qDebug() << "workingSet";
-// for (auto node : workingSet) {
-// qDebug() << "index: " << node;
-// }
-
- // Dijkstra Algorithm
- // https://de.wikipedia.org/wiki/Dijkstra-Algorithmus
- while (workingSet.size() > 0) {
- // serach Node with minimal distance
- double minDist = std::numeric_limits::infinity();
- int minDistIndex_WS = -1; // WS = workinSet
- for (int i = 0; i < workingSet.size(); ++i) {
- const int nodeIndex = workingSet.at(i);
- const double dist = nodeList.at(nodeIndex).distance;
- if (dist < minDist) {
- minDist = dist;
- minDistIndex_WS = i;
- }
- }
- if (minDistIndex_WS == -1)
- return false;
-
- int indexU_NL = workingSet.takeAt(minDistIndex_WS); // NL = nodeList
- if (indexU_NL == endIndex) // shortest path found
- break;
-
- const double distanceU = nodeList.at(indexU_NL).distance;
- //update distance
- for (int i = 0; i < workingSet.size(); ++i) {
- int indexV_NL = workingSet[i]; // NL = nodeList
- Node* v = &nodeList[indexV_NL];
- double dist = distanceDij(indexU_NL, indexV_NL);
- // is ther an alternative path which is shorter?
- double alternative = distanceU + dist;
- if (alternative < v->distance) {
- v->distance = alternative;
- v->predecessorIndex = indexU_NL;
- }
- }
-
- }
- // end Djikstra Algorithm
-
-
- // reverse assemble path
- int e = endIndex;
- while (1) {
- if (e == -1) {
- if (elementPath[0] == startIndex)// check if starting point was reached
- break;
- return false;
- }
- elementPath.prepend(e);
-
- //Update Node
- e = nodeList[e].predecessorIndex;
-
- }
- return true;
- }
-
-} // end OptimisationTools namespace
diff --git a/src/Wima/OptimisationTools.h b/src/Wima/OptimisationTools.h
deleted file mode 100644
index 11c37431dc27d7ae63663b741889d775d5dd14d1..0000000000000000000000000000000000000000
--- a/src/Wima/OptimisationTools.h
+++ /dev/null
@@ -1,12 +0,0 @@
-#pragma once
-#include
-#include
-
-#include
-#include
-
-namespace OptimisationTools {
- bool dijkstraAlgorithm(const int numElements, int startIndex, int endIndex, QVector &elementPath, std::function distanceDij);
-}
-
-
diff --git a/src/Wima/RoutingThread.cpp b/src/Wima/RoutingThread.cpp
deleted file mode 100644
index f45bb3c0349231b9e91a4203ef6c38a7ad95a847..0000000000000000000000000000000000000000
--- a/src/Wima/RoutingThread.cpp
+++ /dev/null
@@ -1,129 +0,0 @@
-#include "RoutingThread.h"
-// std
-#include
-// Qt
-#include
-
-#include "QGCLoggingCategory.h"
-QGC_LOGGING_CATEGORY(RoutingThreadLog, "RoutingThreadLog")
-
-RoutingThread::RoutingThread(QObject *parent)
- : QThread(parent), _calculating(false), _stop(false), _restart(false) {
-
- static std::once_flag flag;
- std::call_once(flag,
- [] { qRegisterMetaType("PtrRoutingData"); });
-}
-
-RoutingThread::~RoutingThread() {
- this->_stop = true;
- Lock lk(this->_mutex);
- this->_restart = true;
- this->_cv.notify_one();
- lk.unlock();
- this->wait();
-}
-
-bool RoutingThread::calculating() const { return this->_calculating; }
-
-void RoutingThread::route(const RoutingParameter &par,
- const Generator &generator) {
- // Sample input.
- Lock lk(this->_mutex);
- this->_par = par;
- this->_generator = generator;
- lk.unlock();
-
- if (!this->isRunning()) {
- this->start();
- } else {
- Lock lk(this->_mutex);
- this->_restart = true;
- this->_cv.notify_one();
- }
-}
-
-void RoutingThread::run() {
- qCDebug(RoutingThreadLog) << "run(): thread start.";
- while (!this->_stop) {
- qCDebug(RoutingThreadLog) << "run(): calculation "
- "started.";
- // Copy input.
- auto start = std::chrono::high_resolution_clock::now();
-
- this->_calculating = true;
- emit calculatingChanged();
- Lock lk(this->_mutex);
- auto par = this->_par;
- auto generator = this->_generator;
- lk.unlock();
- auto safeAreaENU = par.safeArea;
- auto numRuns = par.numRuns;
- auto numSolutionsPerRun = par.numSolutions;
-
- PtrRoutingData pRouteData(new RoutingData());
- auto &transectsENU = pRouteData->transects;
- // Generate transects.
- if (generator(transectsENU)) {
- // Check if generation was successful.
- if (transectsENU.size() == 0) {
- qCDebug(RoutingThreadLog) << "run(): "
- "not able to generate transects.";
- } else {
- // Prepare data for routing.
- auto &solutionVector = pRouteData->solutionVector;
-
- snake::RouteParameter snakePar;
- snakePar.numSolutionsPerRun = numSolutionsPerRun;
- snakePar.numRuns = numRuns;
-
- // Set time limit to 10 min.
- const auto maxRoutingTime = std::chrono::minutes(10);
- const auto routingEnd =
- std::chrono::high_resolution_clock::now() + maxRoutingTime;
- const auto &restart = this->_restart;
- snakePar.stop = [&restart, routingEnd] {
- bool expired = std::chrono::high_resolution_clock::now() > routingEnd;
- return restart || expired;
- };
-
- // Route transects.
- bool success =
- snake::route(safeAreaENU, transectsENU, solutionVector, snakePar);
-
- // Check if routing was successful.
- if ((!success || solutionVector.size() < 1) && !this->_restart) {
- qCDebug(RoutingThreadLog) << "run(): "
- "routing failed. "
- << snakePar.errorString.c_str();
- } else if (this->_restart) {
- qCDebug(RoutingThreadLog) << "run(): "
- "restart requested.";
- } else {
- // Notify main thread.
- emit result(pRouteData);
- qCDebug(RoutingThreadLog) << "run(): "
- "concurrent update success.";
- }
- }
- } // end calculation
- else {
- qCDebug(RoutingThreadLog) << "run(): generator() failed.";
- }
- qCDebug(RoutingThreadLog)
- << "run(): execution time: "
- << std::chrono::duration_cast(
- std::chrono::high_resolution_clock::now() - start)
- .count()
- << " ms";
- // Signal calulation end and set thread to sleep.
- this->_calculating = false;
- emit calculatingChanged();
- Lock lk2(this->_mutex);
- if (!this->_restart) {
- this->_cv.wait(lk2, [this] { return this->_restart.load(); });
- }
- this->_restart = false;
- } // main loop
- qCDebug(RoutingThreadLog) << "run(): thread end.";
-}
diff --git a/src/Wima/RoutingThread.h b/src/Wima/RoutingThread.h
deleted file mode 100644
index bc5a3f11389c15e847db2438e26abe9c316adc93..0000000000000000000000000000000000000000
--- a/src/Wima/RoutingThread.h
+++ /dev/null
@@ -1,63 +0,0 @@
-#pragma once
-
-#include
-#include
-#include
-
-#include "snake.h"
-#include
-#include
-#include
-#include
-
-struct RoutingData {
- snake::Transects transects;
- std::vector solutionVector;
- std::string errorString;
-};
-
-struct RoutingParameter {
- RoutingParameter() : numSolutions(1), numRuns(1) {}
- snake::FPolygon safeArea;
- std::size_t numSolutions;
- std::size_t numRuns;
-};
-//!
-//! \brief The CSWorker class
-//! \note Don't call QThread::start, QThread::quit, etc. onyl use Worker
-//! members!
-class RoutingThread : public QThread {
- Q_OBJECT
- using Lock = std::unique_lock;
-
-public:
- using PtrRoutingData = shared_ptr;
- using Generator = std::function;
- using Consumer = std::function;
-
- RoutingThread(QObject *parent = nullptr);
- ~RoutingThread() override;
-
- bool calculating() const;
-
-public slots:
- void route(const RoutingParameter &par, const Generator &generator);
-
-signals:
- void result(PtrRoutingData pTransects);
- void calculatingChanged();
-
-protected:
- void run() override;
-
-private:
- mutable std::mutex _mutex;
- mutable std::condition_variable _cv;
- // Internal data
- RoutingParameter _par;
- Generator _generator; // transect generator
- // State
- std::atomic_bool _calculating;
- std::atomic_bool _stop;
- std::atomic_bool _restart;
-};
diff --git a/src/Wima/Snake/CircularGenerator.cpp b/src/Wima/Snake/CircularGenerator.cpp
deleted file mode 100644
index 838dae395b68dc2cc7019203fb458542ec4331fd..0000000000000000000000000000000000000000
--- a/src/Wima/Snake/CircularGenerator.cpp
+++ /dev/null
@@ -1,465 +0,0 @@
-#include "CircularGenerator.h"
-
-#include "QGCLoggingCategory.h"
-QGC_LOGGING_CATEGORY(CircularGeneratorLog, "CircularGeneratorLog")
-
-#define CLIPPER_SCALE 1000000
-#include "Wima/Geometry/GenericCircle.h"
-#include "clipper/clipper.hpp"
-
-using namespace ClipperLib;
-template <> inline auto get<0>(const IntPoint &p) { return p.X; }
-template <> inline auto get<1>(const IntPoint &p) { return p.Y; }
-
-#include "SnakeTile.h"
-#include "Wima/RoutingThread.h"
-
-namespace routing {
-
-bool circularTransects(const snake::FPoint &reference,
- const snake::FPolygon &polygon,
- const std::vector &tiles,
- snake::Length deltaR, snake::Angle deltaAlpha,
- snake::Length minLength, snake::Transects &transects);
-
-const char *CircularGenerator::settingsGroup = "CircularGenerator";
-const char *CircularGenerator::distanceName = "TransectDistance";
-const char *CircularGenerator::deltaAlphaName = "DeltaAlpha";
-const char *CircularGenerator::minLengthName = "MinLength";
-const char *CircularGenerator::refPointLatitudeName = "ReferencePointLat";
-const char *CircularGenerator::refPointLongitudeName = "ReferencePointLong";
-const char *CircularGenerator::refPointAltitudeName = "ReferencePointAlt";
-
-CircularGenerator::CircularGenerator(QObject *parent)
- : CircularGenerator(nullptr, parent) {}
-
-CircularGenerator::CircularGenerator(GeneratorBase::Data d, QObject *parent)
- : GeneratorBase(d, parent), _connectionsEstablished(false),
- _metaDataMap(FactMetaData::createMapFromJsonFile(
- QStringLiteral(":/json/CircularGenerator.SettingsGroup.json"), this)),
- _distance(settingsGroup, _metaDataMap[distanceName]),
- _deltaAlpha(settingsGroup, _metaDataMap[deltaAlphaName]),
- _minLength(settingsGroup, _metaDataMap[minLengthName]) {
- establishConnections();
-}
-
-QString CircularGenerator::editorQml() {
- return QStringLiteral("CircularGeneratorEditor.qml");
-}
-
-QString CircularGenerator::mapVisualQml() {
- return QStringLiteral("CircularGeneratorMapVisual.qml");
-}
-
-QString CircularGenerator::name() {
- return QStringLiteral("Circular Generator");
-}
-
-QString CircularGenerator::abbreviation() { return QStringLiteral("C. Gen."); }
-
-bool CircularGenerator::get(Generator &generator) {
- if (this->_d) {
- if (this->_d->isValid()) {
- // Prepare data.
- auto origin = this->_d->origin();
- origin.setAltitude(0);
- if (!origin.isValid()) {
- qCDebug(CircularGeneratorLog) << "get(): origin invalid." << origin;
- return false;
- }
-
- auto ref = this->_reference;
- ref.setAltitude(0);
- if (!ref.isValid()) {
- qCDebug(CircularGeneratorLog) << "get(): reference invalid." << ref;
- return false;
- }
- snake::FPoint reference;
- snake::toENU(origin, ref, reference);
-
- auto geoPolygon = this->_d->measurementArea().coordinateList();
- for (auto &v : geoPolygon) {
- if (v.isValid()) {
- v.setAltitude(0);
- } else {
- qCDebug(CircularGeneratorLog) << "get(): measurement area invalid.";
- for (const auto &w : geoPolygon) {
- qCDebug(CircularGeneratorLog) << w;
- }
- return false;
- }
- }
- auto pPolygon = std::make_shared();
- snake::areaToEnu(origin, geoPolygon, *pPolygon);
-
- // Progress and tiles.
- const auto &progress = this->_d->measurementArea().progress();
- const auto *tiles = this->_d->measurementArea().tiles();
- auto pTiles = std::make_shared>();
- if (progress.size() == tiles->count()) {
- for (int i = 0; i < tiles->count(); ++i) {
- if (progress[i] == 100) {
- const auto *obj = (*tiles)[int(i)];
- const auto *tile = qobject_cast(obj);
-
- if (tile != nullptr) {
- snake::FPolygon tileENU;
- snake::areaToEnu(origin, tile->coordinateList(), tileENU);
- pTiles->push_back(std::move(tileENU));
- } else {
- qCDebug(CircularGeneratorLog)
- << "get(): progress.size() != tiles->count().";
- return false;
- }
- }
- }
- } else {
- qCDebug(CircularGeneratorLog)
- << "get(): progress.size() != tiles->count().";
- return false;
- }
-
- auto geoDepot = this->_d->serviceArea().depot();
- if (!geoDepot.isValid()) {
- qCDebug(CircularGeneratorLog) << "get(): depot invalid." << geoDepot;
- return false;
- }
- snake::FPoint depot;
- snake::toENU(origin, geoDepot, depot);
-
- // Fetch transect parameter.
- auto distance =
- snake::Length(this->_distance.rawValue().toDouble() * bu::si::meter);
- auto minLength =
- snake::Length(this->_minLength.rawValue().toDouble() * bu::si::meter);
- auto alpha = snake::Angle(this->_deltaAlpha.rawValue().toDouble() *
- bu::degree::degree);
-
- generator = [reference, depot, pPolygon, pTiles, distance, alpha,
- minLength](snake::Transects &transects) -> bool {
- bool value = circularTransects(reference, *pPolygon, *pTiles, distance,
- alpha, minLength, transects);
- transects.insert(transects.begin(), snake::FLineString{depot});
- return value;
- };
- return true;
- } else {
- qCDebug(CircularGeneratorLog) << "get(): data invalid.";
- return false;
- }
- } else {
- qCDebug(CircularGeneratorLog) << "get(): data member not set.";
- return false;
- }
-}
-
-QGeoCoordinate CircularGenerator::reference() const { return _reference; }
-
-void CircularGenerator::setReference(const QGeoCoordinate &reference) {
- if (_reference != reference) {
- _reference = reference;
- emit referenceChanged();
- }
-}
-
-void CircularGenerator::resetReferenceIfInvalid() {
- if (!this->_reference.isValid()) {
- resetReference();
- }
-}
-
-void CircularGenerator::resetReference() {
- if (this->_d->measurementArea().center().isValid()) {
- setReference(this->_d->measurementArea().center());
- } else {
- qCWarning(CircularGeneratorLog)
- << "measurement area center" << this->_d->measurementArea().center();
- }
-}
-
-void CircularGenerator::establishConnections() {
- if (this->_d && !this->_connectionsEstablished) {
- connect(this->_d.get(), &AreaData::originChanged, this,
- &GeneratorBase::generatorChanged);
- connect(&this->_d->measurementArea(),
- &WimaMeasurementAreaData::progressChanged, this,
- &GeneratorBase::generatorChanged);
- connect(&this->_d->measurementArea(),
- &WimaMeasurementAreaData::tileDataChanged, this,
- &GeneratorBase::generatorChanged);
- connect(&this->_d->measurementArea(),
- &WimaMeasurementAreaData::centerChanged, this,
- &CircularGenerator::resetReferenceIfInvalid);
- connect(&this->_d->measurementArea(), &WimaMeasurementAreaData::pathChanged,
- this, &GeneratorBase::generatorChanged);
- connect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged, this,
- &GeneratorBase::generatorChanged);
- connect(&this->_d->joinedArea(), &WimaJoinedAreaData::pathChanged, this,
- &GeneratorBase::generatorChanged);
- connect(this->distance(), &Fact::rawValueChanged, this,
- &GeneratorBase::generatorChanged);
- connect(this->deltaAlpha(), &Fact::rawValueChanged, this,
- &GeneratorBase::generatorChanged);
- connect(this->minLength(), &Fact::rawValueChanged, this,
- &GeneratorBase::generatorChanged);
- connect(this, &CircularGenerator::referenceChanged, this,
- &GeneratorBase::generatorChanged);
- this->_connectionsEstablished = true;
- }
-}
-
-void CircularGenerator::deleteConnections() {
- if (this->_d && this->_connectionsEstablished) {
- disconnect(this->_d.get(), &AreaData::originChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(&this->_d->measurementArea(),
- &WimaMeasurementAreaData::progressChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(&this->_d->measurementArea(),
- &WimaMeasurementAreaData::tileDataChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(&this->_d->measurementArea(), &WimaMeasurementAreaData::center,
- this, &CircularGenerator::resetReferenceIfInvalid);
- disconnect(&this->_d->measurementArea(),
- &WimaMeasurementAreaData::pathChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged,
- this, &GeneratorBase::generatorChanged);
- disconnect(&this->_d->joinedArea(), &WimaJoinedAreaData::pathChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(this->distance(), &Fact::rawValueChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(this->deltaAlpha(), &Fact::rawValueChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(this->minLength(), &Fact::rawValueChanged, this,
- &GeneratorBase::generatorChanged);
- disconnect(this, &CircularGenerator::referenceChanged, this,
- &GeneratorBase::generatorChanged);
- this->_connectionsEstablished = false;
- }
-}
-
-Fact *CircularGenerator::distance() { return &_distance; }
-
-Fact *CircularGenerator::deltaAlpha() { return &_deltaAlpha; }
-
-Fact *CircularGenerator::minLength() { return &_minLength; }
-
-bool circularTransects(const snake::FPoint &reference,
- const snake::FPolygon &polygon,
- const std::vector &tiles,
- snake::Length deltaR, snake::Angle deltaAlpha,
- snake::Length minLength, snake::Transects &transects) {
- auto s1 = std::chrono::high_resolution_clock::now();
-
- // Check preconitions
- if (polygon.outer().size() >= 3) {
- using namespace boost::units;
- // Convert geo polygon to ENU polygon.
- std::string error;
- // Check validity.
- if (!bg::is_valid(polygon, error)) {
- qCDebug(CircularGeneratorLog) << "circularTransects(): "
- "invalid polygon.";
- qCDebug(CircularGeneratorLog) << error.c_str();
- std::stringstream ss;
- ss << bg::wkt(polygon);
- qCDebug(CircularGeneratorLog) << ss.str().c_str();
- } else {
- // Calculate polygon distances and angles.
- std::vector