diff --git a/.gitmodules b/.gitmodules index 1e3835f3c7a9cba78b88ca2c0ea91d1c5557166a..162643016c226397eccab7485ee04e83df98d345 100644 --- a/.gitmodules +++ b/.gitmodules @@ -4,3 +4,9 @@ [submodule "libs/mavlink/include/mavlink/v2.0"] path = libs/mavlink/include/mavlink/v2.0 url = https://github.com/mavlink/c_library_v2.git +[submodule "libs/WGS84toCartesian"] + path = libs/WGS84toCartesian + url = https://github.com/chrberger/WGS84toCartesian.git +[submodule "libs/polylabel"] + path = libs/polylabel + url = https://github.com/mapbox/polylabel.git diff --git a/CMakeCache.txt b/CMakeCache.txt new file mode 100644 index 0000000000000000000000000000000000000000..c6a6f2bc44a3ca37b6d2af6d6aa8a209b4f455d0 --- /dev/null +++ b/CMakeCache.txt @@ -0,0 +1,297 @@ +# This is the CMakeCache file. +# For build in directory: /home/valentin/Desktop/drones/qgroundcontrol +# It was generated by CMake: /usr/bin/cmake +# You can edit this file to change values found and used by cmake. +# If you do not want to change any of the values, simply exit the editor. +# If you do want to change a value, simply edit, save, and exit the editor. +# The syntax for the file is as follows: +# KEY:TYPE=VALUE +# KEY is the name of a variable in the cache. +# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. +# VALUE is the current value for the KEY. + +######################## +# EXTERNAL cache entries +######################## + +//Use ccache if available +CCACHE:BOOL=ON + +//Path to a program. +CCACHE_PROGRAM:FILEPATH=CCACHE_PROGRAM-NOTFOUND + +//Path to a program. +CMAKE_AR:FILEPATH=/usr/bin/ar + +//Build type +CMAKE_BUILD_TYPE:STRING=RelWithDebInfo + +//Enable/Disable color output during build. +CMAKE_COLOR_MAKEFILE:BOOL=ON + +//CXX compiler +CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ + +//A wrapper around 'ar' adding the appropriate '--plugin' option +// for the GCC compiler +CMAKE_CXX_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-7 + +//A wrapper around 'ranlib' adding the appropriate '--plugin' option +// for the GCC compiler +CMAKE_CXX_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-7 + +//Flags used by the compiler during all build types. +CMAKE_CXX_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_CXX_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release builds for minimum +// size. +CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds. +CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during release builds with debug info. +CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//Flags used by the linker. +CMAKE_EXE_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Enable/Disable output of compile commands during generation. +CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF + +//Install path prefix, prepended onto install directories. +CMAKE_INSTALL_PREFIX:PATH=/usr/local + +//Path to a program. +CMAKE_LINKER:FILEPATH=/usr/bin/ld + +//Path to a program. +CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make + +//Flags used by the linker during the creation of modules. +CMAKE_MODULE_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_NM:FILEPATH=/usr/bin/nm + +//Path to a program. +CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy + +//Path to a program. +CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump + +//Value Computed by CMake +CMAKE_PROJECT_NAME:STATIC=QGroundControl + +//Path to a program. +CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib + +//Flags used by the linker during the creation of dll's. +CMAKE_SHARED_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//If set, runtime paths are not added when installing shared libraries, +// but are added when building. +CMAKE_SKIP_INSTALL_RPATH:BOOL=NO + +//If set, runtime paths are not added when using shared libraries. +CMAKE_SKIP_RPATH:BOOL=NO + +//Flags used by the linker during the creation of static libraries. +CMAKE_STATIC_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_STRIP:FILEPATH=/usr/bin/strip + +//If this value is on, makefiles will be generated without the +// .SILENT directive, and all commands will be echoed to the console +// during the make. This is useful for debugging only. With Visual +// Studio IDE projects all commands are done without /nologo. +CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE + +//Value Computed by CMake +QGroundControl_BINARY_DIR:STATIC=/home/valentin/Desktop/drones/qgroundcontrol + +//Value Computed by CMake +QGroundControl_SOURCE_DIR:STATIC=/home/valentin/Desktop/drones/qgroundcontrol + +//The directory containing a CMake configuration file for Qt5. +Qt5_DIR:PATH=Qt5_DIR-NOTFOUND + + +######################## +# INTERNAL cache entries +######################## + +//ADVANCED property for variable: CMAKE_AR +CMAKE_AR-ADVANCED:INTERNAL=1 +//STRINGS property for variable: CMAKE_BUILD_TYPE +CMAKE_BUILD_TYPE-STRINGS:INTERNAL=Debug;Release;RelWithDebInfo;MinSizeRel;Coverage +//This is the directory where this CMakeCache.txt was created +CMAKE_CACHEFILE_DIR:INTERNAL=/home/valentin/Desktop/drones/qgroundcontrol +//Major version of cmake used to create the current loaded cache +CMAKE_CACHE_MAJOR_VERSION:INTERNAL=3 +//Minor version of cmake used to create the current loaded cache +CMAKE_CACHE_MINOR_VERSION:INTERNAL=10 +//Patch version of cmake used to create the current loaded cache +CMAKE_CACHE_PATCH_VERSION:INTERNAL=2 +//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE +CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 +//Path to CMake executable. +CMAKE_COMMAND:INTERNAL=/usr/bin/cmake +//Path to cpack program executable. +CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack +//Path to ctest program executable. +CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest +//ADVANCED property for variable: CMAKE_CXX_COMPILER +CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_COMPILER_AR +CMAKE_CXX_COMPILER_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_COMPILER_RANLIB +CMAKE_CXX_COMPILER_RANLIB-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS +CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG +CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL +CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE +CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO +CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//Executable file format +CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS +CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG +CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE +CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS +CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 +//Name of external makefile project generator. +CMAKE_EXTRA_GENERATOR:INTERNAL= +//Name of generator. +CMAKE_GENERATOR:INTERNAL=Unix Makefiles +//Name of generator platform. +CMAKE_GENERATOR_PLATFORM:INTERNAL= +//Name of generator toolset. +CMAKE_GENERATOR_TOOLSET:INTERNAL= +//Source directory with the top level CMakeLists.txt file for this +// project +CMAKE_HOME_DIRECTORY:INTERNAL=/home/valentin/Desktop/drones/qgroundcontrol +//Install .so files without execute permission. +CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 +//ADVANCED property for variable: CMAKE_LINKER +CMAKE_LINKER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MAKE_PROGRAM +CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS +CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG +CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE +CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_NM +CMAKE_NM-ADVANCED:INTERNAL=1 +//number of local generators +CMAKE_NUMBER_OF_MAKEFILES:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJCOPY +CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJDUMP +CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 +//Platform information initialized +CMAKE_PLATFORM_INFO_INITIALIZED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_RANLIB +CMAKE_RANLIB-ADVANCED:INTERNAL=1 +//Path to CMake installation. +CMAKE_ROOT:INTERNAL=/usr/share/cmake-3.10 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS +CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG +CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE +CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH +CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_RPATH +CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS +CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG +CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE +CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STRIP +CMAKE_STRIP-ADVANCED:INTERNAL=1 +//uname command +CMAKE_UNAME:INTERNAL=/bin/uname +//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE +CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 + diff --git a/SurveyComplexItem_delLater.cc b/SurveyComplexItem_delLater.cc deleted file mode 100644 index ca613e297db6224a830916be1aa06fa495f4436b..0000000000000000000000000000000000000000 --- a/SurveyComplexItem_delLater.cc +++ /dev/null @@ -1,713 +0,0 @@ -#include "CircularSurveyComplexItem.h" -#include "JsonHelper.h" -#include "QGCApplication.h" -#include - - -const char* CircularSurveyComplexItem::settingsGroup = "CircularSurvey"; -const char* CircularSurveyComplexItem::deltaRName = "DeltaR"; -const char* CircularSurveyComplexItem::deltaAlphaName = "DeltaAlpha"; -const char* CircularSurveyComplexItem::transectMinLengthName = "TransectMinLength"; -const char* CircularSurveyComplexItem::isSnakePathName = "IsSnakePath"; -const char* CircularSurveyComplexItem::reverseName = "Reverse"; -const char* CircularSurveyComplexItem::maxWaypointsName = "MaxWaypoints"; - - -const char* CircularSurveyComplexItem::jsonComplexItemTypeValue = "circularSurvey"; -const char* CircularSurveyComplexItem::jsonDeltaRKey = "deltaR"; -const char* CircularSurveyComplexItem::jsonDeltaAlphaKey = "deltaAlpha"; -const char* CircularSurveyComplexItem::jsonTransectMinLengthKey = "transectMinLength"; -const char* CircularSurveyComplexItem::jsonIsSnakePathKey = "isSnakePath"; -const char* CircularSurveyComplexItem::jsonReverseKey = "reverse"; -const char* CircularSurveyComplexItem::jsonReferencePointLatKey = "referencePointLat"; -const char* CircularSurveyComplexItem::jsonReferencePointLongKey = "referencePointLong"; -const char* CircularSurveyComplexItem::jsonReferencePointAltKey = "referencePointAlt"; - -CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyView, const QString &kmlOrShpFile, QObject *parent) - : TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent) - , _referencePoint (QGeoCoordinate(0, 0,0)) - , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CircularSurvey.SettingsGroup.json"), this)) - , _deltaR (settingsGroup, _metaDataMap[deltaRName]) - , _deltaAlpha (settingsGroup, _metaDataMap[deltaAlphaName]) - , _transectMinLength (settingsGroup, _metaDataMap[transectMinLengthName]) - , _isSnakePath (settingsGroup, _metaDataMap[isSnakePathName]) - , _reverse (settingsGroup, _metaDataMap[reverseName]) - , _maxWaypoints (settingsGroup, _metaDataMap[maxWaypointsName]) - , _isInitialized (false) - , _reverseOnly (false) - , _referencePointBeingChanged (false) - , _updateCounter (0) -{ - Q_UNUSED(kmlOrShpFile) - _editorQml = "qrc:/qml/CircularSurveyItemEditor.qml"; - connect(&_deltaR, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects); - connect(&_deltaAlpha, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects); - connect(&_transectMinLength, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects); - connect(&_isSnakePath, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects); - connect(&_maxWaypoints, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects); - connect(&_reverse, &Fact::valueChanged, this, &CircularSurveyComplexItem::_reverseTransects); - connect(this, &CircularSurveyComplexItem::refPointChanged, this, &CircularSurveyComplexItem::_rebuildTransects); - //connect(&_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this->) - -} - -void CircularSurveyComplexItem::resetReference() -{ - setRefPoint(_surveyAreaPolygon.center()); -} - -void CircularSurveyComplexItem::setReferencePointBeingChanged(bool changeing) -{ - _referencePointBeingChanged = changeing; -} - -void CircularSurveyComplexItem::setRefPoint(const QGeoCoordinate &refPt) -{ - if (refPt != _referencePoint){ - _referencePoint = refPt; - - emit refPointChanged(); - } -} - -void CircularSurveyComplexItem::setIsInitialized(bool isInitialized) -{ - if (isInitialized != _isInitialized) { - _isInitialized = isInitialized; - - emit isInitializedChanged(); - } -} - -QGeoCoordinate CircularSurveyComplexItem::refPoint() const -{ - return _referencePoint; -} - -Fact *CircularSurveyComplexItem::deltaR() -{ - return &_deltaR; -} - -Fact *CircularSurveyComplexItem::deltaAlpha() -{ - return &_deltaAlpha; -} - -bool CircularSurveyComplexItem::isInitialized() -{ - return _isInitialized; -} - -bool CircularSurveyComplexItem::referencePointBeingChanged() -{ - return _referencePointBeingChanged; -} - -bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) -{ - // We need to pull version first to determine what validation/conversion needs to be performed - QList 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 }, - { jsonDeltaRKey, QJsonValue::Double, true }, - { jsonDeltaAlphaKey, QJsonValue::Double, true }, - { jsonTransectMinLengthKey, QJsonValue::Double, true }, - { jsonIsSnakePathKey, QJsonValue::Bool, true }, - { jsonReverseKey, QJsonValue::Bool, true }, - { jsonReferencePointLatKey, QJsonValue::Double, true }, - { jsonReferencePointLongKey, QJsonValue::Double, true }, - { jsonReferencePointAltKey, QJsonValue::Double, true }, - }; - - if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) { - return false; - } - - QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString(); - QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString(); - if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) { - errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType); - return false; - } - - _ignoreRecalc = true; - - setSequenceNumber(sequenceNumber); - - if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) { - _surveyAreaPolygon.clear(); - return false; - } - - if (!_load(complexObject, errorString)) { - _ignoreRecalc = false; - return false; - } - - _deltaR.setRawValue (complexObject[jsonDeltaRKey].toDouble()); - _deltaAlpha.setRawValue (complexObject[jsonDeltaAlphaKey].toDouble()); - _transectMinLength.setRawValue (complexObject[jsonTransectMinLengthKey].toDouble()); - _referencePoint.setLongitude (complexObject[jsonReferencePointLongKey].toDouble()); - _referencePoint.setLatitude (complexObject[jsonReferencePointLatKey].toDouble()); - _referencePoint.setAltitude (complexObject[jsonReferencePointAltKey].toDouble()); - _isSnakePath.setRawValue (complexObject[jsonIsSnakePathKey].toBool()); - _reverse.setRawValue (complexObject[jsonReverseKey].toBool()); - setIsInitialized(true); - - _ignoreRecalc = false; - - _recalcComplexDistance(); - if (_cameraShots == 0) { - // Shot count was possibly not available from plan file - _recalcCameraShots(); - } - - return true; -} - -void CircularSurveyComplexItem::save(QJsonArray &planItems) -{ - QJsonObject saveObject; - - _save(saveObject); - - saveObject[JsonHelper::jsonVersionKey] = 1; - saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; - saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; - - saveObject[jsonDeltaRKey] = _deltaR.rawValue().toDouble(); - saveObject[jsonDeltaAlphaKey] = _deltaAlpha.rawValue().toDouble(); - saveObject[jsonTransectMinLengthKey] = _transectMinLength.rawValue().toDouble(); - saveObject[jsonIsSnakePathKey] = _isSnakePath.rawValue().toBool(); - saveObject[jsonReverseKey] = _reverse.rawValue().toBool(); - saveObject[jsonReferencePointLongKey] = _referencePoint.longitude(); - saveObject[jsonReferencePointLatKey] = _referencePoint.latitude(); - saveObject[jsonReferencePointAltKey] = _referencePoint.altitude(); - - // Polygon shape - _surveyAreaPolygon.saveToJson(saveObject); - - planItems.append(saveObject); -} - -void CircularSurveyComplexItem::appendMissionItems(QList &items, QObject *missionItemParent) -{ - if (_loadedMissionItems.count()) { - // We have mission items from the loaded plan, use those - _appendLoadedMissionItems(items, missionItemParent); - } else { - // Build the mission items on the fly - _buildAndAppendMissionItems(items, missionItemParent); - } -} - -void CircularSurveyComplexItem::_appendLoadedMissionItems(QList& items, QObject* missionItemParent) -{ - //qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems"; - - int seqNum = _sequenceNumber; - - for (const MissionItem* loadedMissionItem: _loadedMissionItems) { - MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent); - item->setSequenceNumber(seqNum++); - items.append(item); - } -} - -void CircularSurveyComplexItem::_buildAndAppendMissionItems(QList& items, QObject* missionItemParent) -{ - // original code: SurveyComplexItem::_buildAndAppendMissionItems() - //qCDebug(SurveyComplexItemLog) << "_buildAndAppendMissionItems"; - - // Now build the mission items from the transect points - - MissionItem* item; - int seqNum = _sequenceNumber; - // bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool(); - // bool addTriggerAtBeginning = !hoverAndCaptureEnabled() && imagesEverywhere; - //bool firstOverallPoint = true; - - MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT; - - for (const QList& transect: _transects) { - //bool transectEntry = true; - - for (const CoordInfo_t& transectCoordInfo: transect) { - item = new MissionItem(seqNum++, - MAV_CMD_NAV_WAYPOINT, - mavFrame, - 0, // Hold time (delay for hover and capture to settle vehicle before image is taken) - 0.0, // No acceptance radius specified - 0.0, // Pass through waypoint - std::numeric_limits::quiet_NaN(), // Yaw unchanged - transectCoordInfo.coord.latitude(), - transectCoordInfo.coord.longitude(), - transectCoordInfo.coord.altitude(), - true, // autoContinue - false, // isCurrentItem - missionItemParent); - items.append(item); - // implement capture if desired -// if (hoverAndCaptureEnabled()) { -// item = new MissionItem(seqNum++, -// MAV_CMD_IMAGE_START_CAPTURE, -// MAV_FRAME_MISSION, -// 0, // Reserved (Set to 0) -// 0, // Interval (none) -// 1, // Take 1 photo -// qQNaN(), qQNaN(), qQNaN(), qQNaN(), // param 4-7 reserved -// true, // autoContinue -// false, // isCurrentItem -// missionItemParent); -// items.append(item); -// } - -// if (firstOverallPoint && addTriggerAtBeginning) { -// // Start triggering -// addTriggerAtBeginning = false; -// item = new MissionItem(seqNum++, -// MAV_CMD_DO_SET_CAM_TRIGG_DIST, -// MAV_FRAME_MISSION, -// triggerDistance(), // trigger distance -// 0, // shutter integration (ignore) -// 1, // trigger immediately when starting -// 0, 0, 0, 0, // param 4-7 unused -// true, // autoContinue -// false, // isCurrentItem -// missionItemParent); -// items.append(item); -// } - //firstOverallPoint = false; - -// // Possibly add trigger start/stop to survey area entrance/exit -// if (triggerCamera() && !hoverAndCaptureEnabled() && transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge) { -// if (transectEntry) { -// // Start of transect, always start triggering. We do this even if we are taking images everywhere. -// // This allows a restart of the mission in mid-air without losing images from the entire mission. -// // At most you may lose part of a transect. -// item = new MissionItem(seqNum++, -// MAV_CMD_DO_SET_CAM_TRIGG_DIST, -// MAV_FRAME_MISSION, -// triggerDistance(), // trigger distance -// 0, // shutter integration (ignore) -// 1, // trigger immediately when starting -// 0, 0, 0, 0, // param 4-7 unused -// true, // autoContinue -// false, // isCurrentItem -// missionItemParent); -// items.append(item); -// transectEntry = false; -// } else if (!imagesEverywhere && !transectEntry){ -// // End of transect, stop triggering -// item = new MissionItem(seqNum++, -// MAV_CMD_DO_SET_CAM_TRIGG_DIST, -// MAV_FRAME_MISSION, -// 0, // stop triggering -// 0, // shutter integration (ignore) -// 0, // trigger immediately when starting -// 0, 0, 0, 0, // param 4-7 unused -// true, // autoContinue -// false, // isCurrentItem -// missionItemParent); -// items.append(item); -// } -// } - } - } - - // implemetn photo capture if desired -// if (triggerCamera() && !hoverAndCaptureEnabled() && imagesEverywhere) { -// // Stop triggering -// MissionItem* item = new MissionItem(seqNum++, -// MAV_CMD_DO_SET_CAM_TRIGG_DIST, -// MAV_FRAME_MISSION, -// 0, // stop triggering -// 0, // shutter integration (ignore) -// 0, // trigger immediately when starting -// 0, 0, 0, 0, // param 4-7 unused -// true, // autoContinue -// false, // isCurrentItem -// missionItemParent); -// items.append(item); -// } -} - -void CircularSurveyComplexItem::applyNewAltitude(double newAltitude) -{ - _cameraCalc.valueSetIsDistance()->setRawValue(true); - _cameraCalc.distanceToSurface()->setRawValue(newAltitude); - _cameraCalc.setDistanceToSurfaceRelative(true); -} - -double CircularSurveyComplexItem::timeBetweenShots() -{ - return 1; -} - -bool CircularSurveyComplexItem::readyForSave() const -{ - return TransectStyleComplexItem::readyForSave(); -} - -double CircularSurveyComplexItem::additionalTimeDelay() const -{ - return 0; -} - -void CircularSurveyComplexItem::_rebuildTransectsPhase1() -{ - using namespace GeoUtilities; - using namespace PolygonCalculus; - using namespace PlanimetryCalculus; - - // rebuild not necessary? - if (!_isInitialized || _referencePointBeingChanged) - return; - - _updateCounter++; - unsigned int waypointCounter = 0; - - // If the transects are getting rebuilt then any previously loaded mission items are now invalid - if (_loadedMissionItemsParent) { - _loadedMissionItems.clear(); - _loadedMissionItemsParent->deleteLater(); - _loadedMissionItemsParent = nullptr; - } - - - // check if input is valid - if ( _surveyAreaPolygon.count() < 3) { - _transects.clear(); - return; - } - - // reverse transects and return - if (_reverseOnly) { - _reverseOnly = false; - - if (_transects.size() > 1) { - QList> transectsReverse; - transectsReverse.reserve(_transects.size()); - - for (auto list : _transects) { - QList listReverse; - for (auto coordinate : list) - listReverse.prepend(coordinate); - - transectsReverse.prepend(listReverse); - } - _transects = transectsReverse; - - return; - } - } - - _transects.clear(); - QPolygonF surveyPolygon = toQPolygonF(toCartesian2D(_surveyAreaPolygon.coordinateList(), _referencePoint)); - - // some more checks - if (!PolygonCalculus::isSimplePolygon(surveyPolygon)) { - _transects.clear(); - return; - } - - // even more checks - if (!PolygonCalculus::hasClockwiseWinding(surveyPolygon)) - PolygonCalculus::reversePath(surveyPolygon); - - QVector distances; - for (const QPointF &p : surveyPolygon) distances.append(norm(p)); - - // check if input is valid - if ( _deltaAlpha.rawValue() > _deltaAlpha.rawMax() - && _deltaAlpha.rawValue() < _deltaAlpha.rawMin()) - return; - if ( _deltaR.rawValue() > _deltaR.rawMax() - && _deltaR.rawValue() < _deltaR.rawMin()) - return; - - - // fetch input data - double dalpha = _deltaAlpha.rawValue().toDouble()/180.0*M_PI; // radiants - double dr = _deltaR.rawValue().toDouble(); // meter - double lmin = _transectMinLength.rawValue().toDouble(); - double r_min = dr; // meter - double r_max = (*std::max_element(distances.begin(), distances.end())); // meter - unsigned int maxWaypoints = _maxWaypoints.rawValue().toUInt(); - - QPointF origin(0, 0); - IntersectType type; - bool originInside = true; - if (!contains(surveyPolygon, origin, type)) { - QVector angles; - for (const QPointF &p : surveyPolygon) angles.append(truncateAngle(angle(p))); - - // determine r_min by successive approximation - double r = r_min; - while ( r < r_max) { - Circle circle(r, origin); - - if (intersects(circle, surveyPolygon)) { - r_min = r; - break; - } - - r += dr; - } - originInside = false; - } - - - // generate transects - QVector> transectPath; - double r = r_min; - - while (r < r_max) { - Circle circle(r, origin); - QVector intersectPoints; - QVector typeList; - QVector> neighbourList; - if (intersects(circle, surveyPolygon, intersectPoints, neighbourList, typeList)) { - - // intersection Points between circle and polygon, entering polygon - // when walking in counterclockwise direction along circle - QPointFList entryPoints; - // intersection Points between circle and polygon, leaving polygon - // when walking in counterclockwise direction along circle - QPointFList exitPoints; - // determine entryPoints and exit Points - for (int j = 0; j < intersectPoints.size(); j++) { - QVector intersects = intersectPoints[j]; // one pt = tangent, two pt = sekant - - QPointF p1 = surveyPolygon[neighbourList[j].first]; - QPointF p2 = surveyPolygon[neighbourList[j].second]; - QLineF intersetLine(p1, p2); - double lineAngle = angle(intersetLine); - -// int n = 16; -// for (int i = -n; i <= n; i++) { -// double alpha = 2*M_PI*double(i)/double(n); -// qDebug() << i << " " << alpha << " " << truncateAngle(alpha); -// } - - for (QPointF ipt : intersects) { - double circleTangentAngle = angle(ipt)+M_PI_2; - // compare line angle and circle tangent at intersection point - // to determine between exit and entry point -// qDebug() << "lineAngle" << lineAngle*180/M_PI; -// qDebug() << "circleTangentAngle" << circleTangentAngle*180/M_PI; -// qDebug() << "!qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle): " << !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle)); -// qDebug() << "!qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI): " << !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI)); - if ( !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle)) - && !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI) )) - { - if (truncateAngle(circleTangentAngle - lineAngle) > M_PI) { - entryPoints.append(ipt); - } else { - exitPoints.append(ipt); - } - } - } - } - - // sort - std::sort(entryPoints.begin(), entryPoints.end(), [](QPointF p1, QPointF p2) { - return angle(p1) < angle(p2); - }); - std::sort(exitPoints.begin(), exitPoints.end(), [](QPointF p1, QPointF p2) { - return angle(p1) < angle(p2); - }); - - // match entry and exit points - int offset = 0; - double minAngle = std::numeric_limits::infinity(); - for (int k = 0; k < exitPoints.size(); k++) { - QPointF pt = exitPoints[k]; - double alpha = truncateAngle(angle(pt) - angle(entryPoints[0])); - if (minAngle > alpha) { - minAngle = alpha; - offset = k; - } - } - - // generate circle sectors - for (int k = 0; k < entryPoints.size(); k++) { - double alpha1 = angle(entryPoints[k]); - double alpha2 = angle(exitPoints[(k+offset) % entryPoints.size()]); - double dAlpha = truncateAngle(alpha2-alpha1); - int numNodes = int(ceil(dAlpha/dalpha)) + 1; -// qDebug() << "alpha1" << alpha1; -// qDebug() << "alpha2" << alpha2; -// qDebug() << "dAlpha" << dAlpha; -// qDebug() << "numNodes" << numNodes; - - QVector sectorPath = circle.approximateSektor(numNodes, alpha1, alpha2); - // use shortestPath() here if necessary, could be a problem if dr >> - if (sectorPath.size() > 0) { - waypointCounter += uint(sectorPath.size()); - if (waypointCounter > maxWaypoints ) - return; - transectPath.append(sectorPath); - } - } - } else if (originInside) { - // circle fully inside polygon - int numNodes = int(ceil(2*M_PI/dalpha)) + 1; - QVector sectorPath = circle.approximateSektor(numNodes, 0, 2*M_PI); - // use shortestPath() here if necessary, could be a problem if dr >> - waypointCounter += uint(sectorPath.size()); - if (waypointCounter > maxWaypoints ) - return; - transectPath.append(sectorPath); - } - r += dr; - } - - if (transectPath.size() == 0) - return; - - // remove short transects - for (int i = 0; i < transectPath.size(); i++) { - auto transect = transectPath[i]; - double len = 0; - for (int j = 0; j < transect.size()-1; ++j) { - len += PlanimetryCalculus::distance(transect[j], transect[j+1]); - } - - if (len < lmin) - transectPath.removeAt(i--); - } - if (transectPath.size() == 0) - return; - - // optimize path to snake or zig-zag pattern - bool isSnakePattern = _isSnakePath.rawValue().toBool(); - QVector currentSection = transectPath.takeFirst(); - if ( currentSection.isEmpty() ) - return; - QVector optiPath; // optimized path - while( !transectPath.empty() ) { - optiPath.append(currentSection); - QPointF endVertex = currentSection.last(); - double minDist = std::numeric_limits::infinity(); - int index = 0; - bool reversePath = false; - - // iterate over all paths in fullPath and assign the one with the shortest distance to endVertex to currentSection - for (int i = 0; i < transectPath.size(); i++) { - auto iteratorPath = transectPath[i]; - double dist = PlanimetryCalculus::distance(endVertex, iteratorPath.first()); - if ( dist < minDist ) { - minDist = dist; - index = i; - reversePath = false; - } - dist = PlanimetryCalculus::distance(endVertex, iteratorPath.last()); - if (dist < minDist) { - minDist = dist; - index = i; - reversePath = true; - } - } - currentSection = transectPath.takeAt(index); - if (reversePath && isSnakePattern) { - PolygonCalculus::reversePath(currentSection); - } - } - - optiPath.append(currentSection); // append last section - - if (optiPath.size() > _maxWaypoints.rawValue().toInt()) - return; - - - // convert to CoordInfo_t - if (_reverse.rawValue().toBool()) - PolygonCalculus::reversePath(optiPath); - - QVector geoPath = toGeo(optiPath, _referencePoint); - QList transectList; - transectList.reserve(optiPath.size()); - for ( const QGeoCoordinate &coordinate : geoPath) { - CoordInfo_t coordinfo = {coordinate, CoordTypeInterior}; - transectList.append(coordinfo); - } - _transects.append(transectList); - - qDebug() << "CircularSurveyComplexItem::_rebuildTransectsPhase1(): calls: " << _updateCounter; - -} - -void CircularSurveyComplexItem::_recalcComplexDistance() -{ - _complexDistance = 0; - for (int i=0; i<_visualTransectPoints.count() - 1; i++) { - _complexDistance += _visualTransectPoints[i].value().distanceTo(_visualTransectPoints[i+1].value()); - } - emit complexDistanceChanged(); -} - -// no cameraShots in Circular Survey, add if desired -void CircularSurveyComplexItem::_recalcCameraShots() -{ - _cameraShots = 0; -} - -void CircularSurveyComplexItem::_reverseTransects() -{ - _reverseOnly = true; - _rebuildTransects(); -} - - - -Fact *CircularSurveyComplexItem::transectMinLength() -{ - return &_transectMinLength; -} - -Fact *CircularSurveyComplexItem::isSnakePath() -{ - return &_isSnakePath; -} - -Fact *CircularSurveyComplexItem::reverse() -{ - return &_reverse; -} - -Fact *CircularSurveyComplexItem::maxWaypoints() -{ - return &_maxWaypoints; -} - - - - -/*! - \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/libs/WGS84toCartesian b/libs/WGS84toCartesian new file mode 160000 index 0000000000000000000000000000000000000000..15181a849968866efa5ac220d3f7c2e5ac281254 --- /dev/null +++ b/libs/WGS84toCartesian @@ -0,0 +1 @@ +Subproject commit 15181a849968866efa5ac220d3f7c2e5ac281254 diff --git a/libs/mason_packages/.binaries/headers/geometry/1.0.0.tar.gz b/libs/mason_packages/.binaries/headers/geometry/1.0.0.tar.gz new file mode 100644 index 0000000000000000000000000000000000000000..54f900fc7f1c70ac590776bdf87f1e6c8779f7e1 Binary files /dev/null and b/libs/mason_packages/.binaries/headers/geometry/1.0.0.tar.gz differ diff --git a/libs/mason_packages/.binaries/headers/polylabel/1.0.3.tar.gz b/libs/mason_packages/.binaries/headers/polylabel/1.0.3.tar.gz new file mode 100644 index 0000000000000000000000000000000000000000..25e4884688e24ae371d687f33adb060dce167fed Binary files /dev/null and b/libs/mason_packages/.binaries/headers/polylabel/1.0.3.tar.gz differ diff --git a/libs/mason_packages/.binaries/headers/variant/1.1.0.tar.gz b/libs/mason_packages/.binaries/headers/variant/1.1.0.tar.gz new file mode 100644 index 0000000000000000000000000000000000000000..a2eb25c6c1386b820ea9fbc8e7c96a227e1021de Binary files /dev/null and b/libs/mason_packages/.binaries/headers/variant/1.1.0.tar.gz differ diff --git a/libs/mason_packages/.binaries/headers/variant/1.1.4.tar.gz b/libs/mason_packages/.binaries/headers/variant/1.1.4.tar.gz new file mode 100644 index 0000000000000000000000000000000000000000..9b77d23fbda9200ce4f47a7b3387b185ab469043 Binary files /dev/null and b/libs/mason_packages/.binaries/headers/variant/1.1.4.tar.gz differ diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/feature.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/feature.hpp new file mode 100644 index 0000000000000000000000000000000000000000..8d03f4674c3fb71f15e436561f06e454e71c4b46 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/feature.hpp @@ -0,0 +1,113 @@ +#pragma once + +#include + +#include + +#include +#include +#include +#include + +namespace mapbox { +namespace feature { + +struct value; + +struct null_value_t +{ +}; + +constexpr bool operator==(const null_value_t&, const null_value_t&) { return true; } +constexpr bool operator!=(const null_value_t&, const null_value_t&) { return false; } +constexpr bool operator<(const null_value_t&, const null_value_t&) { return false; } + +constexpr null_value_t null_value = null_value_t(); + +// Multiple numeric types (uint64_t, int64_t, double) are present in order to support +// the widest possible range of JSON numbers, which do not have a maximum range. +// Implementations that produce `value`s should use that order for type preference, +// using uint64_t for positive integers, int64_t for negative integers, and double +// for non-integers and integers outside the range of 64 bits. +using value_base = mapbox::util::variant>, + mapbox::util::recursive_wrapper>>; + +struct value : value_base +{ + using value_base::value_base; +}; + +using property_map = std::unordered_map; + +// The same considerations and requirement for numeric types apply as for `value_base`. +using identifier = mapbox::util::variant; + +template +struct feature +{ + using coordinate_type = T; + using geometry_type = mapbox::geometry::geometry; // Fully qualified to avoid GCC -fpermissive error. + + geometry_type geometry; + property_map properties; + identifier id; + + feature() + : geometry(), + properties(), + id() {} + feature(geometry_type const& geom_) + : geometry(geom_), + properties(), + id() {} + feature(geometry_type&& geom_) + : geometry(std::move(geom_)), + properties(), + id() {} + feature(geometry_type const& geom_, property_map const& prop_) + : geometry(geom_), properties(prop_), id() {} + feature(geometry_type&& geom_, property_map&& prop_) + : geometry(std::move(geom_)), + properties(std::move(prop_)), + id() {} + feature(geometry_type const& geom_, property_map const& prop_, identifier const& id_) + : geometry(geom_), + properties(prop_), + id(id_) {} + feature(geometry_type&& geom_, property_map&& prop_, identifier&& id_) + : geometry(std::move(geom_)), + properties(std::move(prop_)), + id(std::move(id_)) {} +}; + +template +constexpr bool operator==(feature const& lhs, feature const& rhs) +{ + return lhs.id == rhs.id && lhs.geometry == rhs.geometry && lhs.properties == rhs.properties; +} + +template +constexpr bool operator!=(feature const& lhs, feature const& rhs) +{ + return !(lhs == rhs); +} + +template class Cont = std::vector> +struct feature_collection : Cont> +{ + using coordinate_type = T; + using feature_type = feature; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + feature_collection(Args&&... args) : container_type(std::forward(args)...) + { + } + feature_collection(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +} // namespace feature +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry.hpp new file mode 100644 index 0000000000000000000000000000000000000000..9caecd9a108c6b452f279c6649519977dd787ac1 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry.hpp @@ -0,0 +1,12 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/box.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/box.hpp new file mode 100644 index 0000000000000000000000000000000000000000..bb3ea5701423601db2a0c4d37b11b7378589a0ea --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/box.hpp @@ -0,0 +1,36 @@ +#pragma once + +#include + +namespace mapbox { +namespace geometry { + +template +struct box +{ + using coordinate_type = T; + using point_type = point; + + constexpr box(point_type const& min_, point_type const& max_) + : min(min_), max(max_) + { + } + + point_type min; + point_type max; +}; + +template +constexpr bool operator==(box const& lhs, box const& rhs) +{ + return lhs.min == rhs.min && lhs.max == rhs.max; +} + +template +constexpr bool operator!=(box const& lhs, box const& rhs) +{ + return lhs.min != rhs.min || lhs.max != rhs.max; +} + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/empty.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/empty.hpp new file mode 100644 index 0000000000000000000000000000000000000000..0ea446d8bc76dcca73f57563c41426fde6ba5c34 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/empty.hpp @@ -0,0 +1,18 @@ +#pragma once + +namespace mapbox { +namespace geometry { + +struct empty +{ +}; // this Geometry type represents the empty point set, ∅, for the coordinate space (OGC Simple Features). + +constexpr bool operator==(empty, empty) { return true; } +constexpr bool operator!=(empty, empty) { return false; } +constexpr bool operator<(empty, empty) { return false; } +constexpr bool operator>(empty, empty) { return false; } +constexpr bool operator<=(empty, empty) { return true; } +constexpr bool operator>=(empty, empty) { return true; } + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/envelope.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/envelope.hpp new file mode 100644 index 0000000000000000000000000000000000000000..e1f722fc540973322731bf73b80145a6950b5ebd --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/envelope.hpp @@ -0,0 +1,33 @@ +#pragma once + +#include +#include + +#include + +namespace mapbox { +namespace geometry { + +template +box envelope(G const& geometry) +{ + using limits = std::numeric_limits; + + T min_t = limits::has_infinity ? -limits::infinity() : limits::min(); + T max_t = limits::has_infinity ? limits::infinity() : limits::max(); + + point min(max_t, max_t); + point max(min_t, min_t); + + for_each_point(geometry, [&](point const& point) { + if (min.x > point.x) min.x = point.x; + if (min.y > point.y) min.y = point.y; + if (max.x < point.x) max.x = point.x; + if (max.y < point.y) max.y = point.y; + }); + + return box(min, max); +} + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/for_each_point.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/for_each_point.hpp new file mode 100644 index 0000000000000000000000000000000000000000..d31b484ffd708c868b51dd1bc45f9e7d73b91158 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/for_each_point.hpp @@ -0,0 +1,51 @@ +#pragma once + +#include + +namespace mapbox { +namespace geometry { + +template +void for_each_point(mapbox::geometry::empty const&, F&&) +{ +} + +template +auto for_each_point(Point&& point, F&& f) + -> decltype(point.x, point.y, void()) +{ + f(std::forward(point)); +} + +template +auto for_each_point(Container&& container, F&& f) + -> decltype(container.begin(), container.end(), void()); + +template +void for_each_point(mapbox::util::variant const& geom, F&& f) +{ + mapbox::util::variant::visit(geom, [&](auto const& g) { + for_each_point(g, f); + }); +} + +template +void for_each_point(mapbox::util::variant& geom, F&& f) +{ + mapbox::util::variant::visit(geom, [&](auto& g) { + for_each_point(g, f); + }); +} + +template +auto for_each_point(Container&& container, F&& f) + -> decltype(container.begin(), container.end(), void()) +{ + for (auto& e : container) + { + for_each_point(e, f); + } +} + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/geometry.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/geometry.hpp new file mode 100644 index 0000000000000000000000000000000000000000..fa1e7c31c4cf3cc2443d586a5422d3758ab4d63a --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/geometry.hpp @@ -0,0 +1,56 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include + +#include + +// stl +#include + +namespace mapbox { +namespace geometry { + +template class Cont = std::vector> +struct geometry_collection; + +template class Cont = std::vector> +using geometry_base = mapbox::util::variant, + line_string, + polygon, + multi_point, + multi_line_string, + multi_polygon, + geometry_collection>; + +template class Cont = std::vector> +struct geometry : geometry_base +{ + using coordinate_type = T; + using geometry_base::geometry_base; +}; + +template class Cont> +struct geometry_collection : Cont> +{ + using coordinate_type = T; + using geometry_type = geometry; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + geometry_collection(Args&&... args) : container_type(std::forward(args)...) + { + } + geometry_collection(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/line_string.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/line_string.hpp new file mode 100644 index 0000000000000000000000000000000000000000..a015f71d1cf96c73e4f69dbcf5ea115c3f6fc50f --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/line_string.hpp @@ -0,0 +1,28 @@ +#pragma once + +// mapbox +#include +// stl +#include + +namespace mapbox { +namespace geometry { + +template class Cont = std::vector> +struct line_string : Cont> +{ + using coordinate_type = T; + using point_type = point; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + line_string(Args&&... args) : container_type(std::forward(args)...) + { + } + line_string(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_line_string.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_line_string.hpp new file mode 100644 index 0000000000000000000000000000000000000000..b528fa61be3bd963546b0f43d4c4f0f8f70668e0 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_line_string.hpp @@ -0,0 +1,28 @@ +#pragma once + +// mapbox +#include +// stl +#include + +namespace mapbox { +namespace geometry { + +template class Cont = std::vector> +struct multi_line_string : Cont> +{ + using coordinate_type = T; + using line_string_type = line_string; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + multi_line_string(Args&&... args) : container_type(std::forward(args)...) + { + } + multi_line_string(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_point.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_point.hpp new file mode 100644 index 0000000000000000000000000000000000000000..060927bf2308f94b8dcd55442867769f92b90937 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_point.hpp @@ -0,0 +1,28 @@ +#pragma once + +// mapbox +#include +// stl +#include + +namespace mapbox { +namespace geometry { + +template class Cont = std::vector> +struct multi_point : Cont> +{ + using coordinate_type = T; + using point_type = point; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + multi_point(Args&&... args) : container_type(std::forward(args)...) + { + } + multi_point(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_polygon.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_polygon.hpp new file mode 100644 index 0000000000000000000000000000000000000000..9546860ede4a368d5e2922a3825e80e1110130dd --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/multi_polygon.hpp @@ -0,0 +1,28 @@ +#pragma once + +// mapbox +#include +// stl +#include + +namespace mapbox { +namespace geometry { + +template class Cont = std::vector> +struct multi_polygon : Cont> +{ + using coordinate_type = T; + using polygon_type = polygon; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + multi_polygon(Args&&... args) : container_type(std::forward(args)...) + { + } + multi_polygon(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/point.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/point.hpp new file mode 100644 index 0000000000000000000000000000000000000000..da8d67733f2a51708d5516d8fc4d52a63bacd3ef --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/point.hpp @@ -0,0 +1,42 @@ +#pragma once + +namespace mapbox { +namespace geometry { + +template +struct point +{ + using coordinate_type = T; + + constexpr point() + : x(), y() + { + } + constexpr point(T x_, T y_) + : x(x_), y(y_) + { + } + + T x; + T y; +}; + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wfloat-equal" + +template +constexpr bool operator==(point const& lhs, point const& rhs) +{ + return lhs.x == rhs.x && lhs.y == rhs.y; +} + +#pragma GCC diagnostic pop + +template +constexpr bool operator!=(point const& lhs, point const& rhs) +{ + return !(lhs == rhs); +} + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/point_arithmetic.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/point_arithmetic.hpp new file mode 100644 index 0000000000000000000000000000000000000000..0c4c63278a58c07f605cdcda7134e87201e931aa --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/point_arithmetic.hpp @@ -0,0 +1,119 @@ +#pragma once + +namespace mapbox { +namespace geometry { + +template +point operator+(point const& lhs, point const& rhs) +{ + return point(lhs.x + rhs.x, lhs.y + rhs.y); +} + +template +point operator+(point const& lhs, T const& rhs) +{ + return point(lhs.x + rhs, lhs.y + rhs); +} + +template +point operator-(point const& lhs, point const& rhs) +{ + return point(lhs.x - rhs.x, lhs.y - rhs.y); +} + +template +point operator-(point const& lhs, T const& rhs) +{ + return point(lhs.x - rhs, lhs.y - rhs); +} + +template +point operator*(point const& lhs, point const& rhs) +{ + return point(lhs.x * rhs.x, lhs.y * rhs.y); +} + +template +point operator*(point const& lhs, T const& rhs) +{ + return point(lhs.x * rhs, lhs.y * rhs); +} + +template +point operator/(point const& lhs, point const& rhs) +{ + return point(lhs.x / rhs.x, lhs.y / rhs.y); +} + +template +point operator/(point const& lhs, T const& rhs) +{ + return point(lhs.x / rhs, lhs.y / rhs); +} + +template +point& operator+=(point& lhs, point const& rhs) +{ + lhs.x += rhs.x; + lhs.y += rhs.y; + return lhs; +} + +template +point& operator+=(point& lhs, T const& rhs) +{ + lhs.x += rhs; + lhs.y += rhs; + return lhs; +} + +template +point& operator-=(point& lhs, point const& rhs) +{ + lhs.x -= rhs.x; + lhs.y -= rhs.y; + return lhs; +} + +template +point& operator-=(point& lhs, T const& rhs) +{ + lhs.x -= rhs; + lhs.y -= rhs; + return lhs; +} + +template +point& operator*=(point& lhs, point const& rhs) +{ + lhs.x *= rhs.x; + lhs.y *= rhs.y; + return lhs; +} + +template +point& operator*=(point& lhs, T const& rhs) +{ + lhs.x *= rhs; + lhs.y *= rhs; + return lhs; +} + +template +point& operator/=(point& lhs, point const& rhs) +{ + lhs.x /= rhs.x; + lhs.y /= rhs.y; + return lhs; +} + +template +point& operator/=(point& lhs, T const& rhs) +{ + lhs.x /= rhs; + lhs.y /= rhs; + return lhs; +} + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/polygon.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/polygon.hpp new file mode 100644 index 0000000000000000000000000000000000000000..5cad7bbf5580e476c1d2c2d9f524f24e68bf66a4 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry/polygon.hpp @@ -0,0 +1,45 @@ +#pragma once + +// mapbox +#include + +// stl +#include + +namespace mapbox { +namespace geometry { + +template class Cont = std::vector> +struct linear_ring : Cont> +{ + using coordinate_type = T; + using point_type = point; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + linear_ring(Args&&... args) : container_type(std::forward(args)...) + { + } + linear_ring(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +template class Cont = std::vector> +struct polygon : Cont> +{ + using coordinate_type = T; + using linear_ring_type = linear_ring; + using container_type = Cont; + using size_type = typename container_type::size_type; + + template + polygon(Args&&... args) : container_type(std::forward(args)...) + { + } + polygon(std::initializer_list args) + : container_type(std::move(args)) {} +}; + +} // namespace geometry +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry_io.hpp b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry_io.hpp new file mode 100644 index 0000000000000000000000000000000000000000..4d91ccc961a79cfd303cac3b5c52230a448a9933 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/include/mapbox/geometry_io.hpp @@ -0,0 +1,98 @@ +#pragma once + +#include +#include + +#include +#include + +namespace mapbox { +namespace geometry { + +std::ostream& operator<<(std::ostream& os, const empty&) +{ + return os << "[]"; +} + +template +std::ostream& operator<<(std::ostream& os, const point& point) +{ + return os << "[" << point.x << "," << point.y << "]"; +} + +template class C, class... Args> +std::ostream& operator<<(std::ostream& os, const C& cont) +{ + os << "["; + for (auto it = cont.cbegin();;) + { + os << *it; + if (++it == cont.cend()) + { + break; + } + os << ","; + } + return os << "]"; +} + +template +std::ostream& operator<<(std::ostream& os, const line_string& geom) +{ + return os << static_cast::container_type>(geom); +} + +template +std::ostream& operator<<(std::ostream& os, const linear_ring& geom) +{ + return os << static_cast::container_type>(geom); +} + +template +std::ostream& operator<<(std::ostream& os, const polygon& geom) +{ + return os << static_cast::container_type>(geom); +} + +template +std::ostream& operator<<(std::ostream& os, const multi_point& geom) +{ + return os << static_cast::container_type>(geom); +} + +template +std::ostream& operator<<(std::ostream& os, const multi_line_string& geom) +{ + return os << static_cast::container_type>(geom); +} + +template +std::ostream& operator<<(std::ostream& os, const multi_polygon& geom) +{ + return os << static_cast::container_type>(geom); +} + +template +std::ostream& operator<<(std::ostream& os, const geometry& geom) +{ + geometry::visit(geom, [&](const auto& g) { os << g; }); + return os; +} + +template +std::ostream& operator<<(std::ostream& os, const geometry_collection& geom) +{ + return os << static_cast::container_type>(geom); +} + +} // namespace geometry + +namespace feature { + +std::ostream& operator<<(std::ostream& os, const null_value_t&) +{ + return os << "[]"; +} + +} // namespace feature +} // namespace mapbox diff --git a/libs/mason_packages/headers/geometry/1.0.0/mason.ini b/libs/mason_packages/headers/geometry/1.0.0/mason.ini new file mode 100644 index 0000000000000000000000000000000000000000..6476b82220dd36d60f906fa172494984ba60c197 --- /dev/null +++ b/libs/mason_packages/headers/geometry/1.0.0/mason.ini @@ -0,0 +1,4 @@ +name=geometry +version=1.0.0 +header_only=true +include_dirs={prefix}/include diff --git a/libs/mason_packages/headers/polylabel/1.0.3/LICENSE b/libs/mason_packages/headers/polylabel/1.0.3/LICENSE new file mode 100644 index 0000000000000000000000000000000000000000..9be4a969fd6267045804b8089bad059e7f674e52 --- /dev/null +++ b/libs/mason_packages/headers/polylabel/1.0.3/LICENSE @@ -0,0 +1,14 @@ +ISC License +Copyright (c) 2016 Mapbox + +Permission to use, copy, modify, and/or distribute this software for any purpose +with or without fee is hereby granted, provided that the above copyright notice +and this permission notice appear in all copies. + +THE SOFTWARE IS PROVIDED "AS IS" AND ISC DISCLAIMS ALL WARRANTIES WITH REGARD TO +THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS. +IN NO EVENT SHALL ISC BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR +CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA +OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS +SOFTWARE. diff --git a/libs/mason_packages/headers/polylabel/1.0.3/README.md b/libs/mason_packages/headers/polylabel/1.0.3/README.md new file mode 100644 index 0000000000000000000000000000000000000000..0310cdb5f1e42fd99049b488f95a7520206011c7 --- /dev/null +++ b/libs/mason_packages/headers/polylabel/1.0.3/README.md @@ -0,0 +1,64 @@ +## polylabel [![Build Status](https://travis-ci.org/mapbox/polylabel.svg?branch=master)](https://travis-ci.org/mapbox/polylabel) + +A fast algorithm for finding polygon _pole of inaccessibility_, +the most distant internal point from the polygon outline (not to be confused with centroid), +implemented as a JavaScript library. +Useful for optimal placement of a text label on a polygon. + +It's an iterative grid algorithm, +inspired by [paper by Garcia-Castellanos & Lombardo, 2007](https://sites.google.com/site/polesofinaccessibility/). +Unlike the one in the paper, this algorithm: + +- guarantees finding **global optimum** within the given precision +- is many times faster (10-40x) + +![](https://cloud.githubusercontent.com/assets/25395/16745865/864a0a30-47c0-11e6-87bc-58acac41a520.png) + +### How the algorithm works + +This is an iterative grid-based algorithm, which starts by covering the polygon with big square cells and then iteratively splitting them in the order of the most promising ones, while aggressively pruning uninteresting cells. + +1. Generate initial square cells that fully cover the polygon (with cell size equal to either width or height, whichever is lower). Calculate distance from the center of each cell to the outer polygon, using negative value if the point is outside the polygon (detected by ray-casting). +2. Put the cells into a priority queue sorted by the maximum potential distance from a point inside a cell, defined as a sum of the distance from the center and the cell radius (equal to `cell_size * sqrt(2) / 2`). +3. Calculate the distance from the centroid of the polygon and pick it as the first "best so far". +4. Pull out cells from the priority queue one by one. If a cell's distance is better than the current best, save it as such. +Then, if the cell potentially contains a better solution that the current best (`cell_max - best_dist > precision`), +split it into 4 children cells and put them in the queue. +5. Stop the algorithm when we have exhausted the queue and return the best cell's center as the pole of inaccessibility. +It will be guaranteed to be a global optimum within the given precision. + +![image](https://cloud.githubusercontent.com/assets/25395/16748630/e6b3336c-47cd-11e6-8059-0eeccf22cf6b.png) + +### JavaScript Usage + +Given polygon coordinates in +[GeoJSON-like format](http://geojson.org/geojson-spec.html#polygon) +and precision (`1.0` by default), +Polylabel returns the pole of inaccessibility coordinate in `[x, y]` format. + +```js +var p = polylabel(polygon, 1.0); +``` + +### TypeScript + +[TypeScript type definitions](https://github.com/DefinitelyTyped/DefinitelyTyped/tree/master/concaveman) +are available via `npm install --save @types/polylabel`. + +### C++ Usage + +It is recommended to install polylabel via [mason](https://github.com/mapbox/mason). You will also need to install its dependencies: [geometry.hpp](https://github.com/mapbox/geometry.hpp) and [variant](https://github.com/mapbox/variant). + +```C++ +#include + +int main() { + mapbox::geometry::polygon polygon = readPolygon(); // Get polygon data from somewhere. + mapbox::geometry::point p = mapbox::polylabel(polygon, 1.0); + return 0; +} +``` + +### Command Line Usage + +An external utility can be found at https://github.com/andrewharvey/geojson-polygon-labels diff --git a/libs/mason_packages/headers/polylabel/1.0.3/include/mapbox/polylabel.hpp b/libs/mason_packages/headers/polylabel/1.0.3/include/mapbox/polylabel.hpp new file mode 100644 index 0000000000000000000000000000000000000000..0e9e2b5433a311c72a6182125890c0f09ca39742 --- /dev/null +++ b/libs/mason_packages/headers/polylabel/1.0.3/include/mapbox/polylabel.hpp @@ -0,0 +1,178 @@ +#pragma once + +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace mapbox { + +namespace detail { + +// get squared distance from a point to a segment +template +T getSegDistSq(const geometry::point& p, + const geometry::point& a, + const geometry::point& b) { + auto x = a.x; + auto y = a.y; + auto dx = b.x - x; + auto dy = b.y - y; + + if (dx != 0 || dy != 0) { + + auto t = ((p.x - x) * dx + (p.y - y) * dy) / (dx * dx + dy * dy); + + if (t > 1) { + x = b.x; + y = b.y; + + } else if (t > 0) { + x += dx * t; + y += dy * t; + } + } + + dx = p.x - x; + dy = p.y - y; + + return dx * dx + dy * dy; +} + +// signed distance from point to polygon outline (negative if point is outside) +template +auto pointToPolygonDist(const geometry::point& point, const geometry::polygon& polygon) { + bool inside = false; + auto minDistSq = std::numeric_limits::infinity(); + + for (const auto& ring : polygon) { + for (std::size_t i = 0, len = ring.size(), j = len - 1; i < len; j = i++) { + const auto& a = ring[i]; + const auto& b = ring[j]; + + if ((a.y > point.y) != (b.y > point.y) && + (point.x < (b.x - a.x) * (point.y - a.y) / (b.y - a.y) + a.x)) inside = !inside; + + minDistSq = std::min(minDistSq, getSegDistSq(point, a, b)); + } + } + + return (inside ? 1 : -1) * std::sqrt(minDistSq); +} + +template +struct Cell { + Cell(const geometry::point& c_, T h_, const geometry::polygon& polygon) + : c(c_), + h(h_), + d(pointToPolygonDist(c, polygon)), + max(d + h * std::sqrt(2)) + {} + + geometry::point c; // cell center + T h; // half the cell size + T d; // distance from cell center to polygon + T max; // max distance to polygon within a cell +}; + +// get polygon centroid +template +Cell getCentroidCell(const geometry::polygon& polygon) { + T area = 0; + geometry::point c { 0, 0 }; + const auto& ring = polygon.at(0); + + for (std::size_t i = 0, len = ring.size(), j = len - 1; i < len; j = i++) { + const geometry::point& a = ring[i]; + const geometry::point& b = ring[j]; + auto f = a.x * b.y - b.x * a.y; + c.x += (a.x + b.x) * f; + c.y += (a.y + b.y) * f; + area += f * 3; + } + + return Cell(area == 0 ? ring.at(0) : c / area, 0, polygon); +} + +} // namespace detail + +template +geometry::point polylabel(const geometry::polygon& polygon, T precision = 1, bool debug = false) { + using namespace detail; + + // find the bounding box of the outer ring + const geometry::box envelope = geometry::envelope(polygon.at(0)); + + const geometry::point size { + envelope.max.x - envelope.min.x, + envelope.max.y - envelope.min.y + }; + + const T cellSize = std::min(size.x, size.y); + T h = cellSize / 2; + + // a priority queue of cells in order of their "potential" (max distance to polygon) + auto compareMax = [] (const Cell& a, const Cell& b) { + return a.max < b.max; + }; + using Queue = std::priority_queue, std::vector>, decltype(compareMax)>; + Queue cellQueue(compareMax); + + if (cellSize == 0) { + return envelope.min; + } + + // cover polygon with initial cells + for (T x = envelope.min.x; x < envelope.max.x; x += cellSize) { + for (T y = envelope.min.y; y < envelope.max.y; y += cellSize) { + cellQueue.push(Cell({x + h, y + h}, h, polygon)); + } + } + + // take centroid as the first best guess + auto bestCell = getCentroidCell(polygon); + + // special case for rectangular polygons + Cell bboxCell(envelope.min + size / 2.0, 0, polygon); + if (bboxCell.d > bestCell.d) { + bestCell = bboxCell; + } + + auto numProbes = cellQueue.size(); + while (!cellQueue.empty()) { + // pick the most promising cell from the queue + auto cell = cellQueue.top(); + cellQueue.pop(); + + // update the best cell if we found a better one + if (cell.d > bestCell.d) { + bestCell = cell; + if (debug) std::cout << "found best " << ::round(1e4 * cell.d) / 1e4 << " after " << numProbes << " probes" << std::endl; + } + + // do not drill down further if there's no chance of a better solution + if (cell.max - bestCell.d <= precision) continue; + + // split the cell into four cells + h = cell.h / 2; + cellQueue.push(Cell({cell.c.x - h, cell.c.y - h}, h, polygon)); + cellQueue.push(Cell({cell.c.x + h, cell.c.y - h}, h, polygon)); + cellQueue.push(Cell({cell.c.x - h, cell.c.y + h}, h, polygon)); + cellQueue.push(Cell({cell.c.x + h, cell.c.y + h}, h, polygon)); + numProbes += 4; + } + + if (debug) { + std::cout << "num probes: " << numProbes << std::endl; + std::cout << "best distance: " << bestCell.d << std::endl; + } + + return bestCell.c; +} + +} // namespace mapbox diff --git a/libs/mason_packages/headers/polylabel/1.0.3/mason.ini b/libs/mason_packages/headers/polylabel/1.0.3/mason.ini new file mode 100644 index 0000000000000000000000000000000000000000..c4a0e6712e67ca840a5868421a6d4faf84c4cc75 --- /dev/null +++ b/libs/mason_packages/headers/polylabel/1.0.3/mason.ini @@ -0,0 +1,4 @@ +name=polylabel +version=1.0.3 +header_only=true +include_dirs={prefix}/include diff --git a/libs/mason_packages/headers/variant/1.1.0/LICENSE b/libs/mason_packages/headers/variant/1.1.0/LICENSE new file mode 100644 index 0000000000000000000000000000000000000000..6c4ce40d5a91a3374defc7c8993d24a4ab96e59d --- /dev/null +++ b/libs/mason_packages/headers/variant/1.1.0/LICENSE @@ -0,0 +1,25 @@ +Copyright (c) MapBox +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +- Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. +- Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or + other materials provided with the distribution. +- Neither the name "MapBox" nor the names of its contributors may be + used to endorse or promote products derived from this software without + specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON +ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. \ No newline at end of file diff --git a/libs/mason_packages/headers/variant/1.1.0/README.md b/libs/mason_packages/headers/variant/1.1.0/README.md new file mode 100644 index 0000000000000000000000000000000000000000..24cdb570b9d9d0907747748da2f8f427f490f617 --- /dev/null +++ b/libs/mason_packages/headers/variant/1.1.0/README.md @@ -0,0 +1,111 @@ +# Mapbox Variant + +An alternative to `boost::variant` for C++11. + +[![Build Status](https://secure.travis-ci.org/mapbox/variant.svg)](https://travis-ci.org/mapbox/variant) +[![Build status](https://ci.appveyor.com/api/projects/status/v9tatx21j1k0fcgy)](https://ci.appveyor.com/project/Mapbox/variant) +[![Coverage Status](https://coveralls.io/repos/mapbox/variant/badge.svg?branch=master&service=github)](https://coveralls.io/r/mapbox/variant?branch=master) + + +## Why use Mapbox Variant? + +Mapbox variant has the same speedy performance of `boost::variant` but is +faster to compile, results in smaller binaries, and has no dependencies. + +For example on OS X 10.9 with clang++ and libc++: + +Test | Mapbox Variant | Boost Variant +---- | -------------- | ------------- +Size of pre-compiled header (release / debug) | 2.8/2.8 MB | 12/15 MB +Size of simple program linking variant (release / debug) | 8/24 K | 12/40 K +Time to compile header | 185 ms | 675 ms + +(Numbers from an older version of Mapbox variant.) + + +## Goals + +Mapbox `variant` has been a very valuable, lightweight alternative for apps +that can use c++11 or c++14 but that do not want a boost dependency. +Mapbox `variant` has also been useful in apps that do depend on boost, like +mapnik, to help (slightly) with compile times and to majorly lessen dependence +on boost in core headers. The original goal and near term goal is to maintain +external API compatibility with `boost::variant` such that Mapbox `variant` +can be a "drop in". At the same time the goal is to stay minimal: Only +implement the features that are actually needed in existing software. So being +an "incomplete" implementation is just fine. + +Currently Mapbox variant doesn't try to be API compatible with the upcoming +variant standard, because the standard is not finished and it would be too much +work. But we'll revisit this decision in the future if needed. + +If Mapbox variant is not for you, have a look at [these other +implementations](doc/other_implementations.md). + +Want to know more about the upcoming standard? Have a look at our +[overview](doc/standards_effort.md). + + +## Depends + + - Compiler supporting `-std=c++11` or `-std=c++14` + +Tested with: + + - g++-4.7 + - g++-4.8 + - g++-4.9 + - g++-5 + - clang++-3.5 + - clang++-3.6 + - clang++-3.7 + - clang++-3.8 + - Visual Studio 2015 + +## Usage + +There is nothing to build, just include `variant.hpp` and +`recursive_wrapper.hpp` in your project. Include `variant_io.hpp` if you need +the `operator<<` overload for variant. + + +## Unit Tests + +On Unix systems compile and run the unit tests with `make test`. + +On Windows run `scripts/build-local.bat`. + + +## Limitations + +* The `variant` can not hold references (something like `variant` is + not possible). You might want to try `std::reference_wrapper` instead. + + +## Deprecations + +* The included implementation of `optional` is deprecated and will be removed + in a future version. See https://github.com/mapbox/variant/issues/64. +* Old versions of the code needed visitors to derive from `static_visitor`. + This is not needed any more and marked as deprecated. The `static_visitor` + class will be removed in future versions. + + +## Benchmarks + +The benchmarks depend on: + + - Boost headers (for benchmarking against `boost::variant`) + - Boost built with `--with-timer` (used for benchmark timing) + +On Unix systems set your boost includes and libs locations and run `make test`: + + export LDFLAGS='-L/opt/boost/lib' + export CXXFLAGS='-I/opt/boost/include' + make bench + + +## Check object sizes + + make sizes /path/to/boost/variant.hpp + diff --git a/libs/mason_packages/headers/variant/1.1.0/include/mapbox/optional.hpp b/libs/mason_packages/headers/variant/1.1.0/include/mapbox/optional.hpp new file mode 100644 index 0000000000000000000000000000000000000000..1185894e7363497e7529a0eb8abb51e6d09e38a7 --- /dev/null +++ b/libs/mason_packages/headers/variant/1.1.0/include/mapbox/optional.hpp @@ -0,0 +1,74 @@ +#ifndef MAPBOX_UTIL_OPTIONAL_HPP +#define MAPBOX_UTIL_OPTIONAL_HPP + +#pragma message("This implementation of optional is deprecated. See https://github.com/mapbox/variant/issues/64.") + +#include +#include + +#include "variant.hpp" + +namespace mapbox { +namespace util { + +template +class optional +{ + static_assert(!std::is_reference::value, "optional doesn't support references"); + + struct none_type + { + }; + + variant variant_; + + public: + optional() = default; + + optional(optional const& rhs) + { + if (this != &rhs) + { // protect against invalid self-assignment + variant_ = rhs.variant_; + } + } + + optional(T const& v) { variant_ = v; } + + explicit operator bool() const noexcept { return variant_.template is(); } + + T const& get() const { return variant_.template get(); } + T& get() { return variant_.template get(); } + + T const& operator*() const { return this->get(); } + T operator*() { return this->get(); } + + optional& operator=(T const& v) + { + variant_ = v; + return *this; + } + + optional& operator=(optional const& rhs) + { + if (this != &rhs) + { + variant_ = rhs.variant_; + } + return *this; + } + + template + void emplace(Args&&... args) + { + variant_ = T{std::forward(args)...}; + } + + void reset() { variant_ = none_type{}; } + +}; // class optional + +} // namespace util +} // namespace mapbox + +#endif // MAPBOX_UTIL_OPTIONAL_HPP diff --git a/libs/mason_packages/headers/variant/1.1.0/include/mapbox/recursive_wrapper.hpp b/libs/mason_packages/headers/variant/1.1.0/include/mapbox/recursive_wrapper.hpp new file mode 100644 index 0000000000000000000000000000000000000000..4becdd689d46649987c7779717ff4965752698b1 --- /dev/null +++ b/libs/mason_packages/headers/variant/1.1.0/include/mapbox/recursive_wrapper.hpp @@ -0,0 +1,122 @@ +#ifndef MAPBOX_UTIL_RECURSIVE_WRAPPER_HPP +#define MAPBOX_UTIL_RECURSIVE_WRAPPER_HPP + +// Based on variant/recursive_wrapper.hpp from boost. +// +// Original license: +// +// Copyright (c) 2002-2003 +// Eric Friedman, Itay Maman +// +// Distributed under the Boost Software License, Version 1.0. (See +// accompanying file LICENSE_1_0.txt or copy at +// http://www.boost.org/LICENSE_1_0.txt) + +#include +#include + +namespace mapbox { +namespace util { + +template +class recursive_wrapper +{ + + T* p_; + + void assign(T const& rhs) + { + this->get() = rhs; + } + + public: + using type = T; + + /** + * Default constructor default initializes the internally stored value. + * For POD types this means nothing is done and the storage is + * uninitialized. + * + * @throws std::bad_alloc if there is insufficient memory for an object + * of type T. + * @throws any exception thrown by the default constructur of T. + */ + recursive_wrapper() + : p_(new T){}; + + ~recursive_wrapper() noexcept { delete p_; }; + + recursive_wrapper(recursive_wrapper const& operand) + : p_(new T(operand.get())) {} + + recursive_wrapper(T const& operand) + : p_(new T(operand)) {} + + recursive_wrapper(recursive_wrapper&& operand) + : p_(new T(std::move(operand.get()))) {} + + recursive_wrapper(T&& operand) + : p_(new T(std::move(operand))) {} + + inline recursive_wrapper& operator=(recursive_wrapper const& rhs) + { + assign(rhs.get()); + return *this; + } + + inline recursive_wrapper& operator=(T const& rhs) + { + assign(rhs); + return *this; + } + + inline void swap(recursive_wrapper& operand) noexcept + { + T* temp = operand.p_; + operand.p_ = p_; + p_ = temp; + } + + recursive_wrapper& operator=(recursive_wrapper&& rhs) noexcept + { + swap(rhs); + return *this; + } + + recursive_wrapper& operator=(T&& rhs) + { + get() = std::move(rhs); + return *this; + } + + T& get() + { + assert(p_); + return *get_pointer(); + } + + T const& get() const + { + assert(p_); + return *get_pointer(); + } + + T* get_pointer() { return p_; } + + const T* get_pointer() const { return p_; } + + operator T const&() const { return this->get(); } + + operator T&() { return this->get(); } + +}; // class recursive_wrapper + +template +inline void swap(recursive_wrapper& lhs, recursive_wrapper& rhs) noexcept +{ + lhs.swap(rhs); +} +} // namespace util +} // namespace mapbox + +#endif // MAPBOX_UTIL_RECURSIVE_WRAPPER_HPP diff --git a/libs/mason_packages/headers/variant/1.1.0/include/mapbox/variant.hpp b/libs/mason_packages/headers/variant/1.1.0/include/mapbox/variant.hpp new file mode 100644 index 0000000000000000000000000000000000000000..db5d3c86b58caf3a787e9b8e8d3fc7d8e5042fa9 --- /dev/null +++ b/libs/mason_packages/headers/variant/1.1.0/include/mapbox/variant.hpp @@ -0,0 +1,901 @@ +#ifndef MAPBOX_UTIL_VARIANT_HPP +#define MAPBOX_UTIL_VARIANT_HPP + +#include +#include // size_t +#include // operator new +#include // runtime_error +#include +#include +#include +#include +#include + +#include "recursive_wrapper.hpp" + +// clang-format off +// [[deprecated]] is only available in C++14, use this for the time being +#if __cplusplus <= 201103L +# ifdef __GNUC__ +# define MAPBOX_VARIANT_DEPRECATED __attribute__((deprecated)) +# elif defined(_MSC_VER) +# define MAPBOX_VARIANT_DEPRECATED __declspec(deprecated) +# else +# define MAPBOX_VARIANT_DEPRECATED +# endif +#else +# define MAPBOX_VARIANT_DEPRECATED [[deprecated]] +#endif + + +#ifdef _MSC_VER + // https://msdn.microsoft.com/en-us/library/bw1hbe6y.aspx + #ifdef NDEBUG + #define VARIANT_INLINE __forceinline + #else + #define VARIANT_INLINE __declspec(noinline) + #endif +#else + #ifdef NDEBUG + #define VARIANT_INLINE inline __attribute__((always_inline)) + #else + #define VARIANT_INLINE __attribute__((noinline)) + #endif +#endif +// clang-format on + +#define VARIANT_MAJOR_VERSION 1 +#define VARIANT_MINOR_VERSION 1 +#define VARIANT_PATCH_VERSION 0 + +#define VARIANT_VERSION (VARIANT_MAJOR_VERSION * 100000) + (VARIANT_MINOR_VERSION * 100) + (VARIANT_PATCH_VERSION) + +namespace mapbox { +namespace util { + +// XXX This should derive from std::logic_error instead of std::runtime_error. +// See https://github.com/mapbox/variant/issues/48 for details. +class bad_variant_access : public std::runtime_error +{ + + public: + explicit bad_variant_access(const std::string& what_arg) + : runtime_error(what_arg) {} + + explicit bad_variant_access(const char* what_arg) + : runtime_error(what_arg) {} + +}; // class bad_variant_access + +template +struct MAPBOX_VARIANT_DEPRECATED static_visitor +{ + using result_type = R; + + protected: + static_visitor() {} + ~static_visitor() {} +}; + +namespace detail { + +static constexpr std::size_t invalid_value = std::size_t(-1); + +template +struct direct_type; + +template +struct direct_type +{ + static constexpr std::size_t index = std::is_same::value + ? sizeof...(Types) + : direct_type::index; +}; + +template +struct direct_type +{ + static constexpr std::size_t index = invalid_value; +}; + +template +struct convertible_type; + +template +struct convertible_type +{ + static constexpr std::size_t index = std::is_convertible::value + ? sizeof...(Types) + : convertible_type::index; +}; + +template +struct convertible_type +{ + static constexpr std::size_t index = invalid_value; +}; + +template +struct value_traits +{ + using value_type = typename std::remove_reference::type; + static constexpr std::size_t direct_index = direct_type::index; + static constexpr bool is_direct = direct_index != invalid_value; + static constexpr std::size_t index = is_direct ? direct_index : convertible_type::index; + static constexpr bool is_valid = index != invalid_value; + static constexpr std::size_t tindex = is_valid ? sizeof...(Types)-index : 0; + using target_type = typename std::tuple_element>::type; +}; + +// check if T is in Types... +template +struct has_type; + +template +struct has_type +{ + static constexpr bool value = std::is_same::value || has_type::value; +}; + +template +struct has_type : std::false_type +{ +}; + +template +struct is_valid_type; + +template +struct is_valid_type +{ + static constexpr bool value = std::is_convertible::value || is_valid_type::value; +}; + +template +struct is_valid_type : std::false_type +{ +}; + +template +struct enable_if_type +{ + using type = R; +}; + +template +struct result_of_unary_visit +{ + using type = typename std::result_of::type; +}; + +template +struct result_of_unary_visit::type> +{ + using type = typename F::result_type; +}; + +template +struct result_of_binary_visit +{ + using type = typename std::result_of::type; +}; + +template +struct result_of_binary_visit::type> +{ + using type = typename F::result_type; +}; + +template +struct static_max; + +template +struct static_max +{ + static const std::size_t value = arg; +}; + +template +struct static_max +{ + static const std::size_t value = arg1 >= arg2 ? static_max::value : static_max::value; +}; + +template +struct variant_helper; + +template +struct variant_helper +{ + VARIANT_INLINE static void destroy(const std::size_t type_index, void* data) + { + if (type_index == sizeof...(Types)) + { + reinterpret_cast(data)->~T(); + } + else + { + variant_helper::destroy(type_index, data); + } + } + + VARIANT_INLINE static void move(const std::size_t old_type_index, void* old_value, void* new_value) + { + if (old_type_index == sizeof...(Types)) + { + new (new_value) T(std::move(*reinterpret_cast(old_value))); + } + else + { + variant_helper::move(old_type_index, old_value, new_value); + } + } + + VARIANT_INLINE static void copy(const std::size_t old_type_index, const void* old_value, void* new_value) + { + if (old_type_index == sizeof...(Types)) + { + new (new_value) T(*reinterpret_cast(old_value)); + } + else + { + variant_helper::copy(old_type_index, old_value, new_value); + } + } +}; + +template <> +struct variant_helper<> +{ + VARIANT_INLINE static void destroy(const std::size_t, void*) {} + VARIANT_INLINE static void move(const std::size_t, void*, void*) {} + VARIANT_INLINE static void copy(const std::size_t, const void*, void*) {} +}; + +template +struct unwrapper +{ + static T const& apply_const(T const& obj) { return obj; } + static T& apply(T& obj) { return obj; } +}; + +template +struct unwrapper> +{ + static auto apply_const(recursive_wrapper const& obj) + -> typename recursive_wrapper::type const& + { + return obj.get(); + } + static auto apply(recursive_wrapper& obj) + -> typename recursive_wrapper::type& + { + return obj.get(); + } +}; + +template +struct unwrapper> +{ + static auto apply_const(std::reference_wrapper const& obj) + -> typename std::reference_wrapper::type const& + { + return obj.get(); + } + static auto apply(std::reference_wrapper& obj) + -> typename std::reference_wrapper::type& + { + return obj.get(); + } +}; + +template +struct dispatcher; + +template +struct dispatcher +{ + VARIANT_INLINE static R apply_const(V const& v, F&& f) + { + if (v.template is()) + { + return f(unwrapper::apply_const(v.template get())); + } + else + { + return dispatcher::apply_const(v, std::forward(f)); + } + } + + VARIANT_INLINE static R apply(V& v, F&& f) + { + if (v.template is()) + { + return f(unwrapper::apply(v.template get())); + } + else + { + return dispatcher::apply(v, std::forward(f)); + } + } +}; + +template +struct dispatcher +{ + VARIANT_INLINE static R apply_const(V const& v, F&& f) + { + return f(unwrapper::apply_const(v.template get())); + } + + VARIANT_INLINE static R apply(V& v, F&& f) + { + return f(unwrapper::apply(v.template get())); + } +}; + +template +struct binary_dispatcher_rhs; + +template +struct binary_dispatcher_rhs +{ + VARIANT_INLINE static R apply_const(V const& lhs, V const& rhs, F&& f) + { + if (rhs.template is()) // call binary functor + { + return f(unwrapper::apply_const(lhs.template get()), + unwrapper::apply_const(rhs.template get())); + } + else + { + return binary_dispatcher_rhs::apply_const(lhs, rhs, std::forward(f)); + } + } + + VARIANT_INLINE static R apply(V& lhs, V& rhs, F&& f) + { + if (rhs.template is()) // call binary functor + { + return f(unwrapper::apply(lhs.template get()), + unwrapper::apply(rhs.template get())); + } + else + { + return binary_dispatcher_rhs::apply(lhs, rhs, std::forward(f)); + } + } +}; + +template +struct binary_dispatcher_rhs +{ + VARIANT_INLINE static R apply_const(V const& lhs, V const& rhs, F&& f) + { + return f(unwrapper::apply_const(lhs.template get()), + unwrapper::apply_const(rhs.template get())); + } + + VARIANT_INLINE static R apply(V& lhs, V& rhs, F&& f) + { + return f(unwrapper::apply(lhs.template get()), + unwrapper::apply(rhs.template get())); + } +}; + +template +struct binary_dispatcher_lhs; + +template +struct binary_dispatcher_lhs +{ + VARIANT_INLINE static R apply_const(V const& lhs, V const& rhs, F&& f) + { + if (lhs.template is()) // call binary functor + { + return f(unwrapper::apply_const(lhs.template get()), + unwrapper::apply_const(rhs.template get())); + } + else + { + return binary_dispatcher_lhs::apply_const(lhs, rhs, std::forward(f)); + } + } + + VARIANT_INLINE static R apply(V& lhs, V& rhs, F&& f) + { + if (lhs.template is()) // call binary functor + { + return f(unwrapper::apply(lhs.template get()), + unwrapper::apply(rhs.template get())); + } + else + { + return binary_dispatcher_lhs::apply(lhs, rhs, std::forward(f)); + } + } +}; + +template +struct binary_dispatcher_lhs +{ + VARIANT_INLINE static R apply_const(V const& lhs, V const& rhs, F&& f) + { + return f(unwrapper::apply_const(lhs.template get()), + unwrapper::apply_const(rhs.template get())); + } + + VARIANT_INLINE static R apply(V& lhs, V& rhs, F&& f) + { + return f(unwrapper::apply(lhs.template get()), + unwrapper::apply(rhs.template get())); + } +}; + +template +struct binary_dispatcher; + +template +struct binary_dispatcher +{ + VARIANT_INLINE static R apply_const(V const& v0, V const& v1, F&& f) + { + if (v0.template is()) + { + if (v1.template is()) + { + return f(unwrapper::apply_const(v0.template get()), + unwrapper::apply_const(v1.template get())); // call binary functor + } + else + { + return binary_dispatcher_rhs::apply_const(v0, v1, std::forward(f)); + } + } + else if (v1.template is()) + { + return binary_dispatcher_lhs::apply_const(v0, v1, std::forward(f)); + } + return binary_dispatcher::apply_const(v0, v1, std::forward(f)); + } + + VARIANT_INLINE static R apply(V& v0, V& v1, F&& f) + { + if (v0.template is()) + { + if (v1.template is()) + { + return f(unwrapper::apply(v0.template get()), + unwrapper::apply(v1.template get())); // call binary functor + } + else + { + return binary_dispatcher_rhs::apply(v0, v1, std::forward(f)); + } + } + else if (v1.template is()) + { + return binary_dispatcher_lhs::apply(v0, v1, std::forward(f)); + } + return binary_dispatcher::apply(v0, v1, std::forward(f)); + } +}; + +template +struct binary_dispatcher +{ + VARIANT_INLINE static R apply_const(V const& v0, V const& v1, F&& f) + { + return f(unwrapper::apply_const(v0.template get()), + unwrapper::apply_const(v1.template get())); // call binary functor + } + + VARIANT_INLINE static R apply(V& v0, V& v1, F&& f) + { + return f(unwrapper::apply(v0.template get()), + unwrapper::apply(v1.template get())); // call binary functor + } +}; + +// comparator functors +struct equal_comp +{ + template + bool operator()(T const& lhs, T const& rhs) const + { + return lhs == rhs; + } +}; + +struct less_comp +{ + template + bool operator()(T const& lhs, T const& rhs) const + { + return lhs < rhs; + } +}; + +template +class comparer +{ + public: + explicit comparer(Variant const& lhs) noexcept + : lhs_(lhs) {} + comparer& operator=(comparer const&) = delete; + // visitor + template + bool operator()(T const& rhs_content) const + { + T const& lhs_content = lhs_.template get(); + return Comp()(lhs_content, rhs_content); + } + + private: + Variant const& lhs_; +}; + +// True if Predicate matches for all of the types Ts +template