Commit f8bfa0a1 authored by Valentin Platzgummer's avatar Valentin Platzgummer

flight view wima menu altitude and speed added plus stats

parent 44644da9
This diff is collapsed.
This diff is collapsed.
......@@ -19,7 +19,7 @@ import QGroundControl.FactControls 1.0
Item {
id: _root
height: 500
height: 700
width: 300
property var wimaController // must be provided by the user
......@@ -39,6 +39,15 @@ Item {
}
}
function getTime(time) {
// time is a double
if(isNaN(time)) {
return "00:00:00"
}
var t = new Date(0, 0, 0, 0, 0, Number(time))
return Qt.formatTime(t, 'hh:mm:ss')
}
// box containing all items
Rectangle {
anchors.left: parent.left
......@@ -139,6 +148,18 @@ Item {
anchors.right: parent.right
visible: missionHeader.checked
QGCLabel { text: qsTr("Speed") }
FactTextField {
fact: wimaController.flightSpeed
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Altitude") }
FactTextField {
fact: wimaController.altitude
Layout.fillWidth: true
}
// Buttons
QGCButton {
id: buttonPreviousMissionPhase
......@@ -228,6 +249,22 @@ Item {
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
}
QGCLabel {
text: wimaController.phaseDistance >= 0 ? wimaController.phaseDistance.toFixed(2) + " m": ""
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
}
QGCLabel {
text: qsTr("Phase Duration: ")
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
}
QGCLabel {
text: wimaController.phaseDuration >= 0 ? getTime(wimaController.phaseDuration) : ""
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
}
}
}
}
......
......@@ -107,9 +107,11 @@ QList<QPointF> Circle::approximate(double angleDiscretisation) const
QList<QPointF> Circle::approximateSektor(int numberOfCorners, double alpha1, double alpha2) const
{
if ( numberOfCorners < 2)
if ( numberOfCorners < 2) {
qWarning("numberOfCorners < 2");
return QList<QPointF>();
return approximateSektor((alpha2-alpha1)/double(numberOfCorners-1), alpha1, alpha2);
}
return approximateSektor(PlanimetryCalculus::truncateAngle(alpha2-alpha1)/double(numberOfCorners-1), alpha1, alpha2);
}
QList<QPointF> Circle::approximateSektor(double angleDiscretisation, double alpha1, double alpha2) const
......
......@@ -27,7 +27,8 @@ CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyV
, _deltaAlpha (settingsGroup, _metaDataMap[deltaAlphaName])
, _transectMinLength (settingsGroup, _metaDataMap[transectMinLengthName])
, _isSnakePath (settingsGroup, _metaDataMap[isSnakePathName])
, _autoGenerated (false)
, _isInitialized (false)
, _updateCounter (0)
{
_editorQml = "qrc:/qml/CircularSurveyItemEditor.qml";
connect(&_deltaR, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects);
......@@ -53,12 +54,12 @@ void CircularSurveyComplexItem::setRefPoint(const QGeoCoordinate &refPt)
}
}
void CircularSurveyComplexItem::setAutoGenerated(bool autoGen)
void CircularSurveyComplexItem::setIsInitialized(bool isInitialized)
{
if (autoGen != _autoGenerated) {
_autoGenerated = autoGen;
if (isInitialized != _isInitialized) {
_isInitialized = isInitialized;
emit autoGeneratedChanged();
emit isInitializedChanged();
}
}
......@@ -77,9 +78,9 @@ Fact *CircularSurveyComplexItem::deltaAlpha()
return &_deltaAlpha;
}
bool CircularSurveyComplexItem::autoGenerated()
bool CircularSurveyComplexItem::isInitialized()
{
return _autoGenerated;
return _isInitialized;
}
bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString)
......@@ -142,7 +143,7 @@ bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int seque
_referencePoint.setLatitude (complexObject[jsonReferencePointLatKey].toDouble());
_referencePoint.setAltitude (complexObject[jsonReferencePointAltKey].toDouble());
_isSnakePath.setRawValue (complexObject[jsonIsSnakePathKey].toBool());
_autoGenerated = true;
setIsInitialized(true);
_ignoreRecalc = false;
......@@ -349,6 +350,11 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
using namespace PolygonCalculus;
using namespace PlanimetryCalculus;
if (!_isInitialized)
return;
_updateCounter++;
// If the transects are getting rebuilt then any previously loaded mission items are now invalid
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
......@@ -437,20 +443,31 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
QPointFList exitPoints;
// determine entryPoints and exit Points
for (int j = 0; j < intersectPoints.size(); j++) {
QList<QPointF> intersects = intersectPoints[j];
QList<QPointF> intersects = intersectPoints[j]; // one pt = tangent, two pt = sekant
QPointF p1 = surveyPolygon[neighbourList[j].first];
QPointF p2 = surveyPolygon[neighbourList[j].second];
QLineF intersetLine(p1, p2);
double lineAngle = truncateAngle(angle(intersetLine));
double lineAngle = angle(intersetLine);
// int n = 16;
// for (int i = -n; i <= n; i++) {
// double alpha = 2*M_PI*double(i)/double(n);
// qDebug() << i << " " << alpha << " " << truncateAngle(alpha);
// }
for (QPointF ipt : intersects) {
double circleTangentAngle = truncateAngle(angle(ipt)+M_PI_2);
double circleTangentAngle = angle(ipt)+M_PI_2;
// compare line angle and circle tangent at intersection point
// to determine between exit and entry point
if ( !qFuzzyCompare(lineAngle, circleTangentAngle)
&& !qFuzzyCompare(lineAngle, truncateAngle(circleTangentAngle + M_PI))) {
if (truncateAngle(lineAngle - circleTangentAngle) < M_PI) {
// qDebug() << "lineAngle" << lineAngle*180/M_PI;
// qDebug() << "circleTangentAngle" << circleTangentAngle*180/M_PI;
// qDebug() << "!qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle): " << !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle));
// qDebug() << "!qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI): " << !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI));
if ( !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle))
&& !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI) ))
{
if (truncateAngle(circleTangentAngle - lineAngle) > M_PI) {
entryPoints.append(ipt);
} else {
exitPoints.append(ipt);
......@@ -479,11 +496,16 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
}
}
// generate circle sectors
for (int k = 0; k < entryPoints.size(); k++) {
double alpha1 = angle(entryPoints[k]);
double alpha2 = angle(exitPoints[(k+offset) % entryPoints.size()]);
double dAlpha = alpha2-alpha1;
double dAlpha = truncateAngle(alpha2-alpha1);
int numNodes = int(ceil(dAlpha/dalpha)) + 1;
// qDebug() << "alpha1" << alpha1;
// qDebug() << "alpha2" << alpha2;
// qDebug() << "dAlpha" << dAlpha;
// qDebug() << "numNodes" << numNodes;
QList<QPointF> sectorPath = circle.approximateSektor(numNodes, alpha1, alpha2);
// use shortestPath() here if necessary, could be a problem if dr >>
......@@ -568,6 +590,8 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
_transects.append(transectList);
}
qDebug() << "CircularSurveyComplexItem::_rebuildTransectsPhase1(): " << _updateCounter;
}
void CircularSurveyComplexItem::_recalcComplexDistance()
......
......@@ -18,19 +18,19 @@ public:
/// @param kmlOrShpFile Polygon comes from this file, empty for default polygon
CircularSurveyComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrShpFile, QObject* parent);
Q_PROPERTY(QGeoCoordinate refPoint READ refPoint WRITE setRefPoint NOTIFY refPointChanged)
Q_PROPERTY(Fact* deltaR READ deltaR CONSTANT)
Q_PROPERTY(Fact* deltaAlpha READ deltaAlpha CONSTANT)
Q_PROPERTY(Fact* transectMinLength READ transectMinLength CONSTANT)
Q_PROPERTY(Fact* isSnakePath READ isSnakePath CONSTANT)
Q_PROPERTY(bool autoGenerated READ autoGenerated NOTIFY autoGeneratedChanged)
Q_PROPERTY(QGeoCoordinate refPoint READ refPoint WRITE setRefPoint NOTIFY refPointChanged)
Q_PROPERTY(Fact* deltaR READ deltaR CONSTANT)
Q_PROPERTY(Fact* deltaAlpha READ deltaAlpha CONSTANT)
Q_PROPERTY(Fact* transectMinLength READ transectMinLength CONSTANT)
Q_PROPERTY(Fact* isSnakePath READ isSnakePath CONSTANT)
Q_PROPERTY(bool isInitialized READ isInitialized WRITE setIsInitialized NOTIFY isInitializedChanged)
Q_INVOKABLE void resetReference(void);
// Property setters
void setRefPoint(const QGeoCoordinate &refPt);
// Set this to true if survey was automatically generated, prevents initialisation from gui.
void setAutoGenerated(bool autoGen);
void setIsInitialized(bool isInitialized);
// Property getters
QGeoCoordinate refPoint() const;
......@@ -39,7 +39,7 @@ public:
Fact *transectMinLength();
Fact *isSnakePath();
// Is true if survey was automatically generated, prevents initialisation from gui.
bool autoGenerated();
bool isInitialized();
// Overrides from ComplexMissionItem
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
......@@ -76,7 +76,7 @@ public:
signals:
void refPointChanged();
void autoGeneratedChanged();
void isInitializedChanged();
private slots:
// Overrides from TransectStyleComplexItem
......@@ -103,7 +103,11 @@ private:
QTimer _updateTimer;
bool _autoGenerated; // set to true if survey was automatically generated, prevents initialisation 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
int _updateCounter;
};
......
......@@ -620,7 +620,7 @@ angle
double angle(const QPointF &p1)
{
return qAtan2(p1.y(), p1.x());
return truncateAngle(qAtan2(p1.y(), p1.x()));
}
bool intersects(const Circle &circle, const QPolygonF &polygon, QList<QPointFList> &intersectionPoints, NeighbourList &neighbourList, IntersectList &typeList)
......@@ -698,6 +698,8 @@ angle
} // end namespace PlanimetryCalculus
......
......@@ -36,5 +36,20 @@
"shortDescription": "Determines whether the mission items of the current mission phase are displayed or not.",
"type": "bool",
"defaultValue": 1
},
{
"name": "FlightSpeed",
"shortDescription": "The mission flight speed.",
"type": "double",
"min" : 0.3,
"max" : 5,
"defaultValue": 2
},
{
"name": "Altitude",
"shortDescription": "The mission altitude.",
"type": "double",
"min" : 1,
"defaultValue": 5
}
]
......@@ -10,6 +10,8 @@ const char* WimaController::maxWaypointsPerPhaseName = "MaxWaypointsPerPhase"
const char* WimaController::startWaypointIndexName = "StartWaypointIndex";
const char* WimaController::showAllMissionItemsName = "ShowAllMissionItems";
const char* WimaController::showCurrentMissionItemsName = "ShowCurrentMissionItems";
const char* WimaController::flightSpeedName = "FlightSpeed";
const char* WimaController::altitudeName = "Altitude";
WimaController::WimaController(QObject *parent)
: QObject (parent)
......@@ -25,10 +27,14 @@ WimaController::WimaController(QObject *parent)
, _maxWaypointsPerPhase (settingsGroup, _metaDataMap[maxWaypointsPerPhaseName])
, _nextPhaseStartWaypointIndex (settingsGroup, _metaDataMap[startWaypointIndexName])
, _showAllMissionItems (settingsGroup, _metaDataMap[showAllMissionItemsName])
, _showCurrentMissionItems (settingsGroup, _metaDataMap[showCurrentMissionItemsName])
, _showCurrentMissionItems (settingsGroup, _metaDataMap[showCurrentMissionItemsName])
, _flightSpeed (settingsGroup, _metaDataMap[flightSpeedName])
, _altitude (settingsGroup, _metaDataMap[altitudeName])
, _startWaypointIndex (0)
, _lastMissionPhaseReached (false)
, _uploadOverrideRequired (false)
, _phaseDistance(-1)
, _phaseDuration(-1)
{
_nextPhaseStartWaypointIndex.setRawValue(int(1));
......@@ -37,6 +43,8 @@ WimaController::WimaController(QObject *parent)
connect(&_overlapWaypoints, &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::recalcCurrentPhase);
connect(&_nextPhaseStartWaypointIndex, &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
connect(&_flightSpeed, &Fact::rawValueChanged, this, &WimaController::updateSpeed);
connect(&_altitude, &Fact::rawValueChanged, this, &WimaController::updateAltitude);
}
QmlObjectListModel* WimaController::visualItems()
......@@ -111,11 +119,31 @@ Fact *WimaController::showCurrentMissionItems()
return &_showCurrentMissionItems;
}
Fact *WimaController::flightSpeed()
{
return &_flightSpeed;
}
Fact *WimaController::altitude()
{
return &_altitude;
}
bool WimaController::uploadOverrideRequired() const
{
return _uploadOverrideRequired;
}
double WimaController::phaseDistance() const
{
return _phaseDistance;
}
double WimaController::phaseDuration() const
{
return _phaseDuration;
}
Fact *WimaController::startWaypointIndex()
{
return &_nextPhaseStartWaypointIndex;
......@@ -317,6 +345,12 @@ bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVa
bool retValue = extractCoordinateList(missionItems, geoCoordintateList, startIndex, endIndex);
for (int i = 0; i < geoCoordintateList.size(); i++) {
QGeoCoordinate vertex = geoCoordintateList[i];
if (qFuzzyIsNull(vertex.latitude()) && qFuzzyIsNull(vertex.longitude()))
geoCoordintateList.removeAt(i);
}
if (!retValue)
return false;
......@@ -539,6 +573,17 @@ bool WimaController::calcNextPhase()
}
takeoffItem->setCoordinate(_takeoffLandPostion);
// create change speed item
_missionController->insertSimpleMissionItem(_takeoffLandPostion, 2);
SimpleMissionItem *speedItem = missionControllerVisuals->value<SimpleMissionItem*>(2);
if (speedItem == nullptr) {
qWarning("WimaController::calcNextPhase(): nullptr");
return false;
}
speedItem->setCoordinate(_takeoffLandPostion);
speedItem->setCommand(MAV_CMD_DO_CHANGE_SPEED);
speedItem->missionItem().setParam2(_flightSpeed.rawValue().toDouble());
// set land command for last mission item
SimpleMissionItem *landItem = missionControllerVisuals->value<SimpleMissionItem*>(missionControllerVisuals->count()-1);
......@@ -561,7 +606,10 @@ bool WimaController::calcNextPhase()
_currentMissionItems.append(visualItemCopy);
}
_setPhaseDistance(_missionController->missionDistance());
_setPhaseDuration(_missionController->missionDistance()/_flightSpeed.rawValue().toDouble());
_missionController->removeAll(); // remove items from _missionController, will be added on upload
updateAltitude();
updateCurrentPath();
emit currentMissionItemsChanged();
......@@ -611,5 +659,47 @@ bool WimaController::setTakeoffLandPosition()
return true;
}
void WimaController::updateSpeed()
{
SimpleMissionItem *item = _currentMissionItems.value<SimpleMissionItem *>(1); // speed item
if (item != nullptr && item->command() == MAV_CMD_DO_CHANGE_SPEED) {
item->missionItem().setParam2(_flightSpeed.rawValue().toDouble());
_setPhaseDuration(_phaseDistance/_flightSpeed.rawValue().toDouble());
}
else {
qWarning("WimaController::updateSpeed(): internal error.");
}
}
void WimaController::updateAltitude()
{
for (int i = 0; i < _currentMissionItems.count(); i++) {
SimpleMissionItem *item = _currentMissionItems.value<SimpleMissionItem *>(i);
if (item == nullptr) {
qWarning("WimaController::updateAltitude(): nullptr");
return;
}
item->altitude()->setRawValue(_altitude.rawValue().toDouble());
}
}
void WimaController::_setPhaseDistance(double distance)
{
if (!qFuzzyCompare(distance, _phaseDistance)) {
_phaseDistance = distance;
emit phaseDistanceChanged();
}
}
void WimaController::_setPhaseDuration(double duration)
{
if (!qFuzzyCompare(duration, _phaseDuration)) {
_phaseDuration = duration;
emit phaseDurationChanged();
}
}
......@@ -51,7 +51,11 @@ public:
Q_PROPERTY(Fact* startWaypointIndex READ startWaypointIndex CONSTANT)
Q_PROPERTY(Fact* showAllMissionItems READ showAllMissionItems CONSTANT)
Q_PROPERTY(Fact* showCurrentMissionItems READ showCurrentMissionItems CONSTANT)
Q_PROPERTY(Fact* flightSpeed READ flightSpeed CONSTANT)
Q_PROPERTY(Fact* altitude READ altitude CONSTANT)
Q_PROPERTY(bool uploadOverrideRequired READ uploadOverrideRequired WRITE setUploadOverrideRequired NOTIFY uploadOverrideRequiredChanged)
Q_PROPERTY(double phaseDistance READ phaseDistance NOTIFY phaseDistanceChanged)
Q_PROPERTY(double phaseDuration READ phaseDuration NOTIFY phaseDurationChanged)
......@@ -75,7 +79,11 @@ public:
Fact* startWaypointIndex (void);
Fact* showAllMissionItems (void);
Fact* showCurrentMissionItems(void);
Fact* flightSpeed (void);
Fact* altitude (void);
bool uploadOverrideRequired (void) const;
double phaseDistance (void) const;
double phaseDuration (void) const;
// Property setters
......@@ -110,6 +118,8 @@ public:
static const char* startWaypointIndexName;
static const char* showAllMissionItemsName;
static const char* showCurrentMissionItemsName;
static const char* flightSpeedName;
static const char* altitudeName;
// Member Methodes
QJsonDocument saveToJson(FileType fileType);
......@@ -136,6 +146,8 @@ signals:
void waypointPathChanged (void);
void currentWaypointPathChanged (void);
void uploadOverrideRequiredChanged (void);
void phaseDistanceChanged (void);
void phaseDurationChanged (void);
private slots:
bool fetchContainerData();
......@@ -144,7 +156,13 @@ private slots:
void updateCurrentPath (void);
void updateNextWaypoint (void);
void recalcCurrentPhase (void);
bool setTakeoffLandPosition(void);
bool setTakeoffLandPosition (void);
void updateSpeed (void);
void updateAltitude (void);
private:
void _setPhaseDistance(double distance);
void _setPhaseDuration(double duration);
private:
......@@ -174,6 +192,8 @@ private:
// defining the first element of the next phase
SettingsFact _showAllMissionItems; // bool value, Determines whether the mission items of the overall mission are displayed or not.
SettingsFact _showCurrentMissionItems; // bool value, Determines whether the mission items of the current mission phase are displayed or not.
SettingsFact _flightSpeed; // mission flight speed
SettingsFact _altitude; // mission altitude
int _endWaypointIndex; // indes of the mission item stored in _missionItems defining the last element
// (which is not part of the return path) of _currentMissionItem
......@@ -182,4 +202,8 @@ private:
bool _lastMissionPhaseReached;
bool _uploadOverrideRequired; // Is set to true if uploadToVehicle() did not suceed because the vehicle is not inside the service area.
// The user can override the upload lock with a slider, this will reset this variable to false.
double _phaseDistance; // the lenth in meters of the current phase
double _phaseDuration; // the phase duration in seconds
};
......@@ -231,7 +231,7 @@ bool WimaPlaner::updateMission()
_circularSurvey->setRefPoint(_measurementArea.center());
_lastSurveyRefPoint = _measurementArea.center();
_surveyRefChanging = false;
_circularSurvey->setAutoGenerated(true); // prevents reinitialisation from gui
_circularSurvey->setIsInitialized(true); // prevents reinitialisation from gui
connect(_circularSurvey->deltaR(), &Fact::rawValueChanged, this, &WimaPlaner::calcArrivalAndReturnPath);
connect(_circularSurvey->deltaAlpha(), &Fact::rawValueChanged, this, &WimaPlaner::calcArrivalAndReturnPath);
connect(_circularSurvey->isSnakePath(), &Fact::rawValueChanged, this, &WimaPlaner::calcArrivalAndReturnPath);
......@@ -433,7 +433,7 @@ bool WimaPlaner::loadFromFile(const QString &filename)
_lastSurveyRefPoint = _circularSurvey->refPoint();
_surveyRefChanging = false;
_circularSurvey->setAutoGenerated(true); // prevents reinitialisation from gui
_circularSurvey->setIsInitialized(true); // prevents reinitialisation from gui
connect(_circularSurvey->deltaR(), &Fact::rawValueChanged, this, &WimaPlaner::calcArrivalAndReturnPath);
connect(_circularSurvey->deltaAlpha(), &Fact::rawValueChanged, this, &WimaPlaner::calcArrivalAndReturnPath);
connect(_circularSurvey->isSnakePath(), &Fact::rawValueChanged, this, &WimaPlaner::calcArrivalAndReturnPath);
......@@ -553,7 +553,7 @@ bool WimaPlaner::calcArrivalAndReturnPath()
qgcApp()->showMessage( QString(tr("Not able to calculate the path from takeoff position to measurement area.")).toLocal8Bit().data());
return false;
}
_arrivalPathLength = path.size()-1; // -1: last item is first measurement point
_arrivalPathLength = path.size()-1;
int sequenceNumber = 0;
for (int i = 1; i < path.count()-1; i++) {
sequenceNumber = _missionController->insertSimpleMissionItem(path.value(i), missionItems->count()-1);
......@@ -596,6 +596,10 @@ bool WimaPlaner::calcArrivalAndReturnPath()
bool WimaPlaner::recalcJoinedArea()
{
setJoinedAreaValid(false);
// check if at least service area and measurement area are available
if (_visualItems.indexOf(&_serviceArea) == -1 || _visualItems.indexOf(&_measurementArea) == -1)
return false;
// check if area paths form simple polygons
if ( !_serviceArea.isSimplePolygon() ) {
qgcApp()->showMessage(tr("Service area is self intersecting and thus not a simple polygon. Only simple polygons allowed.\n"));
......@@ -744,7 +748,10 @@ void WimaPlaner::updateTimerSlot()
// Check if parameter has changed, wait until it stops changing, update mission
// circular survey reference point
if (_circularSurvey != nullptr) {
if (_missionController != nullptr
&& _missionController->visualItems()->indexOf(_circularSurvey) != -1
&& _circularSurvey != nullptr)
{
if (_surveyRefChanging) {
if (_circularSurvey->refPoint() == _lastSurveyRefPoint) { // is it still changing?
calcArrivalAndReturnPath();
......@@ -791,7 +798,9 @@ void WimaPlaner::updateTimerSlot()
// update old values
if (_circularSurvey != nullptr)
if (_missionController != nullptr
&& _missionController->visualItems()->indexOf(_circularSurvey) != -1
&& _circularSurvey != nullptr)
_lastSurveyRefPoint = _circularSurvey->refPoint();
_lastMeasurementAreaPath = _measurementArea.path();
......
......@@ -90,8 +90,9 @@ Item {
}
Component.onCompleted: {
if ( !_missionItem.autoGenerated ) {
_addInitialPolygon()
if ( !_missionItem.isInitialized ) {
_addInitialPolygon()
_missionItem.isInitialized = true // set isInitialized to true, to trigger _rebuildTransectsPhase1 in the last line
_setRefPoint()
}
_addVisualElements()
......
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