/**************************************************************************** * * (c) 2009-2016 QGROUNDCONTROL PROJECT * * QGroundControl is licensed according to the terms in the file * COPYING.md in the root of the source code directory. * ****************************************************************************/ #include "SurveyMissionItem.h" #include "JsonHelper.h" #include "MissionController.h" #include "QGCGeo.h" #include "QGroundControlQmlGlobal.h" #include QGC_LOGGING_CATEGORY(SurveyMissionItemLog, "SurveyMissionItemLog") const char* SurveyMissionItem::jsonComplexItemTypeValue = "survey"; const char* SurveyMissionItem::_jsonPolygonObjectKey = "polygon"; const char* SurveyMissionItem::_jsonGridObjectKey = "grid"; const char* SurveyMissionItem::_jsonGridAltitudeKey = "altitude"; const char* SurveyMissionItem::_jsonGridAltitudeRelativeKey = "relativeAltitude"; const char* SurveyMissionItem::_jsonGridAngleKey = "angle"; const char* SurveyMissionItem::_jsonGridSpacingKey = "spacing"; const char* SurveyMissionItem::_jsonTurnaroundDistKey = "turnAroundDistance"; const char* SurveyMissionItem::_jsonCameraTriggerKey = "cameraTrigger"; const char* SurveyMissionItem::_jsonCameraTriggerDistanceKey = "cameraTriggerDistance"; const char* SurveyMissionItem::_jsonGroundResolutionKey = "groundResolution"; const char* SurveyMissionItem::_jsonFrontalOverlapKey = "imageFrontalOverlap"; const char* SurveyMissionItem::_jsonSideOverlapKey = "imageSideOverlap"; const char* SurveyMissionItem::_jsonCameraSensorWidthKey = "sensorWidth"; const char* SurveyMissionItem::_jsonCameraSensorHeightKey = "sensorHeight"; const char* SurveyMissionItem::_jsonCameraResolutionWidthKey = "resolutionWidth"; const char* SurveyMissionItem::_jsonCameraResolutionHeightKey = "resolutionHeight"; const char* SurveyMissionItem::_jsonCameraFocalLengthKey = "focalLength"; const char* SurveyMissionItem::_jsonCameraObjectKey = "camera"; const char* SurveyMissionItem::_jsonCameraNameKey = "name"; const char* SurveyMissionItem::_jsonManualGridKey = "manualGrid"; const char* SurveyMissionItem::_jsonCameraOrientationLandscapeKey = "orientationLandscape"; const char* SurveyMissionItem::_jsonFixedValueIsAltitudeKey = "fixedValueIsAltitude"; const char* SurveyMissionItem::settingsGroup = "Survey"; const char* SurveyMissionItem::manualGridName = "ManualGrid"; const char* SurveyMissionItem::gridAltitudeName = "GridAltitude"; const char* SurveyMissionItem::gridAltitudeRelativeName = "GridAltitudeRelative"; const char* SurveyMissionItem::gridAngleName = "GridAngle"; const char* SurveyMissionItem::gridSpacingName = "GridSpacing"; const char* SurveyMissionItem::turnaroundDistName = "TurnaroundDist"; const char* SurveyMissionItem::cameraTriggerDistanceName = "CameraTriggerDistance"; const char* SurveyMissionItem::groundResolutionName = "GroundResolution"; const char* SurveyMissionItem::frontalOverlapName = "FrontalOverlap"; const char* SurveyMissionItem::sideOverlapName = "SideOverlap"; const char* SurveyMissionItem::cameraSensorWidthName = "CameraSensorWidth"; const char* SurveyMissionItem::cameraSensorHeightName = "CameraSensorHeight"; const char* SurveyMissionItem::cameraResolutionWidthName = "CameraResolutionWidth"; const char* SurveyMissionItem::cameraResolutionHeightName = "CameraResolutionHeight"; const char* SurveyMissionItem::cameraFocalLengthName = "CameraFocalLength"; const char* SurveyMissionItem::cameraTriggerName = "CameraTrigger"; const char* SurveyMissionItem::cameraOrientationLandscapeName = "CameraOrientationLandscape"; const char* SurveyMissionItem::fixedValueIsAltitudeName = "FixedValueIsAltitude"; const char* SurveyMissionItem::cameraName = "Camera"; SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) : ComplexMissionItem(vehicle, parent) , _sequenceNumber(0) , _dirty(false) , _surveyDistance(0.0) , _cameraShots(0) , _coveredArea(0.0) , _timeBetweenShots(0.0) , _metaDataMap(FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this)) , _manualGridFact (settingsGroup, _metaDataMap[manualGridName]) , _gridAltitudeFact (settingsGroup, _metaDataMap[gridAltitudeName]) , _gridAltitudeRelativeFact (settingsGroup, _metaDataMap[gridAltitudeRelativeName]) , _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName]) , _gridSpacingFact (settingsGroup, _metaDataMap[gridSpacingName]) , _turnaroundDistFact (settingsGroup, _metaDataMap[turnaroundDistName]) , _cameraTriggerFact (settingsGroup, _metaDataMap[cameraTriggerName]) , _cameraTriggerDistanceFact (settingsGroup, _metaDataMap[cameraTriggerDistanceName]) , _groundResolutionFact (settingsGroup, _metaDataMap[groundResolutionName]) , _frontalOverlapFact (settingsGroup, _metaDataMap[frontalOverlapName]) , _sideOverlapFact (settingsGroup, _metaDataMap[sideOverlapName]) , _cameraSensorWidthFact (settingsGroup, _metaDataMap[cameraSensorWidthName]) , _cameraSensorHeightFact (settingsGroup, _metaDataMap[cameraSensorHeightName]) , _cameraResolutionWidthFact (settingsGroup, _metaDataMap[cameraResolutionWidthName]) , _cameraResolutionHeightFact (settingsGroup, _metaDataMap[cameraResolutionHeightName]) , _cameraFocalLengthFact (settingsGroup, _metaDataMap[cameraFocalLengthName]) , _cameraOrientationLandscapeFact (settingsGroup, _metaDataMap[cameraOrientationLandscapeName]) , _fixedValueIsAltitudeFact (settingsGroup, _metaDataMap[fixedValueIsAltitudeName]) , _cameraFact (settingsGroup, _metaDataMap[cameraName]) { _editorQml = "qrc:/qml/SurveyItemEditor.qml"; if (_vehicle->multiRotor()) { _turnaroundDistFact.setRawValue(0); } connect(&_gridSpacingFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_turnaroundDistFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_gridAltitudeFact, &Fact::valueChanged, this, &SurveyMissionItem::_updateCoordinateAltitude); // Signal to Qml when camera value changes to it can recalc connect(&_groundResolutionFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_frontalOverlapFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_sideOverlapFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraSensorWidthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraSensorHeightFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraResolutionWidthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraResolutionHeightFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraFocalLengthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraTriggerFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraTriggerChanged); connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged); // NULL check since object creation during unit testing passes NULL for vehicle if (_vehicle) { connect(_vehicle, &Vehicle::cruiseSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged); connect(_vehicle, &Vehicle::hoverSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged); } } void SurveyMissionItem::_setSurveyDistance(double surveyDistance) { if (!qFuzzyCompare(_surveyDistance, surveyDistance)) { _surveyDistance = surveyDistance; emit complexDistanceChanged(_surveyDistance); } } void SurveyMissionItem::_setCameraShots(int cameraShots) { if (_cameraShots != cameraShots) { _cameraShots = cameraShots; emit cameraShotsChanged(this->cameraShots()); } } void SurveyMissionItem::_setCoveredArea(double coveredArea) { if (!qFuzzyCompare(_coveredArea, coveredArea)) { _coveredArea = coveredArea; emit coveredAreaChanged(_coveredArea); } } void SurveyMissionItem::clearPolygon(void) { // Bug workaround, see below while (_polygonPath.count() > 1) { _polygonPath.takeLast(); } emit polygonPathChanged(); // Although this code should remove the polygon from the map it doesn't. There appears // to be a bug in MapPolygon which causes it to not be redrawn if the list is empty. So // we work around it by using the code above to remove all but the last point which in turn // will cause the polygon to go away. _polygonPath.clear(); _clearGrid(); setDirty(true); emit specifiesCoordinateChanged(); emit lastSequenceNumberChanged(lastSequenceNumber()); } void SurveyMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate) { _polygonPath << QVariant::fromValue(coordinate); emit polygonPathChanged(); int pointCount = _polygonPath.count(); if (pointCount >= 3) { if (pointCount == 3) { emit specifiesCoordinateChanged(); } _generateGrid(); } setDirty(true); } void SurveyMissionItem::adjustPolygonCoordinate(int vertexIndex, const QGeoCoordinate coordinate) { _polygonPath[vertexIndex] = QVariant::fromValue(coordinate); emit polygonPathChanged(); _generateGrid(); setDirty(true); } int SurveyMissionItem::lastSequenceNumber(void) const { int lastSeq = _sequenceNumber; if (_gridPoints.count()) { lastSeq += _gridPoints.count() - 1; if (_cameraTriggerFact.rawValue().toBool()) { // Account for two trigger messages lastSeq += 2; } } return lastSeq; } void SurveyMissionItem::setCoordinate(const QGeoCoordinate& coordinate) { if (_coordinate != coordinate) { _coordinate = coordinate; emit coordinateChanged(_coordinate); } } void SurveyMissionItem::setDirty(bool dirty) { if (_dirty != dirty) { _dirty = dirty; emit dirtyChanged(_dirty); } } void SurveyMissionItem::save(QJsonObject& saveObject) const { saveObject[JsonHelper::jsonVersionKey] = 3; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; saveObject[_jsonCameraTriggerKey] = _cameraTriggerFact.rawValue().toBool(); saveObject[_jsonManualGridKey] = _manualGridFact.rawValue().toBool(); saveObject[_jsonFixedValueIsAltitudeKey] = _fixedValueIsAltitudeFact.rawValue().toBool(); if (_cameraTriggerFact.rawValue().toBool()) { saveObject[_jsonCameraTriggerDistanceKey] = _cameraTriggerDistanceFact.rawValue().toDouble(); } QJsonObject gridObject; gridObject[_jsonGridAltitudeKey] = _gridAltitudeFact.rawValue().toDouble(); gridObject[_jsonGridAltitudeRelativeKey] = _gridAltitudeRelativeFact.rawValue().toBool(); gridObject[_jsonGridAngleKey] = _gridAngleFact.rawValue().toDouble(); gridObject[_jsonGridSpacingKey] = _gridSpacingFact.rawValue().toDouble(); gridObject[_jsonTurnaroundDistKey] = _turnaroundDistFact.rawValue().toDouble(); saveObject[_jsonGridObjectKey] = gridObject; if (!_manualGridFact.rawValue().toBool()) { QJsonObject cameraObject; cameraObject[_jsonCameraNameKey] = _cameraFact.rawValue().toString(); cameraObject[_jsonCameraOrientationLandscapeKey] = _cameraOrientationLandscapeFact.rawValue().toBool(); cameraObject[_jsonCameraSensorWidthKey] = _cameraSensorWidthFact.rawValue().toDouble(); cameraObject[_jsonCameraSensorHeightKey] = _cameraSensorHeightFact.rawValue().toDouble(); cameraObject[_jsonCameraResolutionWidthKey] = _cameraResolutionWidthFact.rawValue().toDouble(); cameraObject[_jsonCameraResolutionHeightKey] = _cameraResolutionHeightFact.rawValue().toDouble(); cameraObject[_jsonCameraFocalLengthKey] = _cameraFocalLengthFact.rawValue().toDouble(); cameraObject[_jsonGroundResolutionKey] = _groundResolutionFact.rawValue().toDouble(); cameraObject[_jsonFrontalOverlapKey] = _frontalOverlapFact.rawValue().toInt(); cameraObject[_jsonSideOverlapKey] = _sideOverlapFact.rawValue().toInt(); saveObject[_jsonCameraObjectKey] = cameraObject; } // Polygon shape QJsonArray polygonArray; for (int i=0; i<_polygonPath.count(); i++) { const QVariant& polyVar = _polygonPath[i]; QJsonValue jsonValue; JsonHelper::saveGeoCoordinate(polyVar.value(), false /* writeAltitude */, jsonValue); polygonArray += jsonValue; } saveObject[_jsonPolygonObjectKey] = polygonArray; } void SurveyMissionItem::setSequenceNumber(int sequenceNumber) { if (_sequenceNumber != sequenceNumber) { _sequenceNumber = sequenceNumber; emit sequenceNumberChanged(sequenceNumber); emit lastSequenceNumberChanged(lastSequenceNumber()); } } void SurveyMissionItem::_clear(void) { clearPolygon(); _clearGrid(); } bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) { QJsonObject v2Object = complexObject; // We need to pull version first to determine what validation/conversion needs to be performed. QList versionKeyInfoList = { { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, }; if (!JsonHelper::validateKeys(v2Object, versionKeyInfoList, errorString)) { return false; } int version = v2Object[JsonHelper::jsonVersionKey].toInt(); if (version != 2 && version != 3) { errorString = tr("QGroundControl does not support this version of survey items"); return false; } if (version == 2) { // Convert to v3 if (v2Object.contains(VisualMissionItem::jsonTypeKey) && v2Object[VisualMissionItem::jsonTypeKey].toString() == QStringLiteral("survey")) { v2Object[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; v2Object[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; } } QList mainKeyInfoList = { { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, { VisualMissionItem::jsonTypeKey, QJsonValue::String, true }, { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true }, { _jsonPolygonObjectKey, QJsonValue::Array, true }, { _jsonGridObjectKey, QJsonValue::Object, true }, { _jsonCameraObjectKey, QJsonValue::Object, false }, { _jsonCameraTriggerKey, QJsonValue::Bool, true }, { _jsonCameraTriggerDistanceKey, QJsonValue::Double, false }, { _jsonManualGridKey, QJsonValue::Bool, true }, { _jsonFixedValueIsAltitudeKey, QJsonValue::Bool, true }, }; if (!JsonHelper::validateKeys(v2Object, mainKeyInfoList, errorString)) { return false; } QString itemType = v2Object[VisualMissionItem::jsonTypeKey].toString(); QString complexType = v2Object[ComplexMissionItem::jsonComplexItemTypeKey].toString(); if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) { errorString = tr("QGroundControl does not support loading this complex mission item type: %1:2").arg(itemType).arg(complexType); return false; } _clear(); setSequenceNumber(sequenceNumber); _manualGridFact.setRawValue (v2Object[_jsonManualGridKey].toBool(true)); _cameraTriggerFact.setRawValue (v2Object[_jsonCameraTriggerKey].toBool(false)); _fixedValueIsAltitudeFact.setRawValue (v2Object[_jsonFixedValueIsAltitudeKey].toBool(true)); _gridAltitudeRelativeFact.setRawValue (v2Object[_jsonGridAltitudeRelativeKey].toBool(true)); QList gridKeyInfoList = { { _jsonGridAltitudeKey, QJsonValue::Double, true }, { _jsonGridAltitudeRelativeKey, QJsonValue::Bool, true }, { _jsonGridAngleKey, QJsonValue::Double, true }, { _jsonGridSpacingKey, QJsonValue::Double, true }, { _jsonTurnaroundDistKey, QJsonValue::Double, true }, }; QJsonObject gridObject = v2Object[_jsonGridObjectKey].toObject(); if (!JsonHelper::validateKeys(gridObject, gridKeyInfoList, errorString)) { return false; } _gridAltitudeFact.setRawValue (gridObject[_jsonGridAltitudeKey].toDouble()); _gridAngleFact.setRawValue (gridObject[_jsonGridAngleKey].toDouble()); _gridSpacingFact.setRawValue (gridObject[_jsonGridSpacingKey].toDouble()); _turnaroundDistFact.setRawValue (gridObject[_jsonTurnaroundDistKey].toDouble()); if (_cameraTriggerFact.rawValue().toBool()) { if (!v2Object.contains(_jsonCameraTriggerDistanceKey)) { errorString = tr("%1 but %2 is missing").arg("cameraTrigger = true").arg("cameraTriggerDistance"); return false; } _cameraTriggerDistanceFact.setRawValue(v2Object[_jsonCameraTriggerDistanceKey].toDouble()); } if (!_manualGridFact.rawValue().toBool()) { if (!v2Object.contains(_jsonCameraObjectKey)) { errorString = tr("%1 but %2 object is missing").arg("manualGrid = false").arg("camera"); return false; } QJsonObject cameraObject = v2Object[_jsonCameraObjectKey].toObject(); // Older code had typo on "imageSideOverlap" incorrectly being "imageSizeOverlap" QString incorrectImageSideOverlap = "imageSizeOverlap"; if (cameraObject.contains(incorrectImageSideOverlap)) { cameraObject[_jsonSideOverlapKey] = cameraObject[incorrectImageSideOverlap]; cameraObject.remove(incorrectImageSideOverlap); } QList cameraKeyInfoList = { { _jsonGroundResolutionKey, QJsonValue::Double, true }, { _jsonFrontalOverlapKey, QJsonValue::Double, true }, { _jsonSideOverlapKey, QJsonValue::Double, true }, { _jsonCameraSensorWidthKey, QJsonValue::Double, true }, { _jsonCameraSensorHeightKey, QJsonValue::Double, true }, { _jsonCameraResolutionWidthKey, QJsonValue::Double, true }, { _jsonCameraResolutionHeightKey, QJsonValue::Double, true }, { _jsonCameraFocalLengthKey, QJsonValue::Double, true }, { _jsonCameraNameKey, QJsonValue::String, true }, { _jsonCameraOrientationLandscapeKey, QJsonValue::Bool, true }, }; if (!JsonHelper::validateKeys(cameraObject, cameraKeyInfoList, errorString)) { return false; } _cameraFact.setRawValue(cameraObject[_jsonCameraNameKey].toString()); _cameraOrientationLandscapeFact.setRawValue(cameraObject[_jsonCameraOrientationLandscapeKey].toBool(true)); _groundResolutionFact.setRawValue (cameraObject[_jsonGroundResolutionKey].toDouble()); _frontalOverlapFact.setRawValue (cameraObject[_jsonFrontalOverlapKey].toInt()); _sideOverlapFact.setRawValue (cameraObject[_jsonSideOverlapKey].toInt()); _cameraSensorWidthFact.setRawValue (cameraObject[_jsonCameraSensorWidthKey].toDouble()); _cameraSensorHeightFact.setRawValue (cameraObject[_jsonCameraSensorHeightKey].toDouble()); _cameraResolutionWidthFact.setRawValue (cameraObject[_jsonCameraResolutionWidthKey].toDouble()); _cameraResolutionHeightFact.setRawValue (cameraObject[_jsonCameraResolutionHeightKey].toDouble()); _cameraFocalLengthFact.setRawValue (cameraObject[_jsonCameraFocalLengthKey].toDouble()); } // Polygon shape QJsonArray polygonArray(v2Object[_jsonPolygonObjectKey].toArray()); for (int i=0; i(); double distance = currentCoord.distanceTo(other); if (distance > greatestDistance) { greatestDistance = distance; } } return greatestDistance; } void SurveyMissionItem::_setExitCoordinate(const QGeoCoordinate& coordinate) { if (_exitCoordinate != coordinate) { _exitCoordinate = coordinate; emit exitCoordinateChanged(coordinate); } } bool SurveyMissionItem::specifiesCoordinate(void) const { return _polygonPath.count() > 2; } void SurveyMissionItem::_clearGrid(void) { // Bug workaround while (_gridPoints.count() > 1) { _gridPoints.takeLast(); } emit gridPointsChanged(); _gridPoints.clear(); } void SurveyMissionItem::_generateGrid(void) { if (_polygonPath.count() < 3 || _gridSpacingFact.rawValue().toDouble() <= 0) { _clearGrid(); return; } _gridPoints.clear(); QList polygonPoints; QList gridPoints; // Convert polygon to Qt coordinate system (y positive is down) qCDebug(SurveyMissionItemLog) << "Convert polygon"; QGeoCoordinate tangentOrigin = _polygonPath[0].value(); for (int i=0; i<_polygonPath.count(); i++) { double y, x, down; convertGeoToNed(_polygonPath[i].value(), tangentOrigin, &y, &x, &down); polygonPoints += QPointF(x, -y); qCDebug(SurveyMissionItemLog) << _polygonPath[i].value() << polygonPoints.last().x() << polygonPoints.last().y(); } double coveredArea = 0.0; for (int i=0; i 0) { _setCameraShots((int)floor(surveyDistance / _cameraTriggerDistanceFact.rawValue().toDouble())); } else { _setCameraShots(0); } emit gridPointsChanged(); emit lastSequenceNumberChanged(lastSequenceNumber()); if (_gridPoints.count()) { QGeoCoordinate coordinate = _gridPoints.first().value(); coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble()); setCoordinate(coordinate); QGeoCoordinate exitCoordinate = _gridPoints.last().value(); exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble()); _setExitCoordinate(exitCoordinate); } } void SurveyMissionItem::_updateCoordinateAltitude(void) { _coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble()); _exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble()); emit coordinateChanged(_coordinate); emit exitCoordinateChanged(_exitCoordinate); } QPointF SurveyMissionItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle) { QPointF rotated; double radians = (M_PI / 180.0) * angle; rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x()); rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y()); return rotated; } void SurveyMissionItem::_intersectLinesWithRect(const QList& lineList, const QRectF& boundRect, QList& resultLines) { QLineF topLine (boundRect.topLeft(), boundRect.topRight()); QLineF bottomLine (boundRect.bottomLeft(), boundRect.bottomRight()); QLineF leftLine (boundRect.topLeft(), boundRect.bottomLeft()); QLineF rightLine (boundRect.topRight(), boundRect.bottomRight()); for (int i=0; i& lineList, const QPolygonF& polygon, QList& resultLines) { for (int i=0; iP2 void SurveyMissionItem::_adjustLineDirection(const QList& lineList, QList& resultLines) { for (int i=0; i 180.0) { adjustedLine.setP1(line.p2()); adjustedLine.setP2(line.p1()); } else { adjustedLine = line; } resultLines += adjustedLine; } } void SurveyMissionItem::_gridGenerator(const QList& polygonPoints, QList& gridPoints) { double gridAngle = _gridAngleFact.rawValue().toDouble(); double gridSpacing = _gridSpacingFact.rawValue().toDouble(); qCDebug(SurveyMissionItemLog) << "SurveyMissionItem::_gridGenerator gridSpacing:gridAngle" << gridSpacing << gridAngle; gridPoints.clear(); // Convert polygon to bounding rect qCDebug(SurveyMissionItemLog) << "Polygon"; QPolygonF polygon; for (int i=0; i lineList; float x = largeBoundRect.topLeft().x() - (gridSpacing / 2); while (x < largeBoundRect.bottomRight().x()) { float yTop = largeBoundRect.topLeft().y() - 100.0; float yBottom = largeBoundRect.bottomRight().y() + 100.0; lineList += QLineF(_rotatePoint(QPointF(x, yTop), center, gridAngle), _rotatePoint(QPointF(x, yBottom), center, gridAngle)); qCDebug(SurveyMissionItemLog) << "line(" << lineList.last().x1() << ", " << lineList.last().y1() << ")-(" << lineList.last().x2() <<", " << lineList.last().y2() << ")"; x += gridSpacing; } // Now intersect the lines with the polygon QList intersectLines; #if 1 _intersectLinesWithPolygon(lineList, polygon, intersectLines); #else // This is handy for debugging grid problems, not for release intersectLines = lineList; #endif // Make sure all lines are going to same direction. Polygon intersection leads to line which // can be in varied directions depending on the order of the intesecting sides. QList resultLines; _adjustLineDirection(intersectLines, resultLines); // Turn into a path float turnaroundDist = _turnaroundDistFact.rawValue().toDouble(); for (int i=0; i 0.0) { gridPoints << line.p2() + turnaroundOffset << line.p2() << line.p1() << line.p1() - turnaroundOffset; } else { gridPoints << line.p2() << line.p1(); } } else { if (turnaroundDist > 0.0) { gridPoints << line.p1() - turnaroundOffset << line.p1() << line.p2() << line.p2() + turnaroundOffset; } else { gridPoints << line.p1() << line.p2(); } } } } QmlObjectListModel* SurveyMissionItem::getMissionItems(void) const { QmlObjectListModel* pMissionItems = new QmlObjectListModel; int seqNum = _sequenceNumber; for (int i=0; i<_gridPoints.count(); i++) { QGeoCoordinate coord = _gridPoints[i].value(); double altitude = _gridAltitudeFact.rawValue().toDouble(); MissionItem* item = new MissionItem(seqNum++, // sequence number MAV_CMD_NAV_WAYPOINT, // MAV_CMD _gridAltitudeRelativeFact.rawValue().toBool() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, // MAV_FRAME 0.0, 0.0, 0.0, 0.0, // param 1-4 coord.latitude(), coord.longitude(), altitude, true, // autoContinue false, // isCurrentItem pMissionItems); // parent - allow delete on pMissionItems to delete everthing pMissionItems->append(item); if (_cameraTriggerFact.rawValue().toBool() && i == 0) { // Turn on camera MissionItem* item = new MissionItem(seqNum++, // sequence number MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD MAV_FRAME_MISSION, // MAV_FRAME _cameraTriggerDistanceFact.rawValue().toDouble(), // trigger distance 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 2-7 true, // autoContinue false, // isCurrentItem pMissionItems); // parent - allow delete on pMissionItems to delete everthing pMissionItems->append(item); } } if (_cameraTriggerFact.rawValue().toBool()) { // Turn off camera MissionItem* item = new MissionItem(seqNum++, // sequence number MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD MAV_FRAME_MISSION, // MAV_FRAME 0.0, // trigger distance 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 2-7 true, // autoContinue false, // isCurrentItem pMissionItems); // parent - allow delete on pMissionItems to delete everthing pMissionItems->append(item); } return pMissionItems; } void SurveyMissionItem::_cameraTriggerChanged(void) { setDirty(true); // Camera trigger adds items emit lastSequenceNumberChanged(lastSequenceNumber()); // We now have camera shot count emit cameraShotsChanged(cameraShots()); } int SurveyMissionItem::cameraShots(void) const { return _cameraTriggerFact.rawValue().toBool() ? _cameraShots : 0; } void SurveyMissionItem::_cameraValueChanged(void) { emit cameraValueChanged(); } double SurveyMissionItem::timeBetweenShots(void) const { return _cruiseSpeed == 0 ? 0 : _cameraTriggerDistanceFact.rawValue().toDouble() / _cruiseSpeed; } void SurveyMissionItem::setCruiseSpeed(double cruiseSpeed) { if (!qFuzzyCompare(_cruiseSpeed, cruiseSpeed)) { _cruiseSpeed = cruiseSpeed; emit timeBetweenShotsChanged(); } }