diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 99025bac2f016905cfd728d4ade9819bc57e10bd..b119dafa3823743c0b7d616cbbce2b50a5e607e7 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -438,12 +438,14 @@ HEADERS += \ src/Wima/Snake/SnakeTiles.h \ src/Wima/Snake/SnakeTilesLocal.h \ src/Wima/Snake/SnakeWorker.h \ + src/Wima/WaypointManager/AreaInterface.h \ + src/Wima/WaypointManager/DefaultManager.h \ src/Wima/WaypointManager/GenericSlicer.h \ src/Wima/WaypointManager/GenericWaypointManager.h \ src/Wima/Geometry/WimaPolygonArray.h \ src/Wima/Snake/snaketile.h \ src/Wima/WaypointManager/Settings.h \ - src/Wima/WaypointManager/utils.h \ + src/Wima/WaypointManager/Utils.h \ src/api/QGCCorePlugin.h \ src/api/QGCOptions.h \ src/api/QGCSettings.h \ @@ -497,10 +499,12 @@ SOURCES += \ src/Wima/Geometry/PolygonArray.cc \ src/Wima/Snake/QNemoProgress.cc \ src/Wima/Snake/SnakeWorker.cc \ + src/Wima/WaypointManager/AreaInterface.cpp \ + src/Wima/WaypointManager/DefaultManager.cpp \ src/Wima/WaypointManager/GenericSlicer.cpp \ src/Wima/WaypointManager/GenericWaypointManager.cpp \ src/Wima/WaypointManager/Settings.cpp \ - src/Wima/WaypointManager/utils.cpp \ + src/Wima/WaypointManager/Utils.cpp \ src/comm/ros_bridge/include/ComPrivateInclude.cpp \ src/comm/ros_bridge/include/MessageTag.cpp \ src/comm/ros_bridge/include/TopicPublisher.cpp \ diff --git a/src/Wima/CircularSurveyComplexItem.h b/src/Wima/CircularSurveyComplexItem.h index efc7b899d607283b2f1a65227c59873a7e5d62a6..0db6cc79dc871cbed3c5932021b8c56794e37639 100644 --- a/src/Wima/CircularSurveyComplexItem.h +++ b/src/Wima/CircularSurveyComplexItem.h @@ -2,11 +2,11 @@ #include "TransectStyleComplexItem.h" -#include "PolygonCalculus.h" -#include "PlanimetryCalculus.h" -#include "GeoUtilities.h" +#include "Geometry/PolygonCalculus.h" +#include "Geometry/PlanimetryCalculus.h" +#include "Geometry/GeoUtilities.h" #include "QVector" -#include "Circle.h" +#include "Geometry/Circle.h" #include "SettingsFact.h" class CircularSurveyComplexItem :public TransectStyleComplexItem diff --git a/src/Wima/Geometry/PolygonCalculus.cc b/src/Wima/Geometry/PolygonCalculus.cc index 4ffe93baa50c0826ee23b5ed2bdbe294671d3ced..0e28adc54e1e0bdc7b4b7d102dd7772214be73c5 100644 --- a/src/Wima/Geometry/PolygonCalculus.cc +++ b/src/Wima/Geometry/PolygonCalculus.cc @@ -1,6 +1,6 @@ #include "PolygonCalculus.h" #include "PlanimetryCalculus.h" -#include "OptimisationTools.h" +#include "Wima/OptimisationTools.h" #include diff --git a/src/Wima/Geometry/WimaArea.h b/src/Wima/Geometry/WimaArea.h index 15c4fa637a75623eaa6676bff5801a7e4ed24222..d4a5bc57129dba312cf580ef5688bd93bea2f1e3 100644 --- a/src/Wima/Geometry/WimaArea.h +++ b/src/Wima/Geometry/WimaArea.h @@ -4,7 +4,6 @@ #include "QGCMapPolyline.h" #include "Vehicle.h" #include "qobject.h" -#include "WimaVehicle.h" #include #include #include "QGCGeo.h" diff --git a/src/Wima/Geometry/WimaAreaData.cc b/src/Wima/Geometry/WimaAreaData.cc index c8672aec04319541d121ae9824e77061c21daec1..e57819f654e9cb4c9aed9e193de7fb5980a5930f 100644 --- a/src/Wima/Geometry/WimaAreaData.cc +++ b/src/Wima/Geometry/WimaAreaData.cc @@ -2,6 +2,7 @@ WimaAreaData::WimaAreaData(QObject *parent) : QObject(parent) + , _listValid(false) { _maxAltitude = 0; } @@ -31,14 +32,15 @@ QGeoCoordinate WimaAreaData::center() const return _center; } -QList WimaAreaData::coordinateList() const +const QList &WimaAreaData::coordinateList() const { - QList coordinateList; - - for ( auto coorinate : _path) - coordinateList.append(coorinate.value()); + static QList list; + if ( !_listValid ) { + for ( auto coorinate : _path) + list.append(coorinate.value()); + } - return coordinateList; + return list; } bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const @@ -54,6 +56,16 @@ bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const return false; } +void WimaAreaData::append(const QGeoCoordinate &c) { + _listValid = false; + _path.push_back(QVariant::fromValue(c)); +} + +void WimaAreaData::clear() { + _listValid = false; + _path.clear(); +} + /*! * \fn void WimaAreaData::setMaxAltitude(double maxAltitude) @@ -72,6 +84,7 @@ void WimaAreaData::setMaxAltitude(double maxAltitude) void WimaAreaData::setPath(const QVariantList &coordinateList) { + _listValid = false; _path.clear(); _path.append(coordinateList); } @@ -113,6 +126,7 @@ void WimaAreaData::assign(const WimaArea &other) */ void WimaAreaData::setPath(const QList &coordinateList) { + _listValid = false; _path.clear(); // copy all coordinates to _path diff --git a/src/Wima/Geometry/WimaAreaData.h b/src/Wima/Geometry/WimaAreaData.h index 3505ac507baab12e8b009cc59d9921a3ea4ea005..04dcb2a88ecff39f68771b337f7d16910345d725 100644 --- a/src/Wima/Geometry/WimaAreaData.h +++ b/src/Wima/Geometry/WimaAreaData.h @@ -21,12 +21,12 @@ public: double maxAltitude() const; QVariantList path() const; QGeoCoordinate center() const; - QList coordinateList() const; + const QList &coordinateList() const; bool containsCoordinate(const QGeoCoordinate &coordinate) const; virtual QString type() const = 0; - void append(const QGeoCoordinate &c) {_path.push_back(QVariant::fromValue(c));} - void clear() {_path.clear();} + void append(const QGeoCoordinate &c); + void clear(); signals: void maxAltitudeChanged (double maxAltitude); @@ -51,5 +51,6 @@ private: double _maxAltitude; QVariantList _path; QGeoCoordinate _center; + bool _listValid; }; diff --git a/src/Wima/Geometry/WimaMeasurementArea.h b/src/Wima/Geometry/WimaMeasurementArea.h index 9d0052503d2d61b13f3c8cec02bf78ba90efbbf6..16ac625358ae037183a0a4843fe74f3d7987e396 100644 --- a/src/Wima/Geometry/WimaMeasurementArea.h +++ b/src/Wima/Geometry/WimaMeasurementArea.h @@ -51,7 +51,6 @@ signals: void bottomLayerAltitudeChanged (void); void numberOfLayersChanged (void); void layerDistanceChanged (void); - void vehicleCorridorChanged (WimaVCorridor* corridor); public slots: void setBottomLayerAltitude (double altitude); diff --git a/src/Wima/Geometry/WimaServiceArea.h b/src/Wima/Geometry/WimaServiceArea.h index a0dbed557c916d54c5d270aa59593e8541530eb5..8baba0d8407f5b7a64ff0380387b1a0cc942485b 100644 --- a/src/Wima/Geometry/WimaServiceArea.h +++ b/src/Wima/Geometry/WimaServiceArea.h @@ -38,7 +38,6 @@ public: signals: void takeOffPositionChanged (void); void landPositionChanged (void); - void vehicleCorridorChanged (WimaVCorridor& corridor); public slots: void setTakeOffPosition (const QGeoCoordinate& coordinate); diff --git a/src/Wima/Snake/SnakeTiles.h b/src/Wima/Snake/SnakeTiles.h index dcb146af5eb9225114a84d78fb251a8e3f601a02..b617acb325732902ddcd4a70cc33dbc0759d6189 100644 --- a/src/Wima/Snake/SnakeTiles.h +++ b/src/Wima/Snake/SnakeTiles.h @@ -1,5 +1,5 @@ #pragma once #include "snaketile.h" -#include "WimaPolygonArray.h" +#include "Wima/Geometry/WimaPolygonArray.h" typedef WimaPolygonArray SnakeTiles; diff --git a/src/Wima/Snake/SnakeTilesLocal.h b/src/Wima/Snake/SnakeTilesLocal.h index a396de7d7883eb97b78783c6cb70227c195844b7..76f8b3702ac864ebc1669f61c41f36f4e624246a 100644 --- a/src/Wima/Snake/SnakeTilesLocal.h +++ b/src/Wima/Snake/SnakeTilesLocal.h @@ -1,8 +1,8 @@ #pragma once #include "ros_bridge/include/MessageGroups.h" -#include "Polygon2D.h" -#include "WimaPolygonArray.h" +#include "Wima/Geometry/Polygon2D.h" +#include "Wima/Geometry/WimaPolygonArray.h" namespace MsgGroups = ROSBridge::MessageGroups; typedef WimaPolygonArray SnakeTilesLocal; diff --git a/src/Wima/Snake/snaketile.h b/src/Wima/Snake/snaketile.h index 69fa8694a03c081c465afdf359dc3e22b0da793f..c41c649ddad8414b781071ec27a65c2c9b06dd32 100644 --- a/src/Wima/Snake/snaketile.h +++ b/src/Wima/Snake/snaketile.h @@ -1,6 +1,6 @@ #pragma once -#include "WimaAreaData.h" +#include "Wima/Geometry/WimaAreaData.h" class SnakeTile : public WimaAreaData { diff --git a/src/Wima/WaypointManager/AreaInterface.cpp b/src/Wima/WaypointManager/AreaInterface.cpp new file mode 100644 index 0000000000000000000000000000000000000000..bba104c07e574c6bdd27b8dce3e611148f1a101b --- /dev/null +++ b/src/Wima/WaypointManager/AreaInterface.cpp @@ -0,0 +1,72 @@ +#include "AreaInterface.h" + +WaypointManager::AreaInterface::AreaInterface() + : _mArea(nullptr) + , _sArea(nullptr) + , _cArea(nullptr) + , _jArea(nullptr) +{ + +} + +WaypointManager::AreaInterface::AreaInterface(WimaMeasurementAreaData *mArea, + WimaServiceAreaData *sArea, + WimaCorridorData *corr, + WimaJoinedAreaData *jArea) + : _mArea(mArea) + , _sArea(sArea) + , _cArea(corr) + , _jArea(jArea) +{ + +} + +void WaypointManager::AreaInterface::setMeasurementArea(WimaMeasurementAreaData *area) +{ + _mArea = area; +} + +void WaypointManager::AreaInterface::setServiceArea(WimaServiceAreaData *area) +{ + _sArea = area; +} + +void WaypointManager::AreaInterface::setCorridor(WimaCorridorData *area) +{ + _cArea = area; +} + +void WaypointManager::AreaInterface::setJoinedArea(WimaJoinedAreaData *area) +{ + _jArea = area; +} + +const WimaCorridorData *WaypointManager::AreaInterface::corridor() const +{ + return _cArea; +} + +const WimaJoinedAreaData *WaypointManager::AreaInterface::joinedArea() const +{ + return _jArea; +} + +WimaMeasurementAreaData *WaypointManager::AreaInterface::measurementArea() +{ + return _mArea; +} + +WimaServiceAreaData *WaypointManager::AreaInterface::serviceArea() +{ + return _sArea; +} + +WimaCorridorData *WaypointManager::AreaInterface::corridor() +{ + return _cArea; +} + +WimaJoinedAreaData *WaypointManager::AreaInterface::joinedArea() +{ + return _jArea; +} diff --git a/src/Wima/WaypointManager/AreaInterface.h b/src/Wima/WaypointManager/AreaInterface.h new file mode 100644 index 0000000000000000000000000000000000000000..431c23eda954f483c5cbc2b5d9c1c72e053fd7a6 --- /dev/null +++ b/src/Wima/WaypointManager/AreaInterface.h @@ -0,0 +1,42 @@ +#pragma once + +#include "Wima/Geometry/WimaMeasurementAreaData.h" +#include "Wima/Geometry/WimaServiceAreaData.h" +#include "Wima/Geometry/WimaCorridorData.h" +#include "Wima/Geometry/WimaJoinedAreaData.h" + +namespace WaypointManager { + +class AreaInterface +{ +public: + AreaInterface(); + AreaInterface(WimaMeasurementAreaData *mArea, + WimaServiceAreaData *sArea, + WimaCorridorData *corr, + WimaJoinedAreaData *jArea); + + void setMeasurementArea (WimaMeasurementAreaData *area); + void setServiceArea (WimaServiceAreaData *area); + void setCorridor (WimaCorridorData *area); + void setJoinedArea (WimaJoinedAreaData *area); + + virtual const WimaMeasurementAreaData *measurementArea() const; + virtual const WimaServiceAreaData *serviceArea() const; + virtual const WimaCorridorData *corridor() const; + virtual const WimaJoinedAreaData *joinedArea() const; + + virtual WimaMeasurementAreaData *measurementArea(); + virtual WimaServiceAreaData *serviceArea(); + virtual WimaCorridorData *corridor(); + virtual WimaJoinedAreaData *joinedArea(); + +private: + WimaMeasurementAreaData *_mArea; + WimaServiceAreaData *_sArea; + WimaCorridorData *_cArea; + WimaJoinedAreaData *_jArea; +}; + + +} // namespace WaypointManager diff --git a/src/Wima/WaypointManager/DefaultManager.cpp b/src/Wima/WaypointManager/DefaultManager.cpp new file mode 100644 index 0000000000000000000000000000000000000000..1c58931ad029820dcf0b62c23700065fc6a42273 --- /dev/null +++ b/src/Wima/WaypointManager/DefaultManager.cpp @@ -0,0 +1,232 @@ +#include "DefaultManager.h" +#include "Wima/Geometry/GeoUtilities.h" +#include "Wima/Geometry/PolygonCalculus.h" + +#include "MissionSettingsItem.h" + +bool WaypointManager::DefaultManager::update() +{ + // extract waypoints + _slice.clear(); + _slicer->update(_waypoints, _slice); + return _worker(); +} + +bool WaypointManager::DefaultManager::next() +{ + // extract waypoints + _slice.clear(); + _slicer->next(_waypoints, _slice); + return _worker(); +} + +bool WaypointManager::DefaultManager::previous() +{ + // extract waypoints + _slice.clear(); + _slicer->previous(_waypoints, _slice); + return _worker(); +} + +bool WaypointManager::DefaultManager::reset() +{ + // extract waypoints + _slice.clear(); + _slicer->reset(_waypoints, _slice); + return _worker(); +} + +bool WaypointManager::DefaultManager::_insertMissionItem(size_t index, const QGeoCoordinate &c, bool doUpdate) +{ + using namespace WaypointManager::Utils; + + if ( !insertMissionItem(c, + index /*insertion index*/, + _missionItems, + _settings->vehicle(), + _settings->isFlyView(), + &_missionItems /*parent*/, + doUpdate /*do update*/) ) + { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): insertMissionItem failed."); + return false; + } + return true; +} + +bool WaypointManager::DefaultManager::_calcShortestPath( + const QGeoCoordinate &start, + const QGeoCoordinate &destination, + QVector &path) +{ + using namespace GeoUtilities; + using namespace PolygonCalculus; + QVector path2D; + bool retVal = PolygonCalculus::shortestPath( + toQPolygonF(toCartesian2D(_areaInterface->joinedArea()->coordinateList(), /*origin*/ start)), + /*start point*/ QPointF(0,0), + /*destination*/ toCartesian2D(destination, start), + /*shortest path*/ path2D); + path.append(toGeo(path2D, /*origin*/ start)); + + return retVal; +} + +bool WaypointManager::DefaultManager::_worker() +{ + using namespace WaypointManager::Utils; + + if (_waypoints.count() < 1) { + return false; + } + + _missionItems.clearAndDeleteContents(); + initialize(_missionItems, _settings->vehicle(), _settings->isFlyView()); + + // calculate path from home to first waypoint + QVector arrivalPath; + if (!_settings->homePosition().isValid()){ + assert(false); + qWarning("WaypointManager::DefaultManager::next(): home position invalid."); + return false; + } + if ( !_calcShortestPath(_settings->homePosition(), _slice.first(), arrivalPath) ) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): Not able to calc path from home position to first waypoint."); + return false; + } + arrivalPath.removeFirst(); + + // calculate path from last waypoint to home + QVector returnPath; + if ( !_calcShortestPath(_slice.last(), _settings->homePosition(), returnPath) ) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): Not able to calc path from home position to last waypoint."); + return false; + } + returnPath.removeFirst(); + returnPath.removeLast(); + + + + // Create mission items. + // Set home position of MissionSettingsItem. + MissionSettingsItem* settingsItem = _missionItems.value(0); + if (settingsItem == nullptr) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): nullptr."); + return false; + } + settingsItem->setCoordinate(_settings->homePosition()); + + // Set takeoff position for first mission item (bug). + _insertMissionItem(1 /*insertion index*/, _settings->homePosition(), false /*do update*/); + SimpleMissionItem *takeoffItem = _missionItems.value(1); + if (takeoffItem == nullptr) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): nullptr."); + return false; + } + takeoffItem->setCoordinate(_settings->homePosition()); + + // Create change speed item. + _insertMissionItem(2 /*insertion index*/, _settings->homePosition(), false /*do update*/); + SimpleMissionItem *speedItem = _missionItems.value(2); + if (speedItem == nullptr) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): nullptr."); + return false; + } + speedItem->setCommand(MAV_CMD_DO_CHANGE_SPEED); + // Set coordinate must be after setCommand (setCommand sets coordinate to zero). + speedItem->setCoordinate(_settings->homePosition()); + speedItem->missionItem().setParam2(_settings->arrivalReturnSpeed()); + + // insert arrival path + for (auto coordinate : arrivalPath) { + _insertMissionItem(_missionItems.count() /*insertion index*/, + coordinate, + false /*do update*/); + } + + // Create change speed item (after arrival path). + int index = _missionItems.count(); + _insertMissionItem(index /*insertion index*/, _slice.first(), false /*do update*/); + speedItem = _missionItems.value(index); + if (speedItem == nullptr) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): nullptr."); + return false; + } + speedItem->setCommand(MAV_CMD_DO_CHANGE_SPEED); // set coordinate must be after setCommand (setCommand sets coordinate to zero) + speedItem->setCoordinate(_slice.first()); + speedItem->missionItem().setParam2(_settings->flightSpeed()); + + // Insert slice. + for (auto coordinate : _slice) { + _insertMissionItem(_missionItems.count() /*insertion index*/, + coordinate, + false /*do update*/); + } + + // Create change speed item, after slice. + index = _missionItems.count(); + _insertMissionItem(index /*insertion index*/, _slice.last(), false /*do update*/); + speedItem = _missionItems.value(index); + if (speedItem == nullptr) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): nullptr."); + return false; + } + speedItem->setCommand(MAV_CMD_DO_CHANGE_SPEED); // set coordinate must be after setCommand (setCommand sets coordinate to zero) + speedItem->setCoordinate(_slice.last()); + speedItem->missionItem().setParam2(_settings->arrivalReturnSpeed()); + + // Insert return path coordinates. + for (auto coordinate : returnPath) { + _insertMissionItem(_missionItems.count() /*insertion index*/, + coordinate, + false /*do update*/); + } + + // Set land command for last mission item. + index = _missionItems.count(); + _insertMissionItem(index /*insertion index*/, _settings->homePosition(), false /*do update*/); + SimpleMissionItem *landItem = _missionItems.value(index); + if (landItem == nullptr) { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): nullptr."); + return false; + } + + MAV_CMD landCmd = _settings->vehicle()->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND; + if (_settings->vehicle()->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) { + landItem->setCommand(landCmd); + } else { + assert(false); + qWarning("WaypointManager::DefaultManager::next(): Land command not supported!"); + return false; + } + + // Prepend arrival path to slice. + for ( long i = arrivalPath.size()-1; i >=0; --i ) + _slice.push_front(arrivalPath[i]); + // Append return path to slice. + for ( auto c : returnPath ) + _slice.push_back(c); + + + // Set altitude. + for (int i = 0; i < _missionItems.count(); ++i) { + SimpleMissionItem *item = _missionItems.value(i); + if (item == nullptr) { + assert(false); + qWarning("WimaController::updateAltitude(): nullptr"); + return false; + } + item->altitude()->setRawValue(_settings->altitude()); + } + + return true; +} diff --git a/src/Wima/WaypointManager/DefaultManager.h b/src/Wima/WaypointManager/DefaultManager.h new file mode 100644 index 0000000000000000000000000000000000000000..80817f05bd7b74d55a10ba05eb39cdb5050c7d0c --- /dev/null +++ b/src/Wima/WaypointManager/DefaultManager.h @@ -0,0 +1,45 @@ +#pragma once + +#include +#include + +#include "GenericWaypointManager.h" +#include "QmlObjectListModel.h" +#include "Settings.h" +#include "AreaInterface.h" + +namespace WaypointManager { + +typedef GenericWaypointManager + ManagerBase; + +class DefaultManager : public ManagerBase +{ +public: + DefaultManager() = delete; + DefaultManager(Slicer *slicer, + Settings *settings, + AreaInterface *interface); + + + virtual bool update() override; + virtual bool next() override; + virtual bool previous() override; + virtual bool reset() override; + +protected: + bool _insertMissionItem(size_t index, const QGeoCoordinate &c, bool doUpdate); + bool _calcShortestPath(const QGeoCoordinate &start, + const QGeoCoordinate &destination, + QVector &path); + + AreaInterface *_areaInterface; +private: + bool _worker(); + +}; + +} // namespace WaypointManager diff --git a/src/Wima/WaypointManager/GenericSlicer.h b/src/Wima/WaypointManager/GenericSlicer.h index ce5930e4fe97fcb75d6c36c857b127ad9b0892d2..992023adbea61d52dc44e8675afbe5ee8f8cce66 100644 --- a/src/Wima/WaypointManager/GenericSlicer.h +++ b/src/Wima/WaypointManager/GenericSlicer.h @@ -3,7 +3,7 @@ #include #include -#include "utils.h" +#include "Utils.h" //! @brief Base class for all waypoint managers. template class Container /*e.g. QVector*/> @@ -15,10 +15,10 @@ public: // Slicing. - void slice (const ContainerType &source, ContainerType &slice); - void next (const ContainerType &source, ContainerType &slice); - void previous (const ContainerType &source, ContainerType &slice); - void reset (const ContainerType &source, ContainerType &slice); + void update (const ContainerType &source, ContainerType &update); + void next (const ContainerType &source, ContainerType &update); + void previous (const ContainerType &source, ContainerType &update); + void reset (const ContainerType &source, ContainerType &update); // Slicing parameters. @@ -134,7 +134,7 @@ void GenericSlicer::_updateIdx(std::size_t size) } template class Container /*e.g. QVector*/> -void GenericSlicer::slice(const ContainerType &source, +void GenericSlicer::update(const ContainerType &source, Container &slice){ if ( !_idxValid) diff --git a/src/Wima/WaypointManager/GenericWaypointManager.h b/src/Wima/WaypointManager/GenericWaypointManager.h index 14cda453f880840d85e76b130e8ca4366a153248..162d3c0fb5d87dc467ac8e054477e69f05dd8730 100644 --- a/src/Wima/WaypointManager/GenericWaypointManager.h +++ b/src/Wima/WaypointManager/GenericWaypointManager.h @@ -3,59 +3,186 @@ #include #include "GenericSlicer.h" -#include "Settings.h" namespace WaypointManager { template class ContainerType> + template class ContainerType, + class MissionItemList, + class SettingsType> class GenericWaypointManager { - typedef GenericSlicer Slicer; public: + typedef GenericSlicer Slicer; typedef ContainerType WaypointList; GenericWaypointManager() = delete; - GenericWaypointManager(Slicer *slicer, Settings *settings); + GenericWaypointManager(Slicer *slicer, SettingsType *settings); // Waypoint editing. void setWaypoints(const WaypointList &waypoints); void push_back (const WaypointType &wp); void push_front (const WaypointType &wp); void clear (); - void insert (int i, const ElementType &wp); - uint32_t size () const; - WaypointType &at (unsigned int i); + void insert (std::size_t i, const WaypointType &wp); + std::size_t size () const; + WaypointType &at (std::size_t i); + + + const WaypointList &waypoints() const; + const WaypointList &slice() const; + const MissionItemList &missionItems() const; + + virtual bool update() = 0; + virtual bool next() = 0; + virtual bool previous() = 0; + virtual bool reset() = 0; + +protected: + WaypointList _waypoints; + WaypointList _slice; + MissionItemList _missionItems; + Slicer *_slicer; + SettingsType *_settings; +}; - const ContainerType &getWaypoints () ; - const ContainerType &getSlcieaypoints () ; - const ContainerType &missionItems () ; +template class ContainerType, + class MissionItemList, + class SettingsType> +GenericWaypointManager::GenericWaypointManager( + Slicer *slicer, + SettingsType *Settings + ) + : _slicer(slicer) + , _settings(_settings) +{} - void slice(); - void next(); - void previous(); - void reset(); +template class ContainerType, + class MissionItemList, + class SettingsType> +void GenericWaypointManager::push_back(const WaypointType &wp) +{ + _waypoints.push_back(wp); +} -private: - WaypointList _waypoints; - WaypointList _slice; - bool _sliceValid; - Slicer *_slicer; - Settings *_settings; +template class ContainerType, + class MissionItemList, + class SettingsType> +void GenericWaypointManager::push_front( + const WaypointType &wp) +{ + _waypoints.push_front(wp); +} -}; +template class ContainerType, + class MissionItemList, + class SettingsType> +void GenericWaypointManager::clear() +{ + _waypoints.clear(); +} +template class ContainerType, + class MissionItemList, + class SettingsType> +void GenericWaypointManager::insert(std::size_t i, + const WaypointType &wp) +{ + _waypoints.insert(i, wp); +} template class ContainerType> -GenericWaypointManager::GenericWaypointManager( - Slicer *slicer, - Settings *Settings) : - _sliceValid(false) - , _slicer(slicer) - , _settings(_settings) -{} + template class ContainerType, + class MissionItemList, + class SettingsType> +std::size_t GenericWaypointManager::size() const +{ + return _waypoints.size(); +} + +template class ContainerType, + class MissionItemList, + class SettingsType> +WaypointType & GenericWaypointManager::at(std::size_t i) +{ + return _waypoints.at(i); +} + +template class ContainerType, + class MissionItemList, + class SettingsType> +const ContainerType &GenericWaypointManager::waypoints() const +{ + return _waypoints; +} + +template class ContainerType, + class MissionItemList, + class SettingsType> +const ContainerType &GenericWaypointManager::slice() const +{ + return _slice; +} + +template class ContainerType, + class MissionItemList, + class SettingsType> +const MissionItemList &GenericWaypointManager::missionItems() const +{ + return _missionItems; +} + +template class ContainerType, + class MissionItemList, + class SettingsType> +void GenericWaypointManager::setWaypoints(const ContainerType &waypoints) +{ + _waypoints = waypoints; +} diff --git a/src/Wima/WaypointManager/Settings.cpp b/src/Wima/WaypointManager/Settings.cpp index 73916727690676c11ddcd6e649e15930b9733600..80e0e1926bafb14d7d9c6c9c1068fb0eaa36b95d 100644 --- a/src/Wima/WaypointManager/Settings.cpp +++ b/src/Wima/WaypointManager/Settings.cpp @@ -1 +1,63 @@ #include "Settings.h" + +void WaypointManager::Settings::setHomePosition(QGeoCoordinate &c) +{ + _homePosition = c; +} +void WaypointManager::Settings::setVehicle(Vehicle *vehicle) +{ + _vehicle = vehicle; +} + +void WaypointManager::Settings::setIsFlyView(bool isFlyView) +{ + _isFlyView = isFlyView; +} + +void WaypointManager::Settings::setArrivalReturnSpeed(double speed) +{ + if (speed > 0) + _arrivalReturnSpeed = speed; +} + +void WaypointManager::Settings::setFlightSpeed(double speed) +{ + if ( speed > 0) + _flightSpeed = speed; +} + +void WaypointManager::Settings::setAltitude(double altitude) +{ + if ( altitude > 0) + _altitude = altitude; +} + +const QGeoCoordinate &WaypointManager::Settings::homePosition() const +{ + return _homePosition; +} + +Vehicle *WaypointManager::Settings::vehicle() const +{ + return _vehicle; +} + +bool WaypointManager::Settings::isFlyView() const +{ + return _isFlyView; +} + +double WaypointManager::Settings::arrivalReturnSpeed() const +{ + return _arrivalReturnSpeed; +} + +double WaypointManager::Settings::flightSpeed() const +{ + return _flightSpeed; +} + +double WaypointManager::Settings::altitude() const +{ + return _altitude; +} diff --git a/src/Wima/WaypointManager/Settings.h b/src/Wima/WaypointManager/Settings.h index c971917060532acdf8f988dafb9c5732bef7b78c..780ac1c943c5049102d191376f58d5941d262ca3 100644 --- a/src/Wima/WaypointManager/Settings.h +++ b/src/Wima/WaypointManager/Settings.h @@ -1,11 +1,38 @@ #pragma once +#include + +#include "Vehicle.h" + namespace WaypointManager { class Settings { public: Settings(); + + void setHomePosition(QGeoCoordinate &c); + void setVehicle(Vehicle *vehicle); + void setIsFlyView(bool isFlyView); + void setArrivalReturnSpeed(double speed); + void setFlightSpeed(double speed); + void setAltitude(double altitude); + + const QGeoCoordinate &homePosition() const; + Vehicle *vehicle() const; + bool isFlyView() const; + double arrivalReturnSpeed() const; + double flightSpeed() const; + double altitude() const; + +private: + QGeoCoordinate _homePosition; + Vehicle *_vehicle; + bool _isFlyView; + double _arrivalReturnSpeed; + double _flightSpeed; + double _altitude; + }; } // namespace WaypointManager diff --git a/src/Wima/WaypointManager/Utils.cpp b/src/Wima/WaypointManager/Utils.cpp new file mode 100644 index 0000000000000000000000000000000000000000..649cec9f5b1381d3700b1d174d8283411e39a1c5 --- /dev/null +++ b/src/Wima/WaypointManager/Utils.cpp @@ -0,0 +1,189 @@ +#include "Utils.h" +#include "MissionSettingsItem.h" + + +template<> +QVariant WaypointManager::Utils::getCoordinate(const SimpleMissionItem* item) +{ + return QVariant::fromValue(item->coordinate()); +} + +bool WaypointManager::Utils::insertMissionItem(const QGeoCoordinate &coordinate, + long index, + QmlObjectListModel &list, + Vehicle* vehicle, + bool flyView, + QObject *parent, + bool doUpdates) +{ + using namespace WaypointManager::Utils; + + if ( !coordinate.isValid() ){ + return false; + } else { + if (parent == nullptr) + parent = &list; + SimpleMissionItem * newItem = new SimpleMissionItem(vehicle, flyView, parent); + + int sequenceNumber = detail::nextSequenceNumber(list); + newItem->setSequenceNumber(sequenceNumber); + newItem->setCoordinate(coordinate); + + // Set command (takeoff if first command). + newItem->setCommand(MAV_CMD_NAV_WAYPOINT); + if (list.count() == 1 + && ( vehicle->fixedWing() + || vehicle->vtol() + || vehicle->multiRotor() ) ) { + MAV_CMD takeoffCmd = vehicle->vtol() + ? MAV_CMD_NAV_VTOL_TAKEOFF + : MAV_CMD_NAV_TAKEOFF; + if (vehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) { + newItem->setCommand(takeoffCmd); + } + } + + // Set altitude and altitude mode from previous item. + if (newItem->specifiesAltitude()) { + double altitude; + int altitudeMode; + + if (detail::previousAltitude(list, --index, altitude, altitudeMode)) { + newItem->altitude()->setRawValue(altitude); + newItem->setAltitudeMode( + static_cast( + altitudeMode) ); + } + } + + list.insert(index, newItem); + + if ( doUpdates ) { + detail::updateSequenceNumbers(list, index); + detail::updateHirarchy(list); + detail::updateHomePosition(list); + } + } + return true; +} + +size_t WaypointManager::Utils::detail::nextSequenceNumber(QmlObjectListModel &list) +{ + if (list.count() >= 1) { + VisualMissionItem* lastItem = list.value(list.count() - 1); + return lastItem->lastSequenceNumber() + 1; + } + return 0; +} + +bool WaypointManager::Utils::detail::previousAltitude(QmlObjectListModel &list, + size_t index, + double &altitude, + int &altitudeMode) +{ + if (index >= size_t(list.count())) { + return false; + } + + for (long i = index; i >= 0; --i) { + VisualMissionItem* visualItem = list.value(i); + + if ( visualItem->specifiesCoordinate() + && !visualItem->isStandaloneCoordinate() ) { + if ( visualItem->isSimpleItem() ) { + SimpleMissionItem* simpleItem = qobject_cast(visualItem); + if (simpleItem->specifiesAltitude()) { + altitude = simpleItem->altitude()->rawValue().toDouble(); + altitudeMode = simpleItem->altitudeMode(); + return true; + } + } + } + } + + return false; +} + +bool WaypointManager::Utils::detail::updateSequenceNumbers(QmlObjectListModel &list, size_t startIdx) +{ + using namespace WaypointManager::Utils; + + if ( list.count() < 1 || startIdx >= size_t(list.count()) ) + return false; + + // Setup ascending sequence numbers for all visual items. + VisualMissionItem* startItem = list.value( + std::max(long(startIdx)-1,long(0)) ); + if (list.count() == 1){ + startItem->setSequenceNumber(0); + } else { + int sequenceNumber = startItem->lastSequenceNumber() + 1; + for (int i=startIdx; i < list.count(); ++i) { + VisualMissionItem* item = list.value(i); + item->setSequenceNumber(sequenceNumber); + sequenceNumber = item->lastSequenceNumber() + 1; + } + } + return true; +} + +bool WaypointManager::Utils::detail::updateHirarchy(QmlObjectListModel &list) +{ + if ( list.count() < 1) + return false; + + VisualMissionItem* currentParentItem = list.value(0); + + currentParentItem->childItems()->clear(); + + for (size_t i = 1; i < size_t( list.count() ); ++i) { + VisualMissionItem* item = list.value(i); + + if (item->specifiesCoordinate()) { + item->childItems()->clear(); + currentParentItem = item; + } else if (item->isSimpleItem()) { + currentParentItem->childItems()->append(item); + } + } + + return true; +} + +bool WaypointManager::Utils::detail::updateHomePosition(QmlObjectListModel &list) +{ + MissionSettingsItem *settingsItem = list.value(0); + + // Set the home position to be a delta from first coordinate + for (int i = 1; i < list.count(); ++i) { + VisualMissionItem* item = list.value(i); + + if (item->specifiesCoordinate() && item->coordinate().isValid()) { + QGeoCoordinate c = item->coordinate().atDistanceAndAzimuth(30, 0); + c.setAltitude(0); + settingsItem->setCoordinate(c); + return true; + } + } + + return false; +} + +void WaypointManager::Utils::initialize(QmlObjectListModel &list, + Vehicle *vehicle, + bool flyView) +{ + MissionSettingsItem* settingsItem = new MissionSettingsItem(vehicle, flyView, &list); + list.insert(0, settingsItem); +} + +bool WaypointManager::Utils::doUpdate(QmlObjectListModel &list) +{ + using namespace WaypointManager::Utils; + + bool ret = detail::updateSequenceNumbers(list, 0); + ret = detail::updateHirarchy(list) == false ? false : ret; + (void)detail::updateHomePosition(list); + + return ret; +} diff --git a/src/Wima/WaypointManager/Utils.h b/src/Wima/WaypointManager/Utils.h new file mode 100644 index 0000000000000000000000000000000000000000..175185d13b270a5758fd8e01547f89c6e89d686a --- /dev/null +++ b/src/Wima/WaypointManager/Utils.h @@ -0,0 +1,179 @@ +#pragma once + +#include "SimpleMissionItem.h" +#include "QmlObjectListModel.h" + +#include + +namespace WaypointManager { +namespace Utils { + + +template +CoordinateType getCoordinate(const SimpleMissionItem* item){ + return item->coordinate(); +} + +template<> +QVariant getCoordinate(const SimpleMissionItem* item); + + +/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList. +template class ContainerType> +bool extract(QmlObjectListModel &missionItems, + ContainerType &coordinateList, + std::size_t startIndex, + std::size_t endIndex) +{ + + if ( startIndex < std::size_t(missionItems.count()) + && endIndex < std::size_t(missionItems.count()) + && missionItems.count() > 0) { + if (startIndex > endIndex) { + if ( !extract(missionItems, + coordinateList, + startIndex, + std::size_t(missionItems.count()-1)) /*recursion*/) + return false; + if ( !extract(missionItems, + coordinateList, + 0, + endIndex) /*recursion*/) + return false; + } else { + for (std::size_t i = startIndex; i <= endIndex; ++i) { + SimpleMissionItem *mItem = missionItems.value(int(i)); + + if (mItem == nullptr) { + coordinateList.clear(); + return false; + } + coordinateList.append(getCoordinate(mItem)); + } + } + } else + return false; + + return true; +} + +/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList. +template class ContainerType> +bool extract(QmlObjectListModel &missionItems, + ContainerType &coordinateList) +{ + + return extract(missionItems, + coordinateList, + std::size_t(0), + std::size_t(missionItems.count()) + ); +} + + +/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList. +template class ContainerType> +bool extract(ContainerType &source, + ContainerType &destination, + std::size_t startIndex, + std::size_t endIndex) +{ + + if ( startIndex < std::size_t(source.size()) + && endIndex < std::size_t(source.size()) + && source.size() > 0) { + if (startIndex > endIndex) { + if ( !extract(source, + destination, + startIndex, + std::size_t(source.size()-1)) /*recursion*/) + return false; + if ( !extract(source, + destination, + 0, + endIndex) /*recursion*/) + return false; + } else { + for (std::size_t i = startIndex; i <= endIndex; ++i) { + destination.append(source[i]); + } + } + } else + return false; + + return true; +} + + +//! +//! \brief Initializes the list \p list. +//! +//! Adds a MissionSettingsItem to \p list. +//! \param list List of VisualMissionItems. +//! \param vehicle Vehicle. +//! \param flyView Fly- or planview. +void initialize(QmlObjectListModel &list, + Vehicle *vehicle, + bool flyView=true); + +//! @brief Creates (from QGeoCoordinate) and Inserts a SimpleMissionItem at the given index to list. +//! \param coordinate Coordinate of the SimpleMissionItem. +//! \param index Index to insert SimpleMissionItem. +//! \param list List of SimpleMissionItems. +//! \param vehicle Vehicle. +//! \param flyView Fly- or planview. +//! \param parent Parent of the SimpleMissionItem (Set to &list if nullptr). +//! \param doUpdates Neccessary update are performed to the list \p list if set to true. Set this to true for the last item only, +//! if inserting multiple items. +//! \return Returns true on success, false either. +//! +//! @note The list must be initialized. (\see \fn initialize) +//! @note This function doesn't establish any signal-slot connections (\see \fn MissionController::_initVisualItem). +//! @note This function doesn't set the MissionFlightStatus_t (\see \fn VisualMissionItem::setMissionFlightStatus). +bool insertMissionItem(const QGeoCoordinate &coordinate, + long index, + QmlObjectListModel &list, + Vehicle *vehicle, + bool flyView=true, + QObject *parent=nullptr, + bool doUpdates=true); + +bool doUpdate(QmlObjectListModel &list); + +namespace detail { + size_t nextSequenceNumber(QmlObjectListModel &list); + bool previousAltitude(QmlObjectListModel &list, + size_t index, + double &altitude, + int &altitudeMode); + + //! @brief Updates the sequence numbers of the VisualMissionItems inside \p list beginning from \p startIdx. + //! + //! Updates the sequence numbers of the VisualMissionItems inside \p list beginning from \pstartIdx. + //! \param list List containing VisualMissionItems. + //! \param startIdx Start index. + //! \return Returns true if successfull, false either. + //! + //! \note The function returns false immediatelly if the list \p list ist empty or + //! the \p startIdx is out of bounds. + //! \note If the list \p list contains only one VisualMissionItem it's sequence number is + //! set to 0. + bool updateSequenceNumbers(QmlObjectListModel &list, size_t startIdx=0); + + //! @brief Update the parent child item hierarchy of the VisualMissionItems inside \p list. + //! + //! \param list List containing VisualMissionItems. + //! \return Returns true if successfull, false either. + //! + //! \note Returns true on success, false either. + bool updateHirarchy(QmlObjectListModel &list); + + //! @brief Updates the home position to the first valid coordinate of the VisualMissionItems inside \p list. + //! + //! \param list List containing VisualMissionItems. + //! \return Returns true if the home position was updated, false either. + bool updateHomePosition(QmlObjectListModel &list); + +} // namespace detail +} // namespace Utils +} // namespace WaypointManager diff --git a/src/Wima/WaypointManager/utils.cpp b/src/Wima/WaypointManager/utils.cpp deleted file mode 100644 index 0831f81f95ea01fbd17cb8a83291956e24a6023c..0000000000000000000000000000000000000000 --- a/src/Wima/WaypointManager/utils.cpp +++ /dev/null @@ -1,8 +0,0 @@ -#include "utils.h" - - -template<> -QVariant getCoordinate(const SimpleMissionItem* item) -{ - return QVariant::fromValue(item->coordinate()); -} diff --git a/src/Wima/WaypointManager/utils.h b/src/Wima/WaypointManager/utils.h deleted file mode 100644 index e94cda664511521fbf8ac8ad59dc2684377ff6a5..0000000000000000000000000000000000000000 --- a/src/Wima/WaypointManager/utils.h +++ /dev/null @@ -1,103 +0,0 @@ -#pragma once - -namespace WaypointManager { -namespace Utils { - - -template -CoordinateType getCoordinate(const SimpleMissionItem* item){ - return item->coordinate(); -} - -template<> -QVariant getCoordinate(const SimpleMissionItem* item); - - -/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList. -template class ContainerType> -bool extract(QmlObjectListModel &missionItems, - ContainerType &coordinateList, - std::size_t startIndex, - std::size_t endIndex) -{ - - if ( startIndex < std::size_t(missionItems.count()) - && endIndex < std::size_t(missionItems.count()) - && missionItems.count() > 0) { - if (startIndex > endIndex) { - if ( !extract(missionItems, - coordinateList, - startIndex, - std::size_t(missionItems.count()-1)) /*recursion*/) - return false; - if ( !extract(missionItems, - coordinateList, - 0, - endIndex) /*recursion*/) - return false; - } else { - for (std::size_t i = startIndex; i <= endIndex; ++i) { - SimpleMissionItem *mItem = missionItems.value(int(i)); - - if (mItem == nullptr) { - coordinateList.clear(); - return false; - } - coordinateList.append(getCoordinate(mItem)); - } - } - } else - return false; - - return true; -} - -/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList. -template class ContainerType> -bool extract(QmlObjectListModel &missionItems, - ContainerType &coordinateList) -{ - - return extract(missionItems, - coordinateList, - std::size_t(0), - std::size_t(missionItems.count()) - ); -} - - -/// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList. -template class ContainerType> -bool extract(ContainerType &source, - ContainerType &destination, - std::size_t startIndex, - std::size_t endIndex) -{ - - if ( startIndex < std::size_t(source.size()) - && endIndex < std::size_t(source.size()) - && source.size() > 0) { - if (startIndex > endIndex) { - if ( !extract(source, - destination, - startIndex, - std::size_t(source.size()-1)) /*recursion*/) - return false; - if ( !extract(source, - destination, - 0, - endIndex) /*recursion*/) - return false; - } else { - for (std::size_t i = startIndex; i <= endIndex; ++i) { - destination.append(source[i]); - } - } - } else - return false; - - return true; -} - -} // namespace WaypointManager -} // namespace WaypointManager diff --git a/src/Wima/WimaController.cc b/src/Wima/WimaController.cc index 4a20e7d7a4e70aee60e8bf18a87f1604fa9220b5..d958dcd0b1cf94ef6db7bb5ba85527f60d53836a 100644 --- a/src/Wima/WimaController.cc +++ b/src/Wima/WimaController.cc @@ -6,9 +6,9 @@ #include "ros_bridge/rapidjson/include/rapidjson/ostreamwrapper.h" #include "ros_bridge/include/CasePacker.h" -#include "QtROSJsonFactory.h" -#include "QtROSTypeFactory.h" -#include "QNemoProgress.h" +#include "Snake/QtROSJsonFactory.h" +#include "Snake/QtROSTypeFactory.h" +#include "Snake/QNemoProgress.h" #include "time.h" #include "assert.h" diff --git a/src/Wima/WimaController.h b/src/Wima/WimaController.h index d8dc0693f335508864a4767c9a209c60c6af59d9..791a22e8b9fa0bbc0da0427a3ff4b4f2db237532 100644 --- a/src/Wima/WimaController.h +++ b/src/Wima/WimaController.h @@ -6,14 +6,14 @@ #include "QGCMapPolygon.h" #include "QmlObjectListModel.h" -#include "WimaArea.h" -#include "WimaMeasurementArea.h" -#include "WimaServiceArea.h" -#include "WimaCorridor.h" +#include "Geometry/WimaArea.h" +#include "Geometry/WimaMeasurementArea.h" +#include "Geometry/WimaServiceArea.h" +#include "Geometry/WimaCorridor.h" #include "WimaDataContainer.h" -#include "WimaMeasurementAreaData.h" -#include "WimaCorridorData.h" -#include "WimaServiceAreaData.h" +#include "Geometry/WimaMeasurementAreaData.h" +#include "Geometry/WimaCorridorData.h" +#include "Geometry/WimaServiceAreaData.h" #include "PlanMasterController.h" #include "MissionController.h" @@ -27,11 +27,11 @@ #include "SettingsManager.h" #include "snake.h" -#include "SnakeWorker.h" -#include "SnakeTiles.h" -#include "SnakeTilesLocal.h" -#include "GeoPoint3D.h" -#include "QNemoProgress.h" +#include "Snake/SnakeWorker.h" +#include "Snake/SnakeTiles.h" +#include "Snake/SnakeTilesLocal.h" +#include "Geometry/GeoPoint3D.h" +#include "Snake/QNemoProgress.h" #include "ros_bridge/include/ROSBridge.h" diff --git a/src/Wima/WimaPlanData.h b/src/Wima/WimaPlanData.h index eb20089c23b7d7d06c33f8e0c8992b86c9e90ec6..0f98ca2c1fab814da16ea68ecc9d45438e0c77e5 100644 --- a/src/Wima/WimaPlanData.h +++ b/src/Wima/WimaPlanData.h @@ -2,11 +2,11 @@ #include -#include "WimaAreaData.h" -#include "WimaServiceAreaData.h" -#include "WimaCorridorData.h" -#include "WimaMeasurementAreaData.h" -#include "WimaJoinedAreaData.h" +#include "Geometry/WimaAreaData.h" +#include "Geometry/WimaServiceAreaData.h" +#include "Geometry/WimaCorridorData.h" +#include "Geometry/WimaMeasurementAreaData.h" +#include "Geometry/WimaJoinedAreaData.h" #include "MissionItem.h" class WimaPlanData : QObject diff --git a/src/Wima/WimaPlaner.h b/src/Wima/WimaPlaner.h index fde1c40edf0399d843b81e050f461420a004864b..7c0454458d0efe37e335f271b3e530b3bf2acd49 100644 --- a/src/Wima/WimaPlaner.h +++ b/src/Wima/WimaPlaner.h @@ -4,16 +4,16 @@ #include "QGCMapPolygon.h" #include "QmlObjectListModel.h" -#include "WimaArea.h" -#include "WimaAreaData.h" -#include "WimaServiceArea.h" -#include "WimaServiceAreaData.h" -#include "WimaMeasurementArea.h" -#include "WimaMeasurementAreaData.h" -#include "WimaCorridor.h" -#include "WimaCorridorData.h" -#include "WimaJoinedArea.h" -#include "WimaJoinedAreaData.h" +#include "Geometry/WimaArea.h" +#include "Geometry/WimaAreaData.h" +#include "Geometry/WimaServiceArea.h" +#include "Geometry/WimaServiceAreaData.h" +#include "Geometry/WimaMeasurementArea.h" +#include "Geometry/WimaMeasurementAreaData.h" +#include "Geometry/WimaCorridor.h" +#include "Geometry/WimaCorridorData.h" +#include "Geometry/WimaJoinedArea.h" +#include "Geometry/WimaJoinedAreaData.h" #include "WimaPlanData.h" #include "WimaDataContainer.h" @@ -26,8 +26,8 @@ #include "QGCApplication.h" #include "OptimisationTools.h" -#include "PlanimetryCalculus.h" -#include "GeoUtilities.h" +#include "Geometry/PlanimetryCalculus.h" +#include "Geometry/GeoUtilities.h" #include "QSignalBlocker"