Browse Source

Merge pull request #6404 from DonLakeFlyer/TransectStyle

Convert Survey complex item to use TransectStyleComplexItem
QGC4.4
Don Gagne 7 years ago committed by GitHub
parent
commit
bc17fe15ce
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 4
      src/MissionManager/CameraSpec.cc
  2. 4
      src/MissionManager/CorridorScanComplexItem.cc
  3. 5
      src/MissionManager/CorridorScanComplexItem.h
  4. 23
      src/MissionManager/MissionController.cc
  5. 1161
      src/MissionManager/SurveyComplexItem.cc
  6. 276
      src/MissionManager/SurveyComplexItem.h
  7. 149
      src/MissionManager/SurveyComplexItemTest.cc
  8. 39
      src/MissionManager/SurveyComplexItemTest.h
  9. 27
      src/MissionManager/TransectStyleComplexItem.cc
  10. 11
      src/MissionManager/TransectStyleComplexItem.h
  11. 14
      src/PlanView/CorridorScanEditor.qml
  12. 747
      src/PlanView/SurveyItemEditor.qml
  13. 16
      src/PlanView/SurveyMapVisual.qml

4
src/MissionManager/CameraSpec.cc

@ -121,8 +121,8 @@ bool CameraSpec::load(const QJsonObject& json, QString& errorString) @@ -121,8 +121,8 @@ bool CameraSpec::load(const QJsonObject& json, QString& errorString)
_sensorWidthFact.setRawValue (json[_sensorWidthName].toDouble());
_sensorHeightFact.setRawValue (json[_sensorHeightName].toDouble());
_imageWidthFact.setRawValue (json[_imageWidthName].toDouble());
_imageHeightFact.setRawValue (json[_imageHeightName].toDouble());
_imageWidthFact.setRawValue (json[_imageWidthName].toInt());
_imageHeightFact.setRawValue (json[_imageHeightName].toInt());
_focalLengthFact.setRawValue (json[_focalLengthName].toDouble());
_landscapeFact.setRawValue (json[_landscapeName].toBool());
_fixedOrientationFact.setRawValue (json[_fixedOrientationName].toBool());

4
src/MissionManager/CorridorScanComplexItem.cc

@ -64,10 +64,6 @@ void CorridorScanComplexItem::save(QJsonArray& planItems) @@ -64,10 +64,6 @@ void CorridorScanComplexItem::save(QJsonArray& planItems)
saveObject[corridorWidthName] = _corridorWidthFact.rawValue().toDouble();
saveObject[_jsonEntryPointKey] = _entryPoint;
QJsonObject cameraCalcObject;
_cameraCalc.save(cameraCalcObject);
saveObject[_jsonCameraCalcKey] = cameraCalcObject;
_corridorPolyline.saveToJson(saveObject);
planItems.append(saveObject);

5
src/MissionManager/CorridorScanComplexItem.h

@ -15,7 +15,6 @@ @@ -15,7 +15,6 @@
#include "QGCLoggingCategory.h"
#include "QGCMapPolyline.h"
#include "QGCMapPolygon.h"
#include "CameraCalc.h"
Q_DECLARE_LOGGING_CATEGORY(CorridorScanComplexItemLog)
@ -26,7 +25,6 @@ class CorridorScanComplexItem : public TransectStyleComplexItem @@ -26,7 +25,6 @@ class CorridorScanComplexItem : public TransectStyleComplexItem
public:
CorridorScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)
@ -46,6 +44,9 @@ public: @@ -46,6 +44,9 @@ public:
void applyNewAltitude (double newAltitude) final;
// Overrides from VisualMissionionItem
QString commandDescription (void) const final { return tr("Corridor Scan"); }
QString commandName (void) const final { return tr("Corridor Scan"); }
QString abbreviation (void) const final { return tr("C"); }
bool readyForSave (void) const;
static const char* jsonComplexItemTypeValue;

23
src/MissionManager/MissionController.cc

@ -265,25 +265,21 @@ bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMission @@ -265,25 +265,21 @@ bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMission
void MissionController::convertToKMLDocument(QDomDocument& document)
{
QJsonObject missionJson;
QmlObjectListModel* visualItems = new QmlObjectListModel();
QList<MissionItem*> missionItems;
QString error;
save(missionJson);
_loadItemsFromJson(missionJson, visualItems, error);
_convertToMissionItems(visualItems, missionItems, this);
if (missionItems.count() == 0) {
QObject* deleteParent = new QObject();
QList<MissionItem*> rgMissionItems;
_convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
if (rgMissionItems.count() == 0) {
return;
}
float homeAltitude = missionJson[_jsonPlannedHomePositionKey].toArray()[2].toDouble();
const double homePositionAltitude = _settingsItem->coordinate().altitude();
QString coord;
QStringList coords;
// Drop home position
bool dropPoint = true;
for(const auto& item : missionItems) {
for(const auto& item : rgMissionItems) {
if(dropPoint) {
dropPoint = false;
continue;
@ -292,7 +288,7 @@ void MissionController::convertToKMLDocument(QDomDocument& document) @@ -292,7 +288,7 @@ void MissionController::convertToKMLDocument(QDomDocument& document)
qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homeAltitude);
double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
coord = QString::number(item->param6(),'f',7) \
+ "," \
+ QString::number(item->param5(),'f',7) \
@ -301,6 +297,9 @@ void MissionController::convertToKMLDocument(QDomDocument& document) @@ -301,6 +297,9 @@ void MissionController::convertToKMLDocument(QDomDocument& document)
coords.append(coord);
}
}
deleteParent->deleteLater();
Kml kml;
kml.points(coords);
kml.save(document);

1161
src/MissionManager/SurveyComplexItem.cc

File diff suppressed because it is too large Load Diff

276
src/MissionManager/SurveyComplexItem.h

@ -9,126 +9,41 @@ @@ -9,126 +9,41 @@
#pragma once
#include "ComplexMissionItem.h"
#include "TransectStyleComplexItem.h"
#include "MissionItem.h"
#include "SettingsFact.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
Q_DECLARE_LOGGING_CATEGORY(SurveyComplexItemLog)
class SurveyComplexItem : public ComplexMissionItem
class SurveyComplexItem : public TransectStyleComplexItem
{
Q_OBJECT
public:
SurveyComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(Fact* gridAltitude READ gridAltitude CONSTANT)
Q_PROPERTY(Fact* gridAltitudeRelative READ gridAltitudeRelative CONSTANT)
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* gridSpacing READ gridSpacing CONSTANT)
Q_PROPERTY(Fact* gridEntryLocation READ gridEntryLocation CONSTANT)
Q_PROPERTY(Fact* turnaroundDist READ turnaroundDist CONSTANT)
Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT)
Q_PROPERTY(Fact* cameraTriggerInTurnaround READ cameraTriggerInTurnaround CONSTANT)
Q_PROPERTY(Fact* hoverAndCapture READ hoverAndCapture CONSTANT)
Q_PROPERTY(Fact* groundResolution READ groundResolution CONSTANT)
Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT)
Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
Q_PROPERTY(Fact* cameraSensorWidth READ cameraSensorWidth CONSTANT)
Q_PROPERTY(Fact* cameraSensorHeight READ cameraSensorHeight CONSTANT)
Q_PROPERTY(Fact* cameraResolutionWidth READ cameraResolutionWidth CONSTANT)
Q_PROPERTY(Fact* cameraResolutionHeight READ cameraResolutionHeight CONSTANT)
Q_PROPERTY(Fact* cameraFocalLength READ cameraFocalLength CONSTANT)
Q_PROPERTY(Fact* cameraOrientationLandscape READ cameraOrientationLandscape CONSTANT)
Q_PROPERTY(Fact* fixedValueIsAltitude READ fixedValueIsAltitude CONSTANT)
Q_PROPERTY(Fact* manualGrid READ manualGrid CONSTANT)
Q_PROPERTY(Fact* camera READ camera CONSTANT)
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* gridEntryLocation READ gridEntryLocation CONSTANT)
Q_PROPERTY(bool cameraOrientationFixed MEMBER _cameraOrientationFixed NOTIFY cameraOrientationFixedChanged)
Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
Q_PROPERTY(bool refly90Degrees READ refly90Degrees WRITE setRefly90Degrees NOTIFY refly90DegreesChanged)
Q_PROPERTY(double cameraMinTriggerInterval MEMBER _cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
QVariantList gridPoints (void) { return _simpleGridPoints; }
Fact* manualGrid (void) { return &_manualGridFact; }
Fact* gridAltitude (void) { return &_gridAltitudeFact; }
Fact* gridAltitudeRelative (void) { return &_gridAltitudeRelativeFact; }
Fact* gridAngle (void) { return &_gridAngleFact; }
Fact* gridSpacing (void) { return &_gridSpacingFact; }
Fact* gridEntryLocation (void) { return &_gridEntryLocationFact; }
Fact* turnaroundDist (void) { return &_turnaroundDistFact; }
Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; }
Fact* cameraTriggerInTurnaround (void) { return &_cameraTriggerInTurnaroundFact; }
Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; }
Fact* groundResolution (void) { return &_groundResolutionFact; }
Fact* frontalOverlap (void) { return &_frontalOverlapFact; }
Fact* sideOverlap (void) { return &_sideOverlapFact; }
Fact* cameraSensorWidth (void) { return &_cameraSensorWidthFact; }
Fact* cameraSensorHeight (void) { return &_cameraSensorHeightFact; }
Fact* cameraResolutionWidth (void) { return &_cameraResolutionWidthFact; }
Fact* cameraResolutionHeight (void) { return &_cameraResolutionHeightFact; }
Fact* cameraFocalLength (void) { return &_cameraFocalLengthFact; }
Fact* cameraOrientationLandscape(void) { return &_cameraOrientationLandscapeFact; }
Fact* fixedValueIsAltitude (void) { return &_fixedValueIsAltitudeFact; }
Fact* camera (void) { return &_cameraFact; }
int cameraShots (void) const;
double coveredArea (void) const { return _coveredArea; }
double timeBetweenShots (void) const;
bool hoverAndCaptureAllowed (void) const;
bool refly90Degrees (void) const { return _refly90Degrees; }
QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
void setRefly90Degrees(bool refly90Degrees);
Fact* gridAngle (void) { return &_gridAngleFact; }
Fact* gridEntryLocation (void) { return &_gridEntryLocationFact; }
// Overrides from ComplexMissionItem
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); }
double complexDistance (void) const final { return _surveyDistance; }
double additionalTimeDelay (void) const final { return _additionalFlightDelaySeconds; }
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); }
// Overrides from VisualMissionItem
// Overrides from TransectStyleComplexItem
void save (QJsonArray& planItems) final;
bool specifiesCoordinate (void) const final { return true; }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesCoordinate (void) const final;
bool specifiesAltitudeOnly (void) const final { return false; }
QString commandDescription (void) const final { return "Survey"; }
QString commandName (void) const final { return "Survey"; }
QString abbreviation (void) const final { return "S"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void applyNewAltitude (double newAltitude) final;
bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final;
void setSequenceNumber (int sequenceNumber) final;
void setTurnaroundDist (double dist) { _turnaroundDistFact.setRawValue(dist); }
void save (QJsonArray& missionItems) final;
// Overrides from VisualMissionionItem
QString commandDescription (void) const final { return tr("Survey"); }
QString commandName (void) const final { return tr("Survey"); }
QString abbreviation (void) const final { return tr("S"); }
bool readyForSave (void) const final;
// Must match json spec for GridEntryLocation
enum EntryLocation {
@ -139,46 +54,19 @@ public: @@ -139,46 +54,19 @@ public:
};
static const char* jsonComplexItemTypeValue;
static const char* settingsGroup;
static const char* manualGridName;
static const char* gridAltitudeName;
static const char* gridAltitudeRelativeName;
static const char* gridAngleName;
static const char* gridSpacingName;
static const char* gridEntryLocationName;
static const char* turnaroundDistName;
static const char* cameraTriggerDistanceName;
static const char* cameraTriggerInTurnaroundName;
static const char* hoverAndCaptureName;
static const char* groundResolutionName;
static const char* frontalOverlapName;
static const char* sideOverlapName;
static const char* cameraSensorWidthName;
static const char* cameraSensorHeightName;
static const char* cameraResolutionWidthName;
static const char* cameraResolutionHeightName;
static const char* cameraFocalLengthName;
static const char* cameraTriggerName;
static const char* cameraOrientationLandscapeName;
static const char* fixedValueIsAltitudeName;
static const char* cameraName;
static const char* jsonV3ComplexItemTypeValue;
signals:
void gridPointsChanged (void);
void cameraShotsChanged (int cameraShots);
void coveredAreaChanged (double coveredArea);
void cameraValueChanged (void);
void gridTypeChanged (QString gridType);
void timeBetweenShotsChanged (void);
void cameraOrientationFixedChanged (bool cameraOrientationFixed);
void refly90DegreesChanged (bool refly90Degrees);
void cameraMinTriggerIntervalChanged (double cameraMinTriggerInterval);
void refly90DegreesChanged(bool refly90Degrees);
private slots:
void _setDirty(void);
void _polygonDirtyChanged(bool dirty);
void _clearInternal(void);
// Overrides from TransectStyleComplexItem
void _rebuildTransectsPhase1(void) final;
void _rebuildTransectsPhase2(void) final;
private:
enum CameraTriggerCode {
@ -188,30 +76,14 @@ private: @@ -188,30 +76,14 @@ private:
CameraTriggerHoverAndCapture
};
void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _generateGrid(void);
void _updateCoordinateAltitude(void);
int _gridGenerator(const QList<QPointF>& polygonPoints, QList<QList<QPointF>>& transectSegments, bool refly);
QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle);
void _intersectLinesWithRect(const QList<QLineF>& lineList, const QRectF& boundRect, QList<QLineF>& resultLines);
void _intersectLinesWithPolygon(const QList<QLineF>& lineList, const QPolygonF& polygon, QList<QLineF>& resultLines);
void _adjustLineDirection(const QList<QLineF>& lineList, QList<QLineF>& resultLines);
void _setSurveyDistance(double surveyDistance);
void _setCameraShots(int cameraShots);
void _setCoveredArea(double coveredArea);
void _cameraValueChanged(void);
int _appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent);
bool _nextTransectCoord(const QList<QGeoCoordinate>& transectPoints, int pointIndex, QGeoCoordinate& coord);
double _triggerDistance(void) const;
bool _triggerCamera(void) const;
bool _imagesEverywhere(void) const;
bool _hoverAndCaptureEnabled(void) const;
bool _hasTurnaround(void) const;
double _turnaroundDistance(void) const;
void _convertTransectToGeo(const QList<QList<QPointF>>& transectSegmentsNED, const QGeoCoordinate& tangentOrigin, QList<QList<QGeoCoordinate>>& transectSegmentsGeo);
bool _appendMissionItemsWorker(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, bool hasRefly, bool buildRefly);
void _optimizeTransectsForShortestDistance(const QGeoCoordinate& distanceCoord, QList<QList<QGeoCoordinate>>& transects);
void _appendGridPointsFromTransects(QList<QList<QGeoCoordinate>>& rgTransectSegments);
qreal _ccw(QPointF pt1, QPointF pt2, QPointF pt3);
qreal _dp(QPointF pt1, QPointF pt2);
void _swapPoints(QList<QPointF>& points, int index1, int index2);
@ -220,78 +92,50 @@ private: @@ -220,78 +92,50 @@ private:
void _adjustTransectsToEntryPointLocation(QList<QList<QGeoCoordinate>>& transects);
bool _gridAngleIsNorthSouthTransects();
double _clampGridAngle90(double gridAngle);
int _calcMissionCommandCount(QList<QList<QGeoCoordinate>>& transectSegments);
int _sequenceNumber;
bool _dirty;
QGCMapPolygon _mapPolygon;
QVariantList _simpleGridPoints; ///< Grid points for drawing simple grid visuals
QList<QList<QGeoCoordinate>> _transectSegments; ///< Internal transect segments including grid exit, turnaround and internal camera points
QList<QList<QGeoCoordinate>> _reflyTransectSegments; ///< Refly segments
QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate;
bool _cameraOrientationFixed;
int _missionCommandCount;
bool _refly90Degrees;
double _additionalFlightDelaySeconds;
double _cameraMinTriggerInterval;
bool _ignoreRecalc;
double _surveyDistance;
int _cameraShots;
double _coveredArea;
double _timeBetweenShots;
double _cruiseSpeed;
void _buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent);
void _appendLoadedMissionItems (QList<MissionItem*>& items, QObject* missionItemParent);
bool _imagesEverywhere(void) const;
bool _triggerCamera(void) const;
bool _hasTurnaround(void) const;
double _turnaroundDistance(void) const;
bool _hoverAndCaptureEnabled(void) const;
bool _loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString);
bool _loadV4(const QJsonObject& complexObject, int sequenceNumber, QString& errorString);
QMap<QString, FactMetaData*> _metaDataMap;
SettingsFact _manualGridFact;
SettingsFact _gridAltitudeFact;
SettingsFact _gridAltitudeRelativeFact;
SettingsFact _gridAngleFact;
SettingsFact _gridSpacingFact;
SettingsFact _gridEntryLocationFact;
SettingsFact _turnaroundDistFact;
SettingsFact _cameraTriggerDistanceFact;
SettingsFact _cameraTriggerInTurnaroundFact;
SettingsFact _hoverAndCaptureFact;
SettingsFact _groundResolutionFact;
SettingsFact _frontalOverlapFact;
SettingsFact _sideOverlapFact;
SettingsFact _cameraSensorWidthFact;
SettingsFact _cameraSensorHeightFact;
SettingsFact _cameraResolutionWidthFact;
SettingsFact _cameraResolutionHeightFact;
SettingsFact _cameraFocalLengthFact;
SettingsFact _cameraOrientationLandscapeFact;
SettingsFact _fixedValueIsAltitudeFact;
SettingsFact _cameraFact;
static const char* _jsonGridObjectKey;
static const char* _jsonGridAltitudeKey;
static const char* _jsonGridAltitudeRelativeKey;
static const char* _jsonGridAngleKey;
static const char* _jsonGridSpacingKey;
static const char* _jsonGridEntryLocationKey;
static const char* _jsonTurnaroundDistKey;
static const char* _jsonCameraTriggerDistanceKey;
static const char* _jsonCameraTriggerInTurnaroundKey;
static const char* _jsonHoverAndCaptureKey;
static const char* _jsonGroundResolutionKey;
static const char* _jsonFrontalOverlapKey;
static const char* _jsonSideOverlapKey;
static const char* _jsonCameraSensorWidthKey;
static const char* _jsonCameraSensorHeightKey;
static const char* _jsonCameraResolutionWidthKey;
static const char* _jsonCameraResolutionHeightKey;
static const char* _jsonCameraFocalLengthKey;
static const char* _jsonCameraMinTriggerIntervalKey;
static const char* _jsonManualGridKey;
static const char* _jsonCameraObjectKey;
static const char* _jsonCameraNameKey;
static const char* _jsonCameraOrientationLandscapeKey;
static const char* _jsonFixedValueIsAltitudeKey;
static const char* _jsonRefly90DegreesKey;
static const char* _jsonV3GridObjectKey;
static const char* _jsonV3GridAltitudeKey;
static const char* _jsonV3GridAltitudeRelativeKey;
static const char* _jsonV3GridAngleKey;
static const char* _jsonV3GridSpacingKey;
static const char* _jsonV3GridEntryLocationKey;
static const char* _jsonV3TurnaroundDistKey;
static const char* _jsonV3CameraTriggerDistanceKey;
static const char* _jsonV3CameraTriggerInTurnaroundKey;
static const char* _jsonV3HoverAndCaptureKey;
static const char* _jsonV3GroundResolutionKey;
static const char* _jsonV3FrontalOverlapKey;
static const char* _jsonV3SideOverlapKey;
static const char* _jsonV3CameraSensorWidthKey;
static const char* _jsonV3CameraSensorHeightKey;
static const char* _jsonV3CameraResolutionWidthKey;
static const char* _jsonV3CameraResolutionHeightKey;
static const char* _jsonV3CameraFocalLengthKey;
static const char* _jsonV3CameraMinTriggerIntervalKey;
static const char* _jsonV3ManualGridKey;
static const char* _jsonV3CameraObjectKey;
static const char* _jsonV3CameraNameKey;
static const char* _jsonV3CameraOrientationLandscapeKey;
static const char* _jsonV3FixedValueIsAltitudeKey;
static const char* _jsonV3Refly90DegreesKey;
static const int _hoverAndCaptureDelaySeconds = 4;
};

149
src/MissionManager/SurveyComplexItemTest.cc

@ -21,21 +21,18 @@ void SurveyComplexItemTest::init(void) @@ -21,21 +21,18 @@ void SurveyComplexItemTest::init(void)
{
UnitTest::init();
_rgSurveySignals[gridPointsChangedIndex] = SIGNAL(gridPointsChanged());
_rgSurveySignals[cameraShotsChangedIndex] = SIGNAL(cameraShotsChanged(int));
_rgSurveySignals[coveredAreaChangedIndex] = SIGNAL(coveredAreaChanged(double));
_rgSurveySignals[cameraValueChangedIndex] = SIGNAL(cameraValueChanged());
_rgSurveySignals[gridTypeChangedIndex] = SIGNAL(gridTypeChanged(QString));
_rgSurveySignals[timeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSurveySignals[cameraOrientationFixedChangedIndex] = SIGNAL(cameraOrientationFixedChanged(bool));
_rgSurveySignals[refly90DegreesChangedIndex] = SIGNAL(refly90DegreesChanged(bool));
_rgSurveySignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_rgSurveySignals[surveyVisualTransectPointsChangedIndex] = SIGNAL(visualTransectPointsChanged());
_rgSurveySignals[surveyCameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
_rgSurveySignals[surveyCoveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
_rgSurveySignals[surveyTimeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSurveySignals[surveyRefly90DegreesChangedIndex] = SIGNAL(refly90DegreesChanged(bool));
_rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_surveyItem = new SurveyComplexItem(_offlineVehicle, this);
_surveyItem->setTurnaroundDist(0); // Unit test written for no turnaround distance
_surveyItem->turnAroundDistance()->setRawValue(0); // Unit test written for no turnaround distance
_surveyItem->setDirty(false);
_mapPolygon = _surveyItem->mapPolygon();
_mapPolygon = _surveyItem->surveyAreaPolygon();
// It's important to check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
@ -62,20 +59,19 @@ void SurveyComplexItemTest::_testDirty(void) @@ -62,20 +59,19 @@ void SurveyComplexItemTest::_testDirty(void)
_surveyItem->setDirty(true);
QVERIFY(_surveyItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
_multiSpy->clearAllSignals();
_surveyItem->setDirty(false);
QVERIFY(!_surveyItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(!_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
QVERIFY(!_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
_multiSpy->clearAllSignals();
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _surveyItem->gridAltitude() << _surveyItem->gridAngle() << _surveyItem->gridSpacing() << _surveyItem->turnaroundDist() << _surveyItem->cameraTriggerDistance() <<
_surveyItem->gridAltitudeRelative() << _surveyItem->cameraTriggerInTurnaround() << _surveyItem->hoverAndCapture();
rgFacts << _surveyItem->gridAngle() << _surveyItem->gridEntryLocation();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
QVERIFY(!_surveyItem->dirty());
@ -84,101 +80,12 @@ void SurveyComplexItemTest::_testDirty(void) @@ -84,101 +80,12 @@ void SurveyComplexItemTest::_testDirty(void)
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpy->checkSignalByMask(surveyDirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
}
rgFacts.clear();
// These facts should not change dirty bit
rgFacts << _surveyItem->groundResolution() << _surveyItem->frontalOverlap() << _surveyItem->sideOverlap() << _surveyItem->cameraSensorWidth() << _surveyItem->cameraSensorHeight() <<
_surveyItem->cameraResolutionWidth() << _surveyItem->cameraResolutionHeight() << _surveyItem->cameraFocalLength() << _surveyItem->cameraOrientationLandscape() <<
_surveyItem->fixedValueIsAltitude() << _surveyItem->camera() << _surveyItem->manualGrid();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
QVERIFY(!_surveyItem->dirty());
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkNoSignalByMask(dirtyChangedMask));
QVERIFY(!_surveyItem->dirty());
_multiSpy->clearAllSignals();
}
rgFacts.clear();
}
void SurveyComplexItemTest::_testCameraValueChanged(void)
{
// These facts should trigger cameraValueChanged when changed
QList<Fact*> rgFacts;
rgFacts << _surveyItem->groundResolution() << _surveyItem->frontalOverlap() << _surveyItem->sideOverlap() << _surveyItem->cameraSensorWidth() << _surveyItem->cameraSensorHeight() <<
_surveyItem->cameraResolutionWidth() << _surveyItem->cameraResolutionHeight() << _surveyItem->cameraFocalLength() << _surveyItem->cameraOrientationLandscape();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkSignalByMask(cameraValueChangedMask));
_multiSpy->clearAllSignals();
}
rgFacts.clear();
// These facts should not trigger cameraValueChanged
rgFacts << _surveyItem->gridAltitude() << _surveyItem->gridAngle() << _surveyItem->gridSpacing() << _surveyItem->turnaroundDist() << _surveyItem->cameraTriggerDistance() <<
_surveyItem->gridAltitudeRelative() << _surveyItem->cameraTriggerInTurnaround() << _surveyItem->hoverAndCapture() <<
_surveyItem->fixedValueIsAltitude() << _surveyItem->camera() << _surveyItem->manualGrid();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkNoSignalByMask(cameraValueChangedMask));
_multiSpy->clearAllSignals();
}
rgFacts.clear();
}
void SurveyComplexItemTest::_testCameraTrigger(void)
{
#if 0
QCOMPARE(_surveyItem->property("cameraTrigger").toBool(), true);
// Set up a grid
for (int i=0; i<3; i++) {
_mapPolygon->appendVertex(_polyPoints[i]);
}
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
int lastSeq = _surveyItem->lastSequenceNumber();
QVERIFY(lastSeq > 0);
// Turning off camera triggering should remove two camera trigger mission items, this should trigger:
// lastSequenceNumberChanged
// dirtyChanged
_surveyItem->setProperty("cameraTrigger", false);
QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq - 2);
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
// Turn on camera triggering and make sure things go back to previous count
_surveyItem->setProperty("cameraTrigger", true);
QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq);
#endif
}
// Clamp expected grid angle from 0<->180. We don't care about opposite angles like 90/270
@ -215,7 +122,7 @@ void SurveyComplexItemTest::_testGridAngle(void) @@ -215,7 +122,7 @@ void SurveyComplexItemTest::_testGridAngle(void)
for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
_surveyItem->gridAngle()->setRawValue(gridAngle);
QVariantList gridPoints = _surveyItem->gridPoints();
QVariantList gridPoints = _surveyItem->visualTransectPoints();
QGeoCoordinate firstTransectEntry = gridPoints[0].value<QGeoCoordinate>();
QGeoCoordinate firstTransectExit = gridPoints[1].value<QGeoCoordinate>();
double azimuth = firstTransectEntry.azimuthTo(firstTransectExit);
@ -258,30 +165,30 @@ void SurveyComplexItemTest::_testItemCount(void) @@ -258,30 +165,30 @@ void SurveyComplexItemTest::_testItemCount(void)
_setPolygon();
_surveyItem->hoverAndCapture()->setRawValue(false);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(false);
_surveyItem->setRefly90Degrees(false);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
_surveyItem->refly90Degrees()->setRawValue(false);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
_surveyItem->hoverAndCapture()->setRawValue(false);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(true);
_surveyItem->setRefly90Degrees(false);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(true);
_surveyItem->refly90Degrees()->setRawValue(false);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
_surveyItem->hoverAndCapture()->setRawValue(true);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(false);
_surveyItem->setRefly90Degrees(false);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
_surveyItem->refly90Degrees()->setRawValue(false);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
_surveyItem->hoverAndCapture()->setRawValue(true);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(false);
_surveyItem->setRefly90Degrees(true);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
_surveyItem->refly90Degrees()->setRawValue(true);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
}

