Commit 9d2ac99e authored by Valentin Platzgummer's avatar Valentin Platzgummer

generators working, wima planer still issues

parent 67cbe3f7
...@@ -195,9 +195,9 @@ ...@@ -195,9 +195,9 @@
<file alias="QGroundControl/Controls/ViewWidget.qml">src/ViewWidgets/ViewWidget.qml</file> <file alias="QGroundControl/Controls/ViewWidget.qml">src/ViewWidgets/ViewWidget.qml</file>
<file alias="Wima/WimaAreaNoVisual.qml">src/Wima/Snake/WimaAreaNoVisual.qml</file> <file alias="Wima/WimaAreaNoVisual.qml">src/Wima/Snake/WimaAreaNoVisual.qml</file>
<file alias="CircularGeneratorEditor.qml">src/WimaView/CircularGeneratorEditor.qml</file> <file alias="CircularGeneratorEditor.qml">src/WimaView/CircularGeneratorEditor.qml</file>
<file alias="Wima/CircularGeneratorMapVisual.qml">src/WimaView/CircularGeneratorMapVisual.qml</file> <file alias="QGroundControl/Controls/CircularGeneratorMapVisual.qml">src/WimaView/CircularGeneratorMapVisual.qml</file>
<file alias="CircularSurveyItemEditor.qml">src/WimaView/CircularSurveyItemEditor.qml</file> <file alias="CircularSurveyItemEditor.qml">src/WimaView/CircularSurveyItemEditor.qml</file>
<file alias="Wima/CircularSurveyMapVisual.qml">src/WimaView/CircularSurveyMapVisual.qml</file> <file alias="QGroundControl/Controls/CircularSurveyMapVisual.qml">src/WimaView/CircularSurveyMapVisual.qml</file>
<file alias="Wima/CoordinateIndicator.qml">src/WimaView/CoordinateIndicator.qml</file> <file alias="Wima/CoordinateIndicator.qml">src/WimaView/CoordinateIndicator.qml</file>
<file alias="Wima/CoordinateIndicatorDrag.qml">src/WimaView/CoordinateIndicatorDrag.qml</file> <file alias="Wima/CoordinateIndicatorDrag.qml">src/WimaView/CoordinateIndicatorDrag.qml</file>
<file alias="Wima/DragCoordinate.qml">src/WimaView/DragCoordinate.qml</file> <file alias="Wima/DragCoordinate.qml">src/WimaView/DragCoordinate.qml</file>
......
...@@ -30,5 +30,9 @@ MapItemView { ...@@ -30,5 +30,9 @@ MapItemView {
object.coordinate1, object.coordinate1,
object.coordinate2, object.coordinate2,
] : [] ] : []
// onParentChanged: {
// console.log("MapItemView, path:" + path)
// }
} }
} }
...@@ -15,7 +15,7 @@ import QtPositioning 5.3 ...@@ -15,7 +15,7 @@ import QtPositioning 5.3
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import Wima 1.0
/// Mission item map visual /// Mission item map visual
Item { Item {
......
...@@ -278,7 +278,7 @@ void CircularSurvey::_updateWorker() { ...@@ -278,7 +278,7 @@ void CircularSurvey::_updateWorker() {
auto origin = this->_pAreaData->origin(); auto origin = this->_pAreaData->origin();
origin.setAltitude(0); origin.setAltitude(0);
if (!origin.isValid()) { if (!origin.isValid()) {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_updateWorker(): origin invalid." << origin; << "_updateWorker(): origin invalid." << origin;
return; return;
} }
...@@ -286,7 +286,7 @@ void CircularSurvey::_updateWorker() { ...@@ -286,7 +286,7 @@ void CircularSurvey::_updateWorker() {
// Convert safe area. // Convert safe area.
auto geoSafeArea = this->_pAreaData->joinedArea().coordinateList(); auto geoSafeArea = this->_pAreaData->joinedArea().coordinateList();
if (!(geoSafeArea.size() >= 3)) { if (!(geoSafeArea.size() >= 3)) {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_updateWorker(): safe area invalid." << geoSafeArea; << "_updateWorker(): safe area invalid." << geoSafeArea;
return; return;
} }
...@@ -294,7 +294,7 @@ void CircularSurvey::_updateWorker() { ...@@ -294,7 +294,7 @@ void CircularSurvey::_updateWorker() {
if (v.isValid()) { if (v.isValid()) {
v.setAltitude(0); v.setAltitude(0);
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_updateWorker(): safe area contains invalid coordinate." << "_updateWorker(): safe area contains invalid coordinate."
<< geoSafeArea; << geoSafeArea;
return; return;
...@@ -314,17 +314,17 @@ void CircularSurvey::_updateWorker() { ...@@ -314,17 +314,17 @@ void CircularSurvey::_updateWorker() {
// Start/Restart routing worker. // Start/Restart routing worker.
this->_pWorker->route(par, g); this->_pWorker->route(par, g);
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_updateWorker(): generator creation failed."; << "_updateWorker(): generator creation failed.";
} }
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_updateWorker(): pGenerator == nullptr, number of registered " << "_updateWorker(): pGenerator == nullptr, number of registered "
"generators: " "generators: "
<< this->_generatorList.size(); << this->_generatorList.size();
} }
} else { } else {
qCWarning(CircularSurveyLog) << "_updateWorker(): plan data invalid."; qCDebug(CircularSurveyLog) << "_updateWorker(): plan data invalid.";
} }
} }
...@@ -343,7 +343,7 @@ void CircularSurvey::_changeVariantWorker() { ...@@ -343,7 +343,7 @@ void CircularSurvey::_changeVariantWorker() {
// Swap route. // Swap route.
if (variant != old_variant) { if (variant != old_variant) {
// Swap in new variant, if condition. // Swap in new variant.
if (variant < std::size_t(this->_variantVector.size())) { if (variant < std::size_t(this->_variantVector.size())) {
if (old_variant != std::numeric_limits<std::size_t>::max()) { if (old_variant != std::numeric_limits<std::size_t>::max()) {
// this->_transects containes a route, swap it back to // this->_transects containes a route, swap it back to
...@@ -355,9 +355,9 @@ void CircularSurvey::_changeVariantWorker() { ...@@ -355,9 +355,9 @@ void CircularSurvey::_changeVariantWorker() {
this->_transects.swap(newVariantCoordinates); this->_transects.swap(newVariantCoordinates);
} else { // error } else { // error
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "Variant out of bounds (variant =" << variant << ")."; << "Variant out of bounds (variant =" << variant << ").";
qCWarning(CircularSurveyLog) << "Resetting variant to zero."; qCDebug(CircularSurveyLog) << "Resetting variant to zero.";
disconnect(&this->_variant, &Fact::rawValueChanged, this, disconnect(&this->_variant, &Fact::rawValueChanged, this,
&CircularSurvey::_changeVariant); &CircularSurvey::_changeVariant);
...@@ -379,33 +379,6 @@ void CircularSurvey::_reverseWorker() { ...@@ -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) { void CircularSurvey::applyNewAltitude(double newAltitude) {
_cameraCalc.valueSetIsDistance()->setRawValue(true); _cameraCalc.valueSetIsDistance()->setRawValue(true);
_cameraCalc.distanceToSurface()->setRawValue(newAltitude); _cameraCalc.distanceToSurface()->setRawValue(newAltitude);
...@@ -432,18 +405,18 @@ double CircularSurvey::additionalTimeDelay() const { return 0; } ...@@ -432,18 +405,18 @@ double CircularSurvey::additionalTimeDelay() const { return 0; }
bool CircularSurvey::registerGenerator( bool CircularSurvey::registerGenerator(
const QString &name, std::shared_ptr<routing::GeneratorBase> g) { const QString &name, std::shared_ptr<routing::GeneratorBase> g) {
if (name.isEmpty()) { if (name.isEmpty()) {
qCWarning(CircularSurveyLog) << "registerGenerator(): empty name string."; qCDebug(CircularSurveyLog) << "registerGenerator(): empty name string.";
return false; return false;
} }
if (!g) { if (!g) {
qCWarning(CircularSurveyLog) << "registerGenerator(): empty generator."; qCDebug(CircularSurveyLog) << "registerGenerator(): empty generator.";
return false; return false;
} }
if (this->_generatorNameList.contains(name)) { if (this->_generatorNameList.contains(name)) {
qCWarning(CircularSurveyLog) << "registerGenerator(): generator " qCDebug(CircularSurveyLog) << "registerGenerator(): generator "
"already registered."; "already registered.";
return false; return false;
} else { } else {
this->_generatorNameList.push_back(name); this->_generatorNameList.push_back(name);
...@@ -467,7 +440,7 @@ bool CircularSurvey::unregisterGenerator(const QString &name) { ...@@ -467,7 +440,7 @@ bool CircularSurvey::unregisterGenerator(const QString &name) {
_switchToGenerator(this->_generatorList.at(index - 1)); _switchToGenerator(this->_generatorList.at(index - 1));
} else { } else {
_switchToGenerator(nullptr); _switchToGenerator(nullptr);
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "unregisterGenerator(): last generator unregistered."; << "unregisterGenerator(): last generator unregistered.";
} }
} }
...@@ -478,7 +451,7 @@ bool CircularSurvey::unregisterGenerator(const QString &name) { ...@@ -478,7 +451,7 @@ bool CircularSurvey::unregisterGenerator(const QString &name) {
emit generatorNameListChanged(); emit generatorNameListChanged();
return true; return true;
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "unregisterGenerator(): generator " << name << " not registered."; << "unregisterGenerator(): generator " << name << " not registered.";
return false; return false;
} }
...@@ -488,10 +461,10 @@ bool CircularSurvey::unregisterGenerator(int index) { ...@@ -488,10 +461,10 @@ bool CircularSurvey::unregisterGenerator(int index) {
if (index > 0 && index < this->_generatorNameList.size()) { if (index > 0 && index < this->_generatorNameList.size()) {
return unregisterGenerator(this->_generatorNameList.at(index)); return unregisterGenerator(this->_generatorNameList.at(index));
} else { } else {
qCWarning(CircularSurveyLog) << "unregisterGenerator(): index (" << index qCDebug(CircularSurveyLog) << "unregisterGenerator(): index (" << index
<< ") out" << ") out"
"of bounds ( " "of bounds ( "
<< this->_generatorList.size() << " )."; << this->_generatorList.size() << " ).";
return false; return false;
} }
} }
...@@ -502,7 +475,7 @@ bool CircularSurvey::switchToGenerator(const QString &name) { ...@@ -502,7 +475,7 @@ bool CircularSurvey::switchToGenerator(const QString &name) {
_switchToGenerator(this->_generatorList.at(index)); _switchToGenerator(this->_generatorList.at(index));
return true; return true;
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "switchToGenerator(): generator " << name << " not registered."; << "switchToGenerator(): generator " << name << " not registered.";
return false; return false;
} }
...@@ -513,10 +486,10 @@ bool CircularSurvey::switchToGenerator(int index) { ...@@ -513,10 +486,10 @@ bool CircularSurvey::switchToGenerator(int index) {
_switchToGenerator(this->_generatorList.at(index)); _switchToGenerator(this->_generatorList.at(index));
return true; return true;
} else { } else {
qCWarning(CircularSurveyLog) << "unregisterGenerator(): index (" << index qCDebug(CircularSurveyLog) << "unregisterGenerator(): index (" << index
<< ") out" << ") out"
"of bounds ( " "of bounds ( "
<< this->_generatorNameList.size() << " )."; << this->_generatorNameList.size() << " ).";
return false; return false;
} }
} }
...@@ -537,30 +510,29 @@ void CircularSurvey::_rebuildTransectsPhase1(void) { ...@@ -537,30 +510,29 @@ void CircularSurvey::_rebuildTransectsPhase1(void) {
auto start = std::chrono::high_resolution_clock::now(); auto start = std::chrono::high_resolution_clock::now();
switch (this->_state) { switch (this->_state) {
case STATE::STORE: case STATE::SKIPP:
qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: store."; qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: skipp.";
this->_storeWorker();
break; break;
case STATE::VARIANT_CHANGE: case STATE::VARIANT_CHANGE:
qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: variant change."; qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: variant change.";
this->_changeVariantWorker(); this->_changeVariantWorker();
break; break;
case STATE::RUN_CHANGE: case STATE::RUN_CHANGE:
qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: run change."; qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: run change.";
this->_changeVariantWorker(); this->_changeVariantWorker();
break; break;
case STATE::REVERSE: case STATE::REVERSE:
qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: reverse."; qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: reverse.";
this->_reverseWorker(); this->_reverseWorker();
break; break;
case STATE::IDLE: case STATE::IDLE:
qCWarning(CircularSurveyLog) << "rebuildTransectsPhase1: update."; qCDebug(CircularSurveyLog) << "rebuildTransectsPhase1: update.";
this->_updateWorker(); this->_updateWorker();
break; break;
} }
this->_state = STATE::IDLE; this->_state = STATE::IDLE;
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "rebuildTransectsPhase1(): " << "rebuildTransectsPhase1(): "
<< std::chrono::duration_cast<std::chrono::milliseconds>( << std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::high_resolution_clock::now() - start) std::chrono::high_resolution_clock::now() - start)
...@@ -585,7 +557,8 @@ void CircularSurvey::_recalcCameraShots() { _cameraShots = 0; } ...@@ -585,7 +557,8 @@ void CircularSurvey::_recalcCameraShots() { _cameraShots = 0; }
void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) { void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
// Store solutions. // Store solutions.
const auto &ori = this->_pAreaData->origin(); auto ori = this->_pAreaData->origin();
ori.setAltitude(0);
const auto &transectsENU = pRoute->transects; const auto &transectsENU = pRoute->transects;
QVector<Variant> variantVector; QVector<Variant> variantVector;
const auto nSolutions = pRoute->solutionVector.size(); const auto nSolutions = pRoute->solutionVector.size();
...@@ -639,19 +612,19 @@ void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) { ...@@ -639,19 +612,19 @@ void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
} }
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_setTransects(): lastTransect.size() == 0"; << "_setTransects(): lastTransect.size() == 0";
} }
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_setTransects(): firstTransect.size() == 0"; << "_setTransects(): firstTransect.size() == 0";
} }
} else { } else {
qCWarning(CircularSurveyLog) qCDebug(CircularSurveyLog)
<< "_setTransects(): transectsInfo.size() <= 1"; << "_setTransects(): transectsInfo.size() <= 1";
} }
} else { } else {
qCWarning(CircularSurveyLog) << "_setTransects(): solution.size() == 0"; qCDebug(CircularSurveyLog) << "_setTransects(): solution.size() == 0";
} }
if (var.size() > 0 && var.front().size() > 0) { if (var.size() > 0 && var.front().size() > 0) {
...@@ -663,9 +636,38 @@ void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) { ...@@ -663,9 +636,38 @@ void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
if (variantVector.size() > 0) { if (variantVector.size() > 0) {
// Swap first route to _transects. // Swap first route to _transects.
this->_variantVector.swap(variantVector); 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(); this->_rebuildTransects();
} else { } else {
qCDebug(CircularSurveyLog)
<< "_setTransects(): failed, variantVector empty.";
this->_state = STATE::IDLE; this->_state = STATE::IDLE;
} }
} }
......
...@@ -104,7 +104,6 @@ private slots: ...@@ -104,7 +104,6 @@ private slots:
void _updateWorker(); void _updateWorker();
void _changeVariantWorker(); void _changeVariantWorker();
void _reverseWorker(); void _reverseWorker();
void _storeWorker();
private: private:
void _appendLoadedMissionItems(QList<MissionItem *> &items, void _appendLoadedMissionItems(QList<MissionItem *> &items,
...@@ -117,7 +116,7 @@ private: ...@@ -117,7 +116,7 @@ private:
// State. // State.
enum class STATE { enum class STATE {
IDLE, IDLE,
STORE, SKIPP,
REVERSE, REVERSE,
VARIANT_CHANGE, VARIANT_CHANGE,
RUN_CHANGE, RUN_CHANGE,
...@@ -137,11 +136,8 @@ private: ...@@ -137,11 +136,8 @@ private:
QStringList _generatorNameList; QStringList _generatorNameList;
PtrGenerator _pGenerator; PtrGenerator _pGenerator;
// Worker // Routing.
PtrWorker _pWorker;
PtrRoutingData _pRoutingData; // remove this, not necessary.
// Routing data.
using Variant = Transects; using Variant = Transects;
QVector<Variant> _variantVector; QVector<Variant> _variantVector;
PtrWorker _pWorker;
}; };
...@@ -2,7 +2,14 @@ ...@@ -2,7 +2,14 @@
WimaAreaData::WimaAreaData(QObject *parent) : QObject(parent) {} 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 { bool WimaAreaData::operator==(const WimaAreaData &data) const {
return this->_path == data._path && this->_center == data._center; return this->_path == data._path && this->_center == data._center;
...@@ -25,7 +32,7 @@ bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const { ...@@ -25,7 +32,7 @@ bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const {
using namespace PolygonCalculus; using namespace PolygonCalculus;
using namespace GeoUtilities; using namespace GeoUtilities;
if (_path.size() > 2) { if (this->coordinateList().size() > 2) {
QPolygonF polygon; QPolygonF polygon;
toCartesianList(this->coordinateList(), coordinate, polygon); toCartesianList(this->coordinateList(), coordinate, polygon);
return PlanimetryCalculus::contains(polygon, QPointF(0, 0)); return PlanimetryCalculus::contains(polygon, QPointF(0, 0));
...@@ -36,44 +43,60 @@ bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const { ...@@ -36,44 +43,60 @@ bool WimaAreaData::containsCoordinate(const QGeoCoordinate &coordinate) const {
void WimaAreaData::append(const QGeoCoordinate &c) { void WimaAreaData::append(const QGeoCoordinate &c) {
_list.append(c); _list.append(c);
_path.push_back(QVariant::fromValue(c)); _path.push_back(QVariant::fromValue(c));
emit pathChanged();
} }
void WimaAreaData::push_back(const QGeoCoordinate &c) { append(c); } void WimaAreaData::push_back(const QGeoCoordinate &c) { append(c); }
void WimaAreaData::clear() { void WimaAreaData::clear() {
_list.clear(); if (_list.size() > 0 || _path.size() > 0) {
_path.clear(); _list.clear();
_path.clear();
emit pathChanged();
}
} }
void WimaAreaData::setPath(const QVariantList &coordinateList) { void WimaAreaData::setPath(const QVariantList &coordinateList) {
_path = coordinateList; if (_path != coordinateList) {
_list.clear(); _setPathImpl(coordinateList);
for (auto variant : coordinateList) { emit pathChanged();
_list.push_back(variant.value<QGeoCoordinate>());
} }
} }
void WimaAreaData::setCenter(const QGeoCoordinate &center) { void WimaAreaData::setCenter(const QGeoCoordinate &center) {
if (_center != center) { if (_center != center) {
_center = center; _center = center;
emit centerChanged(); emit centerChanged();
} }
} }
/*! WimaAreaData &WimaAreaData::operator=(const WimaAreaData &otherData) {
* \fn void WimaAreaData::assign(const WimaAreaData &other) setPath(otherData._list);
* setCenter(otherData._center);
* Assigns \a other to the invoking object return *this;
*/
void WimaAreaData::assign(const WimaAreaData &other) {
setPath(other.path());
setCenter(other.center());
} }
void WimaAreaData::assign(const WimaArea &other) { WimaAreaData &WimaAreaData::operator=(const WimaArea &otherData) {
setPath(other.path()); setPath(otherData.path());
setCenter(other.center()); setCenter(otherData.center());
return *this;
}
void WimaAreaData::_setPathImpl(const QList<QGeoCoordinate> &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<QGeoCoordinate>());
}
} }
/*! /*!
...@@ -83,24 +106,26 @@ void WimaAreaData::assign(const WimaArea &other) { ...@@ -83,24 +106,26 @@ void WimaAreaData::assign(const WimaArea &other) {
* coordinateList. Emits the \c pathChanged() signal. * coordinateList. Emits the \c pathChanged() signal.
*/ */
void WimaAreaData::setPath(const QList<QGeoCoordinate> &coordinateList) { void WimaAreaData::setPath(const QList<QGeoCoordinate> &coordinateList) {
_list = coordinateList; if (_list != coordinateList) {
_setPathImpl(coordinateList);
_path.clear(); emit pathChanged();
// copy all coordinates to _path
for (int i = 0; i < coordinateList.size(); i++) {
_path.append(QVariant::fromValue(coordinateList.value(i)));
} }
emit pathChanged(_path);
} }
bool operator==(const WimaAreaData &m1, const WimaArea &m2) { bool operator==(const WimaAreaData &m1, const WimaArea &m2) {
return m1.path() == m2.path() && m1.center() == m2.center(); return m1.path() == m2.path() && m1.center() == m2.center();
} }
bool operator!=(const WimaAreaData &m1, const WimaArea &m2) { bool operator!=(const WimaAreaData &m1, const WimaArea &m2) {
return !operator==(m1, 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 * \class WimaArea::WimaAreaData
* \brief Class to store and exchange data of a \c WimaArea Object. * \brief Class to store and exchange data of a \c WimaArea Object.
......
#pragma once #pragma once
#include <QObject> #include <QObject>
...@@ -11,16 +11,12 @@ class WimaAreaData ...@@ -11,16 +11,12 @@ class WimaAreaData
{ {
Q_OBJECT Q_OBJECT
public: public:
WimaAreaData(QObject *parent = nullptr);
Q_PROPERTY(const QVariantList path READ path NOTIFY pathChanged) Q_PROPERTY(const QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(QString type READ type CONSTANT) Q_PROPERTY(QString type READ type CONSTANT)
Q_PROPERTY(QString mapVisualQML READ mapVisualQML 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;
bool operator!=(const WimaAreaData &data) const; bool operator!=(const WimaAreaData &data) const;
...@@ -37,8 +33,8 @@ public: ...@@ -37,8 +33,8 @@ public:
void clear(); void clear();
signals: signals:
void pathChanged(const QVariantList &coordinateList); void pathChanged();
void centerChanged(void); void centerChanged();
public slots: public slots:
void setPath(const QList<QGeoCoordinate> &coordinateList); void setPath(const QList<QGeoCoordinate> &coordinateList);
...@@ -46,18 +42,21 @@ public slots: ...@@ -46,18 +42,21 @@ public slots:
void setCenter(const QGeoCoordinate &center); void setCenter(const QGeoCoordinate &center);
protected: protected:
void assign(const WimaAreaData &other); WimaAreaData(const WimaAreaData &otherData, QObject *parent);
void assign(const WimaArea &other); WimaAreaData(const WimaArea &otherData, QObject *parent);
WimaAreaData &operator=(const WimaAreaData &otherData);
WimaAreaData &operator=(const WimaArea &otherData);
private: private:
// Member Functions void _setPathImpl(const QList<QGeoCoordinate> &coordinateList);
void _setPathImpl(const QVariantList &coordinateList);
// Member Variables // Member Variables
// see WimaArea.h for explanation mutable QVariantList _path;
QVariantList _path; QList<QGeoCoordinate> _list;
mutable QList<QGeoCoordinate> _list;
QGeoCoordinate _center; QGeoCoordinate _center;
}; };
bool operator==(const WimaAreaData &m1, const WimaArea &m2); bool operator==(const WimaAreaData &m1, const WimaArea &m2);
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);
...@@ -6,14 +6,10 @@ WimaCorridorData::WimaCorridorData(QObject *parent) : WimaAreaData(parent) {} ...@@ -6,14 +6,10 @@ WimaCorridorData::WimaCorridorData(QObject *parent) : WimaAreaData(parent) {}
WimaCorridorData::WimaCorridorData(const WimaCorridorData &other, WimaCorridorData::WimaCorridorData(const WimaCorridorData &other,
QObject *parent) QObject *parent)
: WimaAreaData(parent) { : WimaAreaData(other, parent) {}
*this = other;
}
WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent) WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent)
: WimaAreaData(parent) { : WimaAreaData(other, parent) {}
*this = other;
}
/*! /*!
* \overload operator=() * \overload operator=()
...@@ -21,8 +17,7 @@ WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent) ...@@ -21,8 +17,7 @@ WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent)
* Assigns \a other to the invoking object. * Assigns \a other to the invoking object.
*/ */
WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other) { WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other) {
this->assign(other); WimaAreaData::operator=(other);
return *this; return *this;
} }
...@@ -32,8 +27,7 @@ WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other) { ...@@ -32,8 +27,7 @@ WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other) {
* Assigns \a other to the invoking object. * Assigns \a other to the invoking object.
*/ */
WimaCorridorData &WimaCorridorData::operator=(const WimaCorridor &other) { WimaCorridorData &WimaCorridorData::operator=(const WimaCorridor &other) {
this->assign(other); WimaAreaData::operator=(other);
return *this; return *this;
} }
...@@ -43,14 +37,6 @@ QString WimaCorridorData::mapVisualQML() const { ...@@ -43,14 +37,6 @@ QString WimaCorridorData::mapVisualQML() const {
QString WimaCorridorData::type() const { return this->typeString; } 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 * \class WimaAreaData::WimaCorridorData
* \brief Class to store and exchange data of a \c WimaCorridorData Object. * \brief Class to store and exchange data of a \c WimaCorridorData Object.
......
...@@ -23,14 +23,4 @@ public: ...@@ -23,14 +23,4 @@ public:
WimaCorridorData *Clone() const { return new WimaCorridorData(*this); } WimaCorridorData *Clone() const { return new WimaCorridorData(*this); }
static const char *typeString; static const char *typeString;
signals:
public slots:
protected:
void assign(const WimaCorridorData &corridorData);
void assign(const WimaCorridor &corridor);
private:
}; };
...@@ -7,15 +7,11 @@ WimaJoinedAreaData::WimaJoinedAreaData(QObject *parent) ...@@ -7,15 +7,11 @@ WimaJoinedAreaData::WimaJoinedAreaData(QObject *parent)
WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedAreaData &other, WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedAreaData &other,
QObject *parent) QObject *parent)
: WimaAreaData(parent) { : WimaAreaData(other, parent) {}
*this = other;
}
WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other, WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other,
QObject *parent) QObject *parent)
: WimaAreaData(parent) { : WimaAreaData(other, parent) {}
*this = other;
}
/*! /*!
* \overload operator=() * \overload operator=()
...@@ -24,8 +20,7 @@ WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other, ...@@ -24,8 +20,7 @@ WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other,
*/ */
WimaJoinedAreaData &WimaJoinedAreaData:: WimaJoinedAreaData &WimaJoinedAreaData::
operator=(const WimaJoinedAreaData &other) { operator=(const WimaJoinedAreaData &other) {
assign(other); WimaAreaData::operator=(other);
return *this; return *this;
} }
...@@ -35,7 +30,7 @@ operator=(const WimaJoinedAreaData &other) { ...@@ -35,7 +30,7 @@ operator=(const WimaJoinedAreaData &other) {
* Assigns \a other to the invoking object. * Assigns \a other to the invoking object.
*/ */
WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedArea &other) { WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedArea &other) {
assign(other); WimaAreaData::operator=(other);
return *this; return *this;
} }
...@@ -45,14 +40,6 @@ QString WimaJoinedAreaData::mapVisualQML() const { ...@@ -45,14 +40,6 @@ QString WimaJoinedAreaData::mapVisualQML() const {
QString WimaJoinedAreaData::type() const { return this->typeString; } 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 * \class WimaAreaData::WimaJoinedAreaData
* \brief Class to store and exchange data of a \c WimaJoinedAreaData Object. * \brief Class to store and exchange data of a \c WimaJoinedAreaData Object.
......
...@@ -24,10 +24,4 @@ public: ...@@ -24,10 +24,4 @@ public:
WimaJoinedAreaData *Clone() const { return new WimaJoinedAreaData(*this); } WimaJoinedAreaData *Clone() const { return new WimaJoinedAreaData(*this); }
static const char *typeString; static const char *typeString;
protected:
void assign(const WimaJoinedAreaData &other);
void assign(const WimaJoinedArea &other);
private:
}; };
...@@ -22,6 +22,7 @@ bool WimaMeasurementAreaData:: ...@@ -22,6 +22,7 @@ bool WimaMeasurementAreaData::
operator==(const WimaMeasurementAreaData &other) const { operator==(const WimaMeasurementAreaData &other) const {
return this->WimaAreaData::operator==(other) && return this->WimaAreaData::operator==(other) &&
this->_tileData == other.tileData() && this->_tileData == other.tileData() &&
this->_progress == other.progress() &&
this->center() == other.center(); this->center() == other.center();
} }
...@@ -33,6 +34,8 @@ operator!=(const WimaMeasurementAreaData &other) const { ...@@ -33,6 +34,8 @@ operator!=(const WimaMeasurementAreaData &other) const {
void WimaMeasurementAreaData::setTileData(const TileData &d) { void WimaMeasurementAreaData::setTileData(const TileData &d) {
if (this->_tileData != d) { if (this->_tileData != d) {
this->_tileData = d; this->_tileData = d;
this->_progress.fill(0, d.size());
emit progressChanged();
emit tileDataChanged(); emit tileDataChanged();
} }
} }
...@@ -51,7 +54,9 @@ void WimaMeasurementAreaData::setProgress(const QVector<int> &d) { ...@@ -51,7 +54,9 @@ void WimaMeasurementAreaData::setProgress(const QVector<int> &d) {
*/ */
WimaMeasurementAreaData &WimaMeasurementAreaData:: WimaMeasurementAreaData &WimaMeasurementAreaData::
operator=(const WimaMeasurementAreaData &other) { operator=(const WimaMeasurementAreaData &other) {
assign(other); WimaAreaData::operator=(other);
setTileData(other._tileData);
setProgress(other._progress);
return *this; return *this;
} }
...@@ -63,7 +68,14 @@ operator=(const WimaMeasurementAreaData &other) { ...@@ -63,7 +68,14 @@ operator=(const WimaMeasurementAreaData &other) {
*/ */
WimaMeasurementAreaData &WimaMeasurementAreaData:: WimaMeasurementAreaData &WimaMeasurementAreaData::
operator=(const WimaMeasurementArea &other) { 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; return *this;
} }
...@@ -102,23 +114,6 @@ const QVector<int> &WimaMeasurementAreaData::progress() const { ...@@ -102,23 +114,6 @@ const QVector<int> &WimaMeasurementAreaData::progress() const {
QVector<int> &WimaMeasurementAreaData::progress() { return this->_progress; } QVector<int> &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, bool operator==(const WimaMeasurementAreaData &m1,
const WimaMeasurementArea &m2) { const WimaMeasurementArea &m2) {
return operator==(*static_cast<const WimaAreaData *>(&m1), return operator==(*static_cast<const WimaAreaData *>(&m1),
......
...@@ -50,10 +50,6 @@ signals: ...@@ -50,10 +50,6 @@ signals:
void tileDataChanged(); void tileDataChanged();
void progressChanged(); void progressChanged();
protected:
void assign(const WimaMeasurementAreaData &other);
void assign(const WimaMeasurementArea &other);
private: private:
TileData _tileData; TileData _tileData;
QVector<int> _progress; QVector<int> _progress;
......
...@@ -7,26 +7,22 @@ WimaServiceAreaData::WimaServiceAreaData(QObject *parent) ...@@ -7,26 +7,22 @@ WimaServiceAreaData::WimaServiceAreaData(QObject *parent)
WimaServiceAreaData::WimaServiceAreaData(const WimaServiceAreaData &other, WimaServiceAreaData::WimaServiceAreaData(const WimaServiceAreaData &other,
QObject *parent) QObject *parent)
: WimaAreaData(parent) { : WimaAreaData(other, parent), _depot(other._depot) {}
*this = other;
}
WimaServiceAreaData::WimaServiceAreaData(const WimaServiceArea &other, WimaServiceAreaData::WimaServiceAreaData(const WimaServiceArea &other,
QObject *parent) QObject *parent)
: WimaAreaData(parent) { : WimaAreaData(other, parent), _depot(other.depot()) {}
*this = other;
}
WimaServiceAreaData &WimaServiceAreaData:: WimaServiceAreaData &WimaServiceAreaData::
operator=(const WimaServiceAreaData &otherData) { operator=(const WimaServiceAreaData &otherData) {
this->assign(otherData); WimaAreaData::operator=(otherData);
this->setDepot(otherData.depot()); this->setDepot(otherData.depot());
return *this; return *this;
} }
WimaServiceAreaData &WimaServiceAreaData:: WimaServiceAreaData &WimaServiceAreaData::
operator=(const WimaServiceArea &otherArea) { operator=(const WimaServiceArea &otherArea) {
this->assign(otherArea); WimaAreaData::operator=(otherArea);
this->setDepot(otherArea.depot()); this->setDepot(otherArea.depot());
return *this; return *this;
} }
...@@ -57,16 +53,6 @@ void WimaServiceAreaData::setDepot(const QGeoCoordinate &newCoordinate) { ...@@ -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 * \class WimaAreaData::WimaServiceAreaData
* \brief Class to store and exchange data of a \c WimaServiceArea Object. * \brief Class to store and exchange data of a \c WimaServiceArea Object.
......
...@@ -31,10 +31,6 @@ signals: ...@@ -31,10 +31,6 @@ signals:
public slots: public slots:
void setDepot(const QGeoCoordinate &newCoordinate); void setDepot(const QGeoCoordinate &newCoordinate);
protected:
void assign(const WimaServiceAreaData &other);
void assign(const WimaServiceArea &other);
private: private:
// see WimaServieArea.h for explanation // see WimaServieArea.h for explanation
QGeoCoordinate _depot; QGeoCoordinate _depot;
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#include <QDebug> #include <QDebug>
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
QGC_LOGGING_CATEGORY(RoutingWorkerLog, "RoutingWorkerLog") QGC_LOGGING_CATEGORY(RoutingThreadLog, "RoutingThreadLog")
RoutingThread::RoutingThread(QObject *parent) RoutingThread::RoutingThread(QObject *parent)
: QThread(parent), _calculating(false), _stop(false), _restart(false) { : QThread(parent), _calculating(false), _stop(false), _restart(false) {
...@@ -44,10 +44,10 @@ void RoutingThread::route(const RoutingParameter &par, ...@@ -44,10 +44,10 @@ void RoutingThread::route(const RoutingParameter &par,
} }
void RoutingThread::run() { void RoutingThread::run() {
qCWarning(RoutingWorkerLog) << "run(): thread start."; qCDebug(RoutingThreadLog) << "run(): thread start.";
while (!this->_stop) { while (!this->_stop) {
qCWarning(RoutingWorkerLog) << "run(): calculation " qCDebug(RoutingThreadLog) << "run(): calculation "
"started."; "started.";
// Copy input. // Copy input.
auto start = std::chrono::high_resolution_clock::now(); auto start = std::chrono::high_resolution_clock::now();
...@@ -67,8 +67,8 @@ void RoutingThread::run() { ...@@ -67,8 +67,8 @@ void RoutingThread::run() {
if (generator(transectsENU)) { if (generator(transectsENU)) {
// Check if generation was successful. // Check if generation was successful.
if (transectsENU.size() == 0) { if (transectsENU.size() == 0) {
qCWarning(RoutingWorkerLog) << "run(): " qCDebug(RoutingThreadLog) << "run(): "
"not able to generate transects."; "not able to generate transects.";
} else { } else {
// Prepare data for routing. // Prepare data for routing.
auto &solutionVector = pRouteData->solutionVector; auto &solutionVector = pRouteData->solutionVector;
...@@ -93,24 +93,24 @@ void RoutingThread::run() { ...@@ -93,24 +93,24 @@ void RoutingThread::run() {
// Check if routing was successful. // Check if routing was successful.
if ((!success || solutionVector.size() < 1) && !this->_restart) { if ((!success || solutionVector.size() < 1) && !this->_restart) {
qCWarning(RoutingWorkerLog) << "run(): " qCDebug(RoutingThreadLog) << "run(): "
"routing failed. " "routing failed. "
<< snakePar.errorString.c_str(); << snakePar.errorString.c_str();
} else if (this->_restart) { } else if (this->_restart) {
qCWarning(RoutingWorkerLog) << "run(): " qCDebug(RoutingThreadLog) << "run(): "
"restart requested."; "restart requested.";
} else { } else {
// Notify main thread. // Notify main thread.
emit result(pRouteData); emit result(pRouteData);
qCWarning(RoutingWorkerLog) << "run(): " qCDebug(RoutingThreadLog) << "run(): "
"concurrent update success."; "concurrent update success.";
} }
} }
} // end calculation } // end calculation
else { else {
qCWarning(RoutingWorkerLog) << "run(): generator() failed."; qCDebug(RoutingThreadLog) << "run(): generator() failed.";
} }
qCWarning(RoutingWorkerLog) qCDebug(RoutingThreadLog)
<< "run(): execution time: " << "run(): execution time: "
<< std::chrono::duration_cast<std::chrono::milliseconds>( << std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::high_resolution_clock::now() - start) std::chrono::high_resolution_clock::now() - start)
...@@ -125,5 +125,5 @@ void RoutingThread::run() { ...@@ -125,5 +125,5 @@ void RoutingThread::run() {
} }
this->_restart = false; this->_restart = false;
} // main loop } // main loop
qCWarning(RoutingWorkerLog) << "run(): thread end."; qCDebug(RoutingThreadLog) << "run(): thread end.";
} }
...@@ -64,14 +64,14 @@ bool CircularGenerator::get(Generator &generator) { ...@@ -64,14 +64,14 @@ bool CircularGenerator::get(Generator &generator) {
auto origin = this->_d->origin(); auto origin = this->_d->origin();
origin.setAltitude(0); origin.setAltitude(0);
if (!origin.isValid()) { if (!origin.isValid()) {
qCWarning(CircularGeneratorLog) << "get(): origin invalid." << origin; qCDebug(CircularGeneratorLog) << "get(): origin invalid." << origin;
return false; return false;
} }
auto ref = this->_reference; auto ref = this->_reference;
ref.setAltitude(0); ref.setAltitude(0);
if (!ref.isValid()) { if (!ref.isValid()) {
qCWarning(CircularGeneratorLog) << "get(): reference invalid." << ref; qCDebug(CircularGeneratorLog) << "get(): reference invalid." << ref;
return false; return false;
} }
snake::FPoint reference; snake::FPoint reference;
...@@ -82,9 +82,9 @@ bool CircularGenerator::get(Generator &generator) { ...@@ -82,9 +82,9 @@ bool CircularGenerator::get(Generator &generator) {
if (v.isValid()) { if (v.isValid()) {
v.setAltitude(0); v.setAltitude(0);
} else { } else {
qCWarning(CircularGeneratorLog) << "get(): measurement area invalid."; qCDebug(CircularGeneratorLog) << "get(): measurement area invalid.";
for (const auto &w : geoPolygon) { for (const auto &w : geoPolygon) {
qCWarning(CircularGeneratorLog) << w; qCDebug(CircularGeneratorLog) << w;
} }
return false; return false;
} }
...@@ -105,21 +105,21 @@ bool CircularGenerator::get(Generator &generator) { ...@@ -105,21 +105,21 @@ bool CircularGenerator::get(Generator &generator) {
snake::areaToEnu(origin, tile->coordinateList(), tileENU); snake::areaToEnu(origin, tile->coordinateList(), tileENU);
pTiles->push_back(std::move(tileENU)); pTiles->push_back(std::move(tileENU));
} else { } else {
qCWarning(CircularGeneratorLog) qCDebug(CircularGeneratorLog)
<< "get(): progress.size() != tiles->count()."; << "get(): progress.size() != tiles->count().";
return false; return false;
} }
} }
} }
} else { } else {
qCWarning(CircularGeneratorLog) qCDebug(CircularGeneratorLog)
<< "get(): progress.size() != tiles->count()."; << "get(): progress.size() != tiles->count().";
return false; return false;
} }
auto geoDepot = this->_d->serviceArea().depot(); auto geoDepot = this->_d->serviceArea().depot();
if (!geoDepot.isValid()) { if (!geoDepot.isValid()) {
qCWarning(CircularGeneratorLog) << "get(): depot invalid." << geoDepot; qCDebug(CircularGeneratorLog) << "get(): depot invalid." << geoDepot;
return false; return false;
} }
snake::FPoint depot; snake::FPoint depot;
...@@ -142,11 +142,11 @@ bool CircularGenerator::get(Generator &generator) { ...@@ -142,11 +142,11 @@ bool CircularGenerator::get(Generator &generator) {
}; };
return true; return true;
} else { } else {
qCWarning(CircularGeneratorLog) << "get(): data invalid."; qCDebug(CircularGeneratorLog) << "get(): data invalid.";
return false; return false;
} }
} else { } else {
qCWarning(CircularGeneratorLog) << "get(): data member not set."; qCDebug(CircularGeneratorLog) << "get(): data member not set.";
return false; return false;
} }
} }
...@@ -160,22 +160,29 @@ void CircularGenerator::setReference(const QGeoCoordinate &reference) { ...@@ -160,22 +160,29 @@ void CircularGenerator::setReference(const QGeoCoordinate &reference) {
} }
} }
void CircularGenerator::resetReferenceIfInvalid() {
if (!this->_reference.isValid()) {
resetReference();
}
}
void CircularGenerator::resetReference() { void CircularGenerator::resetReference() {
setReference(_d->measurementArea().center()); if (this->_d->measurementArea().center().isValid()) {
setReference(this->_d->measurementArea().center());
}
} }
void CircularGenerator::establishConnections() { void CircularGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) { if (this->_d && !this->_connectionsEstablished) {
connect(this->_d.get(), &WimaPlanData::measurementAreaChanged, this,
&GeneratorBase::generatorChanged);
connect(this->_d.get(), &WimaPlanData::originChanged, this, connect(this->_d.get(), &WimaPlanData::originChanged, this,
&GeneratorBase::generatorChanged); &GeneratorBase::generatorChanged);
connect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::progressChanged, this,
&GeneratorBase::generatorChanged);
connect(&this->_d->measurementArea(), connect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this, &WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged); &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, connect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged, this,
&GeneratorBase::generatorChanged); &GeneratorBase::generatorChanged);
connect(this->distance(), &Fact::rawValueChanged, this, connect(this->distance(), &Fact::rawValueChanged, this,
...@@ -192,8 +199,6 @@ void CircularGenerator::establishConnections() { ...@@ -192,8 +199,6 @@ void CircularGenerator::establishConnections() {
void CircularGenerator::deleteConnections() { void CircularGenerator::deleteConnections() {
if (this->_d && this->_connectionsEstablished) { if (this->_d && this->_connectionsEstablished) {
disconnect(this->_d.get(), &WimaPlanData::measurementAreaChanged, this,
&GeneratorBase::generatorChanged);
disconnect(this->_d.get(), &WimaPlanData::originChanged, this, disconnect(this->_d.get(), &WimaPlanData::originChanged, this,
&GeneratorBase::generatorChanged); &GeneratorBase::generatorChanged);
disconnect(&this->_d->measurementArea(), disconnect(&this->_d->measurementArea(),
...@@ -202,6 +207,12 @@ void CircularGenerator::deleteConnections() { ...@@ -202,6 +207,12 @@ void CircularGenerator::deleteConnections() {
disconnect(&this->_d->measurementArea(), disconnect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this, &WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged); &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, disconnect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged,
this, &GeneratorBase::generatorChanged); this, &GeneratorBase::generatorChanged);
disconnect(this->distance(), &Fact::rawValueChanged, this, disconnect(this->distance(), &Fact::rawValueChanged, this,
...@@ -236,12 +247,12 @@ bool circularTransects(const snake::FPoint &reference, ...@@ -236,12 +247,12 @@ bool circularTransects(const snake::FPoint &reference,
std::string error; std::string error;
// Check validity. // Check validity.
if (!bg::is_valid(polygon, error)) { if (!bg::is_valid(polygon, error)) {
qCWarning(CircularGeneratorLog) << "circularTransects(): " qCDebug(CircularGeneratorLog) << "circularTransects(): "
"invalid polygon."; "invalid polygon.";
qCWarning(CircularGeneratorLog) << error.c_str(); qCDebug(CircularGeneratorLog) << error.c_str();
std::stringstream ss; std::stringstream ss;
ss << bg::wkt(polygon); ss << bg::wkt(polygon);
qCWarning(CircularGeneratorLog) << ss.str().c_str(); qCDebug(CircularGeneratorLog) << ss.str().c_str();
} else { } else {
// Calculate polygon distances and angles. // Calculate polygon distances and angles.
std::vector<snake::Length> distances; std::vector<snake::Length> distances;
...@@ -249,7 +260,7 @@ bool circularTransects(const snake::FPoint &reference, ...@@ -249,7 +260,7 @@ bool circularTransects(const snake::FPoint &reference,
std::vector<snake::Angle> angles; std::vector<snake::Angle> angles;
angles.reserve(polygon.outer().size()); angles.reserve(polygon.outer().size());
//#ifdef DEBUG_CIRCULAR_SURVEY //#ifdef DEBUG_CIRCULAR_SURVEY
// qCWarning(CircularGeneratorLog) << "circularTransects():"; // qCDebug(CircularGeneratorLog) << "circularTransects():";
//#endif //#endif
for (const auto &p : polygon.outer()) { for (const auto &p : polygon.outer()) {
snake::Length distance = bg::distance(reference, p) * si::meter; snake::Length distance = bg::distance(reference, p) * si::meter;
...@@ -258,11 +269,11 @@ bool circularTransects(const snake::FPoint &reference, ...@@ -258,11 +269,11 @@ bool circularTransects(const snake::FPoint &reference,
alpha = alpha < 0 * si::radian ? alpha + 2 * M_PI * si::radian : alpha; alpha = alpha < 0 * si::radian ? alpha + 2 * M_PI * si::radian : alpha;
angles.push_back(alpha); angles.push_back(alpha);
//#ifdef DEBUG_CIRCULAR_SURVEY //#ifdef DEBUG_CIRCULAR_SURVEY
// qCWarning(CircularGeneratorLog) << "distances, angles, // qCDebug(CircularGeneratorLog) << "distances, angles,
// coordinates:"; qCWarning(CircularGeneratorLog) << // coordinates:"; qCDebug(CircularGeneratorLog) <<
// to_string(distance).c_str(); qCWarning(CircularGeneratorLog) // to_string(distance).c_str(); qCDebug(CircularGeneratorLog)
// << to_string(snake::Degree(alpha)).c_str(); // << to_string(snake::Degree(alpha)).c_str();
// qCWarning(CircularGeneratorLog) << "x = " << p.get<0>() << "y // qCDebug(CircularGeneratorLog) << "x = " << p.get<0>() << "y
// = " // = "
// << p.get<1>(); // << p.get<1>();
//#endif //#endif
...@@ -285,8 +296,8 @@ bool circularTransects(const snake::FPoint &reference, ...@@ -285,8 +296,8 @@ bool circularTransects(const snake::FPoint &reference,
const auto deltaRScaled = const auto deltaRScaled =
ClipperLib::cInt(std::round(deltaR.value() * CLIPPER_SCALE)); ClipperLib::cInt(std::round(deltaR.value() * CLIPPER_SCALE));
auto referenceScaled = ClipperLib::IntPoint{ auto referenceScaled = ClipperLib::IntPoint{
ClipperLib::cInt(std::round(reference.get<0>())), ClipperLib::cInt(std::round(reference.get<0>() * CLIPPER_SCALE)),
ClipperLib::cInt(std::round(reference.get<1>()))}; ClipperLib::cInt(std::round(reference.get<1>() * CLIPPER_SCALE))};
// Generate circle sectors. // Generate circle sectors.
auto rScaled = rMinScaled; auto rScaled = rMinScaled;
...@@ -295,20 +306,20 @@ bool circularTransects(const snake::FPoint &reference, ...@@ -295,20 +306,20 @@ bool circularTransects(const snake::FPoint &reference,
const auto nSectors = const auto nSectors =
long(std::round(((alpha2 - alpha1) / deltaAlpha).value())); long(std::round(((alpha2 - alpha1) / deltaAlpha).value()));
//#ifdef DEBUG_CIRCULAR_SURVEY //#ifdef DEBUG_CIRCULAR_SURVEY
// qCWarning(CircularGeneratorLog) << "circularTransects(): sector // qCDebug(CircularGeneratorLog) << "circularTransects(): sector
// parameres:"; qCWarning(CircularGeneratorLog) << "alpha1: " << // parameres:"; qCDebug(CircularGeneratorLog) << "alpha1: " <<
// to_string(snake::Degree(alpha1)).c_str(); // to_string(snake::Degree(alpha1)).c_str();
// qCWarning(CircularGeneratorLog) << "alpha2: // qCDebug(CircularGeneratorLog) << "alpha2:
// " // "
// << to_string(snake::Degree(alpha2)).c_str(); // << to_string(snake::Degree(alpha2)).c_str();
// qCWarning(CircularGeneratorLog) << "n: " // qCDebug(CircularGeneratorLog) << "n: "
// << to_string((alpha2 - alpha1) / deltaAlpha).c_str(); // << to_string((alpha2 - alpha1) / deltaAlpha).c_str();
// qCWarning(CircularGeneratorLog) // qCDebug(CircularGeneratorLog)
// << "nSectors: " << nSectors; qCWarning(CircularGeneratorLog) << // << "nSectors: " << nSectors; qCDebug(CircularGeneratorLog) <<
// "rMin: " << to_string(rMin).c_str(); // "rMin: " << to_string(rMin).c_str();
// qCWarning(CircularGeneratorLog) // qCDebug(CircularGeneratorLog)
// << "rMax: " << to_string(rMax).c_str(); // << "rMax: " << to_string(rMax).c_str();
// qCWarning(CircularGeneratorLog) << "nTran: " << nTran; // qCDebug(CircularGeneratorLog) << "nTran: " << nTran;
//#endif //#endif
using ClipperCircle = using ClipperCircle =
GenericCircle<ClipperLib::cInt, ClipperLib::IntPoint>; GenericCircle<ClipperLib::cInt, ClipperLib::IntPoint>;
...@@ -427,7 +438,7 @@ bool circularTransects(const snake::FPoint &reference, ...@@ -427,7 +438,7 @@ bool circularTransects(const snake::FPoint &reference,
} }
} }
qCWarning(CircularGeneratorLog) qCDebug(CircularGeneratorLog)
<< "circularTransects(): transect gen. time: " << "circularTransects(): transect gen. time: "
<< std::chrono::duration_cast<std::chrono::milliseconds>( << std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::high_resolution_clock::now() - s1) std::chrono::high_resolution_clock::now() - s1)
......
...@@ -30,7 +30,6 @@ public: ...@@ -30,7 +30,6 @@ public:
Fact *minLength(); Fact *minLength();
void setReference(const QGeoCoordinate &reference); void setReference(const QGeoCoordinate &reference);
Q_INVOKABLE void resetReference();
static const char *settingsGroup; static const char *settingsGroup;
static const char *distanceName; static const char *distanceName;
...@@ -43,6 +42,10 @@ public: ...@@ -43,6 +42,10 @@ public:
signals: signals:
void referenceChanged(); void referenceChanged();
public slots:
Q_INVOKABLE void resetReferenceIfInvalid();
Q_INVOKABLE void resetReference();
protected: protected:
virtual void establishConnections() override; virtual void establishConnections() override;
virtual void deleteConnections() override; virtual void deleteConnections() override;
......
...@@ -12,13 +12,9 @@ GeneratorBase::GeneratorBase(GeneratorBase::Data d, QObject *parent) ...@@ -12,13 +12,9 @@ GeneratorBase::GeneratorBase(GeneratorBase::Data d, QObject *parent)
GeneratorBase::~GeneratorBase() {} GeneratorBase::~GeneratorBase() {}
QString GeneratorBase::editorQml() { QString GeneratorBase::editorQml() { return QStringLiteral(""); }
return QStringLiteral("EmptyGeneratorEditor.qml");
}
QString GeneratorBase::mapVisualQml() { QString GeneratorBase::mapVisualQml() { return QStringLiteral(""); }
return QStringLiteral("EmptyGeneratorMapVisual.qml");
}
GeneratorBase::Data GeneratorBase::data() const { return _d; } GeneratorBase::Data GeneratorBase::data() const { return _d; }
......
...@@ -49,7 +49,7 @@ bool LinearGenerator::get(Generator &generator) { ...@@ -49,7 +49,7 @@ bool LinearGenerator::get(Generator &generator) {
auto origin = this->_d->origin(); auto origin = this->_d->origin();
origin.setAltitude(0); origin.setAltitude(0);
if (!origin.isValid()) { if (!origin.isValid()) {
qCWarning(LinearGeneratorLog) << "get(): origin invalid."; qCDebug(LinearGeneratorLog) << "get(): origin invalid." << origin;
} }
auto geoPolygon = this->_d->measurementArea().coordinateList(); auto geoPolygon = this->_d->measurementArea().coordinateList();
...@@ -57,9 +57,9 @@ bool LinearGenerator::get(Generator &generator) { ...@@ -57,9 +57,9 @@ bool LinearGenerator::get(Generator &generator) {
if (v.isValid()) { if (v.isValid()) {
v.setAltitude(0); v.setAltitude(0);
} else { } else {
qCWarning(LinearGeneratorLog) << "get(): measurement area invalid."; qCDebug(LinearGeneratorLog) << "get(): measurement area invalid.";
for (const auto &w : geoPolygon) { for (const auto &w : geoPolygon) {
qCWarning(LinearGeneratorLog) << w; qCDebug(LinearGeneratorLog) << w;
} }
return false; return false;
} }
...@@ -80,21 +80,20 @@ bool LinearGenerator::get(Generator &generator) { ...@@ -80,21 +80,20 @@ bool LinearGenerator::get(Generator &generator) {
snake::areaToEnu(origin, tile->coordinateList(), tileENU); snake::areaToEnu(origin, tile->coordinateList(), tileENU);
pTiles->push_back(std::move(tileENU)); pTiles->push_back(std::move(tileENU));
} else { } else {
qCWarning(LinearGeneratorLog) qCDebug(LinearGeneratorLog) << "get(): tile == nullptr";
<< "get(): progress.size() != tiles->count().";
return false; return false;
} }
} }
} }
} else { } else {
qCWarning(LinearGeneratorLog) qCDebug(LinearGeneratorLog)
<< "get(): progress.size() != tiles->count()."; << "get(): progress.size() != tiles->count().";
return false; return false;
} }
auto geoDepot = this->_d->serviceArea().depot(); auto geoDepot = this->_d->serviceArea().depot();
if (!geoDepot.isValid()) { if (!geoDepot.isValid()) {
qCWarning(LinearGeneratorLog) << "get(): depot invalid." << geoDepot; qCDebug(LinearGeneratorLog) << "get(): depot invalid." << geoDepot;
return false; return false;
} }
snake::FPoint depot; snake::FPoint depot;
...@@ -116,11 +115,11 @@ bool LinearGenerator::get(Generator &generator) { ...@@ -116,11 +115,11 @@ bool LinearGenerator::get(Generator &generator) {
}; };
return true; return true;
} else { } else {
qCWarning(LinearGeneratorLog) << "get(): data invalid."; qCDebug(LinearGeneratorLog) << "get(): data invalid.";
return false; return false;
} }
} else { } else {
qCWarning(LinearGeneratorLog) << "get(): data member not set."; qCDebug(LinearGeneratorLog) << "get(): data member not set.";
return false; return false;
} }
} }
...@@ -133,8 +132,6 @@ Fact *LinearGenerator::minLength() { return &_minLength; } ...@@ -133,8 +132,6 @@ Fact *LinearGenerator::minLength() { return &_minLength; }
void LinearGenerator::establishConnections() { void LinearGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) { if (this->_d && !this->_connectionsEstablished) {
connect(this->_d.get(), &WimaPlanData::measurementAreaChanged, this,
&GeneratorBase::generatorChanged);
connect(this->_d.get(), &WimaPlanData::originChanged, this, connect(this->_d.get(), &WimaPlanData::originChanged, this,
&GeneratorBase::generatorChanged); &GeneratorBase::generatorChanged);
connect(&this->_d->measurementArea(), connect(&this->_d->measurementArea(),
...@@ -143,6 +140,8 @@ void LinearGenerator::establishConnections() { ...@@ -143,6 +140,8 @@ void LinearGenerator::establishConnections() {
connect(&this->_d->measurementArea(), connect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this, &WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged); &GeneratorBase::generatorChanged);
connect(&this->_d->measurementArea(), &WimaMeasurementAreaData::pathChanged,
this, &GeneratorBase::generatorChanged);
connect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged, this, connect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged, this,
&GeneratorBase::generatorChanged); &GeneratorBase::generatorChanged);
connect(this->distance(), &Fact::rawValueChanged, this, connect(this->distance(), &Fact::rawValueChanged, this,
...@@ -167,6 +166,9 @@ void LinearGenerator::deleteConnections() { ...@@ -167,6 +166,9 @@ void LinearGenerator::deleteConnections() {
disconnect(&this->_d->measurementArea(), disconnect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::tileDataChanged, this, &WimaMeasurementAreaData::tileDataChanged, this,
&GeneratorBase::generatorChanged); &GeneratorBase::generatorChanged);
disconnect(&this->_d->measurementArea(),
&WimaMeasurementAreaData::pathChanged, this,
&GeneratorBase::generatorChanged);
disconnect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged, disconnect(&this->_d->serviceArea(), &WimaServiceAreaData::depotChanged,
this, &GeneratorBase::generatorChanged); this, &GeneratorBase::generatorChanged);
disconnect(this->distance(), &Fact::rawValueChanged, this, disconnect(this->distance(), &Fact::rawValueChanged, this,
...@@ -195,9 +197,9 @@ bool linearTransects(const snake::FPolygon &polygon, ...@@ -195,9 +197,9 @@ bool linearTransects(const snake::FPolygon &polygon,
std::stringstream ss; std::stringstream ss;
ss << bg::wkt(polygon); ss << bg::wkt(polygon);
qCWarning(LinearGeneratorLog) << "linearTransects(): " qCDebug(LinearGeneratorLog) << "linearTransects(): "
"invalid polygon. " "invalid polygon. "
<< error.c_str() << ss.str().c_str(); << error.c_str() << ss.str().c_str();
} else { } else {
tr::rotate_transformer<bg::degree, double, 2, 2> rotate(angle.value() * tr::rotate_transformer<bg::degree, double, 2, 2> rotate(angle.value() *
180 / M_PI); 180 / M_PI);
...@@ -244,7 +246,7 @@ bool linearTransects(const snake::FPolygon &polygon, ...@@ -244,7 +246,7 @@ bool linearTransects(const snake::FPolygon &polygon,
std::stringstream ss; std::stringstream ss;
ss << "Not able to generate transects. Parameter: distance = " ss << "Not able to generate transects. Parameter: distance = "
<< distance << std::endl; << distance << std::endl;
qCWarning(LinearGeneratorLog) qCDebug(LinearGeneratorLog)
<< "linearTransects(): " << ss.str().c_str(); << "linearTransects(): " << ss.str().c_str();
return false; return false;
} }
...@@ -312,12 +314,12 @@ bool linearTransects(const snake::FPolygon &polygon, ...@@ -312,12 +314,12 @@ bool linearTransects(const snake::FPolygon &polygon,
std::stringstream ss; std::stringstream ss;
ss << "Not able to generatetransects. Parameter: minLength = " ss << "Not able to generatetransects. Parameter: minLength = "
<< minLength << std::endl; << minLength << std::endl;
qCWarning(LinearGeneratorLog) qCDebug(LinearGeneratorLog)
<< "linearTransects(): " << ss.str().c_str(); << "linearTransects(): " << ss.str().c_str();
return false; return false;
} }
qCWarning(LinearGeneratorLog) qCDebug(LinearGeneratorLog)
<< "linearTransects(): time: " << "linearTransects(): time: "
<< std::chrono::duration_cast<std::chrono::milliseconds>( << std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::high_resolution_clock::now() - s1) std::chrono::high_resolution_clock::now() - s1)
......
...@@ -2,6 +2,7 @@ ...@@ -2,6 +2,7 @@
#include "SnakeTilesLocal.h" #include "SnakeTilesLocal.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include "QGCToolbox.h" #include "QGCToolbox.h"
#include "SettingsFact.h" #include "SettingsFact.h"
#include "SettingsManager.h" #include "SettingsManager.h"
...@@ -26,6 +27,8 @@ ...@@ -26,6 +27,8 @@
#include "ros_bridge/rapidjson/include/rapidjson/ostreamwrapper.h" #include "ros_bridge/rapidjson/include/rapidjson/ostreamwrapper.h"
#include "ros_bridge/rapidjson/include/rapidjson/writer.h" #include "ros_bridge/rapidjson/include/rapidjson/writer.h"
QGC_LOGGING_CATEGORY(NemoInterfaceLog, "NemoInterfaceLog")
#define EVENT_TIMER_INTERVAL 100 // ms #define EVENT_TIMER_INTERVAL 100 // ms
auto static timeoutInterval = std::chrono::milliseconds(3000); auto static timeoutInterval = std::chrono::milliseconds(3000);
...@@ -171,15 +174,15 @@ void NemoInterface::Impl::setTileData(const TileData &tileData) { ...@@ -171,15 +174,15 @@ void NemoInterface::Impl::setTileData(const TileData &tileData) {
snake::areaToEnu(origin, tile->coordinateList(), tileENU.path()); snake::areaToEnu(origin, tile->coordinateList(), tileENU.path());
this->tilesENU.polygons().push_back(std::move(tileENU)); this->tilesENU.polygons().push_back(std::move(tileENU));
} else { } else {
qWarning() << "NemoInterface::Impl::setTileData(): nullptr."; qCDebug(NemoInterfaceLog) << "Impl::setTileData(): nullptr.";
break; break;
} }
} }
} else { } else {
qWarning() << "NemoInterface::Impl::setTileData(): Origin invalid."; qCDebug(NemoInterfaceLog) << "Impl::setTileData(): Origin invalid.";
} }
} else { } else {
qWarning() << "NemoInterface::Impl::setTileData(): tile empty."; qCDebug(NemoInterfaceLog) << "Impl::setTileData(): tile empty.";
} }
} }
} else { } else {
...@@ -300,12 +303,17 @@ void NemoInterface::Impl::doTopicServiceSetup() { ...@@ -300,12 +303,17 @@ void NemoInterface::Impl::doTopicServiceSetup() {
std::make_unique<rapidjson::Document>(rapidjson::kObjectType)); std::make_unique<rapidjson::Document>(rapidjson::kObjectType));
auto &origin = this->ENUOrigin; auto &origin = this->ENUOrigin;
rapidjson::Value jOrigin(rapidjson::kObjectType); rapidjson::Value jOrigin(rapidjson::kObjectType);
bool ret = geographic_msgs::geo_point::toJson(origin, jOrigin,
pDoc->GetAllocator());
lk.unlock(); lk.unlock();
Q_ASSERT(ret); if (geographic_msgs::geo_point::toJson(origin, jOrigin,
(void)ret; pDoc->GetAllocator())) {
pDoc->AddMember("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; return pDoc;
}); });
...@@ -318,11 +326,17 @@ void NemoInterface::Impl::doTopicServiceSetup() { ...@@ -318,11 +326,17 @@ void NemoInterface::Impl::doTopicServiceSetup() {
JsonDocUPtr pDoc( JsonDocUPtr pDoc(
std::make_unique<rapidjson::Document>(rapidjson::kObjectType)); std::make_unique<rapidjson::Document>(rapidjson::kObjectType));
rapidjson::Value jSnakeTiles(rapidjson::kObjectType); rapidjson::Value jSnakeTiles(rapidjson::kObjectType);
bool ret = jsk_recognition_msgs::polygon_array::toJson(
this->tilesENU, jSnakeTiles, pDoc->GetAllocator()); if (jsk_recognition_msgs::polygon_array::toJson(
Q_ASSERT(ret); this->tilesENU, jSnakeTiles, pDoc->GetAllocator())) {
(void)ret; lk.unlock();
pDoc->AddMember("tiles", jSnakeTiles, pDoc->GetAllocator()); pDoc->AddMember("tiles", jSnakeTiles, pDoc->GetAllocator());
} else {
lk.unlock();
qCWarning(NemoInterfaceLog)
<< "/snake/get_tiles service: could not create json document.";
}
return pDoc; return pDoc;
}); });
} }
...@@ -379,22 +393,26 @@ void NemoInterface::Impl::publishTilesENU() { ...@@ -379,22 +393,26 @@ void NemoInterface::Impl::publishTilesENU() {
using namespace ros_bridge::messages; using namespace ros_bridge::messages;
JsonDocUPtr jSnakeTiles( JsonDocUPtr jSnakeTiles(
std::make_unique<rapidjson::Document>(rapidjson::kObjectType)); std::make_unique<rapidjson::Document>(rapidjson::kObjectType));
bool ret = jsk_recognition_msgs::polygon_array::toJson( if (jsk_recognition_msgs::polygon_array::toJson(
this->tilesENU, *jSnakeTiles, jSnakeTiles->GetAllocator()); this->tilesENU, *jSnakeTiles, jSnakeTiles->GetAllocator())) {
Q_ASSERT(ret); this->pRosBridge->publish(std::move(jSnakeTiles), "/snake/tiles");
(void)ret; } else {
this->pRosBridge->publish(std::move(jSnakeTiles), "/snake/tiles"); qCWarning(NemoInterfaceLog)
<< "Impl::publishTilesENU: could not create json document.";
}
} }
void NemoInterface::Impl::publishENUOrigin() { void NemoInterface::Impl::publishENUOrigin() {
using namespace ros_bridge::messages; using namespace ros_bridge::messages;
JsonDocUPtr jOrigin( JsonDocUPtr jOrigin(
std::make_unique<rapidjson::Document>(rapidjson::kObjectType)); std::make_unique<rapidjson::Document>(rapidjson::kObjectType));
bool ret = geographic_msgs::geo_point::toJson(this->ENUOrigin, *jOrigin, if (geographic_msgs::geo_point::toJson(this->ENUOrigin, *jOrigin,
jOrigin->GetAllocator()); jOrigin->GetAllocator())) {
Q_ASSERT(ret); this->pRosBridge->publish(std::move(jOrigin), "/snake/origin");
(void)ret; } else {
this->pRosBridge->publish(std::move(jOrigin), "/snake/origin"); qCWarning(NemoInterfaceLog)
<< "Impl::publishENUOrigin: could not create json document.";
}
} }
bool NemoInterface::Impl::setStatus(NemoInterface::STATUS s) { bool NemoInterface::Impl::setStatus(NemoInterface::STATUS s) {
...@@ -421,7 +439,7 @@ void NemoInterface::stop() { this->pImpl->stop(); } ...@@ -421,7 +439,7 @@ void NemoInterface::stop() { this->pImpl->stop(); }
void NemoInterface::publishTileData() { this->pImpl->publishTileData(); } void NemoInterface::publishTileData() { this->pImpl->publishTileData(); }
void NemoInterface::requestProgress() { void NemoInterface::requestProgress() {
qWarning() << "NemoInterface::requestProgress(): dummy."; qCWarning(NemoInterfaceLog) << "requestProgress(): dummy.";
} }
void NemoInterface::setTileData(const TileData &tileData) { void NemoInterface::setTileData(const TileData &tileData) {
......
...@@ -18,8 +18,6 @@ QString SnakeTile::type() const { return "Tile"; } ...@@ -18,8 +18,6 @@ QString SnakeTile::type() const { return "Tile"; }
SnakeTile *SnakeTile::Clone() const { return new SnakeTile(*this); } SnakeTile *SnakeTile::Clone() const { return new SnakeTile(*this); }
SnakeTile &SnakeTile::operator=(const SnakeTile &other) { SnakeTile &SnakeTile::operator=(const SnakeTile &other) {
this->assign(other); this->WimaAreaData::operator=(other);
return *this; return *this;
} }
void SnakeTile::assign(const SnakeTile &other) { WimaAreaData::assign(other); }
...@@ -8,8 +8,7 @@ import QGroundControl.ScreenTools 1.0 ...@@ -8,8 +8,7 @@ import QGroundControl.ScreenTools 1.0
GridLayout { GridLayout {
// Item must be loaded, expects the following properties: property var generator // CircularGenerator
// property var generator
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _margin: ScreenTools.defaultFontPixelWidth / 2
......
import QtQuick 2.0 import QtQuick 2.0
import Wima 1.0
import QGroundControl 1.0
Item { Item {
id: _root id: _root
visible: true
// Expects the following properties:
property var map ///< Map control to place item in property var map ///< Map control to place item in
property var qgcView ///< QGCView to use for popping dialogs property var qgcView ///< QGCView to use for popping dialogs
property var generator property var generator
property bool checked: false property bool checked: false
property var _referenceComponent property var _referenceComponent: undefined
signal clicked() 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: { onVisibleChanged: {
if (visible){ if (visible){
_addRefPoint() _addRefPoint()
...@@ -41,28 +31,56 @@ Item { ...@@ -41,28 +31,56 @@ Item {
} }
} }
Component.onDestroyed: { Component.onDestruction: {
_destroyRefPoint() _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) // Ref. point (Base Station)
Component { Component {
id: refPointComponent id: refPointComponent
DragCoordinate { DragCoordinate {
id: dragCoordinate
property var ref: _root.generator.reference
map: _root.map map: _root.map
qgcView: _root.qgcView qgcView: _root.qgcView
z: QGroundControl.zOrderMapItems z: QGroundControl.zOrderMapItems
checked: _root.checked checked: _root.checked
coordinate: _root.generator.reference coordinate: ref
onDragReleased: {
syncAndBind()
}
Component.onCompleted: {
syncAndBind()
}
onClicked: { onClicked: {
_root.clicked() _root.clicked()
} }
onDragReleased: { function syncAndBind(){
_root.generator.reference = coordinate if (coordinate.latitude !== ref.latitude ||
coordinate = Qt.binding(function (){return _root.generator.reference}) coordinate.longitude !== ref.longitude){
_root.generator.reference = coordinate
}
coordinate = Qt.binding(function(){return _root.generator.reference})
} }
} }
} }
......
...@@ -25,31 +25,24 @@ Rectangle { ...@@ -25,31 +25,24 @@ Rectangle {
//property real availableWidth ///< Width for control //property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor //property var missionItem ///< Mission Item for editor
property real _margin: ScreenTools.defaultFontPixelWidth / 2 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 var _generator: missionItem.generator property var _generator: missionItem.generator
property var _generatorEditor: undefined
function polygonCaptureStarted() { QGCPalette { id: qgcPal; colorGroupEnabled: true }
missionItem.clearPolygon()
}
function polygonCaptureFinished(coordinates) { Component.onCompleted: {
for (var i=0; i<coordinates.length; i++) { _addGeneratorEditor()
missionItem.addPolygonCoordinate(coordinates[i])
}
} }
Component.onDestruction: {
function polygonAdjustVertex(vertexIndex, vertexCoordinate) { _destroyGeneratorEditor()
missionItem.adjustPolygonCoordinate(vertexIndex, vertexCoordinate)
} }
function polygonAdjustStarted() { } on_GeneratorChanged: {
function polygonAdjustFinished() { } _destroyGeneratorEditor()
_addGeneratorEditor()
QGCPalette { id: qgcPal; colorGroupEnabled: true } }
Column { Column {
id: editorColumn id: editorColumn
...@@ -156,13 +149,11 @@ Rectangle { ...@@ -156,13 +149,11 @@ Rectangle {
id: transectsHeader id: transectsHeader
text: qsTr("Generator") text: qsTr("Generator")
} }
Loader{
source: _generator.editorQml
property var generator: _generator
property real margin: _margin
visible: transectsHeader.checked
}
Column{
id:generatorEditorParent
visible: transectsHeader.checked
}
Column{ Column{
anchors.left: parent.left anchors.left: parent.left
...@@ -178,7 +169,7 @@ Rectangle { ...@@ -178,7 +169,7 @@ Rectangle {
onCalculatingChanged: { onCalculatingChanged: {
if(!calculating){ if(!calculating){
// defer hideing // defer hiding
timer.restart() timer.restart()
} }
} }
...@@ -192,4 +183,27 @@ Rectangle { ...@@ -192,4 +183,27 @@ Rectangle {
} }
} }
} // Column } // Column
function _addGeneratorEditor(){
if (_generator.editorQml && !_generatorEditor) {
var component = Qt.createComponent(_generator.editorQml)
if (component.status === Component.Error) {
console.log("Error loading Qml: ",
_generator.editorQml, component.errorString())
} else {
_generatorEditor =
component.createObject(
generatorEditorParent, {
"generator": _root._generator,
})
}
}
}
function _destroyGeneratorEditor(){
if (_generatorEditor){
_generatorEditor.destroy()
_generatorEditor = undefined
}
}
} // Rectangle } // Rectangle
...@@ -26,67 +26,34 @@ Item { ...@@ -26,67 +26,34 @@ Item {
property var qgcView ///< QGCView to use for popping dialogs property var qgcView ///< QGCView to use for popping dialogs
property var _missionItem: object property var _missionItem: object
property var _transectsComponent property var _generator: _missionItem.generator
property var _entryCoordinate
property var _exitCoordinate
signal clicked(int sequenceNumber) property var _transectsComponent: undefined
property var _entryCoordinate: undefined
function _addTransectsComponent(){ property var _exitCoordinate: undefined
if (!_transectsComponent){ property var _generatorVisuals: undefined
_transectsComponent = visualTransectsComponent.createObject(_root)
map.addMapItem(_transectsComponent)
}
}
function _addExitCoordinate(){
if (!_exitCoordinate){
_exitCoordinate = exitPointComponent.createObject(_root)
map.addMapItem(_exitCoordinate)
}
}
function _addEntryCoordinate(){ property bool _isCurrentItem: _missionItem.isCurrentItem
if (!_entryCoordinate){
_entryCoordinate = entryPointComponent.createObject(_root)
map.addMapItem(_entryCoordinate)
}
}
function _destroyEntryCoordinate(){ signal clicked(int sequenceNumber)
if (_entryCoordinate){
map.removeMapItem(_entryCoordinate)
_entryCoordinate.destroy()
_entryCoordinate = undefined
}
}
function _destroyExitCoordinate(){
if (_exitCoordinate){
map.removeMapItem(_exitCoordinate)
_exitCoordinate.destroy()
_exitCoordinate = undefined
}
}
function _destroyTransectsComponent(){
if (_transectsComponent){
map.removeMapItem(_transectsComponent)
_transectsComponent.destroy()
_transectsComponent = undefined
}
}
Component.onCompleted: { Component.onCompleted: {
_addEntryCoordinate() _addEntryCoordinate()
_addExitCoordinate() _addExitCoordinate()
_addTransectsComponent() _addTransectsComponent()
_addGeneratorVisuals()
} }
Component.onDestruction: { Component.onDestruction: {
_destroyEntryCoordinate() _destroyEntryCoordinate()
_destroyExitCoordinate() _destroyExitCoordinate()
_destroyTransectsComponent() _destroyTransectsComponent()
_destroyGeneratorVisuals()
}
on_GeneratorChanged: {
_destroyGeneratorVisuals()
_addGeneratorVisuals()
} }
// Transect lines // Transect lines
...@@ -140,4 +107,82 @@ Item { ...@@ -140,4 +107,82 @@ Item {
} }
} }
} }
// Generator visuals
function _addGeneratorVisuals(){
if (_generator.mapVisualQml && !_generatorVisuals) {
var component = Qt.createComponent(_generator.mapVisualQml)
if (component.status === Component.Error) {
console.log("Error loading Qml: ",
_generator.mapVisualQml, component.errorString())
} else {
_generatorVisuals =
component.createObject(_root, {
"map": _root.map,
"qgcView": _root.qgcView ,
"generator": _root._generator,
"checked": Qt.binding(
function(){
return _root._isCurrentItem
})
})
_generatorVisuals.clicked.connect(
function(){_root.clicked(_missionItem.sequenceNumber)})
}
}
}
function _destroyGeneratorVisuals(){
if(_generatorVisuals){
_generatorVisuals.destroy()
_generatorVisuals = undefined
}
}
function _addTransectsComponent(){
if (!_transectsComponent){
_transectsComponent = visualTransectsComponent.createObject(_root)
map.addMapItem(_transectsComponent)
}
}
function _addExitCoordinate(){
if (!_exitCoordinate){
_exitCoordinate = exitPointComponent.createObject(_root)
map.addMapItem(_exitCoordinate)
}
}
function _addEntryCoordinate(){
if (!_entryCoordinate){
_entryCoordinate = entryPointComponent.createObject(_root)
map.addMapItem(_entryCoordinate)
}
}
function _destroyEntryCoordinate(){
if (_entryCoordinate){
map.removeMapItem(_entryCoordinate)
_entryCoordinate.destroy()
_entryCoordinate = undefined
}
}
function _destroyExitCoordinate(){
if (_exitCoordinate){
map.removeMapItem(_exitCoordinate)
_exitCoordinate.destroy()
_exitCoordinate = undefined
}
}
function _destroyTransectsComponent(){
if (_transectsComponent){
map.removeMapItem(_transectsComponent)
_transectsComponent.destroy()
_transectsComponent = undefined
}
}
} }
...@@ -8,8 +8,7 @@ import QGroundControl.ScreenTools 1.0 ...@@ -8,8 +8,7 @@ import QGroundControl.ScreenTools 1.0
GridLayout { GridLayout {
// Item must be loaded, expects the following properties: property var generator ///< LinearGenerator
// property var generator
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _margin: ScreenTools.defaultFontPixelWidth / 2
...@@ -23,7 +22,14 @@ GridLayout { ...@@ -23,7 +22,14 @@ GridLayout {
Layout.fillWidth: true Layout.fillWidth: true
} }
QGCLabel { text: qsTr("Alpha") } QGCLabel {
text: qsTr("Alpha: ")
Layout.fillWidth: true
}
FactTextField {
fact: generator.alpha
Layout.fillWidth: true
}
QGCSlider { QGCSlider {
id: rSlider id: rSlider
minimumValue: 0 minimumValue: 0
...@@ -33,8 +39,11 @@ GridLayout { ...@@ -33,8 +39,11 @@ GridLayout {
Layout.fillWidth: true Layout.fillWidth: true
Layout.columnSpan: 2 Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5 Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
onValueChanged: generator.alpha.value = value onValueChanged: {
Component.onCompleted: value = 0 generator.alpha.value = value
value = Qt.binding(function(){return generator.alpha.value})
}
Component.onCompleted: value = generator.alpha.value
updateValueWhileDragging: true updateValueWhileDragging: true
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment