/**************************************************************************** * * (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 "TransectStyleComplexItem.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 #include QGC_LOGGING_CATEGORY(TransectStyleComplexItemLog, "TransectStyleComplexItemLog") const char* TransectStyleComplexItem::turnAroundDistanceName = "TurnAroundDistance"; const char* TransectStyleComplexItem::turnAroundDistanceMultiRotorName = "TurnAroundDistanceMultiRotor"; const char* TransectStyleComplexItem::cameraTriggerInTurnAroundName = "CameraTriggerInTurnAround"; const char* TransectStyleComplexItem::hoverAndCaptureName = "HoverAndCapture"; const char* TransectStyleComplexItem::refly90DegreesName = "Refly90Degrees"; const char* TransectStyleComplexItem::terrainAdjustToleranceName = "TerrainAdjustTolerance"; const char* TransectStyleComplexItem::terrainAdjustMaxClimbRateName = "TerrainAdjustMaxClimbRate"; const char* TransectStyleComplexItem::terrainAdjustMaxDescentRateName = "TerrainAdjustMaxDescentRate"; const char* TransectStyleComplexItem::_jsonTransectStyleComplexItemKey = "TransectStyleComplexItem"; const char* TransectStyleComplexItem::_jsonCameraCalcKey = "CameraCalc"; const char* TransectStyleComplexItem::_jsonVisualTransectPointsKey = "VisualTransectPoints"; const char* TransectStyleComplexItem::_jsonItemsKey = "Items"; const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "FollowTerrain"; const char* TransectStyleComplexItem::_jsonCameraShotsKey = "CameraShots"; const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000; TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settingsGroup, QObject* parent) : ComplexMissionItem (vehicle, flyView, parent) , _sequenceNumber (0) , _terrainPolyPathQuery (nullptr) , _ignoreRecalc (false) , _complexDistance (0) , _cameraShots (0) , _cruiseSpeed (0) , _cameraCalc (vehicle, settingsGroup) , _followTerrain (false) , _loadedMissionItemsParent (nullptr) , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this)) , _turnAroundDistanceFact (settingsGroup, _metaDataMap[_vehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName]) , _cameraTriggerInTurnAroundFact (settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName]) , _hoverAndCaptureFact (settingsGroup, _metaDataMap[hoverAndCaptureName]) , _refly90DegreesFact (settingsGroup, _metaDataMap[refly90DegreesName]) , _terrainAdjustToleranceFact (settingsGroup, _metaDataMap[terrainAdjustToleranceName]) , _terrainAdjustMaxClimbRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName]) , _terrainAdjustMaxDescentRateFact (settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName]) , _transectsDirty(true) { _terrainQueryTimer.setInterval(_terrainQueryTimeoutMsecs); _terrainQueryTimer.setSingleShot(true); connect(&_terrainQueryTimer, &QTimer::timeout, this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo); connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_terrainAdjustMaxClimbRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_terrainAdjustMaxDescentRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_terrainAdjustToleranceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged); connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged); connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged); connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged); connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty); connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_terrainAdjustMaxClimbRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_terrainAdjustMaxDescentRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_terrainAdjustToleranceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_setDirty); connect(&_surveyAreaPolygon, &QGCMapPolygon::dirtyChanged, this, &TransectStyleComplexItem::_setIfDirty); connect(&_cameraCalc, &CameraCalc::dirtyChanged, this, &TransectStyleComplexItem::_setIfDirty); connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::coveredAreaChanged); connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &TransectStyleComplexItem::coordinateHasRelativeAltitudeChanged); connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &TransectStyleComplexItem::exitCoordinateHasRelativeAltitudeChanged); connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged); connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_followTerrainChanged); connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_updateTransectAltitude); connect(_cameraCalc.distanceToSurface(), &Fact::rawValueChanged, this, &TransectStyleComplexItem::_clearLoadedMissionItems); setDirty(false); } void TransectStyleComplexItem::_setCameraShots(int cameraShots) { if (_cameraShots != cameraShots) { _cameraShots = cameraShots; emit cameraShotsChanged(); } } void TransectStyleComplexItem::setDirty(bool dirty) { if (!dirty) { _surveyAreaPolygon.setDirty(false); _cameraCalc.setDirty(false); } if (_dirty != dirty) { _dirty = dirty; emit dirtyChanged(_dirty); } } void TransectStyleComplexItem::_save(QJsonObject& complexObject) { QJsonObject innerObject; innerObject[JsonHelper::jsonVersionKey] = 1; innerObject[turnAroundDistanceName] = _turnAroundDistanceFact.rawValue().toDouble(); innerObject[cameraTriggerInTurnAroundName] = _cameraTriggerInTurnAroundFact.rawValue().toBool(); innerObject[hoverAndCaptureName] = _hoverAndCaptureFact.rawValue().toBool(); innerObject[refly90DegreesName] = _refly90DegreesFact.rawValue().toBool(); innerObject[_jsonFollowTerrainKey] = _followTerrain; innerObject[_jsonCameraShotsKey] = _cameraShots; if (_followTerrain) { innerObject[terrainAdjustToleranceName] = _terrainAdjustToleranceFact.rawValue().toDouble(); innerObject[terrainAdjustMaxClimbRateName] = _terrainAdjustMaxClimbRateFact.rawValue().toDouble(); innerObject[terrainAdjustMaxDescentRateName] = _terrainAdjustMaxDescentRateFact.rawValue().toDouble(); } QJsonObject cameraCalcObject; _cameraCalc.save(cameraCalcObject); innerObject[_jsonCameraCalcKey] = cameraCalcObject; QJsonValue transectPointsJson; // Save transects polyline JsonHelper::saveGeoCoordinateArray(_visualTransectPoints, false /* writeAltitude */, transectPointsJson); innerObject[_jsonVisualTransectPointsKey] = transectPointsJson; // Save the interal mission items QJsonArray missionItemsJsonArray; QObject* missionItemParent = new QObject(); QList missionItems; appendMissionItems(missionItems, missionItemParent); for (const MissionItem* missionItem: missionItems) { QJsonObject missionItemJsonObject; missionItem->save(missionItemJsonObject); missionItemsJsonArray.append(missionItemJsonObject); } missionItemParent->deleteLater(); innerObject[_jsonItemsKey] = missionItemsJsonArray; complexObject[_jsonTransectStyleComplexItemKey] = innerObject; } void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber) { if (_sequenceNumber != sequenceNumber) { _sequenceNumber = sequenceNumber; emit sequenceNumberChanged(sequenceNumber); emit lastSequenceNumberChanged(lastSequenceNumber()); } } bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& errorString) { QList keyInfoList = { { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true }, }; if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) { return false; } // The TransectStyleComplexItem is a sub-object of the main complex item object QJsonObject innerObject = complexObject[_jsonTransectStyleComplexItemKey].toObject(); if (innerObject.contains(JsonHelper::jsonVersionKey)) { int version = innerObject[JsonHelper::jsonVersionKey].toInt(); if (version != 1) { errorString = tr("TransectStyleComplexItem version %2 not supported").arg(version); return false; } } QList innerKeyInfoList = { { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, { turnAroundDistanceName, QJsonValue::Double, true }, { cameraTriggerInTurnAroundName, QJsonValue::Bool, true }, { hoverAndCaptureName, QJsonValue::Bool, true }, { refly90DegreesName, QJsonValue::Bool, true }, { _jsonCameraCalcKey, QJsonValue::Object, true }, { _jsonVisualTransectPointsKey, QJsonValue::Array, true }, { _jsonItemsKey, QJsonValue::Array, true }, { _jsonFollowTerrainKey, QJsonValue::Bool, true }, { _jsonCameraShotsKey, QJsonValue::Double, false }, // Not required since it was missing from initial implementation }; if (!JsonHelper::validateKeys(innerObject, innerKeyInfoList, errorString)) { return false; } // Load visual transect points if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) { return false; } _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value() : QGeoCoordinate(); _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value() : QGeoCoordinate(); // Load CameraCalc data if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), errorString)) { return false; } // Load generated mission items _loadedMissionItemsParent = new QObject(this); QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray(); for (const QJsonValue& missionItemJson: missionItemsJsonArray) { MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent); if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) { _loadedMissionItemsParent->deleteLater(); _loadedMissionItemsParent = NULL; return false; } _loadedMissionItems.append(missionItem); } // Load TransectStyleComplexItem individual values _turnAroundDistanceFact.setRawValue (innerObject[turnAroundDistanceName].toDouble()); _cameraTriggerInTurnAroundFact.setRawValue (innerObject[cameraTriggerInTurnAroundName].toBool()); _hoverAndCaptureFact.setRawValue (innerObject[hoverAndCaptureName].toBool()); _refly90DegreesFact.setRawValue (innerObject[refly90DegreesName].toBool()); _followTerrain = innerObject[_jsonFollowTerrainKey].toBool(); // These two keys where not included in initial implementation so they are optional. Without them the values will be // incorrect when loaded though. if (innerObject.contains(_jsonCameraShotsKey)) { _cameraShots = innerObject[_jsonCameraShotsKey].toInt(); } if (_followTerrain) { QList followTerrainKeyInfoList = { { terrainAdjustToleranceName, QJsonValue::Double, true }, { terrainAdjustMaxClimbRateName, QJsonValue::Double, true }, { terrainAdjustMaxDescentRateName, QJsonValue::Double, true }, }; if (!JsonHelper::validateKeys(innerObject, followTerrainKeyInfoList, errorString)) { return false; } _terrainAdjustToleranceFact.setRawValue (innerObject[terrainAdjustToleranceName].toDouble()); _terrainAdjustMaxClimbRateFact.setRawValue (innerObject[terrainAdjustMaxClimbRateName].toDouble()); _terrainAdjustMaxDescentRateFact.setRawValue (innerObject[terrainAdjustMaxDescentRateName].toDouble()); } return true; } double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const { double greatestDistance = 0.0; for (int i=0; i<_visualTransectPoints.count(); i++) { QGeoCoordinate vertex = _visualTransectPoints[i].value(); double distance = vertex.distanceTo(other); if (distance > greatestDistance) { greatestDistance = distance; } } return greatestDistance; } void TransectStyleComplexItem::setMissionFlightStatus(const MissionController::MissionFlightStatus_t &missionFlightStatus) { ComplexMissionItem::setMissionFlightStatus(missionFlightStatus); if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) { _cruiseSpeed = missionFlightStatus.vehicleSpeed; emit timeBetweenShotsChanged(); } } void TransectStyleComplexItem::_setDirty(void) { setDirty(true); } void TransectStyleComplexItem::_setIfDirty(bool dirty) { if (dirty) { setDirty(true); } } void TransectStyleComplexItem::applyNewAltitude(double newAltitude) { Q_UNUSED(newAltitude); // FIXME: NYI //_altitudeFact.setRawValue(newAltitude); } void TransectStyleComplexItem::_updateCoordinateAltitudes(void) { emit coordinateChanged(coordinate()); emit exitCoordinateChanged(exitCoordinate()); } double TransectStyleComplexItem::coveredArea(void) const { return _surveyAreaPolygon.area(); } bool TransectStyleComplexItem::_hasTurnaround(void) const { return _turnaroundDistance() > 0; } double TransectStyleComplexItem::_turnaroundDistance(void) const { return _turnAroundDistanceFact.rawValue().toDouble(); } bool TransectStyleComplexItem::hoverAndCaptureAllowed(void) const { return _vehicle->multiRotor() || _vehicle->vtol(); } void TransectStyleComplexItem::_rebuildTransects(void) { if (_ignoreRecalc) { return; } _rebuildTransectsPhase1(); if (_followTerrain) { // Query the terrain data. Once available terrain heights will be calculated _queryTransectsPathHeightInfo(); } else { // Not following terrain, just add requested altitude to coords double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble(); for (int i=0; i<_transects.count(); i++) { QList& transect = _transects[i]; for (int j=0; j& transect: _transects) { for (const CoordInfo_t& coordInfo: transect) { _visualTransectPoints.append(QVariant::fromValue(coordInfo.coord)); double lat = coordInfo.coord.latitude() + 90.0; double lon = coordInfo.coord.longitude() + 180.0; north = fmax(north, lat); south = fmin(south, lat); east = fmax(east, lon); west = fmin(west, lon); bottom = fmin(bottom, coordInfo.coord.altitude()); top = fmax(top, coordInfo.coord.altitude()); } } //-- Update bounding cube for airspace management control _setBoundingCube(QGCGeoBoundingCube( QGeoCoordinate(north - 90.0, west - 180.0, bottom), QGeoCoordinate(south - 90.0, east - 180.0, top))); emit visualTransectPointsChanged(); _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value() : QGeoCoordinate(); _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value() : QGeoCoordinate(); emit coordinateChanged(_coordinate); emit exitCoordinateChanged(_exitCoordinate); _recalcComplexDistance(); _recalcCameraShots(); emit lastSequenceNumberChanged(lastSequenceNumber()); emit timeBetweenShotsChanged(); emit additionalTimeDelayChanged(); if (!_transectsDirty) emit missionItemReady(); } void TransectStyleComplexItem::_updateTransectAltitude() { double altitude = _cameraCalc.distanceToSurface()->rawValue().toDouble(); if (altitude > 0) for (int h = 0; h < _transects.length(); h++){ QList &list = _transects[h]; for (int i = 0; i < list.length(); i++) { CoordInfo_t &vertex = list[i]; vertex.coord.setAltitude(altitude); } } } void TransectStyleComplexItem::_clearLoadedMissionItems() { if (_loadedMissionItemsParent){ _loadedMissionItems.clear(); _loadedMissionItemsParent->deleteLater(); _loadedMissionItemsParent = nullptr; } } void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void) { _transectsPathHeightInfo.clear(); if (_transects.count()) { // We don't actually send the query until this timer times out. This way we only send // the latest request if we get a bunch in a row. _terrainQueryTimer.start(); } } void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) { // Clear any previous query if (_terrainPolyPathQuery) { // FIXME: We should really be blowing away any previous query here. But internally that is difficult to implement so instead we let // it complete and drop the results. #if 0 // Toss previous query _terrainPolyPathQuery->deleteLater(); #else // Let the signal fall on the floor disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData); #endif _terrainPolyPathQuery = NULL; } // Append all transects into a single PolyPath query QList transectPoints; for (const QList& transect: _transects) { for (const CoordInfo_t& coordInfo: transect) { transectPoints.append(coordInfo.coord); } } if (transectPoints.count() > 1) { _terrainPolyPathQuery = new TerrainPolyPathQuery(this); connect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData); _terrainPolyPathQuery->requestData(transectPoints); } } void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList& rgPathHeightInfo) { _transectsPathHeightInfo.clear(); if (success) { // Break out into individual transects int pathHeightIndex = 0; for (int i=0; i<_transects.count(); i++) { _transectsPathHeightInfo.append(QList()); int cPathHeight = _transects[i].count() - 1; while (cPathHeight-- > 0) { _transectsPathHeightInfo[i].append(rgPathHeightInfo[pathHeightIndex++]); } pathHeightIndex++; // There is an extra on between each transect } // Now that we have terrain data we can adjust _adjustTransectsForTerrain(); } if (_terrainPolyPathQuery != sender()) { qWarning() << "TransectStyleComplexItem::_polyPathTerrainData _terrainPolyPathQuery != sender()"; } disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData); _terrainPolyPathQuery = NULL; } bool TransectStyleComplexItem::readyForSave(void) const { // Make sure we have the terrain data we need return _followTerrain ? _transectsPathHeightInfo.count() : true; } void TransectStyleComplexItem::_adjustTransectsForTerrain(void) { if (_followTerrain) { if (!readyForSave()) { qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready"; qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect.")); return; } // First step is add all interstitial points at max resolution for (int i=0; i<_transects.count(); i++) { _addInterstitialTerrainPoints(_transects[i], _transectsPathHeightInfo[i]); } for (int i=0; i<_transects.count(); i++) { _adjustForMaxRates(_transects[i]); } for (int i=0; i<_transects.count(); i++) { _adjustForTolerance(_transects[i]); } emit lastSequenceNumberChanged(lastSequenceNumber()); } } /// Returns the altitude in between the two points on a line. /// @param precentTowardsTo Example: .25 = twenty five percent along the distance of from to to double TransectStyleComplexItem::_altitudeBetweenCoords(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo) { double fromAlt = fromCoord.altitude(); double toAlt = toCoord.altitude(); double altDiff = toAlt - fromAlt; return fromAlt + (altDiff * percentTowardsTo); } /// Determine the maximum height within the PathHeightInfo /// @param fromIndex First height index to consider /// @param fromIndex Last height index to consider /// @param[out] maxHeight Maximum height /// @return index within PathHeightInfo_t.heights which contains maximum height, -1 no height data in between from and to indices int TransectStyleComplexItem::_maxPathHeight(const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight) { maxHeight = qQNaN(); if (toIndex - fromIndex < 2) { return -1; } fromIndex++; toIndex--; int maxIndex = fromIndex; maxHeight = pathHeightInfo.heights[fromIndex]; for (int i=fromIndex; i<=toIndex; i++) { if (pathHeightInfo.heights[i] > maxHeight) { maxIndex = i; maxHeight = pathHeightInfo.heights[i]; } } return maxIndex; } void TransectStyleComplexItem::_adjustForMaxRates(QList& transect) { double maxClimbRate = _terrainAdjustMaxClimbRateFact.rawValue().toDouble(); double maxDescentRate = _terrainAdjustMaxDescentRateFact.rawValue().toDouble(); double flightSpeed = _missionFlightStatus.vehicleSpeed; if (qIsNaN(flightSpeed) || (maxClimbRate == 0 && maxDescentRate == 0)) { if (qIsNaN(flightSpeed)) { qWarning() << "TransectStyleComplexItem::_adjustForMaxRates called with flightSpeed = NaN"; } return; } if (maxClimbRate > 0) { // Adjust climb rates bool climbRateAdjusted; do { //qDebug() << "climbrate pass"; climbRateAdjusted = false; for (int i=0; i 0 && climbRate - maxClimbRate > 0.1) { double maxAltitudeDelta = maxClimbRate * seconds; fromCoord.setAltitude(toCoord.altitude() - maxAltitudeDelta); //qDebug() << "Adjusting"; climbRateAdjusted = true; } } } while (climbRateAdjusted); } if (maxDescentRate > 0) { // Adjust descent rates bool descentRateAdjusted; maxDescentRate = -maxDescentRate; do { //qDebug() << "descent rate pass"; descentRateAdjusted = false; for (int i=1; i& transect) { QList adjustedPoints; double tolerance = _terrainAdjustToleranceFact.rawValue().toDouble(); int coordIndex = 0; while (coordIndex < transect.count()) { const CoordInfo_t& fromCoordInfo = transect[coordIndex]; adjustedPoints.append(fromCoordInfo); // Walk forward until we fall out of tolerence or find a fixed point while (++coordIndex < transect.count()) { const CoordInfo_t& toCoordInfo = transect[coordIndex]; if (toCoordInfo.coordType != CoordTypeInteriorTerrainAdded || qAbs(fromCoordInfo.coord.altitude() - toCoordInfo.coord.altitude()) > tolerance) { adjustedPoints.append(toCoordInfo); coordIndex++; break; } } } #if 0 qDebug() << "_adjustForTolerance"; for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedPoints) { qDebug() << coordInfo.coordType; } #endif transect = adjustedPoints; } void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList& transect, const QList& transectPathHeightInfo) { QList adjustedTransect; double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble(); for (int i=0; i& rgCoordInfo: _transects) { itemCount += rgCoordInfo.count() * (hoverAndCaptureEnabled() ? 2 : 1); } if (!hoverAndCaptureEnabled() && triggerCamera()) { if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { // One camera start/stop for beginning/end of entire survey itemCount += 2; // One camera start for each transect itemCount += _transects.count(); } else { // Each transect will have a camera start and stop in it itemCount += _transects.count() * 2; } } return _sequenceNumber + itemCount - 1; } } bool TransectStyleComplexItem::coordinateHasRelativeAltitude(void) const { return _cameraCalc.distanceToSurfaceRelative(); } bool TransectStyleComplexItem::exitCoordinateHasRelativeAltitude(void) const { return coordinateHasRelativeAltitude(); } void TransectStyleComplexItem::_followTerrainChanged(bool followTerrain) { _cameraCalc.setDistanceToSurfaceRelative(!followTerrain); if (followTerrain) { _refly90DegreesFact.setRawValue(false); _hoverAndCaptureFact.setRawValue(false); } }