39
src/MissionManager/SurveyComplexItemTest.h

@ -30,42 +30,37 @@ protected: @@ -30,42 +30,37 @@ protected:
private slots:
void _testDirty(void);
void _testCameraValueChanged(void);
void _testCameraTrigger(void);
void _testGridAngle(void);
void _testEntryLocation(void);
void _testItemCount(void);
private:
double _clampGridAngle180(double gridAngle);
void _setPolygon(void);
// SurveyComplexItem signals
enum {
gridPointsChangedIndex = 0,
cameraShotsChangedIndex,
coveredAreaChangedIndex,
cameraValueChangedIndex,
gridTypeChangedIndex,
timeBetweenShotsChangedIndex,
cameraOrientationFixedChangedIndex,
refly90DegreesChangedIndex,
dirtyChangedIndex,
maxSignalIndex
surveyVisualTransectPointsChangedIndex = 0,
surveyCameraShotsChangedIndex,
surveyCoveredAreaChangedIndex,
surveyTimeBetweenShotsChangedIndex,
surveyRefly90DegreesChangedIndex,
surveyDirtyChangedIndex,
surveyMaxSignalIndex
};
enum {
gridPointsChangedMask = 1 << gridPointsChangedIndex,
cameraShotsChangedMask = 1 << cameraShotsChangedIndex,
coveredAreaChangedMask = 1 << coveredAreaChangedIndex,
cameraValueChangedMask = 1 << cameraValueChangedIndex,
gridTypeChangedMask = 1 << gridTypeChangedIndex,
timeBetweenShotsChangedMask = 1 << timeBetweenShotsChangedIndex,
cameraOrientationFixedChangedMask = 1 << cameraOrientationFixedChangedIndex,
refly90DegreesChangedMask = 1 << refly90DegreesChangedIndex,
dirtyChangedMask = 1 << dirtyChangedIndex
surveyVisualTransectPointsChangedMask = 1 << surveyVisualTransectPointsChangedIndex,
surveyCameraShotsChangedMask = 1 << surveyCameraShotsChangedIndex,
surveyCoveredAreaChangedMask = 1 << surveyCoveredAreaChangedIndex,
surveyTimeBetweenShotsChangedMask = 1 << surveyTimeBetweenShotsChangedIndex,
surveyRefly90DegreesChangedMask = 1 << surveyRefly90DegreesChangedIndex,
surveyDirtyChangedMask = 1 << surveyDirtyChangedIndex
};
static const size_t _cSurveySignals = maxSignalIndex;
static const size_t _cSurveySignals = surveyMaxSignalIndex;
const char* _rgSurveySignals[_cSurveySignals];
Vehicle* _offlineVehicle;

