Unverified Commit cdb4cdfd authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6068 from DonLakeFlyer/CorridorScan

Initial Corridor Scan support
parents a849f2e6 e1752cd1
......@@ -9,9 +9,10 @@
<file alias="MavCmdInfoVTOL.json">src/MissionManager/UnitTest/MavCmdInfoVTOL.json</file>
<file alias="MissionPlanner.waypoints">src/MissionManager/UnitTest/MissionPlanner.waypoints</file>
<file alias="OldFileFormat.mission">src/MissionManager/UnitTest/OldFileFormat.mission</file>
<file alias="GoodPolygon.kml">src/MissionManager/UnitTest/GoodPolygon.kml</file>
<file alias="MissingPolygonNode.kml">src/MissionManager/UnitTest/MissingPolygonNode.kml</file>
<file alias="BadXml.kml">src/MissionManager/UnitTest/BadXml.kml</file>
<file alias="BadCoordinatesNode.kml">src/MissionManager/UnitTest/BadCoordinatesNode.kml</file>
<file alias="PolygonAreaTest.kml">src/MissionManager/UnitTest/PolygonAreaTest.kml</file>
<file alias="PolygonGood.kml">src/MissionManager/UnitTest/PolygonGood.kml</file>
<file alias="PolygonMissingNode.kml">src/MissionManager/UnitTest/PolygonMissingNode.kml</file>
<file alias="PolygonBadXml.kml">src/MissionManager/UnitTest/PolygonBadXml.kml</file>
<file alias="PolygonBadCoordinatesNode.kml">src/MissionManager/UnitTest/PolygonBadCoordinatesNode.kml</file>
</qresource>
</RCC>
......@@ -415,6 +415,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestPX4.h \
src/FactSystem/ParameterManagerTest.h \
src/MissionManager/CameraSectionTest.h \
src/MissionManager/CorridorScanComplexItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionControllerTest.h \
......@@ -423,6 +424,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/MissionSettingsTest.h \
src/MissionManager/PlanMasterControllerTest.h \
src/MissionManager/QGCMapPolygonTest.h \
src/MissionManager/QGCMapPolylineTest.h \
src/MissionManager/SectionTest.h \
src/MissionManager/SimpleMissionItemTest.h \
src/MissionManager/SpeedSectionTest.h \
......@@ -452,6 +454,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestPX4.cc \
src/FactSystem/ParameterManagerTest.cc \
src/MissionManager/CameraSectionTest.cc \
src/MissionManager/CorridorScanComplexItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionControllerTest.cc \
......@@ -460,6 +463,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/MissionSettingsTest.cc \
src/MissionManager/PlanMasterControllerTest.cc \
src/MissionManager/QGCMapPolygonTest.cc \
src/MissionManager/QGCMapPolylineTest.cc \
src/MissionManager/SectionTest.cc \
src/MissionManager/SimpleMissionItemTest.cc \
src/MissionManager/SpeedSectionTest.cc \
......@@ -508,6 +512,7 @@ HEADERS += \
src/MissionManager/CameraSection.h \
src/MissionManager/CameraSpec.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/CorridorScanComplexItem.h \
src/MissionManager/FixedWingLandingComplexItem.h \
src/MissionManager/GeoFenceController.h \
src/MissionManager/GeoFenceManager.h \
......@@ -526,6 +531,7 @@ HEADERS += \
src/MissionManager/QGCFencePolygon.h \
src/MissionManager/QGCMapCircle.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/QGCMapPolyline.h \
src/MissionManager/RallyPoint.h \
src/MissionManager/RallyPointController.h \
src/MissionManager/RallyPointManager.h \
......@@ -700,6 +706,7 @@ SOURCES += \
src/MissionManager/CameraSection.cc \
src/MissionManager/CameraSpec.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/CorridorScanComplexItem.cc \
src/MissionManager/FixedWingLandingComplexItem.cc \
src/MissionManager/GeoFenceController.cc \
src/MissionManager/GeoFenceManager.cc \
......@@ -718,6 +725,7 @@ SOURCES += \
src/MissionManager/QGCFencePolygon.cc \
src/MissionManager/QGCMapCircle.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/QGCMapPolyline.cc \
src/MissionManager/RallyPoint.cc \
src/MissionManager/RallyPointController.cc \
src/MissionManager/RallyPointManager.cc \
......
......@@ -18,6 +18,7 @@
<file alias="AnalyzeView.qml">src/AnalyzeView/AnalyzeView.qml</file>
<file alias="AppSettings.qml">src/ui/AppSettings.qml</file>
<file alias="BluetoothSettings.qml">src/ui/preferences/BluetoothSettings.qml</file>
<file alias="CorridorScanEditor.qml">src/PlanView/CorridorScanEditor.qml</file>
<file alias="CustomCommandWidget.qml">src/ViewWidgets/CustomCommandWidget.qml</file>
<file alias="DebugWindow.qml">src/ui/preferences/DebugWindow.qml</file>
<file alias="ESP8266Component.qml">src/AutoPilotPlugins/Common/ESP8266Component.qml</file>
......@@ -48,6 +49,7 @@
<file alias="QGroundControl/Controls/CameraCalc.qml">src/PlanView/CameraCalc.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/PlanView/CameraSection.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
<file alias="QGroundControl/Controls/CorridorScanMapVisual.qml">src/PlanView/CorridorScanMapVisual.qml</file>
<file alias="QGroundControl/Controls/DropButton.qml">src/QmlControls/DropButton.qml</file>
<file alias="QGroundControl/Controls/EditPositionDialog.qml">src/QmlControls/EditPositionDialog.qml</file>
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
......@@ -89,6 +91,7 @@
<file alias="QGroundControl/Controls/QGCMapLabel.qml">src/QmlControls/QGCMapLabel.qml</file>
<file alias="QGroundControl/Controls/QGCMapCircleVisuals.qml">src/MissionManager/QGCMapCircleVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMapPolygonVisuals.qml">src/MissionManager/QGCMapPolygonVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMapPolylineVisuals.qml">src/MissionManager/QGCMapPolylineVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMouseArea.qml">src/QmlControls/QGCMouseArea.qml</file>
<file alias="QGroundControl/Controls/QGCMovableItem.qml">src/QmlControls/QGCMovableItem.qml</file>
<file alias="QGroundControl/Controls/QGCPipable.qml">src/QmlControls/QGCPipable.qml</file>
......@@ -202,6 +205,7 @@
<file alias="QGCMapCircle.Facts.json">src/MissionManager/QGCMapCircle.Facts.json</file>
<file alias="RTK.SettingsGroup.json">src/Settings/RTK.SettingsGroup.json</file>
<file alias="Survey.SettingsGroup.json">src/MissionManager/Survey.SettingsGroup.json</file>
<file alias="CorridorScan.SettingsGroup.json">src/MissionManager/CorridorScan.SettingsGroup.json</file>
<file alias="StructureScan.SettingsGroup.json">src/MissionManager/StructureScan.SettingsGroup.json</file>
<file alias="Units.SettingsGroup.json">src/Settings/Units.SettingsGroup.json</file>
<file alias="Video.SettingsGroup.json">src/Settings/Video.SettingsGroup.json</file>
......
......@@ -49,6 +49,14 @@ public:
Fact* adjustedFootprintSide (void) { return &_adjustedFootprintSideFact; }
Fact* adjustedFootprintFrontal (void) { return &_adjustedFootprintFrontalFact; }
const Fact* valueSetIsDistance (void) const { return &_valueSetIsDistanceFact; }
const Fact* distanceToSurface (void) const { return &_distanceToSurfaceFact; }
const Fact* imageDensity (void) const { return &_imageDensityFact; }
const Fact* frontalOverlap (void) const { return &_frontalOverlapFact; }
const Fact* sideOverlap (void) const { return &_sideOverlapFact; }
const Fact* adjustedFootprintSide (void) const { return &_adjustedFootprintSideFact; }
const Fact* adjustedFootprintFrontal (void) const { return &_adjustedFootprintFrontalFact; }
bool isManualCamera (void) { return cameraName() == manualCameraName(); }
double imageFootprintSide (void) const { return _imageFootprintSide; }
double imageFootprintFrontal (void) const { return _imageFootprintFrontal; }
......
......@@ -47,9 +47,9 @@ public:
static const char* jsonComplexItemTypeKey;
signals:
void complexDistanceChanged (double complexDistance);
void complexDistanceChanged (void);
void greatestDistanceToChanged (void);
void additionalTimeDelayChanged (double additionalTimeDelay);
void additionalTimeDelayChanged (void);
};
#endif
[
{
"name": "Altitude",
"shortDescription": "Altitude for the bottom layer of the structure scan.",
"type": "double",
"units": "m",
"decimalPlaces": 1,
"defaultValue": 50
},
{
"name": "CorridorWidth",
"shortDescription": "Corridor width. Specify 0 width for a single pass scan.",
"type": "double",
"units": "m",
"min": 0,
"decimalPlaces": 1,
"defaultValue": 50
},
{
"name": "Trigger distance",
"shortDescription": "Distance between each triggering of the camera. 0 specifies not camera trigger.",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 25
},
{
"name": "GridSpacing",
"shortDescription": "Amount of spacing in between parallel grid lines.",
"type": "double",
"decimalPlaces": 2,
"min": 0.1,
"units": "m",
"defaultValue": 30
},
{
"name": "TurnaroundDist",
"shortDescription": "Amount of additional distance to add outside the grid area for vehicle turnaround.",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 30
}
]
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "CorridorScanComplexItem.h"
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h"
#include "QGCQGeoCoordinate.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QGCQGeoCoordinate.h"
#include <QPolygonF>
QGC_LOGGING_CATEGORY(CorridorScanComplexItemLog, "CorridorScanComplexItemLog")
const char* CorridorScanComplexItem::_corridorWidthFactName = "CorridorWidth";
const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan";
const char* CorridorScanComplexItem::_jsonCameraCalcKey = "CameraCalc";
QMap<QString, FactMetaData*> CorridorScanComplexItem::_metaDataMap;
CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem (vehicle, parent)
, _sequenceNumber (0)
, _dirty (false)
, _corridorWidthFact (0, _corridorWidthFactName, FactMetaData::valueTypeDouble)
, _ignoreRecalc (false)
, _scanDistance (0.0)
, _cameraShots (0)
, _cameraMinTriggerInterval (0)
, _cameraCalc (vehicle)
{
_editorQml = "qrc:/qml/CorridorScanEditor.qml";
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), NULL /* QObject parent */);
}
_corridorWidthFact.setMetaData(_metaDataMap[_corridorWidthFactName]);
_corridorWidthFact.setRawValue(_corridorWidthFact.rawDefaultValue());
connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_setDirty);
connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_setDirty);
connect(this, &CorridorScanComplexItem::altitudeRelativeChanged, this, &CorridorScanComplexItem::_setDirty);
connect(this, &CorridorScanComplexItem::altitudeRelativeChanged, this, &CorridorScanComplexItem::coordinateHasRelativeAltitudeChanged);
connect(this, &CorridorScanComplexItem::altitudeRelativeChanged, this, &CorridorScanComplexItem::exitCoordinateHasRelativeAltitudeChanged);
connect(&_corridorPolyline, &QGCMapPolyline::dirtyChanged, this, &CorridorScanComplexItem::_polylineDirtyChanged);
connect(&_corridorPolyline, &QGCMapPolyline::countChanged, this, &CorridorScanComplexItem::_polylineCountChanged);
connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildTransects);
connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_rebuildCorridor);
connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildCorridor);
connect(&_corridorPolyline, &QGCMapPolyline::countChanged, this, &CorridorScanComplexItem::_signalLastSequenceNumberChanged);
connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_signalLastSequenceNumberChanged);
connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &CorridorScanComplexItem::_signalLastSequenceNumberChanged);
connect(&_corridorPolygon, &QGCMapPolygon::pathChanged, this, &CorridorScanComplexItem::coveredAreaChanged);
connect(this, &CorridorScanComplexItem::transectPointsChanged, this, &CorridorScanComplexItem::complexDistanceChanged);
connect(this, &CorridorScanComplexItem::transectPointsChanged, this, &CorridorScanComplexItem::greatestDistanceToChanged);
_rebuildCorridor();
}
void CorridorScanComplexItem::_setScanDistance(double scanDistance)
{
if (!qFuzzyCompare(_scanDistance, scanDistance)) {
_scanDistance = scanDistance;
emit complexDistanceChanged();
}
}
void CorridorScanComplexItem::_setCameraShots(int cameraShots)
{
if (_cameraShots != cameraShots) {
_cameraShots = cameraShots;
emit cameraShotsChanged();
}
}
void CorridorScanComplexItem::_clearInternal(void)
{
setDirty(true);
emit specifiesCoordinateChanged();
emit lastSequenceNumberChanged(lastSequenceNumber());
}
void CorridorScanComplexItem::_polylineCountChanged(int count)
{
Q_UNUSED(count);
emit lastSequenceNumberChanged(lastSequenceNumber());
}
int CorridorScanComplexItem::lastSequenceNumber(void) const
{
return _sequenceNumber + ((_corridorPolyline.count() + 2 /* trigger start/stop */) * _transectCount());
}
void CorridorScanComplexItem::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
emit dirtyChanged(_dirty);
}
}
void CorridorScanComplexItem::save(QJsonArray& missionItems)
{
QJsonObject saveObject;
saveObject[JsonHelper::jsonVersionKey] = 1;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
saveObject[_corridorWidthFactName] = _corridorWidthFact.rawValue().toDouble();
QJsonObject cameraCalcObject;
_cameraCalc.save(cameraCalcObject);
saveObject[_jsonCameraCalcKey] = cameraCalcObject;
_corridorPolyline.saveToJson(saveObject);
missionItems.append(saveObject);
}
void CorridorScanComplexItem::setSequenceNumber(int sequenceNumber)
{
if (_sequenceNumber != sequenceNumber) {
_sequenceNumber = sequenceNumber;
emit sequenceNumberChanged(sequenceNumber);
emit lastSequenceNumberChanged(lastSequenceNumber());
}
}
bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true },
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
{ ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
{ _corridorWidthFactName, QJsonValue::Double, true },
{ QGCMapPolyline::jsonPolylineKey, QJsonValue::Array, true },
{ _jsonCameraCalcKey, QJsonValue::Object, true },
};
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
}
_corridorPolyline.clear();
QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
return false;
}
int version = complexObject[JsonHelper::jsonVersionKey].toInt();
if (version != 1) {
errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
return false;
}
setSequenceNumber(sequenceNumber);
if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), errorString)) {
return false;
}
if (!_corridorPolyline.loadFromJson(complexObject, true /* required */, errorString)) {
_corridorPolyline.clear();
_rebuildCorridor();
return false;
}
_rebuildCorridor();
return true;
}
double CorridorScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
{
double greatestDistance = 0.0;
for (int i=0; i<_transectPoints.count(); i++) {
QGeoCoordinate vertex = _transectPoints[i].value<QGeoCoordinate>();
double distance = vertex.distanceTo(other);
if (distance > greatestDistance) {
greatestDistance = distance;
}
}
return greatestDistance;
}
bool CorridorScanComplexItem::specifiesCoordinate(void) const
{
return _corridorPolyline.count() > 1;
}
int CorridorScanComplexItem::_transectCount(void) const
{
double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
double fullWidth = _corridorWidthFact.rawValue().toDouble();
return fullWidth > 0.0 ? qCeil(fullWidth / transectSpacing) : 1;
}
void CorridorScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
int seqNum = _sequenceNumber;
int pointIndex = 0;
while (pointIndex < _transectPoints.count()) {
bool addTrigger = true;
for (int i=0; i<_corridorPolyline.count(); i++) {
QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value<QGeoCoordinate>();
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT,
MAV_FRAME_GLOBAL_RELATIVE_ALT, // FIXME: Manual camera should support AMSL alt
0, // No hold time
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
vertexCoord.latitude(),
vertexCoord.longitude(),
_cameraCalc.distanceToSurface()->rawValue().toDouble(), // Altitude
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
if (addTrigger) {
addTrigger = false;
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
_cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(), // trigger distance
0, // shutter integration (ignore)
1, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
}
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
0, // stop triggering
0, // shutter integration (ignore)
0, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
}
void CorridorScanComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
_cruiseSpeed = missionFlightStatus.vehicleSpeed;
emit timeBetweenShotsChanged();
}
}
void CorridorScanComplexItem::_setDirty(void)
{
setDirty(true);
}
void CorridorScanComplexItem::applyNewAltitude(double newAltitude)
{
Q_UNUSED(newAltitude);
// FIXME: NYI
//_altitudeFact.setRawValue(newAltitude);
}
void CorridorScanComplexItem::_polylineDirtyChanged(bool dirty)
{
if (dirty) {
setDirty(true);
}
}
double CorridorScanComplexItem::timeBetweenShots(void)
{
return _cruiseSpeed == 0 ? 0 : _cameraCalc.adjustedFootprintSide()->rawValue().toDouble() / _cruiseSpeed;
}
void CorridorScanComplexItem::_updateCoordinateAltitudes(void)
{
emit coordinateChanged(coordinate());
emit exitCoordinateChanged(exitCoordinate());
}
void CorridorScanComplexItem::rotateEntryPoint(void)
{
#if 0
_entryVertex++;
if (_entryVertex >= _flightPolygon.count()) {
_entryVertex = 0;
}
emit coordinateChanged(coordinate());
emit exitCoordinateChanged(exitCoordinate());
#endif
}
void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
{
if (_corridorPolyline.count() < 2) {
_corridorPolygon.clear();
return;
}
double halfWidth = _corridorWidthFact.rawValue().toDouble() / 2.0;
QList<QGeoCoordinate> firstSideVertices = _corridorPolyline.offsetPolyline(halfWidth);
QList<QGeoCoordinate> secondSideVertices = _corridorPolyline.offsetPolyline(-halfWidth);
_corridorPolygon.clear();
foreach (const QGeoCoordinate& vertex, firstSideVertices) {
_corridorPolygon.appendVertex(vertex);
}
for (int i=secondSideVertices.count() - 1; i >= 0; i--) {
_corridorPolygon.appendVertex(secondSideVertices[i]);
}
}
void CorridorScanComplexItem::_rebuildTransects(void)
{
_transectPoints.clear();
double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
double fullWidth = _corridorWidthFact.rawValue().toDouble();
double halfWidth = fullWidth / 2.0;
int transectCount = _transectCount();
double normalizedTransectPosition = transectSpacing / 2.0;
_cameraShots = 0;
int singleTransectImageCount = qCeil(_corridorPolyline.length() / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
bool reverseVertices = false;
for (int i=0; i<transectCount; i++) {
_cameraShots += singleTransectImageCount;
double offsetDistance;
if (transectCount == 1) {
// Single transect is flown over scan line
offsetDistance = 0;
} else {
// Convert from normalized to absolute transect offset distance
offsetDistance = halfWidth - normalizedTransectPosition;
}
QList<QGeoCoordinate> transectVertices = _corridorPolyline.offsetPolyline(offsetDistance);
if (reverseVertices) {
reverseVertices = false;
QList<QGeoCoordinate> reversedVertices;
for (int j=transectVertices.count()-1; j>=0; j--) {
reversedVertices.append(transectVertices[j]);
}
transectVertices = reversedVertices;
} else {
reverseVertices = true;
}
for (int i=0; i<transectVertices.count(); i++) {
_transectPoints.append(QVariant::fromValue((transectVertices[i])));
}
normalizedTransectPosition += transectSpacing;
}
_coordinate = _transectPoints.count() ? _transectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _transectPoints.count() ? _transectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
emit transectPointsChanged();
emit cameraShotsChanged();
emit coordinateChanged(_coordinate);
emit exitCoordinateChanged(_exitCoordinate);
}
void CorridorScanComplexItem::_rebuildCorridor(void)
{
_rebuildCorridorPolygon();
_rebuildTransects();
}
void CorridorScanComplexItem::_signalLastSequenceNumberChanged(void)
{
emit lastSequenceNumberChanged(lastSequenceNumber());
}
double CorridorScanComplexItem::coveredArea(void) const
{
return _corridorPolygon.area();
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "SettingsFact.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolyline.h"
#include "QGCMapPolygon.h"
#include "CameraCalc.h"
Q_DECLARE_LOGGING_CATEGORY(CorridorScanComplexItemLog)
class CorridorScanComplexItem : public ComplexMissionItem
{
Q_OBJECT
public:
CorridorScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
Q_PROPERTY(QGCMapPolygon* corridorPolygon READ corridorPolygon CONSTANT)
Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_PROPERTY(double cameraMinTriggerInterval MEMBER _cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged)
CameraCalc* cameraCalc (void) { return &_cameraCalc; }
QGCMapPolyline* corridorPolyline(void) { return &_corridorPolyline; }
QGCMapPolygon* corridorPolygon (void) { return &_corridorPolygon; }
Fact* corridorWidth (void) { return &_corridorWidthFact; }
QVariantList transectPoints (void) { return _transectPoints; }
int cameraShots (void) const { return _cameraShots; }
double timeBetweenShots (void);
double coveredArea (void) const;
Q_INVOKABLE void rotateEntryPoint(void);
// Overrides from ComplexMissionItem
double complexDistance (void) const final { return _scanDistance; }
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("CorridorScanMapVisual.qml"); }
// Overrides from VisualMissionItem
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 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; }
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 true /*_altitudeRelative*/; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final { Q_UNUSED(coordinate); }
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonArray& missionItems) final;
static const char* jsonComplexItemTypeValue;
signals:
void cameraShotsChanged (void);
void timeBetweenShotsChanged (void);
void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval);
void altitudeRelativeChanged (bool altitudeRelative);
void transectPointsChanged (void);
void coveredAreaChanged (void);
private slots:
void _setDirty (void);
void _polylineDirtyChanged (bool dirty);
void _polylineCountChanged (int count);
void _clearInternal (void);
void _updateCoordinateAltitudes (void);
void _signalLastSequenceNumberChanged (void);
void _rebuildCorridor (void);
void _rebuildTransects (void);
private:
void _setExitCoordinate (const QGeoCoordinate& coordinate);
void _setScanDistance (double scanDistance);
void _setCameraShots (int cameraShots);
double _triggerDistance (void) const;
int _transectCount (void) const;
void _rebuildCorridorPolygon(void);
int _sequenceNumber;
bool _dirty;
QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate;
QGCMapPolyline _corridorPolyline;
QGCMapPolygon _corridorPolygon;
Fact _corridorWidthFact;
QVariantList _transectPoints;
bool _ignoreRecalc;
double _scanDistance;
int _cameraShots;
double _timeBetweenShots;
double _cameraMinTriggerInterval;
double _cruiseSpeed;
CameraCalc _cameraCalc;
static QMap<QString, FactMetaData*> _metaDataMap;
static const char* _corridorWidthFactName;
static const char* _jsonCameraCalcKey;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "CorridorScanComplexItemTest.h"
#include "QGCApplication.h"
CorridorScanComplexItemTest::CorridorScanComplexItemTest(void)
: _offlineVehicle(NULL)
{
_linePoints << QGeoCoordinate(47.633550640000003, -122.08982199)
<< QGeoCoordinate(47.634129020000003, -122.08887249)
<< QGeoCoordinate(47.633619320000001, -122.08811074);
}
void CorridorScanComplexItemTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_corridorItem = new CorridorScanComplexItem(_offlineVehicle, this);
// _corridorItem->setTurnaroundDist(0); // Unit test written for no turnaround distance
_corridorItem->setDirty(false);
_mapPolyline = _corridorItem->corridorPolyline();
_rgSignals[complexDistanceChangedIndex] = SIGNAL(complexDistanceChanged());
_rgSignals[greatestDistanceToChangedIndex] = SIGNAL(greatestDistanceToChanged());
_rgSignals[additionalTimeDelayChangedIndex] = SIGNAL(additionalTimeDelayChanged());
_rgSignals[transectPointsChangedIndex] = SIGNAL(transectPointsChanged());
_rgSignals[cameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
_rgSignals[coveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
_rgSignals[timeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_multiSpy = new MultiSignalSpy();
QCOMPARE(_multiSpy->init(_corridorItem, _rgSignals, _cSignals), true);
_rgCorridorPolygonSignals[corridorPolygonPathChangedIndex] = SIGNAL(pathChanged());
_multiSpyCorridorPolygon = new MultiSignalSpy();
QCOMPARE(_multiSpyCorridorPolygon->init(_corridorItem->corridorPolygon(), _rgCorridorPolygonSignals, _cCorridorPolygonSignals), true);
}
void CorridorScanComplexItemTest::cleanup(void)
{
delete _corridorItem;
delete _offlineVehicle;
delete _multiSpy;
}
void CorridorScanComplexItemTest::_testDirty(void)
{
QVERIFY(!_corridorItem->dirty());
_corridorItem->setDirty(false);
QVERIFY(!_corridorItem->dirty());
QVERIFY(_multiSpy->checkNoSignals());
_corridorItem->setDirty(true);
QVERIFY(_corridorItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_multiSpy->clearAllSignals();
_corridorItem->setDirty(false);
QVERIFY(!_corridorItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(!_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_multiSpy->clearAllSignals();
// These facts should set dirty when changed
QList<Fact*> rgFacts;
#if 0
rgFacts << _corridorItem->gridAltitude() << _corridorItem->gridAngle() << _corridorItem->gridSpacing() << _corridorItem->turnaroundDist() << _corridorItem->cameraTriggerDistance() <<
_corridorItem->gridAltitudeRelative() << _corridorItem->cameraTriggerInTurnaround() << _corridorItem->hoverAndCapture();
#endif
rgFacts << _corridorItem->corridorWidth();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
QVERIFY(!_corridorItem->dirty());
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
_corridorItem->setDirty(false);
_multiSpy->clearAllSignals();
}
rgFacts.clear();
// These facts should not change dirty bit
#if 0
rgFacts << _corridorItem->groundResolution() << _corridorItem->frontalOverlap() << _corridorItem->sideOverlap() << _corridorItem->cameraSensorWidth() << _corridorItem->cameraSensorHeight() <<
_corridorItem->cameraResolutionWidth() << _corridorItem->cameraResolutionHeight() << _corridorItem->cameraFocalLength() << _corridorItem->cameraOrientationLandscape() <<
_corridorItem->fixedValueIsAltitude() << _corridorItem->camera() << _corridorItem->manualGrid();
#endif
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
QVERIFY(!_corridorItem->dirty());
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkNoSignalByMask(dirtyChangedMask));
QVERIFY(!_corridorItem->dirty());
_multiSpy->clearAllSignals();
}
rgFacts.clear();
}
void CorridorScanComplexItemTest::_testCameraTrigger(void)
{
#if 0
QCOMPARE(_corridorItem->property("cameraTrigger").toBool(), true);
// Set up a grid
for (int i=0; i<3; i++) {
_mapPolyline->appendVertex(_linePoints[i]);
}
_corridorItem->setDirty(false);
_multiSpy->clearAllSignals();
int lastSeq = _corridorItem->lastSequenceNumber();
QVERIFY(lastSeq > 0);
// Turning off camera triggering should remove two camera trigger mission items, this should trigger:
// lastSequenceNumberChanged
// dirtyChanged
_corridorItem->setProperty("cameraTrigger", false);
QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq - 2);
_corridorItem->setDirty(false);
_multiSpy->clearAllSignals();
// Turn on camera triggering and make sure things go back to previous count
_corridorItem->setProperty("cameraTrigger", true);
QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq);
#endif
}
void CorridorScanComplexItemTest::_setPolyline(void)
{
for (int i=0; i<_linePoints.count(); i++) {
QGeoCoordinate& vertex = _linePoints[i];
_mapPolyline->appendVertex(vertex);
}
}
#if 0
void CorridorScanComplexItemTest::_testEntryLocation(void)
{
_setPolygon();
for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
_corridorItem->gridAngle()->setRawValue(gridAngle);
QList<QGeoCoordinate> rgSeenEntryCoords;
QList<int> rgEntryLocation;
rgEntryLocation << SurveyMissionItem::EntryLocationTopLeft
<< SurveyMissionItem::EntryLocationTopRight
<< SurveyMissionItem::EntryLocationBottomLeft
<< SurveyMissionItem::EntryLocationBottomRight;
// Validate that each entry location is unique
for (int i=0; i<rgEntryLocation.count(); i++) {
int entryLocation = rgEntryLocation[i];
_corridorItem->gridEntryLocation()->setRawValue(entryLocation);
QVERIFY(!rgSeenEntryCoords.contains(_corridorItem->coordinate()));
rgSeenEntryCoords << _corridorItem->coordinate();
}
rgSeenEntryCoords.clear();
}
}
#endif
void CorridorScanComplexItemTest::_testItemCount(void)
{
QList<MissionItem*> items;
_setPolyline();
// _corridorItem->cameraTriggerInTurnaround()->setRawValue(false);
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _corridorItem->lastSequenceNumber());
items.clear();
}
void CorridorScanComplexItemTest::_testPathChanges(void)
{
_setPolyline();
_corridorItem->setDirty(false);
_multiSpy->clearAllSignals();
_multiSpyCorridorPolygon->clearAllSignals();
QGeoCoordinate vertex = _mapPolyline->vertexCoordinate(1);
vertex.setLatitude(vertex.latitude() + 0.01);
_mapPolyline->adjustVertex(1, vertex);
QVERIFY(_corridorItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalsByMask(dirtyChangedMask | transectPointsChangedMask | cameraShotsChangedMask | coveredAreaChangedMask | complexDistanceChangedMask | greatestDistanceToChangedMask));
QVERIFY(_multiSpyCorridorPolygon->checkSignalsByMask(corridorPolygonPathChangedMask));
_multiSpy->clearAllSignals();
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include "CorridorScanComplexItem.h"
#include <QGeoCoordinate>
class CorridorScanComplexItemTest : public UnitTest
{
Q_OBJECT
public:
CorridorScanComplexItemTest(void);
protected:
void init(void) final;
void cleanup(void) final;
private slots:
void _testDirty(void);
void _testCameraTrigger(void);
// void _testEntryLocation(void);
void _testItemCount(void);
void _testPathChanges(void);
private:
void _setPolyline(void);
enum {
complexDistanceChangedIndex = 0,
greatestDistanceToChangedIndex,
additionalTimeDelayChangedIndex,
transectPointsChangedIndex,
cameraShotsChangedIndex,
coveredAreaChangedIndex,
timeBetweenShotsChangedIndex,
dirtyChangedIndex,
maxSignalIndex
};
enum {
complexDistanceChangedMask = 1 << complexDistanceChangedIndex,
greatestDistanceToChangedMask = 1 << greatestDistanceToChangedIndex,
additionalTimeDelayChangedMask = 1 << additionalTimeDelayChangedIndex,
transectPointsChangedMask = 1 << transectPointsChangedIndex,
cameraShotsChangedMask = 1 << cameraShotsChangedIndex,
coveredAreaChangedMask = 1 << coveredAreaChangedIndex,
timeBetweenShotsChangedMask = 1 << timeBetweenShotsChangedIndex,
dirtyChangedMask = 1 << dirtyChangedIndex
};
static const size_t _cSignals = maxSignalIndex;
const char* _rgSignals[_cSignals];
enum {
corridorPolygonPathChangedIndex = 0,
maxCorridorPolygonSignalIndex
};
enum {
corridorPolygonPathChangedMask = 1 << corridorPolygonPathChangedIndex,
};
static const size_t _cCorridorPolygonSignals = maxCorridorPolygonSignalIndex;
const char* _rgCorridorPolygonSignals[_cCorridorPolygonSignals];
Vehicle* _offlineVehicle;
MultiSignalSpy* _multiSpy;
MultiSignalSpy* _multiSpyCorridorPolygon;
CorridorScanComplexItem* _corridorItem;
QGCMapPolyline* _mapPolyline;
QList<QGeoCoordinate> _linePoints;
};
......@@ -19,7 +19,7 @@
#include "SurveyMissionItem.h"
#include "FixedWingLandingComplexItem.h"
#include "StructureScanComplexItem.h"
#include "StructureScanComplexItem.h"
#include "CorridorScanComplexItem.h"
#include "JsonHelper.h"
#include "ParameterManager.h"
#include "QGroundControlQmlGlobal.h"
......@@ -63,6 +63,7 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
, _surveyMissionItemName(tr("Survey"))
, _fwLandingMissionItemName(tr("Fixed Wing Landing"))
, _structureScanMissionItemName(tr("Structure Scan"))
, _corridorScanMissionItemName(tr("Corridor Scan"))
, _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
, _progressPct(0)
, _currentPlanViewIndex(-1)
......@@ -388,22 +389,41 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
{
ComplexMissionItem* newItem;
bool surveyStyleItem = false;
int sequenceNumber = _nextSequenceNumber();
if (itemName == _surveyMissionItemName) {
newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
newItem->setCoordinate(mapCenterCoordinate);
// If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
surveyStyleItem = true;
} else if (itemName == _fwLandingMissionItemName) {
newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
} else if (itemName == _structureScanMissionItemName) {
newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
} else if (itemName == _corridorScanMissionItemName) {
newItem = new CorridorScanComplexItem(_controllerVehicle, _visualItems);
surveyStyleItem = true;
} else {
qWarning() << "Internal error: Unknown complex item:" << itemName;
return sequenceNumber;
}
if (surveyStyleItem) {
bool rollSupported = false;
bool pitchSupported = false;
bool yawSupported = false;
// If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
CameraSection* cameraSection = settingsItem->cameraSection();
// Set camera to photo mode (leave alone if user already specified)
if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
cameraSection->setSpecifyCameraMode(true);
cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
}
// Point gimbal straight down
if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
// If the user already specified a gimbal angle leave it alone
......@@ -412,14 +432,8 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
cameraSection->gimbalPitch()->setRawValue(-90.0);
}
}
} else if (itemName == _fwLandingMissionItemName) {
newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
} else if (itemName == _structureScanMissionItemName) {
newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
} else {
qWarning() << "Internal error: Unknown complex item:" << itemName;
return sequenceNumber;
}
newItem->setSequenceNumber(sequenceNumber);
_initVisualItem(newItem);
......@@ -437,17 +451,17 @@ void MissionController::removeMissionItem(int index)
return;
}
bool surveyRemoved = _visualItems->value<SurveyMissionItem*>(index);
bool removeSurveyStyle = _visualItems->value<SurveyMissionItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
_deinitVisualItem(item);
item->deleteLater();
if (surveyRemoved) {
// Determine if the mission still has another survey in it
if (removeSurveyStyle) {
// Determine if the mission still has another survey style item in it
bool foundSurvey = false;
for (int i=1; i<_visualItems->count(); i++) {
if (_visualItems->value<SurveyMissionItem*>(i)) {
if (_visualItems->value<SurveyMissionItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(index)) {
foundSurvey = true;
break;
}
......@@ -697,6 +711,15 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(structureItem);
} else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, visualItems);
if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(corridorItem);
} else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
......@@ -1841,6 +1864,7 @@ QStringList MissionController::complexMissionItemNames(void) const
QStringList complexItems;
complexItems.append(_surveyMissionItemName);
complexItems.append(_corridorScanMissionItemName);
if (_controllerVehicle->fixedWing()) {
complexItems.append(_fwLandingMissionItemName);
}
......
......@@ -253,6 +253,7 @@ private:
QString _surveyMissionItemName;
QString _fwLandingMissionItemName;
QString _structureScanMissionItemName;
QString _corridorScanMissionItemName;
AppSettings* _appSettings;
double _progressPct;
int _currentPlanViewIndex;
......
......@@ -362,7 +362,7 @@ QGeoCoordinate QGCMapPolygon::vertexCoordinate(int vertex) const
}
}
QList<QPointF> QGCMapPolygon::nedPolygon(void)
QList<QPointF> QGCMapPolygon::nedPolygon(void) const
{
QList<QPointF> nedPolygon;
......@@ -515,3 +515,19 @@ bool QGCMapPolygon::loadKMLFile(const QString& kmlFile)
return true;
}
double QGCMapPolygon::area(void) const
{
// https://www.mathopenref.com/coordpolygonarea2.html
double coveredArea = 0.0;
QList<QPointF> nedVertices = nedPolygon();
for (int i=0; i<nedVertices.count(); i++) {
if (i != 0) {
coveredArea += nedVertices[i - 1].x() * nedVertices[i].y() - nedVertices[i].x() * nedVertices[i -1].y();
} else {
coveredArea += nedVertices.last().x() * nedVertices[i].y() - nedVertices[i].x() * nedVertices.last().y();
}
}
return 0.5 * fabs(coveredArea);
}
......@@ -77,7 +77,10 @@ public:
bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
/// Convert polygon to NED and return (D is ignored)
QList<QPointF> nedPolygon(void);
QList<QPointF> nedPolygon(void) const;
/// Returns the area of the polygon in meters squared
double area(void) const;
// Property methods
......
......@@ -205,17 +205,17 @@ void QGCMapPolygonTest::_testVertexManipulation(void)
void QGCMapPolygonTest::_testKMLLoad(void)
{
QVERIFY(_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/GoodPolygon.kml")));
QVERIFY(_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonGood.kml")));
setExpectedMessageBox(QMessageBox::Ok);
QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/BadXml.kml")));
QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonBadXml.kml")));
checkExpectedMessageBox();
setExpectedMessageBox(QMessageBox::Ok);
QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/MissingPolygonNode.kml")));
QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonMissingNode.kml")));
checkExpectedMessageBox();
setExpectedMessageBox(QMessageBox::Ok);
QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/BadCoordinatesNode.kml")));
QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonBadCoordinatesNode.kml")));
checkExpectedMessageBox();
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "QGCMapPolyline.h"
#include "QGCGeo.h"
#include "JsonHelper.h"
#include "QGCQGeoCoordinate.h"
#include "QGCApplication.h"
#include <QGeoRectangle>
#include <QDebug>
#include <QJsonArray>
#include <QLineF>
#include <QFile>
#include <QDomDocument>
const char* QGCMapPolyline::jsonPolylineKey = "polyline";
QGCMapPolyline::QGCMapPolyline(QObject* parent)
: QObject (parent)
, _dirty (false)
, _interactive (false)
{
_init();
}
QGCMapPolyline::QGCMapPolyline(const QGCMapPolyline& other, QObject* parent)
: QObject (parent)
, _dirty (false)
, _interactive (false)
{
*this = other;
_init();
}
const QGCMapPolyline& QGCMapPolyline::operator=(const QGCMapPolyline& other)
{
clear();
QVariantList vertices = other.path();
for (int i=0; i<vertices.count(); i++) {
appendVertex(vertices[i].value<QGeoCoordinate>());
}
setDirty(true);
return *this;
}
void QGCMapPolyline::_init(void)
{
connect(&_polylineModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolyline::_polylineModelDirtyChanged);
connect(&_polylineModel, &QmlObjectListModel::countChanged, this, &QGCMapPolyline::_polylineModelCountChanged);
}
void QGCMapPolyline::clear(void)
{
_polylinePath.clear();
emit pathChanged();
_polylineModel.clearAndDeleteContents();
emit cleared();
setDirty(true);
}
void QGCMapPolyline::adjustVertex(int vertexIndex, const QGeoCoordinate coordinate)
{
_polylinePath[vertexIndex] = QVariant::fromValue(coordinate);
emit pathChanged();
_polylineModel.value<QGCQGeoCoordinate*>(vertexIndex)->setCoordinate(coordinate);
setDirty(true);
}
void QGCMapPolyline::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
if (!dirty) {
_polylineModel.setDirty(false);
}
emit dirtyChanged(dirty);
}
}
QGeoCoordinate QGCMapPolyline::_coordFromPointF(const QPointF& point) const
{
QGeoCoordinate coord;
if (_polylinePath.count() > 0) {
QGeoCoordinate tangentOrigin = _polylinePath[0].value<QGeoCoordinate>();
convertNedToGeo(-point.y(), point.x(), 0, tangentOrigin, &coord);
}
return coord;
}
QPointF QGCMapPolyline::_pointFFromCoord(const QGeoCoordinate& coordinate) const
{
if (_polylinePath.count() > 0) {
double y, x, down;
QGeoCoordinate tangentOrigin = _polylinePath[0].value<QGeoCoordinate>();
convertGeoToNed(coordinate, tangentOrigin, &y, &x, &down);
return QPointF(x, -y);
}
return QPointF();
}
void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path)
{
_polylinePath.clear();
_polylineModel.clearAndDeleteContents();
foreach (const QGeoCoordinate& coord, path) {
_polylinePath.append(QVariant::fromValue(coord));
_polylineModel.append(new QGCQGeoCoordinate(coord, this));
}
setDirty(true);
emit pathChanged();
}
void QGCMapPolyline::setPath(const QVariantList& path)
{
_polylinePath = path;
_polylineModel.clearAndDeleteContents();
for (int i=0; i<_polylinePath.count(); i++) {
_polylineModel.append(new QGCQGeoCoordinate(_polylinePath[i].value<QGeoCoordinate>(), this));
}
setDirty(true);
emit pathChanged();
}
void QGCMapPolyline::saveToJson(QJsonObject& json)
{
QJsonValue jsonValue;
JsonHelper::saveGeoCoordinateArray(_polylinePath, false /* writeAltitude*/, jsonValue);
json.insert(jsonPolylineKey, jsonValue);
setDirty(false);
}
bool QGCMapPolyline::loadFromJson(const QJsonObject& json, bool required, QString& errorString)
{
errorString.clear();
clear();
if (required) {
if (!JsonHelper::validateRequiredKeys(json, QStringList(jsonPolylineKey), errorString)) {
return false;
}
} else if (!json.contains(jsonPolylineKey)) {
return true;
}
if (!JsonHelper::loadGeoCoordinateArray(json[jsonPolylineKey], false /* altitudeRequired */, _polylinePath, errorString)) {
return false;
}
for (int i=0; i<_polylinePath.count(); i++) {
_polylineModel.append(new QGCQGeoCoordinate(_polylinePath[i].value<QGeoCoordinate>(), this));
}
setDirty(false);
emit pathChanged();
return true;
}
QList<QGeoCoordinate> QGCMapPolyline::coordinateList(void) const
{
QList<QGeoCoordinate> coords;
for (int i=0; i<_polylinePath.count(); i++) {
coords.append(_polylinePath[i].value<QGeoCoordinate>());
}
return coords;
}
void QGCMapPolyline::splitSegment(int vertexIndex)
{
int nextIndex = vertexIndex + 1;
if (nextIndex > _polylinePath.length() - 1) {
return;
}
QGeoCoordinate firstVertex = _polylinePath[vertexIndex].value<QGeoCoordinate>();
QGeoCoordinate nextVertex = _polylinePath[nextIndex].value<QGeoCoordinate>();
double distance = firstVertex.distanceTo(nextVertex);
double azimuth = firstVertex.azimuthTo(nextVertex);
QGeoCoordinate newVertex = firstVertex.atDistanceAndAzimuth(distance / 2, azimuth);
if (nextIndex == 0) {
appendVertex(newVertex);
} else {
_polylineModel.insert(nextIndex, new QGCQGeoCoordinate(newVertex, this));
_polylinePath.insert(nextIndex, QVariant::fromValue(newVertex));
emit pathChanged();
}
}
void QGCMapPolyline::appendVertex(const QGeoCoordinate& coordinate)
{
_polylinePath.append(QVariant::fromValue(coordinate));
_polylineModel.append(new QGCQGeoCoordinate(coordinate, this));
emit pathChanged();
}
void QGCMapPolyline::removeVertex(int vertexIndex)
{
if (vertexIndex < 0 || vertexIndex > _polylinePath.length() - 1) {
qWarning() << "Call to removeVertex with bad vertexIndex:count" << vertexIndex << _polylinePath.length();
return;
}
if (_polylinePath.length() <= 2) {
// Don't allow the user to trash the polyline
return;
}
QObject* coordObj = _polylineModel.removeAt(vertexIndex);
coordObj->deleteLater();
_polylinePath.removeAt(vertexIndex);
emit pathChanged();
}
void QGCMapPolyline::setInteractive(bool interactive)
{
if (_interactive != interactive) {
_interactive = interactive;
emit interactiveChanged(interactive);
}
}
QGeoCoordinate QGCMapPolyline::vertexCoordinate(int vertex) const
{
if (vertex >= 0 && vertex < _polylinePath.count()) {
return _polylinePath[vertex].value<QGeoCoordinate>();
} else {
qWarning() << "QGCMapPolyline::vertexCoordinate bad vertex requested";
return QGeoCoordinate();
}
}
QList<QPointF> QGCMapPolyline::nedPolyline(void)
{
QList<QPointF> nedPolyline;
if (count() > 0) {
QGeoCoordinate tangentOrigin = vertexCoordinate(0);
for (int i=0; i<_polylinePath.count(); i++) {
double y, x, down;
QGeoCoordinate vertex = vertexCoordinate(i);
if (i == 0) {
// This avoids a nan calculation that comes out of convertGeoToNed
x = y = 0;
} else {
convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
}
nedPolyline += QPointF(x, y);
}
}
return nedPolyline;
}
QList<QGeoCoordinate> QGCMapPolyline::offsetPolyline(double distance)
{
QList<QGeoCoordinate> rgNewPolyline;
// I'm sure there is some beautiful famous algorithm to do this, but here is a brute force method
if (count() > 1) {
// Convert the polygon to NED
QList<QPointF> rgNedVertices = nedPolyline();
// Walk the edges, offsetting by the specified distance
QList<QLineF> rgOffsetEdges;
for (int i=0; i<rgNedVertices.count() - 1; i++) {
QLineF offsetEdge;
QLineF originalEdge(rgNedVertices[i], rgNedVertices[i + 1]);
QLineF workerLine = originalEdge;
workerLine.setLength(distance);
workerLine.setAngle(workerLine.angle() - 90.0);
offsetEdge.setP1(workerLine.p2());
workerLine.setPoints(originalEdge.p2(), originalEdge.p1());
workerLine.setLength(distance);
workerLine.setAngle(workerLine.angle() + 90.0);
offsetEdge.setP2(workerLine.p2());
rgOffsetEdges.append(offsetEdge);
}
QGeoCoordinate tangentOrigin = vertexCoordinate(0);
// Add first vertex
QGeoCoordinate coord;
convertNedToGeo(rgOffsetEdges[0].p1().y(), rgOffsetEdges[0].p1().x(), 0, tangentOrigin, &coord);
rgNewPolyline.append(coord);
// Intersect the offset edges to generate new central vertices
QPointF newVertex;
for (int i=1; i<rgOffsetEdges.count(); i++) {
if (rgOffsetEdges[i - 1].intersect(rgOffsetEdges[i], &newVertex) == QLineF::NoIntersection) {
// Two lines are colinear
newVertex = rgOffsetEdges[i].p2();
}
convertNedToGeo(newVertex.y(), newVertex.x(), 0, tangentOrigin, &coord);
rgNewPolyline.append(coord);
}
// Add last vertex
int lastIndex = rgOffsetEdges.count() - 1;
convertNedToGeo(rgOffsetEdges[lastIndex].p2().y(), rgOffsetEdges[lastIndex].p2().x(), 0, tangentOrigin, &coord);
rgNewPolyline.append(coord);
}
return rgNewPolyline;
}
bool QGCMapPolyline::loadKMLFile(const QString& kmlFile)
{
QFile file(kmlFile);
if (!file.exists()) {
qgcApp()->showMessage(tr("File not found: %1").arg(kmlFile));
return false;
}
if (!file.open(QIODevice::ReadOnly)) {
qgcApp()->showMessage(tr("Unable to open file: %1 error: $%2").arg(kmlFile).arg(file.errorString()));
return false;
}
QDomDocument doc;
QString errorMessage;
int errorLine;
if (!doc.setContent(&file, &errorMessage, &errorLine)) {
qgcApp()->showMessage(tr("Unable to parse KML file: %1 error: %2 line: %3").arg(kmlFile).arg(errorMessage).arg(errorLine));
return false;
}
QDomNodeList rgNodes = doc.elementsByTagName("Polygon");
if (rgNodes.count() == 0) {
qgcApp()->showMessage(tr("Unable to find Polygon node in KML"));
return false;
}
QDomNode coordinatesNode = rgNodes.item(0).namedItem("outerBoundaryIs").namedItem("LinearRing").namedItem("coordinates");
if (coordinatesNode.isNull()) {
qgcApp()->showMessage(tr("Internal error: Unable to find coordinates node in KML"));
return false;
}
QString coordinatesString = coordinatesNode.toElement().text().simplified();
QStringList rgCoordinateStrings = coordinatesString.split(" ");
QList<QGeoCoordinate> rgCoords;
for (int i=0; i<rgCoordinateStrings.count()-1; i++) {
QString coordinateString = rgCoordinateStrings[i];
QStringList rgValueStrings = coordinateString.split(",");
QGeoCoordinate coord;
coord.setLongitude(rgValueStrings[0].toDouble());
coord.setLatitude(rgValueStrings[1].toDouble());
rgCoords.append(coord);
}
// Determine winding, reverse if needed
double sum = 0;
for (int i=0; i<rgCoords.count(); i++) {
QGeoCoordinate coord1 = rgCoords[i];
QGeoCoordinate coord2 = (i == rgCoords.count() - 1) ? rgCoords[0] : rgCoords[i+1];
sum += (coord2.longitude() - coord1.longitude()) * (coord2.latitude() + coord1.latitude());
}
bool reverse = sum < 0.0;
if (reverse) {
QList<QGeoCoordinate> rgReversed;
for (int i=0; i<rgCoords.count(); i++) {
rgReversed.prepend(rgCoords[i]);
}
rgCoords = rgReversed;
}
clear();
for (int i=0; i<rgCoords.count(); i++) {
appendVertex(rgCoords[i]);
}
return true;
}
void QGCMapPolyline::_polylineModelDirtyChanged(bool dirty)
{
if (dirty) {
setDirty(true);
}
}
void QGCMapPolyline::_polylineModelCountChanged(int count)
{
emit countChanged(count);
}
double QGCMapPolyline::length(void) const
{
double length = 0;
for (int i=0; i<_polylinePath.count() - 1; i++) {
QGeoCoordinate from = _polylinePath[i].value<QGeoCoordinate>();
QGeoCoordinate to = _polylinePath[i+1].value<QGeoCoordinate>();
length += from.distanceTo(to);
}
return length;
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QGeoCoordinate>
#include <QVariantList>
#include "QmlObjectListModel.h"
class QGCMapPolyline : public QObject
{
Q_OBJECT
public:
QGCMapPolyline(QObject* parent = NULL);
QGCMapPolyline(const QGCMapPolyline& other, QObject* parent = NULL);
const QGCMapPolyline& operator=(const QGCMapPolyline& other);
Q_PROPERTY(int count READ count NOTIFY countChanged)
Q_PROPERTY(QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged)
Q_INVOKABLE void clear(void);
Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
Q_INVOKABLE void removeVertex(int vertexIndex);
/// Adjust the value for the specified coordinate
/// @param vertexIndex Polygon point index to modify (0-based)
/// @param coordinate New coordinate for point
Q_INVOKABLE void adjustVertex(int vertexIndex, const QGeoCoordinate coordinate);
/// Splits the line segment comprised of vertexIndex -> vertexIndex + 1
Q_INVOKABLE void splitSegment(int vertexIndex);
/// Offsets the current polyline edges by the specified distance in meters
/// @return Offset set of vertices
QList<QGeoCoordinate> offsetPolyline(double distance);
/// Loads a polyline from a KML file
/// @return true: success
Q_INVOKABLE bool loadKMLFile(const QString& kmlFile);
/// Returns the path in a list of QGeoCoordinate's format
QList<QGeoCoordinate> coordinateList(void) const;
/// Returns the QGeoCoordinate for the vertex specified
QGeoCoordinate vertexCoordinate(int vertex) const;
/// Saves the polyline to the json object.
/// @param json Json object to save to
void saveToJson(QJsonObject& json);
/// Load a polyline from json
/// @param json Json object to load from
/// @param required true: no polygon in object will generate error
/// @param errorString Error string if return is false
/// @return true: success, false: failure (errorString set)
bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
/// Convert polyline to NED and return (D is ignored)
QList<QPointF> nedPolyline(void);
/// Returns the length of the polyline in meters
double length(void) const;
// Property methods
int count (void) const { return _polylinePath.count(); }
bool dirty (void) const { return _dirty; }
void setDirty (bool dirty);
bool interactive (void) const { return _interactive; }
QVariantList path (void) const { return _polylinePath; }
QmlObjectListModel* qmlPathModel(void) { return &_polylineModel; }
QmlObjectListModel& pathModel (void) { return _polylineModel; }
void setPath (const QList<QGeoCoordinate>& path);
void setPath (const QVariantList& path);
void setInteractive (bool interactive);
static const char* jsonPolylineKey;
signals:
void countChanged (int count);
void pathChanged (void);
void dirtyChanged (bool dirty);
void cleared (void);
void interactiveChanged (bool interactive);
private slots:
void _polylineModelCountChanged(int count);
void _polylineModelDirtyChanged(bool dirty);
private:
void _init(void);
QGeoCoordinate _coordFromPointF(const QPointF& point) const;
QPointF _pointFFromCoord(const QGeoCoordinate& coordinate) const;
QVariantList _polylinePath;
QmlObjectListModel _polylineModel;
bool _dirty;
bool _interactive;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "QGCMapPolylineTest.h"
#include "QGCApplication.h"
#include "QGCQGeoCoordinate.h"
QGCMapPolylineTest::QGCMapPolylineTest(void)
{
_linePoints << QGeoCoordinate(47.635638361473475, -122.09269407980834 ) <<
QGeoCoordinate(47.635638361473475, -122.08545246602667) <<
QGeoCoordinate(47.63057923872075, -122.08545246602667) <<
QGeoCoordinate(47.63057923872075, -122.09269407980834);
}
void QGCMapPolylineTest::init(void)
{
UnitTest::init();
_rgSignals[countChangedIndex] = SIGNAL(countChanged(int));
_rgSignals[pathChangedIndex] = SIGNAL(pathChanged());
_rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_rgSignals[clearedIndex] = SIGNAL(cleared());
_rgModelSignals[modelCountChangedIndex] = SIGNAL(countChanged(int));
_rgModelSignals[modelDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_mapPolyline = new QGCMapPolyline(this);
_pathModel = _mapPolyline->qmlPathModel();
QVERIFY(_pathModel);
_multiSpyPolyline = new MultiSignalSpy();
QCOMPARE(_multiSpyPolyline->init(_mapPolyline, _rgSignals, _cSignals), true);
_multiSpyModel = new MultiSignalSpy();
QCOMPARE(_multiSpyModel->init(_pathModel, _rgModelSignals, _cModelSignals), true);
}
void QGCMapPolylineTest::cleanup(void)
{
delete _mapPolyline;
delete _multiSpyPolyline;
delete _multiSpyModel;
}
void QGCMapPolylineTest::_testDirty(void)
{
// Check basic dirty bit set/get
QVERIFY(!_mapPolyline->dirty());
QVERIFY(!_pathModel->dirty());
_mapPolyline->setDirty(false);
QVERIFY(!_mapPolyline->dirty());
QVERIFY(!_pathModel->dirty());
QVERIFY(_multiSpyPolyline->checkNoSignals());
QVERIFY(_multiSpyModel->checkNoSignals());
_mapPolyline->setDirty(true);
QVERIFY(_mapPolyline->dirty());
QVERIFY(!_pathModel->dirty());
QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpyModel->checkNoSignals());
_multiSpyPolyline->clearAllSignals();
_mapPolyline->setDirty(false);
QVERIFY(!_mapPolyline->dirty());
QVERIFY(!_pathModel->dirty());
QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(!_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpyModel->checkNoSignals());
_multiSpyPolyline->clearAllSignals();
_pathModel->setDirty(true);
QVERIFY(_pathModel->dirty());
QVERIFY(_mapPolyline->dirty());
QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask));
QVERIFY(_multiSpyModel->pullBoolFromSignalIndex(modelDirtyChangedIndex));
_multiSpyPolyline->clearAllSignals();
_multiSpyModel->clearAllSignals();
_mapPolyline->setDirty(false);
QVERIFY(!_mapPolyline->dirty());
QVERIFY(!_pathModel->dirty());
QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(!_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask));
QVERIFY(!_multiSpyModel->pullBoolFromSignalIndex(modelDirtyChangedIndex));
_multiSpyPolyline->clearAllSignals();
_multiSpyModel->clearAllSignals();
}
void QGCMapPolylineTest::_testVertexManipulation(void)
{
// Vertex addition testing
for (int i=0; i<_linePoints.count(); i++) {
QCOMPARE(_mapPolyline->count(), i);
_mapPolyline->appendVertex(_linePoints[i]);
QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(pathChangedMask | dirtyChangedMask | countChangedMask));
QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask | modelCountChangedMask));
QCOMPARE(_multiSpyPolyline->pullIntFromSignalIndex(countChangedIndex), i+1);
QCOMPARE(_multiSpyModel->pullIntFromSignalIndex(modelCountChangedIndex), i+1);
QVERIFY(_mapPolyline->dirty());
QVERIFY(_pathModel->dirty());
QCOMPARE(_mapPolyline->count(), i+1);
QVariantList vertexList = _mapPolyline->path();
QCOMPARE(vertexList.count(), i+1);
QCOMPARE(vertexList[i].value<QGeoCoordinate>(), _linePoints[i]);
QCOMPARE(_pathModel->count(), i+1);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(i)->coordinate(), _linePoints[i]);
_mapPolyline->setDirty(false);
_multiSpyPolyline->clearAllSignals();
_multiSpyModel->clearAllSignals();
}
// Vertex adjustment testing
QGCQGeoCoordinate* geoCoord = _pathModel->value<QGCQGeoCoordinate*>(1);
QSignalSpy coordSpy(geoCoord, SIGNAL(coordinateChanged(QGeoCoordinate)));
QSignalSpy coordDirtySpy(geoCoord, SIGNAL(dirtyChanged(bool)));
QGeoCoordinate adjustCoord(_linePoints[1].latitude() + 1, _linePoints[1].longitude() + 1);
_mapPolyline->adjustVertex(1, adjustCoord);
QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(pathChangedMask | dirtyChangedMask));
QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask));
QCOMPARE(coordSpy.count(), 1);
QCOMPARE(coordDirtySpy.count(), 1);
QCOMPARE(geoCoord->coordinate(), adjustCoord);
QVariantList vertexList = _mapPolyline->path();
QCOMPARE(vertexList[0].value<QGeoCoordinate>(), _linePoints[0]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(0)->coordinate(), _linePoints[0]);
QCOMPARE(vertexList[2].value<QGeoCoordinate>(), _linePoints[2]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(2)->coordinate(), _linePoints[2]);
QCOMPARE(vertexList[3].value<QGeoCoordinate>(), _linePoints[3]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(3)->coordinate(), _linePoints[3]);
_mapPolyline->setDirty(false);
_multiSpyPolyline->clearAllSignals();
_multiSpyModel->clearAllSignals();
// Vertex removal testing
_mapPolyline->removeVertex(1);
QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(pathChangedMask | dirtyChangedMask | countChangedMask));
QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask | modelCountChangedMask));
QCOMPARE(_mapPolyline->count(), 3);
vertexList = _mapPolyline->path();
QCOMPARE(vertexList.count(), 3);
QCOMPARE(_pathModel->count(), 3);
QCOMPARE(vertexList[0].value<QGeoCoordinate>(), _linePoints[0]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(0)->coordinate(), _linePoints[0]);
QCOMPARE(vertexList[1].value<QGeoCoordinate>(), _linePoints[2]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(1)->coordinate(), _linePoints[2]);
QCOMPARE(vertexList[2].value<QGeoCoordinate>(), _linePoints[3]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(2)->coordinate(), _linePoints[3]);
// Clear testing
_mapPolyline->clear();
QVERIFY(_multiSpyPolyline->checkOnlySignalsByMask(pathChangedMask | dirtyChangedMask | countChangedMask | clearedMask));
QVERIFY(_multiSpyModel->checkOnlySignalsByMask(modelDirtyChangedMask | modelCountChangedMask));
QVERIFY(_mapPolyline->dirty());
QVERIFY(_pathModel->dirty());
QCOMPARE(_mapPolyline->count(), 0);
vertexList = _mapPolyline->path();
QCOMPARE(vertexList.count(), 0);
QCOMPARE(_pathModel->count(), 0);
}
#if 0
void QGCMapPolylineTest::_testKMLLoad(void)
{
QVERIFY(_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/PolygonGood.kml")));
setExpectedMessageBox(QMessageBox::Ok);
QVERIFY(!_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/BadXml.kml")));
checkExpectedMessageBox();
setExpectedMessageBox(QMessageBox::Ok);
QVERIFY(!_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/MissingPolygonNode.kml")));
checkExpectedMessageBox();
setExpectedMessageBox(QMessageBox::Ok);
QVERIFY(!_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/BadCoordinatesNode.kml")));
checkExpectedMessageBox();
}
#endif
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "UnitTest.h"
#include "MultiSignalSpy.h"
#include "QGCMapPolyline.h"
#include "QmlObjectListModel.h"
class QGCMapPolylineTest : public UnitTest
{
Q_OBJECT
public:
QGCMapPolylineTest(void);
protected:
void init(void) final;
void cleanup(void) final;
private slots:
void _testDirty(void);
void _testVertexManipulation(void);
// void _testKMLLoad(void);
private:
enum {
countChangedIndex = 0,
pathChangedIndex,
dirtyChangedIndex,
clearedIndex,
maxSignalIndex
};
enum {
countChangedMask = 1 << countChangedIndex,
pathChangedMask = 1 << pathChangedIndex,
dirtyChangedMask = 1 << dirtyChangedIndex,
clearedMask = 1 << clearedIndex,
};
static const size_t _cSignals = maxSignalIndex;
const char* _rgSignals[_cSignals];
enum {
modelCountChangedIndex = 0,
modelDirtyChangedIndex,
maxModelSignalIndex
};
enum {
modelCountChangedMask = 1 << modelCountChangedIndex,
modelDirtyChangedMask = 1 << modelDirtyChangedIndex,
};
static const size_t _cModelSignals = maxModelSignalIndex;
const char* _rgModelSignals[_cModelSignals];
MultiSignalSpy* _multiSpyPolyline;
MultiSignalSpy* _multiSpyModel;
QGCMapPolyline* _mapPolyline;
QmlObjectListModel* _pathModel;
QList<QGeoCoordinate> _linePoints;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// QGCmapPolyline map visuals
Item {
id: _root
property var qgcView ///< QGCView for popping dialogs
property var mapControl ///< Map control to place item in
property var mapPolyline ///< QGCMapPolyline object
property bool interactive: mapPolyline.interactive
property int lineWidth: 3
property color lineColor: "#be781c"
property var _polylineComponent
property var _dragHandlesComponent
property var _splitHandlesComponent
property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap
property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2
function addVisuals() {
_polylineComponent = polylineComponent.createObject(mapControl)
mapControl.addMapItem(_polylineComponent)
}
function removeVisuals() {
_polylineComponent.destroy()
}
function addHandles() {
if (!_dragHandlesComponent) {
_dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
_splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
}
}
function removeHandles() {
if (_dragHandlesComponent) {
_dragHandlesComponent.destroy()
_dragHandlesComponent = undefined
}
if (_splitHandlesComponent) {
_splitHandlesComponent.destroy()
_splitHandlesComponent = undefined
}
}
/// Calculate the default/initial polyline
function defaultPolylineVertices() {
var x = map.centerViewport.x + (map.centerViewport.width / 2)
var yInset = map.centerViewport.height / 4
var topPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + yInset), false /* clipToViewPort */)
var bottomPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + map.centerViewport.height - yInset), false /* clipToViewPort */)
return [ topPointCoord, bottomPointCoord ]
}
/// Add an initial 2 point polyline
function addInitialPolyline() {
if (mapPolyline.count < 2) {
mapPolyline.clear()
var initialVertices = defaultPolylineVertices()
mapPolyline.appendVertex(initialVertices[0])
mapPolyline.appendVertex(initialVertices[1])
}
}
/// Reset polyline back to initial default
function resetPolyline() {
mapPolyline.clear()
addInitialPolyline()
}
onInteractiveChanged: {
if (interactive) {
addHandles()
} else {
removeHandles()
}
}
Component.onCompleted: {
addVisuals()
if (interactive) {
addHandles()
}
}
Component.onDestruction: {
removeVisuals()
removeHandles()
}
QGCPalette { id: qgcPal }
QGCFileDialog {
id: kmlLoadDialog
qgcView: _root.qgcView
folder: QGroundControl.settingsManager.appSettings.missionSavePath
title: qsTr("Select KML File")
selectExisting: true
nameFilters: [ qsTr("KML files (*.kml)") ]
onAcceptedForLoad: {
mapPolyline.loadKMLFile(file)
close()
}
}
Component {
id: polylineComponent
MapPolyline {
line.width: lineWidth
line.color: lineColor
path: mapPolyline.path
}
}
Component {
id: splitHandleComponent
MapQuickItem {
id: mapQuickItem
anchorPoint.x: splitHandle.width / 2
anchorPoint.y: splitHandle.height / 2
property int vertexIndex
sourceItem: Rectangle {
id: splitHandle
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
radius: width / 2
border.color: "white"
color: "transparent"
opacity: .50
z: _zorderSplitHandle
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter
text: "+"
}
QGCMouseArea {
fillItem: parent
onClicked: mapPolyline.splitSegment(mapQuickItem.vertexIndex)
}
}
}
}
Component {
id: splitHandlesComponent
Repeater {
model: mapPolyline.path
delegate: Item {
property var _splitHandle
property var _vertices: mapPolyline.path
function _setHandlePosition() {
var nextIndex = index + 1
var distance = _vertices[index].distanceTo(_vertices[nextIndex])
var azimuth = _vertices[index].azimuthTo(_vertices[nextIndex])
_splitHandle.coordinate = _vertices[index].atDistanceAndAzimuth(distance / 2, azimuth)
}
Component.onCompleted: {
if (index + 1 <= _vertices.length - 1) {
_splitHandle = splitHandleComponent.createObject(mapControl)
_splitHandle.vertexIndex = index
_setHandlePosition()
mapControl.addMapItem(_splitHandle)
}
}
Component.onDestruction: {
if (_splitHandle) {
_splitHandle.destroy()
}
}
}
}
}
// Control which is used to drag polygon vertices
Component {
id: dragAreaComponent
MissionItemIndicatorDrag {
id: dragArea
z: _zorderDragHandle
property int polylineVertex
property bool _creationComplete: false
Component.onCompleted: _creationComplete = true
onItemCoordinateChanged: {
if (_creationComplete) {
// During component creation some bad coordinate values got through which screws up draw
mapPolyline.adjustVertex(polylineVertex, itemCoordinate)
}
}
onClicked: mapPolyline.removeVertex(polylineVertex)
}
}
Component {
id: dragHandleComponent
MapQuickItem {
id: mapQuickItem
anchorPoint.x: dragHandle.width / 2
anchorPoint.y: dragHandle.height / 2
z: _zorderDragHandle
property int polylineVertex
sourceItem: Rectangle {
id: dragHandle
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
radius: width / 2
color: "white"
opacity: .90
}
}
}
// Add all polygon vertex drag handles to the map
Component {
id: dragHandlesComponent
Repeater {
model: mapPolyline.pathModel
delegate: Item {
property var _visuals: [ ]
Component.onCompleted: {
var dragHandle = dragHandleComponent.createObject(mapControl)
dragHandle.coordinate = Qt.binding(function() { return object.coordinate })
dragHandle.polylineVertex = Qt.binding(function() { return index })
mapControl.addMapItem(dragHandle)
var dragArea = dragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": object.coordinate })
dragArea.polylineVertex = Qt.binding(function() { return index })
_visuals.push(dragHandle)
_visuals.push(dragArea)
}
Component.onDestruction: {
for (var i=0; i<_visuals.length; i++) {
_visuals[i].destroy()
}
_visuals = [ ]
}
}
}
}
}
......@@ -102,7 +102,7 @@ void StructureScanComplexItem::_setScanDistance(double scanDistance)
{
if (!qFuzzyCompare(_scanDistance, scanDistance)) {
_scanDistance = scanDistance;
emit complexDistanceChanged(_scanDistance);
emit complexDistanceChanged();
}
}
......
......@@ -159,7 +159,7 @@ void SurveyMissionItem::_setSurveyDistance(double surveyDistance)
{
if (!qFuzzyCompare(_surveyDistance, surveyDistance)) {
_surveyDistance = surveyDistance;
emit complexDistanceChanged(_surveyDistance);
emit complexDistanceChanged();
}
}
......@@ -742,7 +742,7 @@ void SurveyMissionItem::_generateGrid(void)
if (_hoverAndCaptureEnabled()) {
_additionalFlightDelaySeconds = cameraShots * _hoverAndCaptureDelaySeconds;
}
emit additionalTimeDelayChanged(_additionalFlightDelaySeconds);
emit additionalTimeDelayChanged();
emit gridPointsChanged();
......
<?xml version="1.0" encoding="UTF-8"?>
<kml xmlns="http://www.opengis.net/kml/2.2" xmlns:gx="http://www.google.com/kml/ext/2.2" xmlns:kml="http://www.opengis.net/kml/2.2" xmlns:atom="http://www.w3.org/2005/Atom">
<Document>
<name>AreaTestPolygon.kmz</name>
<StyleMap id="m_ylw-pushpin">
<Pair>
<key>normal</key>
<styleUrl>#s_ylw-pushpin</styleUrl>
</Pair>
<Pair>
<key>highlight</key>
<styleUrl>#s_ylw-pushpin_hl</styleUrl>
</Pair>
</StyleMap>
<Style id="s_ylw-pushpin">
<IconStyle>
<scale>1.1</scale>
<Icon>
<href>http://maps.google.com/mapfiles/kml/pushpin/ylw-pushpin.png</href>
</Icon>
<hotSpot x="20" y="2" xunits="pixels" yunits="pixels"/>
</IconStyle>
</Style>
<Style id="s_ylw-pushpin_hl">
<IconStyle>
<scale>1.3</scale>
<Icon>
<href>http://maps.google.com/mapfiles/kml/pushpin/ylw-pushpin.png</href>
</Icon>
<hotSpot x="20" y="2" xunits="pixels" yunits="pixels"/>
</IconStyle>
</Style>
<Placemark>
<name>Untitled Polygon</name>
<styleUrl>#m_ylw-pushpin</styleUrl>
<Polygon>
<tessellate>1</tessellate>
<outerBoundaryIs>
<LinearRing>
<coordinates>
-122.1059149362712,47.65965281788451,0 -122.1044593196253,47.66002598220988,0 -122.1047336695092,47.66034166158975,0 -122.1061470943783,47.6599810708829,0 -122.1059149362712,47.65965281788451,0
</coordinates>
</LinearRing>
</outerBoundaryIs>
</Polygon>
</Placemark>
</Document>
</kml>
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtQuick.Extras 1.4
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controls 1.0
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
width: availableWidth
color: qgcPal.windowShadeDark
radius: _radius
// The following properties must be available up the hierarchy chain
//property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
function polygonCaptureStarted() {
missionItem.clearPolygon()
}
function polygonCaptureFinished(coordinates) {
for (var i=0; i<coordinates.length; i++) {
missionItem.addPolygonCoordinate(coordinates[i])
}
}
function polygonAdjustVertex(vertexIndex, vertexCoordinate) {
missionItem.adjustPolygonCoordinate(vertexIndex, vertexCoordinate)
}
function polygonAdjustStarted() { }
function polygonAdjustFinished() { }
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Column {
id: editorColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("WARNING WORK IN PROGRESS: BE VERY CAREFUL WHEN FLYING")
wrapMode: Text.WordWrap
color: qgcPal.warningText
font.pointSize: ScreenTools.smallFontPointSize
}
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))
wrapMode: Text.WordWrap
color: qgcPal.warningText
visible: missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
}
CameraCalc {
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true
distanceToSurfaceLabel: qsTr("Altitude")
frontalDistanceLabel: qsTr("Trigger Distance")
sideDistanceLabel: qsTr("Spacing")
}
SectionHeader {
id: corridorHeader
text: qsTr("Corridor")
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: corridorHeader.checked
QGCLabel { text: qsTr("Width") }
FactTextField {
fact: missionItem.corridorWidth
Layout.fillWidth: true
}
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
}
Grid {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
visible: statsHeader.checked
QGCLabel { text: qsTr("Photo count") }
QGCLabel { text: missionItem.cameraShots }
QGCLabel { text: qsTr("Photo interval") }
QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") }
}
} // Column
} // Rectangle
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.Controls 1.0
/// Corridor Scan Complex Mission Item visuals
Item {
id: _root
property var map ///< Map control to place item in
property var qgcView ///< QGCView to use for popping dialogs
property var _missionItem: object
property var _entryCoordinate
property var _exitCoordinate
property var _transectLines
signal clicked(int sequenceNumber)
function _addVisualElements() {
_entryCoordinate = entryPointComponent.createObject(map)
_exitCoordinate = exitPointComponent.createObject(map)
_transectLines = transectsComponent.createObject(map)
map.addMapItem(_entryCoordinate)
map.addMapItem(_exitCoordinate)
map.addMapItem(_transectLines)
}
function _destroyVisualElements() {
_entryCoordinate.destroy()
_exitCoordinate.destroy()
_transectLines.destroy()
}
Component.onCompleted: {
mapPolylineVisuals.addInitialPolyline()
_addVisualElements()
}
Component.onDestruction: {
_destroyVisualElements()
}
QGCMapPolygonVisuals {
qgcView: _root.qgcView
mapControl: map
mapPolygon: object.corridorPolygon
interactive: false
interiorColor: "green"
interiorOpacity: 0.25
}
QGCMapPolylineVisuals {
id: mapPolylineVisuals
qgcView: _root.qgcView
mapControl: map
mapPolyline: object.corridorPolyline
interactive: _missionItem.isCurrentItem
lineWidth: 3
lineColor: "#be781c"
}
// Entry point
Component {
id: entryPointComponent
MapQuickItem {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.coordinate
visible: _missionItem.coordinate.isValid
sourceItem: MissionItemIndexLabel {
index: _missionItem.sequenceNumber
label: "Entry"
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
// Exit point
Component {
id: exitPointComponent
MapQuickItem {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.exitCoordinate
visible: _missionItem.exitCoordinate.isValid
sourceItem: MissionItemIndexLabel {
index: _missionItem.lastSequenceNumber
label: "Exit"
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
}
}
}
// Transect lines
Component {
id: transectsComponent
MapPolyline {
line.color: "white"
line.width: 2
path: _missionItem.transectPoints
}
}
}
......@@ -48,6 +48,7 @@ QGCListView 1.0 QGCListView.qml
QGCMapLabel 1.0 QGCMapLabel.qml
QGCMapCircleVisuals 1.0 QGCMapCircleVisuals.qml
QGCMapPolygonVisuals 1.0 QGCMapPolygonVisuals.qml
QGCMapPolylineVisuals 1.0 QGCMapPolylineVisuals.qml
QGCMouseArea 1.0 QGCMouseArea.qml
QGCMovableItem 1.0 QGCMovableItem.qml
QGCPipable 1.0 QGCPipable.qml
......
......@@ -40,6 +40,8 @@
#include "QGCMapPolygonTest.h"
#include "AudioOutputTest.h"
#include "StructureScanComplexItemTest.h"
#include "QGCMapPolylineTest.h"
#include "CorridorScanComplexItemTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
......@@ -67,6 +69,8 @@ UT_REGISTER_TEST(MissionSettingsTest)
UT_REGISTER_TEST(QGCMapPolygonTest)
UT_REGISTER_TEST(AudioOutputTest)
UT_REGISTER_TEST(StructureScanComplexItemTest)
UT_REGISTER_TEST(CorridorScanComplexItemTest)
UT_REGISTER_TEST(QGCMapPolylineTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
......
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