diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index ea0820229ab0bd25d5eb544dae573dab9a1815e4..0c50bb2111b92f00d6af7227e5ae8abd3df3b819 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -195,9 +195,9 @@
src/ViewWidgets/ViewWidget.qml
src/Wima/Snake/WimaAreaNoVisual.qml
src/WimaView/CircularGeneratorEditor.qml
- src/WimaView/CircularGeneratorMapVisual.qml
+ src/WimaView/CircularGeneratorMapVisual.qml
src/WimaView/CircularSurveyItemEditor.qml
- src/WimaView/CircularSurveyMapVisual.qml
+ src/WimaView/CircularSurveyMapVisual.qml
src/WimaView/CoordinateIndicator.qml
src/WimaView/CoordinateIndicatorDrag.qml
src/WimaView/DragCoordinate.qml
diff --git a/src/FlightMap/MapItems/MissionLineView.qml b/src/FlightMap/MapItems/MissionLineView.qml
index 39382391f3f2d2c5569351083fa3086716f21f93..3d0adac28314740044b34457383cb52d084778af 100644
--- a/src/FlightMap/MapItems/MissionLineView.qml
+++ b/src/FlightMap/MapItems/MissionLineView.qml
@@ -30,5 +30,9 @@ MapItemView {
object.coordinate1,
object.coordinate2,
] : []
+
+// onParentChanged: {
+// console.log("MapItemView, path:" + path)
+// }
}
}
diff --git a/src/PlanView/MissionItemMapVisual.qml b/src/PlanView/MissionItemMapVisual.qml
index 96d07ff67e432bbb20d331ed5c32b23c03dcc1c1..49eb8c601e3544121ff30a36fdffcd08c3c2e228 100644
--- a/src/PlanView/MissionItemMapVisual.qml
+++ b/src/PlanView/MissionItemMapVisual.qml
@@ -15,7 +15,7 @@ import QtPositioning 5.3
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
-
+import Wima 1.0
/// Mission item map visual
Item {
diff --git a/src/Wima/CircularSurvey.cc b/src/Wima/CircularSurvey.cc
index 625abee8f52124eff91e0b9e15078e6d820a567b..bce2505828c5e0efa5fe5ddf433594f2f25197b1 100644
--- a/src/Wima/CircularSurvey.cc
+++ b/src/Wima/CircularSurvey.cc
@@ -278,7 +278,7 @@ void CircularSurvey::_updateWorker() {
auto origin = this->_pAreaData->origin();
origin.setAltitude(0);
if (!origin.isValid()) {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_updateWorker(): origin invalid." << origin;
return;
}
@@ -286,7 +286,7 @@ void CircularSurvey::_updateWorker() {
// Convert safe area.
auto geoSafeArea = this->_pAreaData->joinedArea().coordinateList();
if (!(geoSafeArea.size() >= 3)) {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_updateWorker(): safe area invalid." << geoSafeArea;
return;
}
@@ -294,7 +294,7 @@ void CircularSurvey::_updateWorker() {
if (v.isValid()) {
v.setAltitude(0);
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_updateWorker(): safe area contains invalid coordinate."
<< geoSafeArea;
return;
@@ -314,17 +314,17 @@ void CircularSurvey::_updateWorker() {
// Start/Restart routing worker.
this->_pWorker->route(par, g);
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_updateWorker(): generator creation failed.";
}
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_updateWorker(): pGenerator == nullptr, number of registered "
"generators: "
<< this->_generatorList.size();
}
} else {
- qCWarning(CircularSurveyLog) << "_updateWorker(): plan data invalid.";
+ qCDebug(CircularSurveyLog) << "_updateWorker(): plan data invalid.";
}
}
@@ -343,7 +343,7 @@ void CircularSurvey::_changeVariantWorker() {
// Swap route.
if (variant != old_variant) {
- // Swap in new variant, if condition.
+ // Swap in new variant.
if (variant < std::size_t(this->_variantVector.size())) {
if (old_variant != std::numeric_limits::max()) {
// this->_transects containes a route, swap it back to
@@ -355,9 +355,9 @@ void CircularSurvey::_changeVariantWorker() {
this->_transects.swap(newVariantCoordinates);
} else { // error
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "Variant out of bounds (variant =" << variant << ").";
- qCWarning(CircularSurveyLog) << "Resetting variant to zero.";
+ qCDebug(CircularSurveyLog) << "Resetting variant to zero.";
disconnect(&this->_variant, &Fact::rawValueChanged, this,
&CircularSurvey::_changeVariant);
@@ -379,33 +379,6 @@ void CircularSurvey::_reverseWorker() {
}
}
-void CircularSurvey::_storeWorker() {
- // If the transects are getting rebuilt then any previously loaded
- // mission items are now invalid.
- if (_loadedMissionItemsParent) {
- _loadedMissionItems.clear();
- _loadedMissionItemsParent->deleteLater();
- _loadedMissionItemsParent = nullptr;
- }
-
- // Add route variant names.
- this->_variantNames.clear();
- for (std::size_t i = 1; i <= std::size_t(this->_variantVector.size()); ++i) {
- this->_variantNames.append(QString::number(i));
- }
- emit variantNamesChanged();
-
- disconnect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
- this->_variant.setCookedValue(QVariant(0));
- connect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
- this->_changeVariantWorker();
-
- // Mark transect as stored and ready.
- this->_transectsDirty = false;
-}
-
void CircularSurvey::applyNewAltitude(double newAltitude) {
_cameraCalc.valueSetIsDistance()->setRawValue(true);
_cameraCalc.distanceToSurface()->setRawValue(newAltitude);
@@ -432,18 +405,18 @@ double CircularSurvey::additionalTimeDelay() const { return 0; }
bool CircularSurvey::registerGenerator(
const QString &name, std::shared_ptr g) {
if (name.isEmpty()) {
- qCWarning(CircularSurveyLog) << "registerGenerator(): empty name string.";
+ qCDebug(CircularSurveyLog) << "registerGenerator(): empty name string.";
return false;
}
if (!g) {
- qCWarning(CircularSurveyLog) << "registerGenerator(): empty generator.";
+ qCDebug(CircularSurveyLog) << "registerGenerator(): empty generator.";
return false;
}
if (this->_generatorNameList.contains(name)) {
- qCWarning(CircularSurveyLog) << "registerGenerator(): generator "
- "already registered.";
+ qCDebug(CircularSurveyLog) << "registerGenerator(): generator "
+ "already registered.";
return false;
} else {
this->_generatorNameList.push_back(name);
@@ -467,7 +440,7 @@ bool CircularSurvey::unregisterGenerator(const QString &name) {
_switchToGenerator(this->_generatorList.at(index - 1));
} else {
_switchToGenerator(nullptr);
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "unregisterGenerator(): last generator unregistered.";
}
}
@@ -478,7 +451,7 @@ bool CircularSurvey::unregisterGenerator(const QString &name) {
emit generatorNameListChanged();
return true;
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "unregisterGenerator(): generator " << name << " not registered.";
return false;
}
@@ -488,10 +461,10 @@ bool CircularSurvey::unregisterGenerator(int index) {
if (index > 0 && index < this->_generatorNameList.size()) {
return unregisterGenerator(this->_generatorNameList.at(index));
} else {
- qCWarning(CircularSurveyLog) << "unregisterGenerator(): index (" << index
- << ") out"
- "of bounds ( "
- << this->_generatorList.size() << " ).";
+ qCDebug(CircularSurveyLog) << "unregisterGenerator(): index (" << index
+ << ") out"
+ "of bounds ( "
+ << this->_generatorList.size() << " ).";
return false;
}
}
@@ -502,7 +475,7 @@ bool CircularSurvey::switchToGenerator(const QString &name) {
_switchToGenerator(this->_generatorList.at(index));
return true;
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "switchToGenerator(): generator " << name << " not registered.";
return false;
}
@@ -513,10 +486,10 @@ bool CircularSurvey::switchToGenerator(int index) {
_switchToGenerator(this->_generatorList.at(index));
return true;
} else {
- qCWarning(CircularSurveyLog) << "unregisterGenerator(): index (" << index
- << ") out"
- "of bounds ( "
- << this->_generatorNameList.size() << " ).";
+ qCDebug(CircularSurveyLog) << "unregisterGenerator(): index (" << index
+ << ") out"
+ "of bounds ( "
+ << this->_generatorNameList.size() << " ).";
return false;
}
}
@@ -537,30 +510,29 @@ void CircularSurvey::_rebuildTransectsPhase1(void) {
auto start = std::chrono::high_resolution_clock::now();
switch (this->_state) {
- case STATE::STORE:
- qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: store.";
- this->_storeWorker();
+ case STATE::SKIPP:
+ qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: skipp.";
break;
case STATE::VARIANT_CHANGE:
- qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: variant change.";
+ qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: variant change.";
this->_changeVariantWorker();
break;
case STATE::RUN_CHANGE:
- qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: run change.";
+ qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: run change.";
this->_changeVariantWorker();
break;
case STATE::REVERSE:
- qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: reverse.";
+ qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: reverse.";
this->_reverseWorker();
break;
case STATE::IDLE:
- qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: update.";
+ qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: update.";
this->_updateWorker();
break;
}
this->_state = STATE::IDLE;
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "rebuildTransectsPhase1(): "
<< std::chrono::duration_cast(
std::chrono::high_resolution_clock::now() - start)
@@ -585,7 +557,8 @@ void CircularSurvey::_recalcCameraShots() { _cameraShots = 0; }
void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
// Store solutions.
- const auto &ori = this->_pAreaData->origin();
+ auto ori = this->_pAreaData->origin();
+ ori.setAltitude(0);
const auto &transectsENU = pRoute->transects;
QVector variantVector;
const auto nSolutions = pRoute->solutionVector.size();
@@ -639,19 +612,19 @@ void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
}
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_setTransects(): lastTransect.size() == 0";
}
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_setTransects(): firstTransect.size() == 0";
}
} else {
- qCWarning(CircularSurveyLog)
+ qCDebug(CircularSurveyLog)
<< "_setTransects(): transectsInfo.size() <= 1";
}
} else {
- qCWarning(CircularSurveyLog) << "_setTransects(): solution.size() == 0";
+ qCDebug(CircularSurveyLog) << "_setTransects(): solution.size() == 0";
}
if (var.size() > 0 && var.front().size() > 0) {
@@ -663,9 +636,38 @@ void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
if (variantVector.size() > 0) {
// Swap first route to _transects.
this->_variantVector.swap(variantVector);
- this->_state = STATE::STORE;
+
+ // If the transects are getting rebuilt then any previously loaded
+ // mission items are now invalid.
+ if (_loadedMissionItemsParent) {
+ _loadedMissionItems.clear();
+ _loadedMissionItemsParent->deleteLater();
+ _loadedMissionItemsParent = nullptr;
+ }
+
+ // Add route variant names.
+ this->_variantNames.clear();
+ for (std::size_t i = 1; i <= std::size_t(this->_variantVector.size());
+ ++i) {
+ this->_variantNames.append(QString::number(i));
+ }
+ emit variantNamesChanged();
+
+ disconnect(&this->_variant, &Fact::rawValueChanged, this,
+ &CircularSurvey::_changeVariant);
+ this->_variant.setCookedValue(QVariant(0));
+ connect(&this->_variant, &Fact::rawValueChanged, this,
+ &CircularSurvey::_changeVariant);
+ this->_changeVariantWorker();
+
+ // Mark transect ready.
+ this->_transectsDirty = false;
+
+ this->_state = STATE::SKIPP;
this->_rebuildTransects();
} else {
+ qCDebug(CircularSurveyLog)
+ << "_setTransects(): failed, variantVector empty.";
this->_state = STATE::IDLE;
}
}
diff --git a/src/Wima/CircularSurvey.h b/src/Wima/CircularSurvey.h
index 06a1a93d844decd10b3170a6174db8fa9ec39d05..aa24ef999f25a1dc95eb9aba9f4bcb55886b3454 100644
--- a/src/Wima/CircularSurvey.h
+++ b/src/Wima/CircularSurvey.h
@@ -104,7 +104,6 @@ private slots:
void _updateWorker();
void _changeVariantWorker();
void _reverseWorker();
- void _storeWorker();
private:
void _appendLoadedMissionItems(QList &items,
@@ -117,7 +116,7 @@ private:
// State.
enum class STATE {
IDLE,
- STORE,
+ SKIPP,
REVERSE,
VARIANT_CHANGE,
RUN_CHANGE,
@@ -137,11 +136,8 @@ private:
QStringList _generatorNameList;
PtrGenerator _pGenerator;
- // Worker
- PtrWorker _pWorker;
- PtrRoutingData _pRoutingData; // remove this, not necessary.
-
- // Routing data.
+ // Routing.
using Variant = Transects;
QVector _variantVector;
+ PtrWorker _pWorker;
};
diff --git a/src/Wima/Geometry/WimaAreaData.cc b/src/Wima/Geometry/WimaAreaData.cc
index 56909032e92b43b0f046de1858681cecd8e7e793..ca977dc226454138182d6dd182a09cb5e4bce920 100644
--- a/src/Wima/Geometry/WimaAreaData.cc
+++ b/src/Wima/Geometry/WimaAreaData.cc
@@ -2,7 +2,14 @@
WimaAreaData::WimaAreaData(QObject *parent) : QObject(parent) {}
-WimaAreaData::~WimaAreaData() {}
+WimaAreaData::WimaAreaData(const WimaAreaData &other, QObject *parent)
+ : QObject(parent), _path(other._path), _list(other._list),
+ _center(other._center) {}
+
+WimaAreaData::WimaAreaData(const WimaArea &otherData, QObject *parent)
+ : QObject(parent), _center(otherData.center()) {
+ _setPathImpl(otherData.path());
+}
bool WimaAreaData::operator==(const WimaAreaData &data) const {
return this->_path == data._path && this->_center == data._center;
@@ -25,7 +32,7 @@ bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const {
using namespace PolygonCalculus;
using namespace GeoUtilities;
- if (_path.size() > 2) {
+ if (this->coordinateList().size() > 2) {
QPolygonF polygon;
toCartesianList(this->coordinateList(), coordinate, polygon);
return PlanimetryCalculus::contains(polygon, QPointF(0, 0));
@@ -36,44 +43,60 @@ bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const {
void WimaAreaData::append(const QGeoCoordinate &c) {
_list.append(c);
_path.push_back(QVariant::fromValue(c));
+ emit pathChanged();
}
void WimaAreaData::push_back(const QGeoCoordinate &c) { append(c); }
void WimaAreaData::clear() {
- _list.clear();
- _path.clear();
+ if (_list.size() > 0 || _path.size() > 0) {
+ _list.clear();
+ _path.clear();
+ emit pathChanged();
+ }
}
void WimaAreaData::setPath(const QVariantList &coordinateList) {
- _path = coordinateList;
- _list.clear();
- for (auto variant : coordinateList) {
- _list.push_back(variant.value());
+ if (_path != coordinateList) {
+ _setPathImpl(coordinateList);
+ emit pathChanged();
}
}
void WimaAreaData::setCenter(const QGeoCoordinate ¢er) {
if (_center != center) {
_center = center;
-
emit centerChanged();
}
}
-/*!
- * \fn void WimaAreaData::assign(const WimaAreaData &other)
- *
- * Assigns \a other to the invoking object
- */
-void WimaAreaData::assign(const WimaAreaData &other) {
- setPath(other.path());
- setCenter(other.center());
+WimaAreaData &WimaAreaData::operator=(const WimaAreaData &otherData) {
+ setPath(otherData._list);
+ setCenter(otherData._center);
+ return *this;
}
-void WimaAreaData::assign(const WimaArea &other) {
- setPath(other.path());
- setCenter(other.center());
+WimaAreaData &WimaAreaData::operator=(const WimaArea &otherData) {
+ setPath(otherData.path());
+ setCenter(otherData.center());
+ return *this;
+}
+
+void WimaAreaData::_setPathImpl(const QList &coordinateList) {
+ _list = coordinateList;
+ _path.clear();
+ // copy all coordinates to _path
+ for (const auto &vertex : coordinateList) {
+ _path.append(QVariant::fromValue(vertex));
+ }
+}
+
+void WimaAreaData::_setPathImpl(const QVariantList &coordinateList) {
+ _path = coordinateList;
+ _list.clear();
+ for (const auto &variant : coordinateList) {
+ _list.push_back(variant.value());
+ }
}
/*!
@@ -83,24 +106,26 @@ void WimaAreaData::assign(const WimaArea &other) {
* coordinateList. Emits the \c pathChanged() signal.
*/
void WimaAreaData::setPath(const QList &coordinateList) {
- _list = coordinateList;
-
- _path.clear();
- // copy all coordinates to _path
- for (int i = 0; i < coordinateList.size(); i++) {
- _path.append(QVariant::fromValue(coordinateList.value(i)));
+ if (_list != coordinateList) {
+ _setPathImpl(coordinateList);
+ emit pathChanged();
}
-
- emit pathChanged(_path);
}
bool operator==(const WimaAreaData &m1, const WimaArea &m2) {
return m1.path() == m2.path() && m1.center() == m2.center();
}
+
bool operator!=(const WimaAreaData &m1, const WimaArea &m2) {
return !operator==(m1, m2);
}
+bool operator==(const WimaArea &m1, const WimaAreaData &m2) { return m2 == m1; }
+
+bool operator!=(const WimaArea &m1, const WimaAreaData &m2) {
+ return !operator==(m2, m1);
+}
+
/*!
* \class WimaArea::WimaAreaData
* \brief Class to store and exchange data of a \c WimaArea Object.
diff --git a/src/Wima/Geometry/WimaAreaData.h b/src/Wima/Geometry/WimaAreaData.h
index ffbc4c61287cc27ce85f232730e6971f0f45510f..b9348aa5fcfe9ad63271cc7aea27a023665f7101 100644
--- a/src/Wima/Geometry/WimaAreaData.h
+++ b/src/Wima/Geometry/WimaAreaData.h
@@ -1,4 +1,4 @@
-#pragma once
+#pragma once
#include
@@ -11,16 +11,12 @@ class WimaAreaData
{
Q_OBJECT
public:
+ WimaAreaData(QObject *parent = nullptr);
+
Q_PROPERTY(const QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(QString type READ type CONSTANT)
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT)
- WimaAreaData(QObject *parent = nullptr);
- ~WimaAreaData();
- WimaAreaData(const WimaAreaData &otherData) = delete; // avoid slicing
- WimaAreaData &
- operator=(const WimaAreaData &otherData) = delete; // avoid slicing
-
bool operator==(const WimaAreaData &data) const;
bool operator!=(const WimaAreaData &data) const;
@@ -37,8 +33,8 @@ public:
void clear();
signals:
- void pathChanged(const QVariantList &coordinateList);
- void centerChanged(void);
+ void pathChanged();
+ void centerChanged();
public slots:
void setPath(const QList &coordinateList);
@@ -46,18 +42,21 @@ public slots:
void setCenter(const QGeoCoordinate ¢er);
protected:
- void assign(const WimaAreaData &other);
- void assign(const WimaArea &other);
+ WimaAreaData(const WimaAreaData &otherData, QObject *parent);
+ WimaAreaData(const WimaArea &otherData, QObject *parent);
+ WimaAreaData &operator=(const WimaAreaData &otherData);
+ WimaAreaData &operator=(const WimaArea &otherData);
private:
- // Member Functions
-
+ void _setPathImpl(const QList &coordinateList);
+ void _setPathImpl(const QVariantList &coordinateList);
// Member Variables
- // see WimaArea.h for explanation
- QVariantList _path;
- mutable QList _list;
+ mutable QVariantList _path;
+ QList _list;
QGeoCoordinate _center;
};
bool operator==(const WimaAreaData &m1, const WimaArea &m2);
bool operator!=(const WimaAreaData &m1, const WimaArea &m2);
+bool operator==(const WimaArea &m1, const WimaAreaData &m2);
+bool operator!=(const WimaArea &m1, const WimaAreaData &m2);
diff --git a/src/Wima/Geometry/WimaCorridorData.cpp b/src/Wima/Geometry/WimaCorridorData.cpp
index 23abae3b71656fe99514d906db26055157b82677..2bd90d6e6013e5c877fe1a9bcb4031de9f538197 100644
--- a/src/Wima/Geometry/WimaCorridorData.cpp
+++ b/src/Wima/Geometry/WimaCorridorData.cpp
@@ -6,14 +6,10 @@ WimaCorridorData::WimaCorridorData(QObject *parent) : WimaAreaData(parent) {}
WimaCorridorData::WimaCorridorData(const WimaCorridorData &other,
QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
+ : WimaAreaData(other, parent) {}
WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
+ : WimaAreaData(other, parent) {}
/*!
* \overload operator=()
@@ -21,8 +17,7 @@ WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent)
* Assigns \a other to the invoking object.
*/
WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other) {
- this->assign(other);
-
+ WimaAreaData::operator=(other);
return *this;
}
@@ -32,8 +27,7 @@ WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other) {
* Assigns \a other to the invoking object.
*/
WimaCorridorData &WimaCorridorData::operator=(const WimaCorridor &other) {
- this->assign(other);
-
+ WimaAreaData::operator=(other);
return *this;
}
@@ -43,14 +37,6 @@ QString WimaCorridorData::mapVisualQML() const {
QString WimaCorridorData::type() const { return this->typeString; }
-void WimaCorridorData::assign(const WimaCorridorData &corridorData) {
- WimaAreaData::assign(corridorData);
-}
-
-void WimaCorridorData::assign(const WimaCorridor &corridor) {
- WimaAreaData::assign(corridor);
-}
-
/*!
* \class WimaAreaData::WimaCorridorData
* \brief Class to store and exchange data of a \c WimaCorridorData Object.
diff --git a/src/Wima/Geometry/WimaCorridorData.h b/src/Wima/Geometry/WimaCorridorData.h
index b5557a599b28a2d858a67e32e00f0a765f1dbedc..a319b54382969564cf3e9bc1eef37116677ca80a 100644
--- a/src/Wima/Geometry/WimaCorridorData.h
+++ b/src/Wima/Geometry/WimaCorridorData.h
@@ -23,14 +23,4 @@ public:
WimaCorridorData *Clone() const { return new WimaCorridorData(*this); }
static const char *typeString;
-
-signals:
-
-public slots:
-
-protected:
- void assign(const WimaCorridorData &corridorData);
- void assign(const WimaCorridor &corridor);
-
-private:
};
diff --git a/src/Wima/Geometry/WimaJoinedAreaData.cc b/src/Wima/Geometry/WimaJoinedAreaData.cc
index 2929a0d84fa0f97c1ec2f36bf277d55ec83ea5d1..0b7a540ba5b25dfe078d6ba08d51a222531dc673 100644
--- a/src/Wima/Geometry/WimaJoinedAreaData.cc
+++ b/src/Wima/Geometry/WimaJoinedAreaData.cc
@@ -7,15 +7,11 @@ WimaJoinedAreaData::WimaJoinedAreaData(QObject *parent)
WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedAreaData &other,
QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
+ : WimaAreaData(other, parent) {}
WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other,
QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
+ : WimaAreaData(other, parent) {}
/*!
* \overload operator=()
@@ -24,8 +20,7 @@ WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other,
*/
WimaJoinedAreaData &WimaJoinedAreaData::
operator=(const WimaJoinedAreaData &other) {
- assign(other);
-
+ WimaAreaData::operator=(other);
return *this;
}
@@ -35,7 +30,7 @@ operator=(const WimaJoinedAreaData &other) {
* Assigns \a other to the invoking object.
*/
WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedArea &other) {
- assign(other);
+ WimaAreaData::operator=(other);
return *this;
}
@@ -45,14 +40,6 @@ QString WimaJoinedAreaData::mapVisualQML() const {
QString WimaJoinedAreaData::type() const { return this->typeString; }
-void WimaJoinedAreaData::assign(const WimaJoinedAreaData &other) {
- WimaAreaData::assign(other);
-}
-
-void WimaJoinedAreaData::assign(const WimaJoinedArea &other) {
- WimaAreaData::assign(other);
-}
-
/*!
* \class WimaAreaData::WimaJoinedAreaData
* \brief Class to store and exchange data of a \c WimaJoinedAreaData Object.
diff --git a/src/Wima/Geometry/WimaJoinedAreaData.h b/src/Wima/Geometry/WimaJoinedAreaData.h
index 1d205dcb1b278fba95698b8e5efd0cec0bb14537..35c903580747f018e1682958c199bd5985193599 100644
--- a/src/Wima/Geometry/WimaJoinedAreaData.h
+++ b/src/Wima/Geometry/WimaJoinedAreaData.h
@@ -24,10 +24,4 @@ public:
WimaJoinedAreaData *Clone() const { return new WimaJoinedAreaData(*this); }
static const char *typeString;
-
-protected:
- void assign(const WimaJoinedAreaData &other);
- void assign(const WimaJoinedArea &other);
-
-private:
};
diff --git a/src/Wima/Geometry/WimaMeasurementAreaData.cc b/src/Wima/Geometry/WimaMeasurementAreaData.cc
index 45a66e540ec56746a534d582427d3a41f4afaaf3..5d0b68fcc3b16aaf18b248600ab6404002e08378 100644
--- a/src/Wima/Geometry/WimaMeasurementAreaData.cc
+++ b/src/Wima/Geometry/WimaMeasurementAreaData.cc
@@ -22,6 +22,7 @@ bool WimaMeasurementAreaData::
operator==(const WimaMeasurementAreaData &other) const {
return this->WimaAreaData::operator==(other) &&
this->_tileData == other.tileData() &&
+ this->_progress == other.progress() &&
this->center() == other.center();
}
@@ -33,6 +34,8 @@ operator!=(const WimaMeasurementAreaData &other) const {
void WimaMeasurementAreaData::setTileData(const TileData &d) {
if (this->_tileData != d) {
this->_tileData = d;
+ this->_progress.fill(0, d.size());
+ emit progressChanged();
emit tileDataChanged();
}
}
@@ -51,7 +54,9 @@ void WimaMeasurementAreaData::setProgress(const QVector &d) {
*/
WimaMeasurementAreaData &WimaMeasurementAreaData::
operator=(const WimaMeasurementAreaData &other) {
- assign(other);
+ WimaAreaData::operator=(other);
+ setTileData(other._tileData);
+ setProgress(other._progress);
return *this;
}
@@ -63,7 +68,14 @@ operator=(const WimaMeasurementAreaData &other) {
*/
WimaMeasurementAreaData &WimaMeasurementAreaData::
operator=(const WimaMeasurementArea &other) {
- assign(other);
+ WimaAreaData::operator=(other);
+ if (other.ready()) {
+ setTileData(other.tileData());
+ setProgress(other.progress());
+ } else {
+ qWarning() << "WimaMeasurementAreaData::operator=(): WimaMeasurementArea "
+ "not ready.";
+ }
return *this;
}
@@ -102,23 +114,6 @@ const QVector &WimaMeasurementAreaData::progress() const {
QVector &WimaMeasurementAreaData::progress() { return this->_progress; }
-void WimaMeasurementAreaData::assign(const WimaMeasurementAreaData &other) {
- WimaAreaData::assign(other);
- setTileData(other._tileData);
- setProgress(other._progress);
-}
-
-void WimaMeasurementAreaData::assign(const WimaMeasurementArea &other) {
- WimaAreaData::assign(other);
- if (other.ready()) {
- setTileData(other.tileData());
- setProgress(other.progress());
- } else {
- qWarning()
- << "WimaMeasurementAreaData::assign(): WimaMeasurementArea not ready.";
- }
-}
-
bool operator==(const WimaMeasurementAreaData &m1,
const WimaMeasurementArea &m2) {
return operator==(*static_cast(&m1),
diff --git a/src/Wima/Geometry/WimaMeasurementAreaData.h b/src/Wima/Geometry/WimaMeasurementAreaData.h
index 68481ffb6d243da305158ceff6e584461993ab54..dde208291fdd5c69080d651e9f828dcdd3852bf7 100644
--- a/src/Wima/Geometry/WimaMeasurementAreaData.h
+++ b/src/Wima/Geometry/WimaMeasurementAreaData.h
@@ -50,10 +50,6 @@ signals:
void tileDataChanged();
void progressChanged();
-protected:
- void assign(const WimaMeasurementAreaData &other);
- void assign(const WimaMeasurementArea &other);
-
private:
TileData _tileData;
QVector _progress;
diff --git a/src/Wima/Geometry/WimaServiceAreaData.cc b/src/Wima/Geometry/WimaServiceAreaData.cc
index 7496e90953d1a88a55a21c7760befb06845dd4b9..ef52635dfe56dab66a887408c2f5315a99cc268f 100644
--- a/src/Wima/Geometry/WimaServiceAreaData.cc
+++ b/src/Wima/Geometry/WimaServiceAreaData.cc
@@ -7,26 +7,22 @@ WimaServiceAreaData::WimaServiceAreaData(QObject *parent)
WimaServiceAreaData::WimaServiceAreaData(const WimaServiceAreaData &other,
QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
+ : WimaAreaData(other, parent), _depot(other._depot) {}
WimaServiceAreaData::WimaServiceAreaData(const WimaServiceArea &other,
QObject *parent)
- : WimaAreaData(parent) {
- *this = other;
-}
+ : WimaAreaData(other, parent), _depot(other.depot()) {}
WimaServiceAreaData &WimaServiceAreaData::
operator=(const WimaServiceAreaData &otherData) {
- this->assign(otherData);
+ WimaAreaData::operator=(otherData);
this->setDepot(otherData.depot());
return *this;
}
WimaServiceAreaData &WimaServiceAreaData::
operator=(const WimaServiceArea &otherArea) {
- this->assign(otherArea);
+ WimaAreaData::operator=(otherArea);
this->setDepot(otherArea.depot());
return *this;
}
@@ -57,16 +53,6 @@ void WimaServiceAreaData::setDepot(const QGeoCoordinate &newCoordinate) {
}
}
-void WimaServiceAreaData::assign(const WimaServiceAreaData &other) {
- WimaAreaData::assign(other);
- setDepot(other.depot());
-}
-
-void WimaServiceAreaData::assign(const WimaServiceArea &other) {
- WimaAreaData::assign(other);
- setDepot(other.depot());
-}
-
/*!
* \class WimaAreaData::WimaServiceAreaData
* \brief Class to store and exchange data of a \c WimaServiceArea Object.
diff --git a/src/Wima/Geometry/WimaServiceAreaData.h b/src/Wima/Geometry/WimaServiceAreaData.h
index 08f616e4bbdd14e0558898519fb08cb200a7db6d..2b93a20964008977061f992314174feee299d408 100644
--- a/src/Wima/Geometry/WimaServiceAreaData.h
+++ b/src/Wima/Geometry/WimaServiceAreaData.h
@@ -31,10 +31,6 @@ signals:
public slots:
void setDepot(const QGeoCoordinate &newCoordinate);
-protected:
- void assign(const WimaServiceAreaData &other);
- void assign(const WimaServiceArea &other);
-
private:
// see WimaServieArea.h for explanation
QGeoCoordinate _depot;
diff --git a/src/Wima/RoutingThread.cpp b/src/Wima/RoutingThread.cpp
index 5b34bdd7e2a2f3a5e75ceffd9d3f33d4aeb6e353..f45bb3c0349231b9e91a4203ef6c38a7ad95a847 100644
--- a/src/Wima/RoutingThread.cpp
+++ b/src/Wima/RoutingThread.cpp
@@ -5,7 +5,7 @@
#include
#include "QGCLoggingCategory.h"
-QGC_LOGGING_CATEGORY(RoutingWorkerLog, "RoutingWorkerLog")
+QGC_LOGGING_CATEGORY(RoutingThreadLog, "RoutingThreadLog")
RoutingThread::RoutingThread(QObject *parent)
: QThread(parent), _calculating(false), _stop(false), _restart(false) {
@@ -44,10 +44,10 @@ void RoutingThread::route(const RoutingParameter &par,
}
void RoutingThread::run() {
- qCWarning(RoutingWorkerLog) << "run(): thread start.";
+ qCDebug(RoutingThreadLog) << "run(): thread start.";
while (!this->_stop) {
- qCWarning(RoutingWorkerLog) << "run(): calculation "
- "started.";
+ qCDebug(RoutingThreadLog) << "run(): calculation "
+ "started.";
// Copy input.
auto start = std::chrono::high_resolution_clock::now();
@@ -67,8 +67,8 @@ void RoutingThread::run() {
if (generator(transectsENU)) {
// Check if generation was successful.
if (transectsENU.size() == 0) {
- qCWarning(RoutingWorkerLog) << "run(): "
- "not able to generate transects.";
+ qCDebug(RoutingThreadLog) << "run(): "
+ "not able to generate transects.";
} else {
// Prepare data for routing.
auto &solutionVector = pRouteData->solutionVector;
@@ -93,24 +93,24 @@ void RoutingThread::run() {
// Check if routing was successful.
if ((!success || solutionVector.size() < 1) && !this->_restart) {
- qCWarning(RoutingWorkerLog) << "run(): "
- "routing failed. "
- << snakePar.errorString.c_str();
+ qCDebug(RoutingThreadLog) << "run(): "
+ "routing failed. "
+ << snakePar.errorString.c_str();
} else if (this->_restart) {
- qCWarning(RoutingWorkerLog) << "run(): "
- "restart requested.";
+ qCDebug(RoutingThreadLog) << "run(): "
+ "restart requested.";
} else {
// Notify main thread.
emit result(pRouteData);
- qCWarning(RoutingWorkerLog) << "run(): "
- "concurrent update success.";
+ qCDebug(RoutingThreadLog) << "run(): "
+ "concurrent update success.";
}
}
} // end calculation
else {
- qCWarning(RoutingWorkerLog) << "run(): generator() failed.";
+ qCDebug(RoutingThreadLog) << "run(): generator() failed.";
}
- qCWarning(RoutingWorkerLog)
+ qCDebug(RoutingThreadLog)
<< "run(): execution time: "
<< std::chrono::duration_cast(
std::chrono::high_resolution_clock::now() - start)
@@ -125,5 +125,5 @@ void RoutingThread::run() {
}
this->_restart = false;
} // main loop
- qCWarning(RoutingWorkerLog) << "run(): thread end.";
+ qCDebug(RoutingThreadLog) << "run(): thread end.";
}
diff --git a/src/Wima/Snake/CircularGenerator.cpp b/src/Wima/Snake/CircularGenerator.cpp
index 3267d5ab473080c8c829c95c5be2090878e7d215..669fc53f6b1d34f31797fac505d3b581c19a6e61 100644
--- a/src/Wima/Snake/CircularGenerator.cpp
+++ b/src/Wima/Snake/CircularGenerator.cpp
@@ -64,14 +64,14 @@ bool CircularGenerator::get(Generator &generator) {
auto origin = this->_d->origin();
origin.setAltitude(0);
if (!origin.isValid()) {
- qCWarning(CircularGeneratorLog) << "get(): origin invalid." << origin;
+ qCDebug(CircularGeneratorLog) << "get(): origin invalid." << origin;
return false;
}
auto ref = this->_reference;
ref.setAltitude(0);
if (!ref.isValid()) {
- qCWarning(CircularGeneratorLog) << "get(): reference invalid." << ref;
+ qCDebug(CircularGeneratorLog) << "get(): reference invalid." << ref;
return false;
}
snake::FPoint reference;
@@ -82,9 +82,9 @@ bool CircularGenerator::get(Generator &generator) {
if (v.isValid()) {
v.setAltitude(0);
} else {
- qCWarning(CircularGeneratorLog) << "get(): measurement area invalid.";
+ qCDebug(CircularGeneratorLog) << "get(): measurement area invalid.";
for (const auto &w : geoPolygon) {
- qCWarning(CircularGeneratorLog) << w;
+ qCDebug(CircularGeneratorLog) << w;
}
return false;
}
@@ -105,21 +105,21 @@ bool CircularGenerator::get(Generator &generator) {
snake::areaToEnu(origin, tile->coordinateList(), tileENU);
pTiles->push_back(std::move(tileENU));
} else {
- qCWarning(CircularGeneratorLog)
+ qCDebug(CircularGeneratorLog)
<< "get(): progress.size() != tiles->count().";
return false;
}
}
}
} else {
- qCWarning(CircularGeneratorLog)
+ qCDebug(CircularGeneratorLog)
<< "get(): progress.size() != tiles->count().";
return false;
}
auto geoDepot = this->_d->serviceArea().depot();
if (!geoDepot.isValid()) {
- qCWarning(CircularGeneratorLog) << "get(): depot invalid." << geoDepot;
+ qCDebug(CircularGeneratorLog) << "get(): depot invalid." << geoDepot;
return false;
}
snake::FPoint depot;
@@ -142,11 +142,11 @@ bool CircularGenerator::get(Generator &generator) {
};
return true;
} else {
- qCWarning(CircularGeneratorLog) << "get(): data invalid.";
+ qCDebug(CircularGeneratorLog) << "get(): data invalid.";
return false;
}
} else {
- qCWarning(CircularGeneratorLog) << "get(): data member not set.";
+ qCDebug(CircularGeneratorLog) << "get(): data member not set.";
return false;
}
}
@@ -160,22 +160,29 @@ void CircularGenerator::setReference(const QGeoCoordinate &reference) {
}
}
+void CircularGenerator::resetReferenceIfInvalid() {
+ if (!this->_reference.isValid()) {
+ resetReference();
+ }
+}
+
void CircularGenerator::resetReference() {
- setReference(_d->measurementArea().center());
+ if (this->_d->measurementArea().center().isValid()) {
+ setReference(this->_d->measurementArea().center());
+ }
}
void CircularGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) {
- connect(this->_d.get(), &WimaPlanData::measurementAreaChanged, this,
- &GeneratorBase::generatorChanged);
connect(this->_d.get(), &WimaPlanData::originChanged, this,
&GeneratorBase::generatorChanged);
- connect(&this->_d->measurementArea(),
- &WimaMeasurementAreaData::progressChanged, this,
- &GeneratorBase::generatorChanged);
connect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged);
+ connect(&this->_d->measurementArea(), &WimaMeasurementAreaData::pathChanged,
+ this, &CircularGenerator::resetReferenceIfInvalid);
+ connect(&this->_d->measurementArea(), &WimaMeasurementAreaData::pathChanged,
+ this, &GeneratorBase::generatorChanged);
connect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged, this,
&GeneratorBase::generatorChanged);
connect(this->distance(), &Fact::rawValueChanged, this,
@@ -192,8 +199,6 @@ void CircularGenerator::establishConnections() {
void CircularGenerator::deleteConnections() {
if (this->_d && this->_connectionsEstablished) {
- disconnect(this->_d.get(), &WimaPlanData::measurementAreaChanged, this,
- &GeneratorBase::generatorChanged);
disconnect(this->_d.get(), &WimaPlanData::originChanged, this,
&GeneratorBase::generatorChanged);
disconnect(&this->_d->measurementArea(),
@@ -202,6 +207,12 @@ void CircularGenerator::deleteConnections() {
disconnect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged);
+ disconnect(&this->_d->measurementArea(),
+ &WimaMeasurementAreaData::pathChanged, this,
+ &CircularGenerator::resetReferenceIfInvalid);
+ disconnect(&this->_d->measurementArea(),
+ &WimaMeasurementAreaData::pathChanged, this,
+ &GeneratorBase::generatorChanged);
disconnect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged,
this, &GeneratorBase::generatorChanged);
disconnect(this->distance(), &Fact::rawValueChanged, this,
@@ -236,12 +247,12 @@ bool circularTransects(const snake::FPoint &reference,
std::string error;
// Check validity.
if (!bg::is_valid(polygon, error)) {
- qCWarning(CircularGeneratorLog) << "circularTransects(): "
- "invalid polygon.";
- qCWarning(CircularGeneratorLog) << error.c_str();
+ qCDebug(CircularGeneratorLog) << "circularTransects(): "
+ "invalid polygon.";
+ qCDebug(CircularGeneratorLog) << error.c_str();
std::stringstream ss;
ss << bg::wkt(polygon);
- qCWarning(CircularGeneratorLog) << ss.str().c_str();
+ qCDebug(CircularGeneratorLog) << ss.str().c_str();
} else {
// Calculate polygon distances and angles.
std::vector distances;
@@ -249,7 +260,7 @@ bool circularTransects(const snake::FPoint &reference,
std::vector angles;
angles.reserve(polygon.outer().size());
//#ifdef DEBUG_CIRCULAR_SURVEY
- // qCWarning(CircularGeneratorLog) << "circularTransects():";
+ // qCDebug(CircularGeneratorLog) << "circularTransects():";
//#endif
for (const auto &p : polygon.outer()) {
snake::Length distance = bg::distance(reference, p) * si::meter;
@@ -258,11 +269,11 @@ bool circularTransects(const snake::FPoint &reference,
alpha = alpha < 0 * si::radian ? alpha + 2 * M_PI * si::radian : alpha;
angles.push_back(alpha);
//#ifdef DEBUG_CIRCULAR_SURVEY
- // qCWarning(CircularGeneratorLog) << "distances, angles,
- // coordinates:"; qCWarning(CircularGeneratorLog) <<
- // to_string(distance).c_str(); qCWarning(CircularGeneratorLog)
+ // qCDebug(CircularGeneratorLog) << "distances, angles,
+ // coordinates:"; qCDebug(CircularGeneratorLog) <<
+ // to_string(distance).c_str(); qCDebug(CircularGeneratorLog)
// << to_string(snake::Degree(alpha)).c_str();
- // qCWarning(CircularGeneratorLog) << "x = " << p.get<0>() << "y
+ // qCDebug(CircularGeneratorLog) << "x = " << p.get<0>() << "y
// = "
// << p.get<1>();
//#endif
@@ -285,8 +296,8 @@ bool circularTransects(const snake::FPoint &reference,
const auto deltaRScaled =
ClipperLib::cInt(std::round(deltaR.value() * CLIPPER_SCALE));
auto referenceScaled = ClipperLib::IntPoint{
- ClipperLib::cInt(std::round(reference.get<0>())),
- ClipperLib::cInt(std::round(reference.get<1>()))};
+ ClipperLib::cInt(std::round(reference.get<0>() * CLIPPER_SCALE)),
+ ClipperLib::cInt(std::round(reference.get<1>() * CLIPPER_SCALE))};
// Generate circle sectors.
auto rScaled = rMinScaled;
@@ -295,20 +306,20 @@ bool circularTransects(const snake::FPoint &reference,
const auto nSectors =
long(std::round(((alpha2 - alpha1) / deltaAlpha).value()));
//#ifdef DEBUG_CIRCULAR_SURVEY
- // qCWarning(CircularGeneratorLog) << "circularTransects(): sector
- // parameres:"; qCWarning(CircularGeneratorLog) << "alpha1: " <<
+ // qCDebug(CircularGeneratorLog) << "circularTransects(): sector
+ // parameres:"; qCDebug(CircularGeneratorLog) << "alpha1: " <<
// to_string(snake::Degree(alpha1)).c_str();
- // qCWarning(CircularGeneratorLog) << "alpha2:
+ // qCDebug(CircularGeneratorLog) << "alpha2:
// "
// << to_string(snake::Degree(alpha2)).c_str();
- // qCWarning(CircularGeneratorLog) << "n: "
+ // qCDebug(CircularGeneratorLog) << "n: "
// << to_string((alpha2 - alpha1) / deltaAlpha).c_str();
- // qCWarning(CircularGeneratorLog)
- // << "nSectors: " << nSectors; qCWarning(CircularGeneratorLog) <<
+ // qCDebug(CircularGeneratorLog)
+ // << "nSectors: " << nSectors; qCDebug(CircularGeneratorLog) <<
// "rMin: " << to_string(rMin).c_str();
- // qCWarning(CircularGeneratorLog)
+ // qCDebug(CircularGeneratorLog)
// << "rMax: " << to_string(rMax).c_str();
- // qCWarning(CircularGeneratorLog) << "nTran: " << nTran;
+ // qCDebug(CircularGeneratorLog) << "nTran: " << nTran;
//#endif
using ClipperCircle =
GenericCircle;
@@ -427,7 +438,7 @@ bool circularTransects(const snake::FPoint &reference,
}
}
- qCWarning(CircularGeneratorLog)
+ qCDebug(CircularGeneratorLog)
<< "circularTransects(): transect gen. time: "
<< std::chrono::duration_cast(
std::chrono::high_resolution_clock::now() - s1)
diff --git a/src/Wima/Snake/CircularGenerator.h b/src/Wima/Snake/CircularGenerator.h
index e286fe584fa3a904b2b586356b74c61a1d0508c9..d4458a2292ea9b90317d2be338f0848b6fe56503 100644
--- a/src/Wima/Snake/CircularGenerator.h
+++ b/src/Wima/Snake/CircularGenerator.h
@@ -30,7 +30,6 @@ public:
Fact *minLength();
void setReference(const QGeoCoordinate &reference);
- Q_INVOKABLE void resetReference();
static const char *settingsGroup;
static const char *distanceName;
@@ -43,6 +42,10 @@ public:
signals:
void referenceChanged();
+public slots:
+ Q_INVOKABLE void resetReferenceIfInvalid();
+ Q_INVOKABLE void resetReference();
+
protected:
virtual void establishConnections() override;
virtual void deleteConnections() override;
diff --git a/src/Wima/Snake/GeneratorBase.cc b/src/Wima/Snake/GeneratorBase.cc
index 03d8d581ac4c6b18bf930172724380f7a78dbc43..bc315e54b9bd9319d433208f20a75bf29a53c5bd 100644
--- a/src/Wima/Snake/GeneratorBase.cc
+++ b/src/Wima/Snake/GeneratorBase.cc
@@ -12,13 +12,9 @@ GeneratorBase::GeneratorBase(GeneratorBase::Data d, QObject *parent)
GeneratorBase::~GeneratorBase() {}
-QString GeneratorBase::editorQml() {
- return QStringLiteral("EmptyGeneratorEditor.qml");
-}
+QString GeneratorBase::editorQml() { return QStringLiteral(""); }
-QString GeneratorBase::mapVisualQml() {
- return QStringLiteral("EmptyGeneratorMapVisual.qml");
-}
+QString GeneratorBase::mapVisualQml() { return QStringLiteral(""); }
GeneratorBase::Data GeneratorBase::data() const { return _d; }
diff --git a/src/Wima/Snake/LinearGenerator.cpp b/src/Wima/Snake/LinearGenerator.cpp
index 6fa668de1fed36ae1b573e683c1d4f948c091a8e..19d7da6d76aa4c483795901fca2868b2c454ed4a 100644
--- a/src/Wima/Snake/LinearGenerator.cpp
+++ b/src/Wima/Snake/LinearGenerator.cpp
@@ -49,7 +49,7 @@ bool LinearGenerator::get(Generator &generator) {
auto origin = this->_d->origin();
origin.setAltitude(0);
if (!origin.isValid()) {
- qCWarning(LinearGeneratorLog) << "get(): origin invalid.";
+ qCDebug(LinearGeneratorLog) << "get(): origin invalid." << origin;
}
auto geoPolygon = this->_d->measurementArea().coordinateList();
@@ -57,9 +57,9 @@ bool LinearGenerator::get(Generator &generator) {
if (v.isValid()) {
v.setAltitude(0);
} else {
- qCWarning(LinearGeneratorLog) << "get(): measurement area invalid.";
+ qCDebug(LinearGeneratorLog) << "get(): measurement area invalid.";
for (const auto &w : geoPolygon) {
- qCWarning(LinearGeneratorLog) << w;
+ qCDebug(LinearGeneratorLog) << w;
}
return false;
}
@@ -80,21 +80,20 @@ bool LinearGenerator::get(Generator &generator) {
snake::areaToEnu(origin, tile->coordinateList(), tileENU);
pTiles->push_back(std::move(tileENU));
} else {
- qCWarning(LinearGeneratorLog)
- << "get(): progress.size() != tiles->count().";
+ qCDebug(LinearGeneratorLog) << "get(): tile == nullptr";
return false;
}
}
}
} else {
- qCWarning(LinearGeneratorLog)
+ qCDebug(LinearGeneratorLog)
<< "get(): progress.size() != tiles->count().";
return false;
}
auto geoDepot = this->_d->serviceArea().depot();
if (!geoDepot.isValid()) {
- qCWarning(LinearGeneratorLog) << "get(): depot invalid." << geoDepot;
+ qCDebug(LinearGeneratorLog) << "get(): depot invalid." << geoDepot;
return false;
}
snake::FPoint depot;
@@ -116,11 +115,11 @@ bool LinearGenerator::get(Generator &generator) {
};
return true;
} else {
- qCWarning(LinearGeneratorLog) << "get(): data invalid.";
+ qCDebug(LinearGeneratorLog) << "get(): data invalid.";
return false;
}
} else {
- qCWarning(LinearGeneratorLog) << "get(): data member not set.";
+ qCDebug(LinearGeneratorLog) << "get(): data member not set.";
return false;
}
}
@@ -133,8 +132,6 @@ Fact *LinearGenerator::minLength() { return &_minLength; }
void LinearGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) {
- connect(this->_d.get(), &WimaPlanData::measurementAreaChanged, this,
- &GeneratorBase::generatorChanged);
connect(this->_d.get(), &WimaPlanData::originChanged, this,
&GeneratorBase::generatorChanged);
connect(&this->_d->measurementArea(),
@@ -143,6 +140,8 @@ void LinearGenerator::establishConnections() {
connect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged);
+ connect(&this->_d->measurementArea(), &WimaMeasurementAreaData::pathChanged,
+ this, &GeneratorBase::generatorChanged);
connect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged, this,
&GeneratorBase::generatorChanged);
connect(this->distance(), &Fact::rawValueChanged, this,
@@ -167,6 +166,9 @@ void LinearGenerator::deleteConnections() {
disconnect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged);
+ disconnect(&this->_d->measurementArea(),
+ &WimaMeasurementAreaData::pathChanged, this,
+ &GeneratorBase::generatorChanged);
disconnect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged,
this, &GeneratorBase::generatorChanged);
disconnect(this->distance(), &Fact::rawValueChanged, this,
@@ -195,9 +197,9 @@ bool linearTransects(const snake::FPolygon &polygon,
std::stringstream ss;
ss << bg::wkt(polygon);
- qCWarning(LinearGeneratorLog) << "linearTransects(): "
- "invalid polygon. "
- << error.c_str() << ss.str().c_str();
+ qCDebug(LinearGeneratorLog) << "linearTransects(): "
+ "invalid polygon. "
+ << error.c_str() << ss.str().c_str();
} else {
tr::rotate_transformer rotate(angle.value() *
180 / M_PI);
@@ -244,7 +246,7 @@ bool linearTransects(const snake::FPolygon &polygon,
std::stringstream ss;
ss << "Not able to generate transects. Parameter: distance = "
<< distance << std::endl;
- qCWarning(LinearGeneratorLog)
+ qCDebug(LinearGeneratorLog)
<< "linearTransects(): " << ss.str().c_str();
return false;
}
@@ -312,12 +314,12 @@ bool linearTransects(const snake::FPolygon &polygon,
std::stringstream ss;
ss << "Not able to generatetransects. Parameter: minLength = "
<< minLength << std::endl;
- qCWarning(LinearGeneratorLog)
+ qCDebug(LinearGeneratorLog)
<< "linearTransects(): " << ss.str().c_str();
return false;
}
- qCWarning(LinearGeneratorLog)
+ qCDebug(LinearGeneratorLog)
<< "linearTransects(): time: "
<< std::chrono::duration_cast(
std::chrono::high_resolution_clock::now() - s1)
diff --git a/src/Wima/Snake/NemoInterface.cpp b/src/Wima/Snake/NemoInterface.cpp
index f5187778dc3088a804aca08d352b0bdeb6bee21b..41b04046d57426e39a6ae65e21e0f9e8a2af9234 100644
--- a/src/Wima/Snake/NemoInterface.cpp
+++ b/src/Wima/Snake/NemoInterface.cpp
@@ -2,6 +2,7 @@
#include "SnakeTilesLocal.h"
#include "QGCApplication.h"
+#include "QGCLoggingCategory.h"
#include "QGCToolbox.h"
#include "SettingsFact.h"
#include "SettingsManager.h"
@@ -26,6 +27,8 @@
#include "ros_bridge/rapidjson/include/rapidjson/ostreamwrapper.h"
#include "ros_bridge/rapidjson/include/rapidjson/writer.h"
+QGC_LOGGING_CATEGORY(NemoInterfaceLog, "NemoInterfaceLog")
+
#define EVENT_TIMER_INTERVAL 100 // ms
auto static timeoutInterval = std::chrono::milliseconds(3000);
@@ -171,15 +174,15 @@ void NemoInterface::Impl::setTileData(const TileData &tileData) {
snake::areaToEnu(origin, tile->coordinateList(), tileENU.path());
this->tilesENU.polygons().push_back(std::move(tileENU));
} else {
- qWarning() << "NemoInterface::Impl::setTileData(): nullptr.";
+ qCDebug(NemoInterfaceLog) << "Impl::setTileData(): nullptr.";
break;
}
}
} else {
- qWarning() << "NemoInterface::Impl::setTileData(): Origin invalid.";
+ qCDebug(NemoInterfaceLog) << "Impl::setTileData(): Origin invalid.";
}
} else {
- qWarning() << "NemoInterface::Impl::setTileData(): tile empty.";
+ qCDebug(NemoInterfaceLog) << "Impl::setTileData(): tile empty.";
}
}
} else {
@@ -300,12 +303,17 @@ void NemoInterface::Impl::doTopicServiceSetup() {
std::make_unique(rapidjson::kObjectType));
auto &origin = this->ENUOrigin;
rapidjson::Value jOrigin(rapidjson::kObjectType);
- bool ret = geographic_msgs::geo_point::toJson(origin, jOrigin,
- pDoc->GetAllocator());
lk.unlock();
- Q_ASSERT(ret);
- (void)ret;
- pDoc->AddMember("origin", jOrigin, pDoc->GetAllocator());
+ if (geographic_msgs::geo_point::toJson(origin, jOrigin,
+ pDoc->GetAllocator())) {
+ lk.unlock();
+ pDoc->AddMember("origin", jOrigin, pDoc->GetAllocator());
+ } else {
+ lk.unlock();
+ qCWarning(NemoInterfaceLog)
+ << "/snake/get_origin service: could not create json document.";
+ }
+
return pDoc;
});
@@ -318,11 +326,17 @@ void NemoInterface::Impl::doTopicServiceSetup() {
JsonDocUPtr pDoc(
std::make_unique(rapidjson::kObjectType));
rapidjson::Value jSnakeTiles(rapidjson::kObjectType);
- bool ret = jsk_recognition_msgs::polygon_array::toJson(
- this->tilesENU, jSnakeTiles, pDoc->GetAllocator());
- Q_ASSERT(ret);
- (void)ret;
- pDoc->AddMember("tiles", jSnakeTiles, pDoc->GetAllocator());
+
+ if (jsk_recognition_msgs::polygon_array::toJson(
+ this->tilesENU, jSnakeTiles, pDoc->GetAllocator())) {
+ lk.unlock();
+ pDoc->AddMember("tiles", jSnakeTiles, pDoc->GetAllocator());
+ } else {
+ lk.unlock();
+ qCWarning(NemoInterfaceLog)
+ << "/snake/get_tiles service: could not create json document.";
+ }
+
return pDoc;
});
}
@@ -379,22 +393,26 @@ void NemoInterface::Impl::publishTilesENU() {
using namespace ros_bridge::messages;
JsonDocUPtr jSnakeTiles(
std::make_unique(rapidjson::kObjectType));
- bool ret = jsk_recognition_msgs::polygon_array::toJson(
- this->tilesENU, *jSnakeTiles, jSnakeTiles->GetAllocator());
- Q_ASSERT(ret);
- (void)ret;
- this->pRosBridge->publish(std::move(jSnakeTiles), "/snake/tiles");
+ if (jsk_recognition_msgs::polygon_array::toJson(
+ this->tilesENU, *jSnakeTiles, jSnakeTiles->GetAllocator())) {
+ this->pRosBridge->publish(std::move(jSnakeTiles), "/snake/tiles");
+ } else {
+ qCWarning(NemoInterfaceLog)
+ << "Impl::publishTilesENU: could not create json document.";
+ }
}
void NemoInterface::Impl::publishENUOrigin() {
using namespace ros_bridge::messages;
JsonDocUPtr jOrigin(
std::make_unique(rapidjson::kObjectType));
- bool ret = geographic_msgs::geo_point::toJson(this->ENUOrigin, *jOrigin,
- jOrigin->GetAllocator());
- Q_ASSERT(ret);
- (void)ret;
- this->pRosBridge->publish(std::move(jOrigin), "/snake/origin");
+ if (geographic_msgs::geo_point::toJson(this->ENUOrigin, *jOrigin,
+ jOrigin->GetAllocator())) {
+ this->pRosBridge->publish(std::move(jOrigin), "/snake/origin");
+ } else {
+ qCWarning(NemoInterfaceLog)
+ << "Impl::publishENUOrigin: could not create json document.";
+ }
}
bool NemoInterface::Impl::setStatus(NemoInterface::STATUS s) {
@@ -421,7 +439,7 @@ void NemoInterface::stop() { this->pImpl->stop(); }
void NemoInterface::publishTileData() { this->pImpl->publishTileData(); }
void NemoInterface::requestProgress() {
- qWarning() << "NemoInterface::requestProgress(): dummy.";
+ qCWarning(NemoInterfaceLog) << "requestProgress(): dummy.";
}
void NemoInterface::setTileData(const TileData &tileData) {
diff --git a/src/Wima/Snake/SnakeTile.cpp b/src/Wima/Snake/SnakeTile.cpp
index ba2ffcbaf8b6dc568dd76a1e607072bf21a3ee99..397a2e917bcbd6281144aabb62ae42f4964c20f8 100644
--- a/src/Wima/Snake/SnakeTile.cpp
+++ b/src/Wima/Snake/SnakeTile.cpp
@@ -18,8 +18,6 @@ QString SnakeTile::type() const { return "Tile"; }
SnakeTile *SnakeTile::Clone() const { return new SnakeTile(*this); }
SnakeTile &SnakeTile::operator=(const SnakeTile &other) {
- this->assign(other);
+ this->WimaAreaData::operator=(other);
return *this;
}
-
-void SnakeTile::assign(const SnakeTile &other) { WimaAreaData::assign(other); }
diff --git a/src/WimaView/CircularGeneratorEditor.qml b/src/WimaView/CircularGeneratorEditor.qml
index b0c8eb6ecdecd383346b50aeb7fc2f3f55f30e61..c70751f87fed7c85a8aded01e4bc25e7181ca8e3 100644
--- a/src/WimaView/CircularGeneratorEditor.qml
+++ b/src/WimaView/CircularGeneratorEditor.qml
@@ -8,8 +8,7 @@ import QGroundControl.ScreenTools 1.0
GridLayout {
- // Item must be loaded, expects the following properties:
-// property var generator
+ property var generator // CircularGenerator
property real _margin: ScreenTools.defaultFontPixelWidth / 2
diff --git a/src/WimaView/CircularGeneratorMapVisual.qml b/src/WimaView/CircularGeneratorMapVisual.qml
index 1e9ee419dc8a8fa6146e9b726ad53410558eb75d..6a7fea20642669f18bb3d9536095bff358b5bce2 100644
--- a/src/WimaView/CircularGeneratorMapVisual.qml
+++ b/src/WimaView/CircularGeneratorMapVisual.qml
@@ -1,32 +1,22 @@
-import QtQuick 2.0
+import QtQuick 2.0
+import Wima 1.0
+import QGroundControl 1.0
Item {
id: _root
+ visible: true
+
+ // Expects the following properties:
property var map ///< Map control to place item in
property var qgcView ///< QGCView to use for popping dialogs
property var generator
property bool checked: false
- property var _referenceComponent
+ property var _referenceComponent: undefined
signal clicked()
- function _addRefPoint(){
- if (!_referenceComponent){
- _referenceComponent = refPointComponent.createObject(_root)
- map.addMapItem(_referenceComponent)
- }
- }
-
- function _destroyRefPoint(){
- if (_referenceComponent){
- map.removeMapItem(_referenceComponent)
- _referenceComponent.destroy()
- _referenceComponent = undefined
- }
- }
-
onVisibleChanged: {
if (visible){
_addRefPoint()
@@ -41,28 +31,56 @@ Item {
}
}
- Component.onDestroyed: {
+ Component.onDestruction: {
_destroyRefPoint()
}
+ function _addRefPoint(){
+ if (!_referenceComponent){
+ _referenceComponent = refPointComponent.createObject(_root)
+ map.addMapItem(_referenceComponent)
+ }
+ }
+
+ function _destroyRefPoint(){
+ if (_referenceComponent){
+ map.removeMapItem(_referenceComponent)
+ _referenceComponent.destroy()
+ _referenceComponent = undefined
+ }
+ }
+
// Ref. point (Base Station)
Component {
id: refPointComponent
DragCoordinate {
+ id: dragCoordinate
+
+ property var ref: _root.generator.reference
+
map: _root.map
qgcView: _root.qgcView
z: QGroundControl.zOrderMapItems
checked: _root.checked
- coordinate: _root.generator.reference
+ coordinate: ref
+ onDragReleased: {
+ syncAndBind()
+ }
+ Component.onCompleted: {
+ syncAndBind()
+ }
onClicked: {
_root.clicked()
}
- onDragReleased: {
- _root.generator.reference = coordinate
- coordinate = Qt.binding(function (){return _root.generator.reference})
+ function syncAndBind(){
+ if (coordinate.latitude !== ref.latitude ||
+ coordinate.longitude !== ref.longitude){
+ _root.generator.reference = coordinate
+ }
+ coordinate = Qt.binding(function(){return _root.generator.reference})
}
}
}
diff --git a/src/WimaView/CircularSurveyItemEditor.qml b/src/WimaView/CircularSurveyItemEditor.qml
index 932131f2f1e635539b0f6240786cffe919e92060..fc0cb381565e5aa2c32db8d4b5fc385b6d627fdc 100644
--- a/src/WimaView/CircularSurveyItemEditor.qml
+++ b/src/WimaView/CircularSurveyItemEditor.qml
@@ -25,31 +25,24 @@ Rectangle {
//property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor
- property real _margin: ScreenTools.defaultFontPixelWidth / 2
- property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
- property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
- property real _cameraMinTriggerInterval: missionItem.cameraCalc.minTriggerInterval.rawValue
+ property real _margin: ScreenTools.defaultFontPixelWidth / 2
- property var _generator: missionItem.generator
+ property var _generator: missionItem.generator
+ property var _generatorEditor: undefined
- function polygonCaptureStarted() {
- missionItem.clearPolygon()
- }
+ QGCPalette { id: qgcPal; colorGroupEnabled: true }
- function polygonCaptureFinished(coordinates) {
- for (var i=0; i