27
src/MissionManager/TransectStyleComplexItem.cc

@ -101,8 +101,13 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString set @@ -101,8 +101,13 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString set
connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::coveredAreaChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &TransectStyleComplexItem::coordinateHasRelativeAltitudeChanged);
connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &TransectStyleComplexItem::exitCoordinateHasRelativeAltitudeChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_followTerrainChanged);
}
void TransectStyleComplexItem::_setCameraShots(int cameraShots)
@ -693,3 +698,21 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const @@ -693,3 +698,21 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
}
}
bool TransectStyleComplexItem::coordinateHasRelativeAltitude(void) const
{
return _cameraCalc.distanceToSurfaceRelative();
}
bool TransectStyleComplexItem::exitCoordinateHasRelativeAltitude(void) const
{
return coordinateHasRelativeAltitude();
}
void TransectStyleComplexItem::_followTerrainChanged(bool followTerrain)
{
if (followTerrain) {
_cameraCalc.setDistanceToSurfaceRelative(false);
_refly90DegreesFact.setRawValue(false);
_hoverAndCaptureFact.setRawValue(false);
}
}

11
src/MissionManager/TransectStyleComplexItem.h

@ -87,9 +87,6 @@ public: @@ -87,9 +87,6 @@ public:
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesAltitudeOnly (void) const final { return false; }
QString commandDescription (void) const final { return tr("Corridor Scan"); }
QString commandName (void) const final { return tr("Corridor Scan"); }
QString abbreviation (void) const final { return "S"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
@ -98,9 +95,12 @@ public: @@ -98,9 +95,12 @@ public:
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const override;
QString commandDescription (void) const override { return tr("Transect"); }
QString commandName (void) const override { return tr("Transect"); }
QString abbreviation (void) const override { return tr("T"); }
bool coordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
bool coordinateHasRelativeAltitude (void) const final;
bool exitCoordinateHasRelativeAltitude (void) const final;
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
@ -200,6 +200,7 @@ protected: @@ -200,6 +200,7 @@ protected:
private slots:
void _reallyQueryTransectsPathHeightInfo(void);
void _followTerrainChanged (bool followTerrain);
private:
void _queryTransectsPathHeightInfo (void);

14
src/PlanView/CorridorScanEditor.qml

@ -13,7 +13,6 @@ import QGroundControl.FactControls 1.0 @@ -13,7 +13,6 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Survery mission items
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
@ -57,11 +56,6 @@ Rectangle { @@ -57,11 +56,6 @@ Rectangle {
spacing: _margin
QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
}
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1))
@ -115,7 +109,7 @@ Rectangle { @@ -115,7 +109,7 @@ Rectangle {
anchors.left: parent.left
text: qsTr("Relative altitude")
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
Layout.columnSpan: 2
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
@ -158,12 +152,6 @@ Rectangle { @@ -158,12 +152,6 @@ Rectangle {
columns: 2
visible: followsTerrainCheckBox.checked
QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
Layout.columnSpan: 2
}
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance

747
src/PlanView/SurveyItemEditor.qml

@ -13,7 +13,6 @@ import QGroundControl.FactControls 1.0 @@ -13,7 +13,6 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Survery mission items
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
@ -25,93 +24,9 @@ Rectangle { @@ -25,93 +24,9 @@ Rectangle {
//property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property int _cameraIndex: 1
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _cameraList: [ qsTr("Manual Grid (no camera specs)"), qsTr("Custom Camera Grid") ]
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property var _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : []
readonly property int _gridTypeManual: 0
readonly property int _gridTypeCustomCamera: 1
readonly property int _gridTypeCamera: 2
Component.onCompleted: {
for (var i=0; i<_vehicle.staticCameraList.length; i++) {
_cameraList.push(_vehicle.staticCameraList[i].name)
}
gridTypeCombo.model = _cameraList
if (missionItem.manualGrid.value) {
gridTypeCombo.currentIndex = _gridTypeManual
} else {
var index = -1
for (index=0; index<_cameraList.length; index++) {
if (_cameraList[index] === missionItem.camera.value) {
break;
}
}
missionItem.cameraOrientationFixed = false
if (index == _cameraList.length) {
gridTypeCombo.currentIndex = _gridTypeCustomCamera
} else {
gridTypeCombo.currentIndex = index
if (index != 1) {
// Specific camera is selected
var camera = _vehicleCameraList[index - _gridTypeCamera]
missionItem.cameraOrientationFixed = camera.fixedOrientation
missionItem.cameraMinTriggerInterval = camera.minTriggerInterval
}
}
}
recalcFromCameraValues()
}
function recalcFromCameraValues() {
var focalLength = missionItem.cameraFocalLength.rawValue
var sensorWidth = missionItem.cameraSensorWidth.rawValue
var sensorHeight = missionItem.cameraSensorHeight.rawValue
var imageWidth = missionItem.cameraResolutionWidth.rawValue
var imageHeight = missionItem.cameraResolutionHeight.rawValue
var altitude = missionItem.gridAltitude.rawValue
var groundResolution= missionItem.groundResolution.rawValue
var frontalOverlap = missionItem.frontalOverlap.rawValue
var sideOverlap = missionItem.sideOverlap.rawValue
if (focalLength <= 0 || sensorWidth <= 0 || sensorHeight <= 0 || imageWidth <= 0 || imageHeight <= 0 || groundResolution <= 0) {
return
}
var imageSizeSideGround //size in side (non flying) direction of the image on the ground
var imageSizeFrontGround //size in front (flying) direction of the image on the ground
var gridSpacing
var cameraTriggerDistance
if (missionItem.fixedValueIsAltitude.value) {
groundResolution = (altitude * sensorWidth * 100) / (imageWidth * focalLength)
} else {
altitude = (imageWidth * groundResolution * focalLength) / (sensorWidth * 100)
}
if (missionItem.cameraOrientationLandscape.value) {
imageSizeSideGround = (imageWidth * groundResolution) / 100
imageSizeFrontGround = (imageHeight * groundResolution) / 100
} else {
imageSizeSideGround = (imageHeight * groundResolution) / 100
imageSizeFrontGround = (imageWidth * groundResolution) / 100
}
gridSpacing = imageSizeSideGround * ( (100-sideOverlap) / 100 )
cameraTriggerDistance = imageSizeFrontGround * ( (100-frontalOverlap) / 100 )
if (missionItem.fixedValueIsAltitude.value) {
missionItem.groundResolution.rawValue = groundResolution
} else {
missionItem.gridAltitude.rawValue = altitude
}
missionItem.gridSpacing.rawValue = gridSpacing
missionItem.cameraTriggerDistance.rawValue = cameraTriggerDistance
}
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
function polygonCaptureStarted() {
missionItem.clearPolygon()
@ -130,52 +45,8 @@ Rectangle { @@ -130,52 +45,8 @@ Rectangle {
function polygonAdjustStarted() { }
function polygonAdjustFinished() { }
property bool _noCameraValueRecalc: false ///< Prevents uneeded recalcs
Connections {
target: missionItem.camera
onValueChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && !_noCameraValueRecalc) {
recalcFromCameraValues()
}
}
}
Connections {
target: missionItem.gridAltitude
onValueChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && missionItem.fixedValueIsAltitude.value && !_noCameraValueRecalc) {
recalcFromCameraValues()
}
}
}
Connections {
target: missionItem
onCameraValueChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && !_noCameraValueRecalc) {
recalcFromCameraValues()
}
}
}
QGCPalette { id: qgcPal; colorGroupEnabled: true }
ExclusiveGroup {
id: cameraOrientationGroup
onCurrentChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera) {
recalcFromCameraValues()
}
}
}
ExclusiveGroup { id: fixedValueGroup }
Column {
id: editorColumn
anchors.margins: _margin
@ -190,352 +61,20 @@ Rectangle { @@ -190,352 +61,20 @@ Rectangle {
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1))
wrapMode: Text.WordWrap
color: qgcPal.warningText
visible: missionItem.manualGrid.value !== true && missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
}
SectionHeader {
id: cameraHeader
text: qsTr("Camera")
showSpacer: false
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: cameraHeader.checked
QGCComboBox {
id: gridTypeCombo
anchors.left: parent.left
anchors.right: parent.right
model: _cameraList
currentIndex: -1
onActivated: {
if (index == _gridTypeManual) {
missionItem.manualGrid.value = true
missionItem.fixedValueIsAltitude.value = true
} else if (index == _gridTypeCustomCamera) {
missionItem.manualGrid.value = false
missionItem.camera.value = gridTypeCombo.textAt(index)
missionItem.cameraOrientationFixed = false
missionItem.cameraMinTriggerInterval = 0
} else {
missionItem.manualGrid.value = false
missionItem.camera.value = gridTypeCombo.textAt(index)
_noCameraValueRecalc = true
var listIndex = index - _gridTypeCamera
missionItem.cameraSensorWidth.rawValue = _vehicleCameraList[listIndex].sensorWidth
missionItem.cameraSensorHeight.rawValue = _vehicleCameraList[listIndex].sensorHeight
missionItem.cameraResolutionWidth.rawValue = _vehicleCameraList[listIndex].imageWidth
missionItem.cameraResolutionHeight.rawValue = _vehicleCameraList[listIndex].imageHeight
missionItem.cameraFocalLength.rawValue = _vehicleCameraList[listIndex].focalLength
missionItem.cameraOrientationLandscape.rawValue = _vehicleCameraList[listIndex].landscape ? 1 : 0
missionItem.cameraOrientationFixed = _vehicleCameraList[listIndex].fixedOrientation
missionItem.cameraMinTriggerInterval = _vehicleCameraList[listIndex].minTriggerInterval
_noCameraValueRecalc = false
recalcFromCameraValues()
}
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: missionItem.manualGrid.value
QGCCheckBox {
id: cameraTriggerDistanceCheckBox
anchors.baseline: cameraTriggerDistanceField.baseline
text: qsTr("Trigger Distance")
checked: missionItem.cameraTriggerDistance.rawValue > 0
onClicked: {
if (checked) {
missionItem.cameraTriggerDistance.value = missionItem.cameraTriggerDistance.defaultValue
} else {
missionItem.cameraTriggerDistance.value = 0
}
}
}
FactTextField {
id: cameraTriggerDistanceField
Layout.fillWidth: true
fact: missionItem.cameraTriggerDistance
enabled: cameraTriggerDistanceCheckBox.checked
}
}
visible: missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
}
// Camera based grid ui
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: gridTypeCombo.currentIndex !== _gridTypeManual
Row {
spacing: _margin
anchors.horizontalCenter: parent.horizontalCenter
visible: !missionItem.cameraOrientationFixed
QGCRadioButton {
width: _editFieldWidth
text: "Landscape"
checked: !!missionItem.cameraOrientationLandscape.value
exclusiveGroup: cameraOrientationGroup
onClicked: missionItem.cameraOrientationLandscape.value = 1
}
QGCRadioButton {
id: cameraOrientationPortrait
text: "Portrait"
checked: !missionItem.cameraOrientationLandscape.value
exclusiveGroup: cameraOrientationGroup
onClicked: missionItem.cameraOrientationLandscape.value = 0
}
}
Column {
id: custCameraCol
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: gridTypeCombo.currentIndex === _gridTypeCustomCamera
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
Item { Layout.fillWidth: true }
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Width")
}
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Height")
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel { text: qsTr("Sensor"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraSensorWidth
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraSensorHeight
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel { text: qsTr("Image"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraResolutionWidth
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraResolutionHeight
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel {
text: qsTr("Focal length")
Layout.fillWidth: true
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraFocalLength
}
}
} // Column - custom camera
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
Item { Layout.fillWidth: true }
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Front Lap")
}
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Side Lap")
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel { text: qsTr("Overlap"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.frontalOverlap
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.sideOverlap
}
}
FactCheckBox {
text: qsTr("Hover and capture image")
fact: missionItem.hoverAndCapture
visible: missionItem.hoverAndCaptureAllowed
onClicked: {
if (checked) {
missionItem.cameraTriggerInTurnaround.rawValue = false
}
}
}
FactCheckBox {
text: qsTr("Take images in turnarounds")
fact: missionItem.cameraTriggerInTurnaround
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true
}
SectionHeader {
id: gridHeader
text: qsTr("Grid")
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: gridHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: gridHeader.checked
QGCLabel {
id: angleText
text: qsTr("Angle")
Layout.fillWidth: true
}
Rectangle {
id: windRoseButton
width: ScreenTools.implicitTextFieldHeight
height: width
color: qgcPal.button
visible: _vehicle ? _vehicle.fixedWing : false
QGCColoredImage {
anchors.fill: parent
source: "/res/wind-rose.svg"
smooth: true
color: qgcPal.buttonText
}
QGCMouseArea {
fillItem: parent
onClicked: {
windRosePie.angle = Number(gridAngleText.text)
var cords = windRoseButton.mapToItem(_root, 0, 0)
windRosePie.popup(cords.x + windRoseButton.width / 2, cords.y + windRoseButton.height / 2)
}
}
}
}
FactTextField {
id: gridAngleText
fact: missionItem.gridAngle
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Turnaround dist") }
FactTextField {
fact: missionItem.turnaroundDist
Layout.fillWidth: true
}
QGCLabel {
text: qsTr("Entry")
}
FactComboBox {
fact: missionItem.gridEntryLocation
indexModel: false
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("Refly at 90 degree offset")
checked: missionItem.refly90Degrees
onClicked: missionItem.refly90Degrees = checked
Layout.columnSpan: 2
}
QGCLabel {
wrapMode: Text.WordWrap
text: qsTr("Select one:")
Layout.preferredWidth: parent.width
Layout.columnSpan: 2
}
QGCRadioButton {
id: fixedAltitudeRadio
text: qsTr("Altitude")
checked: !!missionItem.fixedValueIsAltitude.value
exclusiveGroup: fixedValueGroup
onClicked: missionItem.fixedValueIsAltitude.value = 1
}
FactTextField {
fact: missionItem.gridAltitude
enabled: fixedAltitudeRadio.checked
Layout.fillWidth: true
}
QGCRadioButton {
id: fixedGroundResolutionRadio
text: qsTr("Ground res")
checked: !missionItem.fixedValueIsAltitude.value
exclusiveGroup: fixedValueGroup
onClicked: missionItem.fixedValueIsAltitude.value = 0
}
FactTextField {
fact: missionItem.groundResolution
enabled: fixedGroundResolutionRadio.checked
Layout.fillWidth: true
}
}
CameraCalc {
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true
distanceToSurfaceLabel: qsTr("Altitude")
frontalDistanceLabel: qsTr("Trigger Distance")
sideDistanceLabel: qsTr("Spacing")
}
// Manual grid ui
SectionHeader {
id: manualGridHeader
text: qsTr("Grid")
visible: gridTypeCombo.currentIndex === _gridTypeManual
id: corridorHeader
text: qsTr("Transects")
}
GridLayout {
@ -544,73 +83,25 @@ Rectangle { @@ -544,73 +83,25 @@ Rectangle {
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: manualGridHeader.visible && manualGridHeader.checked
RowLayout {
spacing: _margin
QGCLabel {
id: manualAngleText
text: qsTr("Angle")
Layout.fillWidth: true
}
Rectangle {
id: manualWindRoseButton
width: ScreenTools.implicitTextFieldHeight
height: width
color: qgcPal.button
visible: _vehicle ? _vehicle.fixedWing : false
QGCColoredImage {
anchors.fill: parent
source: "/res/wind-rose.svg"
smooth: true
color: qgcPal.buttonText
}
QGCMouseArea {
fillItem: parent
onClicked: {
windRosePie.angle = Number(gridAngleText.text)
var cords = manualWindRoseButton.mapToItem(_root, 0, 0)
windRosePie.popup(cords.x + manualWindRoseButton.width / 2, cords.y + manualWindRoseButton.height / 2)
}
}
}
}
visible: corridorHeader.checked
QGCLabel { text: qsTr("Angle") }
FactTextField {
id: manualGridAngleText
fact: missionItem.gridAngle
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Spacing") }
FactTextField {
fact: missionItem.gridSpacing
fact: missionItem.gridAngle
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Altitude") }
FactTextField {
fact: missionItem.gridAltitude
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Turnaround dist") }
FactTextField {
fact: missionItem.turnaroundDist
fact: missionItem.turnAroundDistance
Layout.fillWidth: true
}
QGCLabel {
text: qsTr("Entry")
visible: !windRoseButton.visible
}
FactComboBox {
id: gridAngleBox
fact: missionItem.gridEntryLocation
visible: !windRoseButton.visible
indexModel: false
Layout.fillWidth: true
}
@ -619,6 +110,7 @@ Rectangle { @@ -619,6 +110,7 @@ Rectangle {
text: qsTr("Hover and capture image")
fact: missionItem.hoverAndCapture
visible: missionItem.hoverAndCaptureAllowed
enabled: !missionItem.followTerrain
Layout.columnSpan: 2
onClicked: {
if (checked) {
@ -628,174 +120,87 @@ Rectangle { @@ -628,174 +120,87 @@ Rectangle {
}
FactCheckBox {
text: qsTr("Take images in turnarounds")
fact: missionItem.cameraTriggerInTurnaround
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true
text: qsTr("Refly at 90 degree offset")
fact: missionItem.refly90Degrees
enabled: !missionItem.followTerrain
Layout.columnSpan: 2
}
QGCCheckBox {
text: qsTr("Refly at 90 degree offset")
checked: missionItem.refly90Degrees
onClicked: missionItem.refly90Degrees = checked
FactCheckBox {
text: qsTr("Take images in turnarounds")
fact: missionItem.cameraTriggerInTurnAround
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true
Layout.columnSpan: 2
}
FactCheckBox {
QGCCheckBox {
id: relAlt
anchors.left: parent.left
text: qsTr("Relative altitude")
fact: missionItem.gridAltitudeRelative
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
Layout.columnSpan: 2
}
}
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
SectionHeader {
id: statsHeader
text: qsTr("Statistics") }
Grid {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
visible: statsHeader.checked
QGCLabel { text: qsTr("Survey Area") }
QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
QGCLabel { text: qsTr("Photo Count") }
QGCLabel { text: missionItem.cameraShots }
QGCLabel { text: qsTr("Photo Interval") }
QGCLabel {
text: {
var timeVal = missionItem.timeBetweenShots
if(!isFinite(timeVal) || missionItem.cameraShots === 0) {
return qsTr("N/A")
}
return timeVal.toFixed(1) + " " + qsTr("secs")
Connections {
target: missionItem.cameraCalc
onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
}
}
QGCLabel { text: qsTr("Trigger Distance") }
QGCLabel { text: missionItem.cameraTriggerDistance.valueString + " " + QGroundControl.appSettingsDistanceUnitsString }
}
}
QGCColoredImage {
id: windRoseArrow
source: "/res/wind-rose-arrow.svg"
visible: windRosePie.visible
width: windRosePie.width / 5
height: width * 1.454
smooth: true
color: qgcPal.colorGrey
transform: Rotation {
origin.x: windRoseArrow.width / 2
origin.y: windRoseArrow.height / 2
axis { x: 0; y: 0; z: 1 } angle: windRosePie.angle
}
x: windRosePie.x + Math.sin(- windRosePie.angle*Math.PI/180 - Math.PI/2)*(windRosePie.width/2 - windRoseArrow.width/2) + windRosePie.width / 2 - windRoseArrow.width / 2
y: windRosePie.y + Math.cos(- windRosePie.angle*Math.PI/180 - Math.PI/2)*(windRosePie.width/2 - windRoseArrow.width/2) + windRosePie.height / 2 - windRoseArrow.height / 2
z: windRosePie.z + 1
}
QGCColoredImage {
id: windGuru
source: "/res/wind-guru.svg"
visible: windRosePie.visible
width: windRosePie.width / 3
height: width * 4.28e-1
smooth: true
color: qgcPal.colorGrey
transform: Rotation {
origin.x: windGuru.width / 2
origin.y: windGuru.height / 2
axis { x: 0; y: 0; z: 1 } angle: windRosePie.angle + 180
SectionHeader {
id: terrainHeader
text: qsTr("Terrain")
checked: missionItem.followTerrain
}
x: windRosePie.x + Math.sin(- windRosePie.angle*Math.PI/180 - 3*Math.PI/2)*(windRosePie.width/2) + windRosePie.width / 2 - windGuru.width / 2
y: windRosePie.y + Math.cos(- windRosePie.angle*Math.PI/180 - 3*Math.PI/2)*(windRosePie.height/2) + windRosePie.height / 2 - windGuru.height / 2
z: windRosePie.z + 1
}
Item {
id: windRosePie
height: 2.6*windRoseButton.height
width: 2.6*windRoseButton.width
visible: false
focus: true
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: terrainHeader.checked
property string colorCircle: qgcPal.windowShade
property string colorBackground: qgcPal.colorGrey
property real lineWidth: windRoseButton.width / 3
property real angle: Number(gridAngleText.text)
QGCCheckBox {
id: followsTerrainCheckBox
text: qsTr("Vehicle follows terrain")
checked: missionItem.followTerrain
onClicked: missionItem.followTerrain = checked
}
Canvas {
id: windRoseCanvas
anchors.fill: parent
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: followsTerrainCheckBox.checked
onPaint: {
var ctx = getContext("2d")
var x = width / 2
var y = height / 2
var angleWidth = 0.03 * Math.PI
var start = windRosePie.angle*Math.PI/180 - angleWidth
var end = windRosePie.angle*Math.PI/180 + angleWidth
ctx.reset()
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance
Layout.fillWidth: true
}
ctx.beginPath()
ctx.arc(x, y, (width / 3) - windRosePie.lineWidth / 2, 0, 2*Math.PI, false)
ctx.lineWidth = windRosePie.lineWidth
ctx.strokeStyle = windRosePie.colorBackground
ctx.stroke()
QGCLabel { text: qsTr("Max Climb Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxClimbRate
Layout.fillWidth: true
}
ctx.beginPath()
ctx.arc(x, y, (width / 3) - windRosePie.lineWidth / 2, start, end, false)
ctx.lineWidth = windRosePie.lineWidth
ctx.strokeStyle = windRosePie.colorCircle
ctx.stroke()
QGCLabel { text: qsTr("Max Descent Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxDescentRate
Layout.fillWidth: true
}
}
}
onFocusChanged: {
visible = focus
}
function popup(x, y) {
if (x !== undefined)
windRosePie.x = x - windRosePie.width / 2
if (y !== undefined)
windRosePie.y = y - windRosePie.height / 2
windRosePie.visible = true
windRosePie.focus = true
missionItemEditorListView.interactive = false
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
}
MouseArea {
id: mouseArea
anchors.fill: parent
acceptedButtons: Qt.LeftButton | Qt.RightButton
onClicked: {
windRosePie.visible = false
missionItemEditorListView.interactive = true
}
onPositionChanged: {
var point = Qt.point(mouseX - parent.width / 2, mouseY - parent.height / 2)
var angle = Math.round(Math.atan2(point.y, point.x) * 180 / Math.PI)
windRoseCanvas.requestPaint()
windRosePie.angle = angle
gridAngleText.text = angle
gridAngleText.editingFinished()
if(angle > -135 && angle <= -45) {
gridAngleBox.activated(2) // or 3
} else if(angle > -45 && angle <= 45) {
gridAngleBox.activated(2) // or 0
} else if(angle > 45 && angle <= 135) {
gridAngleBox.activated(1) // or 0
} else if(angle > 135 || angle <= -135) {
gridAngleBox.activated(1) // or 3
}
}
}
}
}
TransectStyleComplexItemStats { }
} // Column
} // Rectangle

16
src/PlanView/SurveyMapVisual.qml

@ -26,24 +26,24 @@ Item { @@ -26,24 +26,24 @@ Item {
property var qgcView ///< QGCView to use for popping dialogs
property var _missionItem: object
property var _mapPolygon: object.mapPolygon
property var _gridComponent
property var _mapPolygon: object.surveyAreaPolygon
property var _visualTransectsComponent
property var _entryCoordinate
property var _exitCoordinate
signal clicked(int sequenceNumber)
function _addVisualElements() {
_gridComponent = gridComponent.createObject(map)
_visualTransectsComponent = visualTransectsComponent.createObject(map)
_entryCoordinate = entryPointComponent.createObject(map)
_exitCoordinate = exitPointComponent.createObject(map)
map.addMapItem(_gridComponent)
map.addMapItem(_visualTransectsComponent)
map.addMapItem(_entryCoordinate)
map.addMapItem(_exitCoordinate)
}
function _destroyVisualElements() {
_gridComponent.destroy()
_visualTransectsComponent.destroy()
_entryCoordinate.destroy()
_exitCoordinate.destroy()
}
@ -100,14 +100,14 @@ Item { @@ -100,14 +100,14 @@ Item {
interiorOpacity: 0.5
}
// Survey grid lines
// Transect lines
Component {
id: gridComponent
id: visualTransectsComponent
MapPolyline {
line.color: "white"
line.width: 2
path: _missionItem.gridPoints
path: _missionItem.visualTransectPoints
}
}

Loading…
Cancel
Save