Commit 6cda7cf4 authored by Valentin Platzgummer's avatar Valentin Platzgummer

solved some bugs, circ survey update, interactivity wimaArea, wimaPlaner autoupdate

parent e02648a3
...@@ -59,6 +59,7 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyVie ...@@ -59,6 +59,7 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyVie
, _terrainAdjustToleranceFact (settingsGroup, _metaDataMap[terrainAdjustToleranceName]) , _terrainAdjustToleranceFact (settingsGroup, _metaDataMap[terrainAdjustToleranceName])
, _terrainAdjustMaxClimbRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName]) , _terrainAdjustMaxClimbRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName])
, _terrainAdjustMaxDescentRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName]) , _terrainAdjustMaxDescentRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName])
, _transectsDirty(true)
{ {
_terrainQueryTimer.setInterval(_terrainQueryTimeoutMsecs); _terrainQueryTimer.setInterval(_terrainQueryTimeoutMsecs);
_terrainQueryTimer.setSingleShot(true); _terrainQueryTimer.setSingleShot(true);
...@@ -419,6 +420,9 @@ void TransectStyleComplexItem::_rebuildTransects(void) ...@@ -419,6 +420,9 @@ void TransectStyleComplexItem::_rebuildTransects(void)
emit lastSequenceNumberChanged(lastSequenceNumber()); emit lastSequenceNumberChanged(lastSequenceNumber());
emit timeBetweenShotsChanged(); emit timeBetweenShotsChanged();
emit additionalTimeDelayChanged(); emit additionalTimeDelayChanged();
if (!_transectsDirty)
emit missionItemReady();
} }
void TransectStyleComplexItem::_updateTransectAltitude() void TransectStyleComplexItem::_updateTransectAltitude()
......
...@@ -127,6 +127,7 @@ signals: ...@@ -127,6 +127,7 @@ signals:
void visualTransectPointsChanged (void); void visualTransectPointsChanged (void);
void coveredAreaChanged (void); void coveredAreaChanged (void);
void followTerrainChanged (bool followTerrain); void followTerrainChanged (bool followTerrain);
void missionItemReady (void);
protected slots: protected slots:
void _setDirty (void); void _setDirty (void);
...@@ -208,6 +209,9 @@ private slots: ...@@ -208,6 +209,9 @@ private slots:
void _reallyQueryTransectsPathHeightInfo(void); void _reallyQueryTransectsPathHeightInfo(void);
void _followTerrainChanged (bool followTerrain); void _followTerrainChanged (bool followTerrain);
protected:
bool _transectsDirty;
private: private:
void _queryTransectsPathHeightInfo (void); void _queryTransectsPathHeightInfo (void);
void _adjustTransectsForTerrain (void); void _adjustTransectsForTerrain (void);
...@@ -216,4 +220,6 @@ private: ...@@ -216,4 +220,6 @@ private:
void _adjustForTolerance (QList<CoordInfo_t>& transect); void _adjustForTolerance (QList<CoordInfo_t>& transect);
double _altitudeBetweenCoords (const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo); double _altitudeBetweenCoords (const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo);
int _maxPathHeight (const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight); int _maxPathHeight (const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight);
}; };
#include "CircularSurveyComplexItem.h" #include "CircularSurveyComplexItem.h"
#include "JsonHelper.h" #include "JsonHelper.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include <chrono> #include <chrono>
...@@ -35,9 +35,7 @@ CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyV ...@@ -35,9 +35,7 @@ CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyV
, _maxWaypoints (settingsGroup, _metaDataMap[maxWaypointsName]) , _maxWaypoints (settingsGroup, _metaDataMap[maxWaypointsName])
, _isInitialized (false) , _isInitialized (false)
, _reverseOnly (false) , _reverseOnly (false)
, _referencePointBeingChanged (false)
, _updateCounter (0) , _updateCounter (0)
, _transectsDiry (true)
{ {
Q_UNUSED(kmlOrShpFile) Q_UNUSED(kmlOrShpFile)
_editorQml = "qrc:/qml/CircularSurveyItemEditor.qml"; _editorQml = "qrc:/qml/CircularSurveyItemEditor.qml";
...@@ -100,11 +98,6 @@ bool CircularSurveyComplexItem::isInitialized() ...@@ -100,11 +98,6 @@ bool CircularSurveyComplexItem::isInitialized()
return _isInitialized; return _isInitialized;
} }
bool CircularSurveyComplexItem::referencePointBeingChanged()
{
return _referencePointBeingChanged;
}
bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString)
{ {
// We need to pull version first to determine what validation/conversion needs to be performed // We need to pull version first to determine what validation/conversion needs to be performed
...@@ -207,7 +200,7 @@ void CircularSurveyComplexItem::save(QJsonArray &planItems) ...@@ -207,7 +200,7 @@ void CircularSurveyComplexItem::save(QJsonArray &planItems)
void CircularSurveyComplexItem::appendMissionItems(QList<MissionItem *> &items, QObject *missionItemParent) void CircularSurveyComplexItem::appendMissionItems(QList<MissionItem *> &items, QObject *missionItemParent)
{ {
if (_transectsDiry) if (_transectsDirty)
return; return;
if (_loadedMissionItems.count()) { if (_loadedMissionItems.count()) {
// We have mission items from the loaded plan, use those // We have mission items from the loaded plan, use those
...@@ -221,7 +214,7 @@ void CircularSurveyComplexItem::appendMissionItems(QList<MissionItem *> &items, ...@@ -221,7 +214,7 @@ void CircularSurveyComplexItem::appendMissionItems(QList<MissionItem *> &items,
void CircularSurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) void CircularSurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{ {
//qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems"; //qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems";
if (_transectsDiry) if (_transectsDirty)
return; return;
int seqNum = _sequenceNumber; int seqNum = _sequenceNumber;
...@@ -239,7 +232,7 @@ void CircularSurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& ...@@ -239,7 +232,7 @@ void CircularSurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>&
// Now build the mission items from the transect points // Now build the mission items from the transect points
if (_transectsDiry) if (_transectsDirty)
return; return;
MissionItem* item; MissionItem* item;
...@@ -291,11 +284,11 @@ double CircularSurveyComplexItem::additionalTimeDelay() const ...@@ -291,11 +284,11 @@ double CircularSurveyComplexItem::additionalTimeDelay() const
return 0; return 0;
} }
void CircularSurveyComplexItem::_rebuildTransectsPhase1(void){ void CircularSurveyComplexItem::_rebuildTransectsPhase1(void){
if (_fastRecalc){ if (_doFastRecalc){
_rebuildTransectsFast(); _rebuildTransectsFast();
} else { } else {
_rebuildTransectsSlow(); _rebuildTransectsSlow();
_fastRecalc = true; _doFastRecalc = true;
} }
} }
...@@ -366,7 +359,8 @@ void CircularSurveyComplexItem::_rebuildTransectsFast() ...@@ -366,7 +359,8 @@ void CircularSurveyComplexItem::_rebuildTransectsFast()
_rebuildTransectsToGeo(optiPath, _referencePoint); _rebuildTransectsToGeo(optiPath, _referencePoint);
_transectsDirty = true;
//_triggerSlowRecalcTimer.start(triggerTime);
qDebug() << "CircularSurveyComplexItem::_rebuildTransectsPhase1(): calls: " << _updateCounter; qDebug() << "CircularSurveyComplexItem::_rebuildTransectsPhase1(): calls: " << _updateCounter;
} }
...@@ -375,7 +369,24 @@ void CircularSurveyComplexItem::_rebuildTransectsSlow() ...@@ -375,7 +369,24 @@ void CircularSurveyComplexItem::_rebuildTransectsSlow()
{ {
using namespace GeoUtilities; using namespace GeoUtilities;
using namespace PolygonCalculus; using namespace PolygonCalculus;
using namespace PlanimetryCalculus; using namespace PlanimetryCalculus;
if (_reverseOnly) { // reverse transects and return
_reverseOnly = false;
QList<QList<CoordInfo_t>> transectsReverse;
transectsReverse.reserve(_transects.size());
for (auto list : _transects) {
QList<CoordInfo_t> listReverse;
for (auto coordinate : list)
listReverse.prepend(coordinate);
transectsReverse.prepend(listReverse);
}
_transects = transectsReverse;
return;
}
_transects.clear(); _transects.clear();
...@@ -390,27 +401,6 @@ void CircularSurveyComplexItem::_rebuildTransectsSlow() ...@@ -390,27 +401,6 @@ void CircularSurveyComplexItem::_rebuildTransectsSlow()
_loadedMissionItemsParent = nullptr; _loadedMissionItemsParent = nullptr;
} }
if (_reverseOnly) { // reverse transects and return
_reverseOnly = false;
if (_transects.size() > 1) {
QList<QList<CoordInfo_t>> transectsReverse;
transectsReverse.reserve(_transects.size());
for (auto list : _transects) {
QList<CoordInfo_t> listReverse;
for (auto coordinate : list)
listReverse.prepend(coordinate);
transectsReverse.prepend(listReverse);
}
_transects = transectsReverse;
return;
}
}
QVector<QVector<QPointF>> transectPath; QVector<QVector<QPointF>> transectPath;
if(!_generateTransectPath(transectPath, surveyPolygon)) if(!_generateTransectPath(transectPath, surveyPolygon))
return; return;
...@@ -465,21 +455,22 @@ void CircularSurveyComplexItem::_rebuildTransectsSlow() ...@@ -465,21 +455,22 @@ void CircularSurveyComplexItem::_rebuildTransectsSlow()
return; return;
_rebuildTransectsToGeo(optimizedPath, _referencePoint); _rebuildTransectsToGeo(optimizedPath, _referencePoint);
_transectsDiry = false;
_transectsDirty = false;
//_triggerSlowRecalcTimer.stop(); // stop any pending slow recalculations
return;
} }
void CircularSurveyComplexItem::_triggerSlowRecalc() void CircularSurveyComplexItem::_triggerSlowRecalc()
{ {
_fastRecalc = false; _doFastRecalc = false;
_rebuildTransects(); _rebuildTransects();
} }
void CircularSurveyComplexItem::_recalcComplexDistance() void CircularSurveyComplexItem::_recalcComplexDistance()
{ {
_complexDistance = 0; _complexDistance = 0;
if (_transectsDiry) if (_transectsDirty)
return; return;
for (int i=0; i<_visualTransectPoints.count() - 1; i++) { for (int i=0; i<_visualTransectPoints.count() - 1; i++) {
_complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>()); _complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
...@@ -496,7 +487,7 @@ void CircularSurveyComplexItem::_recalcCameraShots() ...@@ -496,7 +487,7 @@ void CircularSurveyComplexItem::_recalcCameraShots()
void CircularSurveyComplexItem::_reverseTransects() void CircularSurveyComplexItem::_reverseTransects()
{ {
_reverseOnly = true; _reverseOnly = true;
_rebuildTransectsSlow(); _triggerSlowRecalc();
} }
bool CircularSurveyComplexItem::_shortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QVector<QGeoCoordinate> &shortestPath) bool CircularSurveyComplexItem::_shortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QVector<QGeoCoordinate> &shortestPath)
......
...@@ -83,6 +83,8 @@ public: ...@@ -83,6 +83,8 @@ public:
static const char* jsonReferencePointLatKey; static const char* jsonReferencePointLatKey;
static const char* jsonReferencePointAltKey; static const char* jsonReferencePointAltKey;
static const long triggerTime = 50; // trigger time (ms) for _triggerSlowRecalcTimer
signals: signals:
void refPointChanged(); void refPointChanged();
void isInitializedChanged(); void isInitializedChanged();
...@@ -122,15 +124,13 @@ private: ...@@ -122,15 +124,13 @@ private:
SettingsFact _reverse; // reverses the _transects path SettingsFact _reverse; // reverses the _transects path
SettingsFact _maxWaypoints; // the maximum number of waypoints _transects (TransectStyleComplexItem) can contain (to avoid performance hits) SettingsFact _maxWaypoints; // the maximum number of waypoints _transects (TransectStyleComplexItem) can contain (to avoid performance hits)
QTimer _updateTimer; QTimer _triggerSlowRecalcTimer;
bool _isInitialized; // indicates if the polygon and refpoint etc. are initialized, prevents reinitialisation from gui and execution of _rebuildTransectsPhase1 during init from gui bool _isInitialized; // indicates if the polygon and refpoint etc. are initialized, prevents reinitialisation from gui and execution of _rebuildTransectsPhase1 during init from gui
bool _reverseOnly; // if this is true _rebuildTransectsPhase1() will reverse the path only, _rebuildTransectsPhase1() resets _reverseOnly bool _reverseOnly; // if this is true _rebuildTransectsPhase1() will reverse the path only, _rebuildTransectsPhase1() resets _reverseOnly
bool _referencePointBeingChanged; // is set to true by gui, if user is changeing the reference point bool _doFastRecalc; // fast recalc of transects if set, see _rebuildTransectsPhase1 for furhter explanation
bool _fastRecalc; // see _rebuildTransectsPhase1 for explanation
int _updateCounter; int _updateCounter;
int _transectsDiry;
}; };
......
...@@ -139,6 +139,11 @@ namespace PolygonCalculus { ...@@ -139,6 +139,11 @@ namespace PolygonCalculus {
if ( !isSimplePolygon(polygon1) || !isSimplePolygon(polygon2)) { if ( !isSimplePolygon(polygon1) || !isSimplePolygon(polygon2)) {
return JoinPolygonError::NotSimplePolygon; return JoinPolygonError::NotSimplePolygon;
} }
if (polygon1 == polygon2) {
joinedPolygon = polygon1;
return JoinPolygonError::PolygonJoined;
}
if ( !hasClockwiseWinding(polygon1)) { if ( !hasClockwiseWinding(polygon1)) {
reversePath(polygon1); reversePath(polygon1);
} }
...@@ -171,6 +176,7 @@ namespace PolygonCalculus { ...@@ -171,6 +176,7 @@ namespace PolygonCalculus {
// possible nextVertex (if no intersection between currentVertex and protoVertex with crossPoly) // possible nextVertex (if no intersection between currentVertex and protoVertex with crossPoly)
int nextVertexNumber = nextVertexIndex(walkerPoly->size(), startIndex); int nextVertexNumber = nextVertexIndex(walkerPoly->size(), startIndex);
QPointF protoNextVertex = walkerPoly->value(nextVertexNumber); QPointF protoNextVertex = walkerPoly->value(nextVertexNumber);
long counter = 0;
while (1) { while (1) {
//qDebug("nextVertexNumber: %i", nextVertexNumber); //qDebug("nextVertexNumber: %i", nextVertexNumber);
joinedPolygon.append(currentVertex); joinedPolygon.append(currentVertex);
...@@ -232,6 +238,12 @@ namespace PolygonCalculus { ...@@ -232,6 +238,12 @@ namespace PolygonCalculus {
return PolygonJoined; return PolygonJoined;
} }
} }
counter++;
if (counter > 1e5) {
qWarning("PolygonCalculus::join(): no successfull termination!");
return Error;
}
} }
} else { } else {
......
...@@ -9,7 +9,7 @@ ...@@ -9,7 +9,7 @@
namespace PolygonCalculus { namespace PolygonCalculus {
enum JoinPolygonError { NotSimplePolygon, PolygonJoined, Disjoint, PathSizeLow}; enum JoinPolygonError { NotSimplePolygon, PolygonJoined, Disjoint, PathSizeLow, Error};
typedef QList<QVector3D> QVector3DList; typedef QList<QVector3D> QVector3DList;
typedef QList<QPointF> QPointFList; typedef QList<QPointF> QPointFList;
......
...@@ -143,15 +143,15 @@ void WimaArea::updatePolygonConnections(QVariant showBorderPolygon) ...@@ -143,15 +143,15 @@ void WimaArea::updatePolygonConnections(QVariant showBorderPolygon)
void WimaArea::recalcInteractivity() void WimaArea::recalcInteractivity()
{ {
if ( _wimaAreaInteractive == false) { if ( _wimaAreaInteractive == false) {
this->setWimaAreaInteractive(false); QGCMapPolygon::setInteractive(false);
_borderPolygon.setInteractive(false); _borderPolygon.setInteractive(false);
} else { } else {
if (_showBorderPolygon.rawValue().toBool() == true) { if (_showBorderPolygon.rawValue().toBool() == true) {
_borderPolygon.setInteractive(true); _borderPolygon.setInteractive(true);
this->setInteractive(false); QGCMapPolygon::setInteractive(false);
} else { } else {
_borderPolygon.setInteractive(false); _borderPolygon.setInteractive(false);
this->setInteractive(true); QGCMapPolygon::setInteractive(true);
} }
} }
} }
......
...@@ -29,9 +29,9 @@ WimaPlaner::WimaPlaner(QObject *parent) ...@@ -29,9 +29,9 @@ WimaPlaner::WimaPlaner(QObject *parent)
_lastServiceAreaPath = _serviceArea.path(); _lastServiceAreaPath = _serviceArea.path();
_lastCorridorPath = _corridor.path(); _lastCorridorPath = _corridor.path();
connect(this, &WimaPlaner::currentPolygonIndexChanged, this, &WimaPlaner::recalcPolygonInteractivity); connect(this, &WimaPlaner::currentPolygonIndexChanged, this, &WimaPlaner::recalcPolygonInteractivity);
connect(&_updateTimer, &QTimer::timeout, this, &WimaPlaner::updateTimerSlot); connect(&_updateTimer, &QTimer::timeout, this, &WimaPlaner::updateTimerSlot);
connect(this, &WimaPlaner::joinedAreaValidChanged, this, &WimaPlaner::updateMission); connect(this, &WimaPlaner::joinedAreaValidChanged, this, &WimaPlaner::updateMission);
_updateTimer.setInterval(500); // 250 ms means: max update time 2*250 ms _updateTimer.setInterval(500); // 250 ms means: max update time 2*250 ms
_updateTimer.start(); _updateTimer.start();
...@@ -242,19 +242,13 @@ bool WimaPlaner::updateMission() ...@@ -242,19 +242,13 @@ bool WimaPlaner::updateMission()
_lastSurveyRefPoint = _measurementArea.center(); _lastSurveyRefPoint = _measurementArea.center();
_surveyRefChanging = false; _surveyRefChanging = false;
_circularSurvey->setIsInitialized(true); // prevents reinitialisation from gui _circularSurvey->setIsInitialized(true); // prevents reinitialisation from gui
// connect(_circularSurvey->deltaR(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer); connect(_circularSurvey, &TransectStyleComplexItem::missionItemReady, this, &WimaPlaner::calcArrivalAndReturnPath);
// connect(_circularSurvey->deltaAlpha(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
// connect(_circularSurvey->isSnakePath(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
// connect(_circularSurvey->transectMinLength(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
// connect(_circularSurvey->reverse(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
connect(_circularSurvey, &TransectStyleComplexItem::visualTransectPointsChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
} }
// update survey area // update survey area
_circularSurvey->surveyAreaPolygon()->clear(); _circularSurvey->surveyAreaPolygon()->clear();
_circularSurvey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList()); _circularSurvey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList());
_circularSurvey->comprehensiveUpdate();
//calcArrivalAndReturnPath();
setReadyForSync(true); setReadyForSync(true);
return true; return true;
...@@ -445,12 +439,7 @@ bool WimaPlaner::loadFromFile(const QString &filename) ...@@ -445,12 +439,7 @@ bool WimaPlaner::loadFromFile(const QString &filename)
_lastSurveyRefPoint = _circularSurvey->refPoint(); _lastSurveyRefPoint = _circularSurvey->refPoint();
_surveyRefChanging = false; _surveyRefChanging = false;
_circularSurvey->setIsInitialized(true); // prevents reinitialisation from gui _circularSurvey->setIsInitialized(true); // prevents reinitialisation from gui
// connect(_circularSurvey->deltaR(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer); connect(_circularSurvey, &TransectStyleComplexItem::missionItemReady, this, &WimaPlaner::calcArrivalAndReturnPath);
// connect(_circularSurvey->deltaAlpha(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
// connect(_circularSurvey->isSnakePath(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
// connect(_circularSurvey->transectMinLength(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
// connect(_circularSurvey->reverse(), &Fact::rawValueChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
connect(_circularSurvey, &TransectStyleComplexItem::visualTransectPointsChanged, this, &WimaPlaner::startCalcArrivalAndReturnTimer);
break; break;
} }
} }
...@@ -484,7 +473,8 @@ void WimaPlaner::recalcPolygonInteractivity(int index) ...@@ -484,7 +473,8 @@ void WimaPlaner::recalcPolygonInteractivity(int index)
if (index >= 0 && index < _visualItems.count()) { if (index >= 0 && index < _visualItems.count()) {
resetAllInteractive(); resetAllInteractive();
WimaArea* interactivePoly = qobject_cast<WimaArea*>(_visualItems.get(index)); WimaArea* interactivePoly = qobject_cast<WimaArea*>(_visualItems.get(index));
interactivePoly->setWimaAreaInteractive(true); if (interactivePoly != nullptr)
interactivePoly->setWimaAreaInteractive(true);
} }
} }
...@@ -637,8 +627,8 @@ bool WimaPlaner::recalcJoinedArea() ...@@ -637,8 +627,8 @@ bool WimaPlaner::recalcJoinedArea()
_joinedArea.setPath(_serviceArea.path()); _joinedArea.setPath(_serviceArea.path());
_joinedArea.join(_corridor); _joinedArea.join(_corridor);
if ( !_joinedArea.join(_measurementArea) ) { if ( !_joinedArea.join(_measurementArea) ) {
qgcApp()->showMessage(tr("Not able to join areas. Service area and measurement" /*qgcApp()->showMessage(tr("Not able to join areas. Service area and measurement"
" must have a overlapping section, or be connected through a corridor.")); " must have a overlapping section, or be connected through a corridor."));*/
return false; // this happens if all areas are pairwise disjoint return false; // this happens if all areas are pairwise disjoint
} }
...@@ -789,6 +779,7 @@ void WimaPlaner::updateTimerSlot() ...@@ -789,6 +779,7 @@ void WimaPlaner::updateTimerSlot()
if (_measurementAreaChanging) { if (_measurementAreaChanging) {
if (_measurementArea.path() == _lastMeasurementAreaPath) { // is it still changing? if (_measurementArea.path() == _lastMeasurementAreaPath) { // is it still changing?
recalcJoinedArea(); recalcJoinedArea();
calcArrivalAndReturnPath();
_measurementAreaChanging = false; _measurementAreaChanging = false;
} }
} else { } else {
...@@ -800,6 +791,7 @@ void WimaPlaner::updateTimerSlot() ...@@ -800,6 +791,7 @@ void WimaPlaner::updateTimerSlot()
if (_corridorChanging) { if (_corridorChanging) {
if (_corridor.path() == _lastCorridorPath) { // is it still changing? if (_corridor.path() == _lastCorridorPath) { // is it still changing?
recalcJoinedArea(); recalcJoinedArea();
calcArrivalAndReturnPath();
_corridorChanging = false; _corridorChanging = false;
} }
} else { } else {
...@@ -811,6 +803,7 @@ void WimaPlaner::updateTimerSlot() ...@@ -811,6 +803,7 @@ void WimaPlaner::updateTimerSlot()
if (_serviceAreaChanging) { if (_serviceAreaChanging) {
if (_serviceArea.path() == _lastServiceAreaPath) { // is it still changing? if (_serviceArea.path() == _lastServiceAreaPath) { // is it still changing?
recalcJoinedArea(); recalcJoinedArea();
calcArrivalAndReturnPath();
_serviceAreaChanging = false; _serviceAreaChanging = false;
} }
} else { } else {
......
...@@ -37,9 +37,9 @@ Rectangle { ...@@ -37,9 +37,9 @@ Rectangle {
polyline.interactive = polylineInteractive; polyline.interactive = polylineInteractive;
}*/ }*/
onPolygonInteractiveChanged: { // onPolygonInteractiveChanged: {
polygon.interactive = polygonInteractive; // polygon.interactive = polygonInteractive;
} // }
/*function editPolyline(){ /*function editPolyline(){
if (polylineInteractive){ if (polylineInteractive){
......
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